diff --git a/python/convenience_tool_box/notes.md b/python/convenience_tool_box/notes.md
new file mode 100644
index 0000000000000000000000000000000000000000..667374ee9d6a958d1ea10e4e85339a7ee60b3555
--- /dev/null
+++ b/python/convenience_tool_box/notes.md
@@ -0,0 +1,8 @@
+# convenience toolbox
+------------------------
+a collection of random scripts useful when working with the real robot
+
+# TODO
+------
+- make linear jog better (redo the whole program in whatever way you see fit)
+- write joint jog
diff --git a/python/examples/.drawing_from_input_drawing.py.swp b/python/examples/.drawing_from_input_drawing.py.swp
index dab6cd932f3d42ae427684d8449babf19a525544..c061a573335cdd9389217cc9fdfe3698ab20895d 100644
Binary files a/python/examples/.drawing_from_input_drawing.py.swp and b/python/examples/.drawing_from_input_drawing.py.swp differ
diff --git a/python/examples/clik_new.py b/python/examples/clik_new.py
new file mode 100644
index 0000000000000000000000000000000000000000..6d3b1082d9ddcedb200b633534ca1822023e6e04
--- /dev/null
+++ b/python/examples/clik_new.py
@@ -0,0 +1,69 @@
+import argparse
+from functools import partial
+from ur_simple_control.managers import ControlLoopManager, RobotManager
+# TODO merge the 2 clik files
+from ur_simple_control.clik.clik_point_to_point import getClikController, controlLoopClik 
+"""
+Every imaginable magic number, flag and setting is put in here.
+This way the rest of the code is clean.
+If you want to know what these various arguments do, just grep 
+though the code to find them (but replace '-' with '_' in multi-word arguments).
+All the sane defaults are here, and you can change any number of them as an argument
+when running your program. If you want to change a drastic amount of them, and
+not have to run a super long commands, just copy-paste this function and put your
+own parameters as default ones.
+NOTE1: the args object obtained from args = parser.get_args()
+is pushed all around the rest of the code (because it's tidy), so don't change their names.
+NOTE2: that you need to copy-paste and add aguments you need
+to the script you will be writing. This is kept here 
+only as a convenient reference point.
+"""
+def get_args():
+    parser = argparse.ArgumentParser(description='Run closed loop inverse kinematics \
+            of various kinds. Make sure you know what the goal is before you run!',
+            formatter_class=argparse.ArgumentDefaultsHelpFormatter)
+    parser.add_argument('--simulation', action=argparse.BooleanOptionalAction, 
+            help="whether you are running the UR simulator", default=False)
+    parser.add_argument('--pinocchio-only', action=argparse.BooleanOptionalAction, 
+            help="whether you want to just integrate with pinocchio", 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('--goal-error', type=float, \
+            help="the final position error you are happy with", default=1e-2)
+    parser.add_argument('--max-iterations', type=int, \
+            help="maximum allowable iteration number (it runs at 500Hz)", default=100000)
+    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, 0.5 by default \
+                    BE CAREFUL WITH THIS.", default=0.5)
+    parser.add_argument('--tikhonov-damp', type=float, \
+            help="damping scalar in tiknohov regularization", default=1e-3)
+    # 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')
+
+    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
+
+if __name__ == "__main__": 
+    args = get_args()
+    robot = RobotManager(args)
+    Mgoal = robot.defineGoalPoint()
+    clik_controller = getClikController(args)
+    controlLoop = partial(controlLoopClik, robot, clik_controller)
+    # we're not using any past data or logging, hence the empty arguments
+    loop_manager = ControlLoopManager(robot, controlLoop, args, {}, {})
+    loop_manager.run()
diff --git a/python/examples/drawing_from_input_drawing.py b/python/examples/drawing_from_input_drawing.py
index caa9671d44d0494af92debfb4d85b32cd586d742..d307dacce0df41e1e437b7f84245af6c7a5d4e7e 100644
--- a/python/examples/drawing_from_input_drawing.py
+++ b/python/examples/drawing_from_input_drawing.py
@@ -1,47 +1,36 @@
-# TODO
 # this is the main file for the drawing your drawings with a dmp with force feedback
 # TODO:
-# 1. clean up these instantiations in a separate util file
-#    and just do a line-liner importing -> need to make this a package to get rid
-#    of the relative-path imports
 # 2. delete the unnecessary comments
 # 3. figure out how to scale the dmp velocity when creating it -> DONE (arg for tc)
-# 4. parametrize everything, put argparse with defaults in a separate file
-#    like in tianshou examples. make magic numbers arguments!
-#    also add helpfull error messages based on this, ex. if interfaces couldn't connect
-#    with the simulation argument on, write out "check whether you started the simulator"
-# 5. remove all unused code:
-#    - for stuff that could work, make a separate file
-#    - just remove stuff that's a remnant of past tries
-# 6. put visualization into a separate file for visualization 
 # 7. put an actual low-pass filter over the force-torque sensor
 # 8. add some code to pick up the marker from a prespecified location
 # 9. add the (optional) decomposition of force feedback so that
 #    you get hybrid motion-force control
 # 10. write documentation as you go along
-# 11. put gripper class in util or something,
-#     package it and then have it one place instead of copying it everywhere
-# 12. make this a mainfile, put everything that could be turned into a function elsewhere
+# BIG TODO:
+# DOES NOT WORK WITH SPEED SLIDER =/= 1.0!!!!!!!!!!!!!!!!!!!!!!!!!!!
 
 import pinocchio as pin
 import numpy as np
 import matplotlib.pyplot as plt
 import copy
 import argparse
+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 files as well, they don't deserve to be separate
+# 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
-from ur_simple_control.clik.clik_trajectory_following import map2DPathTo3DPlane
+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
+from ur_simple_control.visualize.visualize import plotFromDict
 
 #######################################################################
 #                            arguments                                #
 #######################################################################
-# TODO sort these somehow
 def getArgs():
     #######################################################################
     #                          generic arguments                          #
@@ -71,9 +60,9 @@ def getArgs():
     parser.add_argument('--speed-slider', type=float,\
             help="cap robot's speed with the speed slider \
                     to something between 0 and 1, 0.5 by default \
-                    BE CAREFUL WITH THIS.", default=0.5)
+                    BE CAREFUL WITH THIS.", default=0.4)
     parser.add_argument('--max-iterations', type=int, \
-            help="maximum allowable iteration number (it runs at 500Hz)", default=100000)
+            help="maximum allowable iteration number (it runs at 500Hz)", default=50000)
     #######################################################################
     #                 your controller specific arguments                  #
     #######################################################################
@@ -129,12 +118,14 @@ 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.35)
+            default=0.3)
     parser.add_argument('--board-height', type=float, \
             help="height of the board (in meters) the robot will write on", \
-            default=0.4)
+            default=0.3)
     parser.add_argument('--calibration', action=argparse.BooleanOptionalAction, \
             help="whether you want to do calibration", default=True)
+    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('--n-calibration-tests', type=int, \
             help="number of calibration tests you want to run", default=10)
     parser.add_argument('--clik-goal-error', type=float, \
@@ -200,7 +191,7 @@ def controlLoopWriting(dmp, tc, controller, robot, i, past_data):
     wrench = np.average(np.array(past_data['wrench']), axis=0)
     pin.forwardKinematics(robot.model, robot.data, q)
     J = pin.computeJointJacobian(robot.model, robot.data, q, robot.JOINT_ID)
-    dq = robot.getQd().reshape((6,1))
+    dq = robot.getQd()[:6].reshape((6,1))
     # get joitn 
     tau = J.T @ wrench
     tau = tau[:6].reshape((6,1))
@@ -209,8 +200,9 @@ def controlLoopWriting(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)
-    vel_cmd = dmp.vel + kp * (dmp.pos - q6.reshape((6,1))) - alpha * tau
-    robot.sendQd(vel_cmd, acceleration, dt)
+    # solve this q number connundrum
+    vel_cmd = dmp.vel + args.kp * (dmp.pos - q[:6].reshape((6,1))) - args.alpha * tau
+    robot.sendQd(vel_cmd)
 
     # TODO find a better criterion for stopping
     if (np.linalg.norm(dmp.vel) < 0.0001) and (i > 5000):
@@ -220,7 +212,8 @@ def controlLoopWriting(dmp, tc, controller, robot, i, past_data):
         breakFlag = True
 
     # log what you said you'd log
-    log_item['qs'] = q6.reshape((6,))
+    # TODO fix the q6 situation (hide this)
+    log_item['qs'] = q[:6].reshape((6,))
     log_item['dmp_poss'] = dmp.pos.reshape((6,))
     log_item['dqs'] = dq.reshape((6,))
     log_item['dmp_vels'] = dmp.vel.reshape((6,))
@@ -239,32 +232,45 @@ if __name__ == "__main__":
     #######################################################################
     
     # draw the path on the screen
-    pixel_path = drawPath()
-    
-    # make it 3D
-    path = map2DPathTo3DPlane(pixel_path, args.board_width, args.board_height)
-    # TODO: run calibration here
-    # TODO: create calibration related arguments 
-    # add an offset of the marker (this is of course approximate)
-    # TODO: fix z axis in 2D to 3D path
-    # TODO: make this an argument once the rest is OK
-    path = path + np.array([0.0, 0.0, -0.0938])
+    if args.draw_new:
+        pixel_path = drawPath()
+        # make it 3D
+    else:
+        pixel_path_file_path = './path_in_pixels.csv'
+        pixel_path = np.genfromtxt(pixel_path_file_path, delimiter=',')
     # do calibration if specified
     if args.calibration:
-        R, translation = calibratePlane(robot, args.n_calibrations_tests)
+        rotation_matrix, translation_vector, q_init = calibratePlane(robot, args.n_calibration_tests)
     else:
         # TODO: save this somewhere obviously
-        raise NotImplementedError("you gotta give me that R somehow, 'cos there is no default atm")
-    # create a joint space trajectory based on the path
-    transf_body_to_board = pin.SE3(R, p)
-    #TODO find and fix q_init here
-    # ideally you obtain it as a part of the calibration process.
-    # of course you will or won't use/provide a new one based
-    # on some argument.
-    #q_init = np.array([1.584, -1.859, -0.953, -1.309, 1.578, -0.006, 0.0, 0.0])
-    joint_trajectory = clikCartesianPathIntoJointPath(path, args, robot, \
-        clikController, q_init, transf_body_task_frame)
+        # 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.19406676, 0.59990556, 0.57585894])
+        rotation_matrix = np.array([[1.,         0.,         0.01298926],
+            [ 0.        , -0.83234077,  0.55411201],
+            [ 0.        , -0.55411201, -0.83234077]])
 
+    # and if you don't want to draw new nor calibrate, but you want the same path
+    # with a different clik, i'm sorry, i can't put that if here.
+    # atm running the same joint trajectory on the same thing makes for easier testing
+    # of the final system.
+    if args.draw_new or args.calibration:
+        # make the path 3D
+        path = map2DPathTo3DPlane(pixel_path, args.board_width, args.board_height)
+        # TODO: fix and trust z axis in 2D to 3D path
+        # TODO: add an offset of the marker (this is of course approximate)
+        # TODO: make this an argument once the rest is OK
+        # ---> just go to the board while you have the marker ready to find this
+        # ---> do that right here
+        path = path + np.array([0.0, 0.0, -0.0938])
+        # create a joint space trajectory based on the 3D path
+        joint_trajectory = clikCartesianPathIntoJointPath(path, args, robot, \
+            clikController, q_init, rotation_matrix, translation_vector)
+    else:
+        joint_trajectory_file_path = './joint_trajectory.csv'
+        joint_trajectory = np.genfromtxt(joint_trajectory_file_path, delimiter=',')
+    
     # create DMP based on the trajectory
     dmp = DMP(joint_trajectory)
     if not args.temporal_coupling:
@@ -272,11 +278,12 @@ if __name__ == "__main__":
     else:
         # TODO test whether this works (it should, but test it)
         # test the interplay between this and the speed slider
-        v_max_ndarray = np.ones(6) * robot.max_qd
+        # ---> SPEED SLIDER HAS TO BE AT 1.0
+        v_max_ndarray = np.ones(robot.n_joints) * robot.max_qd #* args.speed_slider
         # test the interplay between this and the speed slider
         # args.acceleration is the actual maximum you're using
-        a_max_ndarray = np.ones(6) * args.acceleration
-        tc = TCVelAccConstrained(gamma_nominal, gamma_a, v_max, a_max, eps_tc)
+        a_max_ndarray = np.ones(robot.n_joints) * args.acceleration #* args.speed_slider
+        tc = TCVelAccConstrained(args.gamma_nominal, args.gamma_a, v_max_ndarray, a_max_ndarray, args.eps_tc)
 
     # 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 
@@ -310,8 +317,13 @@ if __name__ == "__main__":
     # move to initial pose
     # this is a blocking call 
     robot.rtde_control.moveJ(dmp.pos.reshape((6,)))
+    # and now we can actually run
     loop_manager.run()
+
+    # plot results
+    plotFromDict(log_dict, args)
+    # TODO: add some math to analyze path precision
+
     
-    # and now we can actually run
 
 
diff --git a/python/examples/joint_trajectory.csv b/python/examples/joint_trajectory.csv
new file mode 100644
index 0000000000000000000000000000000000000000..c118ee3b69432e4e5637b8931250b241e2ac3eea
--- /dev/null
+++ b/python/examples/joint_trajectory.csv
@@ -0,0 +1,2240 @@
+0.00000,1.40868,-1.31092,-1.83030,-0.98193,1.65843,-0.13214
+0.00223,1.40812,-1.31122,-1.83006,-0.98192,1.65873,-0.13260
+0.00447,1.40757,-1.31152,-1.82981,-0.98190,1.65903,-0.13306
+0.00670,1.40702,-1.31181,-1.82957,-0.98189,1.65933,-0.13351
+0.00893,1.40649,-1.31209,-1.82934,-0.98187,1.65962,-0.13395
+0.01117,1.40597,-1.31237,-1.82911,-0.98186,1.65990,-0.13438
+0.01340,1.40546,-1.31265,-1.82888,-0.98184,1.66018,-0.13480
+0.01563,1.40495,-1.31292,-1.82865,-0.98183,1.66046,-0.13522
+0.01787,1.40445,-1.31319,-1.82843,-0.98182,1.66073,-0.13563
+0.02010,1.40397,-1.31345,-1.82821,-0.98181,1.66100,-0.13604
+0.02233,1.40349,-1.31371,-1.82800,-0.98180,1.66126,-0.13643
+0.02456,1.40302,-1.31397,-1.82778,-0.98178,1.66152,-0.13682
+0.02680,1.40255,-1.31422,-1.82757,-0.98177,1.66177,-0.13721
+0.02903,1.40210,-1.31446,-1.82737,-0.98176,1.66202,-0.13758
+0.03126,1.40187,-1.31459,-1.82727,-0.98176,1.66214,-0.13777
+0.03350,1.40139,-1.31485,-1.82705,-0.98175,1.66241,-0.13817
+0.03573,1.40091,-1.31510,-1.82684,-0.98173,1.66267,-0.13857
+0.03796,1.40044,-1.31535,-1.82663,-0.98172,1.66292,-0.13895
+0.04020,1.39998,-1.31560,-1.82643,-0.98171,1.66318,-0.13934
+0.04243,1.39953,-1.31584,-1.82622,-0.98170,1.66343,-0.13971
+0.04466,1.39902,-1.31611,-1.82601,-0.98169,1.66370,-0.14013
+0.04690,1.39853,-1.31637,-1.82579,-0.98168,1.66397,-0.14054
+0.04913,1.39804,-1.31663,-1.82558,-0.98166,1.66424,-0.14095
+0.05136,1.39756,-1.31689,-1.82537,-0.98165,1.66450,-0.14134
+0.05360,1.39709,-1.31714,-1.82516,-0.98164,1.66476,-0.14173
+0.05583,1.39663,-1.31738,-1.82496,-0.98163,1.66501,-0.14212
+0.05806,1.39618,-1.31762,-1.82476,-0.98162,1.66526,-0.14249
+0.06029,1.39602,-1.31771,-1.82469,-0.98162,1.66535,-0.14262
+0.06253,1.39537,-1.31809,-1.82435,-0.98161,1.66571,-0.14317
+0.06476,1.39472,-1.31847,-1.82403,-0.98161,1.66606,-0.14370
+0.06699,1.39409,-1.31884,-1.82370,-0.98161,1.66641,-0.14423
+0.06923,1.39347,-1.31921,-1.82338,-0.98161,1.66675,-0.14474
+0.07146,1.39286,-1.31957,-1.82307,-0.98161,1.66708,-0.14525
+0.07369,1.39226,-1.31992,-1.82276,-0.98161,1.66741,-0.14575
+0.07593,1.39167,-1.32027,-1.82245,-0.98161,1.66773,-0.14624
+0.07816,1.39109,-1.32061,-1.82215,-0.98161,1.66805,-0.14672
+0.08039,1.39052,-1.32095,-1.82186,-0.98161,1.66836,-0.14719
+0.08263,1.38996,-1.32128,-1.82157,-0.98161,1.66867,-0.14766
+0.08486,1.38941,-1.32160,-1.82128,-0.98161,1.66897,-0.14811
+0.08709,1.38887,-1.32192,-1.82100,-0.98161,1.66927,-0.14856
+0.08933,1.38834,-1.32224,-1.82072,-0.98161,1.66956,-0.14900
+0.09156,1.38782,-1.32255,-1.82045,-0.98161,1.66985,-0.14944
+0.09379,1.38731,-1.32285,-1.82018,-0.98162,1.67013,-0.14986
+0.09603,1.38680,-1.32315,-1.81991,-0.98162,1.67041,-0.15028
+0.09826,1.38631,-1.32345,-1.81965,-0.98162,1.67068,-0.15069
+0.10049,1.38582,-1.32374,-1.81939,-0.98163,1.67095,-0.15110
+0.10272,1.38535,-1.32402,-1.81914,-0.98163,1.67121,-0.15150
+0.10496,1.38488,-1.32431,-1.81889,-0.98163,1.67147,-0.15189
+0.10719,1.38442,-1.32458,-1.81865,-0.98164,1.67172,-0.15227
+0.10942,1.38396,-1.32485,-1.81841,-0.98164,1.67197,-0.15265
+0.11166,1.38352,-1.32512,-1.81817,-0.98165,1.67222,-0.15302
+0.11389,1.38307,-1.32539,-1.81793,-0.98165,1.67246,-0.15339
+0.11612,1.38258,-1.32568,-1.81768,-0.98165,1.67273,-0.15380
+0.11836,1.38210,-1.32596,-1.81743,-0.98166,1.67300,-0.15420
+0.12059,1.38163,-1.32624,-1.81719,-0.98166,1.67326,-0.15460
+0.12282,1.38116,-1.32651,-1.81695,-0.98166,1.67352,-0.15498
+0.12506,1.38071,-1.32678,-1.81671,-0.98166,1.67377,-0.15537
+0.12729,1.38026,-1.32704,-1.81648,-0.98167,1.67402,-0.15574
+0.12952,1.37982,-1.32730,-1.81625,-0.98167,1.67426,-0.15611
+0.13176,1.37968,-1.32738,-1.81618,-0.98167,1.67433,-0.15622
+0.13399,1.37919,-1.32767,-1.81594,-0.98167,1.67461,-0.15663
+0.13622,1.37871,-1.32795,-1.81569,-0.98167,1.67487,-0.15703
+0.13845,1.37823,-1.32822,-1.81546,-0.98168,1.67513,-0.15743
+0.14069,1.37777,-1.32849,-1.81522,-0.98168,1.67539,-0.15782
+0.14292,1.37731,-1.32875,-1.81499,-0.98168,1.67564,-0.15820
+0.14515,1.37686,-1.32902,-1.81476,-0.98168,1.67589,-0.15858
+0.14739,1.37642,-1.32927,-1.81454,-0.98168,1.67614,-0.15895
+0.14962,1.37627,-1.32936,-1.81447,-0.98168,1.67622,-0.15907
+0.15185,1.37566,-1.32969,-1.81419,-0.98168,1.67655,-0.15958
+0.15409,1.37505,-1.33003,-1.81391,-0.98167,1.67689,-0.16008
+0.15632,1.37446,-1.33035,-1.81364,-0.98167,1.67721,-0.16058
+0.15855,1.37388,-1.33067,-1.81337,-0.98167,1.67753,-0.16106
+0.16079,1.37331,-1.33099,-1.81310,-0.98166,1.67784,-0.16154
+0.16302,1.37275,-1.33130,-1.81284,-0.98166,1.67815,-0.16200
+0.16525,1.37220,-1.33161,-1.81258,-0.98166,1.67845,-0.16246
+0.16749,1.37166,-1.33191,-1.81233,-0.98165,1.67875,-0.16291
+0.16972,1.37113,-1.33220,-1.81208,-0.98165,1.67905,-0.16336
+0.17195,1.37061,-1.33249,-1.81183,-0.98165,1.67933,-0.16379
+0.17418,1.37010,-1.33278,-1.81159,-0.98165,1.67962,-0.16422
+0.17642,1.36959,-1.33306,-1.81135,-0.98165,1.67989,-0.16464
+0.17865,1.36910,-1.33334,-1.81111,-0.98165,1.68017,-0.16506
+0.18088,1.36861,-1.33361,-1.81088,-0.98165,1.68044,-0.16547
+0.18312,1.36813,-1.33388,-1.81065,-0.98165,1.68070,-0.16587
+0.18535,1.36766,-1.33414,-1.81043,-0.98165,1.68096,-0.16626
+0.18758,1.36720,-1.33440,-1.81021,-0.98165,1.68121,-0.16664
+0.18982,1.36675,-1.33466,-1.80999,-0.98165,1.68147,-0.16702
+0.19205,1.36630,-1.33491,-1.80978,-0.98165,1.68171,-0.16740
+0.19428,1.36603,-1.33506,-1.80965,-0.98165,1.68186,-0.16762
+0.19652,1.36554,-1.33534,-1.80942,-0.98165,1.68213,-0.16804
+0.19875,1.36505,-1.33561,-1.80919,-0.98165,1.68240,-0.16844
+0.20098,1.36458,-1.33587,-1.80897,-0.98165,1.68266,-0.16884
+0.20322,1.36411,-1.33613,-1.80875,-0.98165,1.68292,-0.16923
+0.20545,1.36365,-1.33639,-1.80853,-0.98165,1.68317,-0.16962
+0.20768,1.36320,-1.33664,-1.80831,-0.98165,1.68342,-0.16999
+0.20992,1.36276,-1.33689,-1.80810,-0.98166,1.68367,-0.17036
+0.21215,1.36262,-1.33697,-1.80804,-0.98166,1.68374,-0.17048
+0.21438,1.36215,-1.33723,-1.80782,-0.98166,1.68401,-0.17087
+0.21661,1.36168,-1.33749,-1.80760,-0.98166,1.68426,-0.17126
+0.21885,1.36123,-1.33774,-1.80739,-0.98166,1.68451,-0.17165
+0.22108,1.36078,-1.33799,-1.80718,-0.98166,1.68476,-0.17202
+0.22331,1.36032,-1.33824,-1.80696,-0.98166,1.68501,-0.17240
+0.22555,1.35975,-1.33855,-1.80671,-0.98165,1.68533,-0.17288
+0.22778,1.35919,-1.33886,-1.80646,-0.98165,1.68564,-0.17335
+0.23001,1.35864,-1.33916,-1.80621,-0.98165,1.68594,-0.17381
+0.23225,1.35810,-1.33945,-1.80597,-0.98164,1.68624,-0.17427
+0.23448,1.35756,-1.33974,-1.80573,-0.98164,1.68653,-0.17471
+0.23671,1.35704,-1.34003,-1.80549,-0.98164,1.68682,-0.17515
+0.23895,1.35653,-1.34031,-1.80526,-0.98164,1.68710,-0.17558
+0.24118,1.35602,-1.34059,-1.80503,-0.98164,1.68738,-0.17600
+0.24341,1.35553,-1.34086,-1.80480,-0.98164,1.68766,-0.17642
+0.24565,1.35504,-1.34113,-1.80458,-0.98164,1.68793,-0.17683
+0.24788,1.35456,-1.34139,-1.80436,-0.98164,1.68819,-0.17723
+0.25011,1.35409,-1.34165,-1.80414,-0.98164,1.68845,-0.17762
+0.25234,1.35363,-1.34191,-1.80393,-0.98164,1.68871,-0.17801
+0.25458,1.35317,-1.34216,-1.80372,-0.98164,1.68896,-0.17839
+0.25681,1.35273,-1.34240,-1.80351,-0.98164,1.68920,-0.17877
+0.25904,1.35237,-1.34260,-1.80335,-0.98164,1.68940,-0.17907
+0.26128,1.35188,-1.34287,-1.80312,-0.98164,1.68967,-0.17948
+0.26351,1.35139,-1.34313,-1.80290,-0.98164,1.68994,-0.17989
+0.26574,1.35092,-1.34340,-1.80269,-0.98164,1.69020,-0.18028
+0.26798,1.35045,-1.34365,-1.80247,-0.98164,1.69046,-0.18067
+0.27021,1.35000,-1.34390,-1.80226,-0.98164,1.69071,-0.18106
+0.27244,1.34955,-1.34415,-1.80206,-0.98164,1.69096,-0.18144
+0.27468,1.34910,-1.34440,-1.80185,-0.98164,1.69120,-0.18181
+0.27691,1.34897,-1.34447,-1.80179,-0.98164,1.69128,-0.18192
+0.27914,1.34850,-1.34473,-1.80158,-0.98164,1.69154,-0.18232
+0.28138,1.34803,-1.34498,-1.80137,-0.98164,1.69179,-0.18271
+0.28361,1.34758,-1.34523,-1.80116,-0.98165,1.69205,-0.18309
+0.28584,1.34713,-1.34548,-1.80095,-0.98165,1.69229,-0.18346
+0.28808,1.34669,-1.34573,-1.80075,-0.98165,1.69254,-0.18384
+0.29031,1.34620,-1.34601,-1.80051,-0.98166,1.69281,-0.18425
+0.29254,1.34572,-1.34629,-1.80027,-0.98166,1.69307,-0.18465
+0.29477,1.34526,-1.34656,-1.80003,-0.98167,1.69333,-0.18504
+0.29701,1.34479,-1.34683,-1.79980,-0.98168,1.69358,-0.18543
+0.29924,1.34434,-1.34709,-1.79957,-0.98168,1.69383,-0.18581
+0.30147,1.34390,-1.34735,-1.79935,-0.98169,1.69408,-0.18618
+0.30371,1.34346,-1.34761,-1.79913,-0.98170,1.69432,-0.18655
+0.30594,1.34323,-1.34774,-1.79901,-0.98170,1.69445,-0.18674
+0.30817,1.34267,-1.34806,-1.79874,-0.98171,1.69475,-0.18721
+0.31041,1.34212,-1.34837,-1.79848,-0.98171,1.69506,-0.18768
+0.31264,1.34157,-1.34868,-1.79822,-0.98172,1.69536,-0.18813
+0.31487,1.34104,-1.34899,-1.79796,-0.98172,1.69565,-0.18858
+0.31711,1.34052,-1.34929,-1.79771,-0.98173,1.69594,-0.18902
+0.31934,1.34000,-1.34958,-1.79746,-0.98173,1.69622,-0.18945
+0.32157,1.33950,-1.34987,-1.79721,-0.98174,1.69650,-0.18988
+0.32381,1.33900,-1.35015,-1.79697,-0.98175,1.69677,-0.19029
+0.32604,1.33851,-1.35043,-1.79673,-0.98175,1.69704,-0.19070
+0.32827,1.33803,-1.35071,-1.79650,-0.98176,1.69731,-0.19111
+0.33050,1.33756,-1.35098,-1.79627,-0.98177,1.69757,-0.19150
+0.33274,1.33710,-1.35125,-1.79604,-0.98177,1.69782,-0.19189
+0.33497,1.33664,-1.35151,-1.79582,-0.98178,1.69807,-0.19227
+0.33720,1.33620,-1.35177,-1.79560,-0.98179,1.69832,-0.19265
+0.33944,1.33576,-1.35202,-1.79538,-0.98179,1.69856,-0.19302
+0.34167,1.33541,-1.35222,-1.79521,-0.98180,1.69876,-0.19331
+0.34390,1.33492,-1.35250,-1.79497,-0.98181,1.69902,-0.19372
+0.34614,1.33445,-1.35277,-1.79474,-0.98181,1.69928,-0.19412
+0.34837,1.33398,-1.35304,-1.79451,-0.98182,1.69954,-0.19451
+0.35060,1.33352,-1.35330,-1.79429,-0.98183,1.69979,-0.19490
+0.35284,1.33307,-1.35356,-1.79407,-0.98184,1.70004,-0.19528
+0.35507,1.33263,-1.35382,-1.79385,-0.98184,1.70029,-0.19565
+0.35730,1.33220,-1.35407,-1.79364,-0.98185,1.70053,-0.19602
+0.35954,1.33210,-1.35412,-1.79359,-0.98185,1.70058,-0.19609
+0.36177,1.33162,-1.35439,-1.79336,-0.98186,1.70084,-0.19650
+0.36400,1.33115,-1.35467,-1.79313,-0.98187,1.70110,-0.19690
+0.36623,1.33068,-1.35493,-1.79291,-0.98187,1.70136,-0.19729
+0.36847,1.33022,-1.35519,-1.79268,-0.98188,1.70161,-0.19768
+0.37070,1.32977,-1.35545,-1.79247,-0.98189,1.70186,-0.19806
+0.37293,1.32933,-1.35571,-1.79225,-0.98189,1.70211,-0.19843
+0.37517,1.32889,-1.35596,-1.79204,-0.98190,1.70235,-0.19880
+0.37740,1.32873,-1.35605,-1.79196,-0.98191,1.70243,-0.19893
+0.37963,1.32803,-1.35649,-1.79157,-0.98193,1.70282,-0.19952
+0.38187,1.32735,-1.35692,-1.79118,-0.98195,1.70319,-0.20010
+0.38410,1.32667,-1.35734,-1.79081,-0.98197,1.70356,-0.20066
+0.38633,1.32601,-1.35776,-1.79044,-0.98200,1.70393,-0.20122
+0.38857,1.32535,-1.35817,-1.79007,-0.98202,1.70428,-0.20177
+0.39080,1.32471,-1.35858,-1.78971,-0.98204,1.70463,-0.20231
+0.39303,1.32409,-1.35897,-1.78935,-0.98207,1.70498,-0.20284
+0.39527,1.32347,-1.35937,-1.78900,-0.98209,1.70532,-0.20336
+0.39750,1.32286,-1.35975,-1.78866,-0.98211,1.70565,-0.20387
+0.39973,1.32226,-1.36013,-1.78832,-0.98214,1.70598,-0.20437
+0.40197,1.32168,-1.36050,-1.78799,-0.98216,1.70630,-0.20486
+0.40420,1.32110,-1.36087,-1.78766,-0.98219,1.70661,-0.20535
+0.40643,1.32054,-1.36123,-1.78733,-0.98221,1.70692,-0.20582
+0.40866,1.31998,-1.36158,-1.78702,-0.98224,1.70723,-0.20629
+0.41090,1.31944,-1.36193,-1.78670,-0.98226,1.70753,-0.20675
+0.41313,1.31890,-1.36227,-1.78639,-0.98228,1.70782,-0.20720
+0.41536,1.31837,-1.36261,-1.78609,-0.98231,1.70811,-0.20765
+0.41760,1.31786,-1.36294,-1.78579,-0.98233,1.70840,-0.20808
+0.41983,1.31735,-1.36327,-1.78549,-0.98236,1.70867,-0.20851
+0.42206,1.31685,-1.36359,-1.78520,-0.98238,1.70895,-0.20893
+0.42430,1.31636,-1.36390,-1.78492,-0.98241,1.70922,-0.20934
+0.42653,1.31588,-1.36421,-1.78464,-0.98243,1.70948,-0.20975
+0.42876,1.31540,-1.36452,-1.78436,-0.98246,1.70974,-0.21015
+0.43100,1.31494,-1.36482,-1.78408,-0.98248,1.71000,-0.21054
+0.43323,1.31448,-1.36511,-1.78382,-0.98250,1.71025,-0.21093
+0.43546,1.31403,-1.36540,-1.78355,-0.98253,1.71050,-0.21131
+0.43770,1.31359,-1.36569,-1.78329,-0.98255,1.71074,-0.21168
+0.43993,1.31316,-1.36597,-1.78303,-0.98258,1.71098,-0.21205
+0.44216,1.31273,-1.36624,-1.78278,-0.98260,1.71122,-0.21241
+0.44439,1.31232,-1.36651,-1.78253,-0.98263,1.71145,-0.21276
+0.44663,1.31222,-1.36658,-1.78248,-0.98263,1.71150,-0.21284
+0.44886,1.31168,-1.36691,-1.78218,-0.98265,1.71180,-0.21330
+0.45109,1.31114,-1.36725,-1.78188,-0.98268,1.71209,-0.21375
+0.45333,1.31062,-1.36757,-1.78159,-0.98270,1.71238,-0.21419
+0.45556,1.31011,-1.36789,-1.78131,-0.98272,1.71266,-0.21463
+0.45779,1.30960,-1.36821,-1.78102,-0.98274,1.71294,-0.21505
+0.46003,1.30911,-1.36852,-1.78075,-0.98277,1.71321,-0.21547
+0.46226,1.30862,-1.36883,-1.78047,-0.98279,1.71348,-0.21588
+0.46449,1.30814,-1.36913,-1.78020,-0.98281,1.71374,-0.21629
+0.46673,1.30767,-1.36943,-1.77994,-0.98283,1.71400,-0.21669
+0.46896,1.30721,-1.36972,-1.77968,-0.98286,1.71425,-0.21708
+0.47119,1.30675,-1.37000,-1.77942,-0.98288,1.71450,-0.21746
+0.47343,1.30631,-1.37029,-1.77917,-0.98290,1.71475,-0.21784
+0.47566,1.30587,-1.37056,-1.77892,-0.98293,1.71499,-0.21821
+0.47789,1.30544,-1.37084,-1.77867,-0.98295,1.71523,-0.21857
+0.48013,1.30501,-1.37110,-1.77843,-0.98297,1.71546,-0.21893
+0.48236,1.30467,-1.37133,-1.77823,-0.98299,1.71565,-0.21922
+0.48459,1.30374,-1.37196,-1.77765,-0.98304,1.71615,-0.22001
+0.48682,1.30282,-1.37258,-1.77708,-0.98310,1.71665,-0.22078
+0.48906,1.30192,-1.37319,-1.77652,-0.98315,1.71714,-0.22154
+0.49129,1.30103,-1.37379,-1.77596,-0.98320,1.71762,-0.22228
+0.49352,1.30017,-1.37438,-1.77542,-0.98326,1.71809,-0.22301
+0.49576,1.29931,-1.37496,-1.77488,-0.98331,1.71856,-0.22373
+0.49799,1.29848,-1.37554,-1.77435,-0.98336,1.71901,-0.22444
+0.50022,1.29766,-1.37610,-1.77383,-0.98342,1.71946,-0.22513
+0.50246,1.29685,-1.37665,-1.77332,-0.98347,1.71990,-0.22581
+0.50469,1.29606,-1.37720,-1.77281,-0.98353,1.72033,-0.22648
+0.50692,1.29528,-1.37773,-1.77232,-0.98358,1.72076,-0.22714
+0.50916,1.29451,-1.37826,-1.77182,-0.98363,1.72117,-0.22778
+0.51139,1.29376,-1.37878,-1.77134,-0.98369,1.72158,-0.22842
+0.51362,1.29302,-1.37929,-1.77087,-0.98374,1.72198,-0.22904
+0.51586,1.29230,-1.37979,-1.77040,-0.98380,1.72238,-0.22965
+0.51809,1.29159,-1.38028,-1.76994,-0.98385,1.72277,-0.23025
+0.52032,1.29089,-1.38077,-1.76948,-0.98390,1.72315,-0.23084
+0.52255,1.29020,-1.38124,-1.76904,-0.98396,1.72352,-0.23142
+0.52479,1.28953,-1.38171,-1.76859,-0.98401,1.72389,-0.23199
+0.52702,1.28887,-1.38217,-1.76816,-0.98406,1.72425,-0.23255
+0.52925,1.28822,-1.38263,-1.76773,-0.98412,1.72461,-0.23310
+0.53149,1.28758,-1.38307,-1.76731,-0.98417,1.72495,-0.23364
+0.53372,1.28696,-1.38351,-1.76690,-0.98422,1.72530,-0.23418
+0.53595,1.28634,-1.38395,-1.76649,-0.98427,1.72563,-0.23470
+0.53819,1.28573,-1.38437,-1.76609,-0.98432,1.72596,-0.23521
+0.54042,1.28514,-1.38479,-1.76569,-0.98438,1.72629,-0.23571
+0.54265,1.28456,-1.38520,-1.76531,-0.98443,1.72661,-0.23621
+0.54489,1.28398,-1.38560,-1.76492,-0.98448,1.72692,-0.23669
+0.54712,1.28342,-1.38600,-1.76455,-0.98453,1.72723,-0.23717
+0.54935,1.28287,-1.38639,-1.76417,-0.98458,1.72753,-0.23764
+0.55159,1.28233,-1.38677,-1.76381,-0.98463,1.72783,-0.23810
+0.55382,1.28179,-1.38715,-1.76345,-0.98468,1.72812,-0.23855
+0.55605,1.28127,-1.38752,-1.76309,-0.98473,1.72841,-0.23900
+0.55828,1.28076,-1.38789,-1.76274,-0.98478,1.72869,-0.23944
+0.56052,1.28025,-1.38825,-1.76240,-0.98483,1.72897,-0.23987
+0.56275,1.27975,-1.38860,-1.76206,-0.98488,1.72924,-0.24029
+0.56498,1.27927,-1.38895,-1.76173,-0.98492,1.72951,-0.24070
+0.56722,1.27879,-1.38929,-1.76140,-0.98497,1.72977,-0.24111
+0.56945,1.27832,-1.38962,-1.76108,-0.98502,1.73003,-0.24151
+0.57168,1.27785,-1.38995,-1.76076,-0.98507,1.73028,-0.24191
+0.57392,1.27740,-1.39028,-1.76045,-0.98511,1.73053,-0.24229
+0.57615,1.27695,-1.39060,-1.76014,-0.98516,1.73077,-0.24267
+0.57838,1.27652,-1.39091,-1.75984,-0.98521,1.73101,-0.24304
+0.58062,1.27609,-1.39122,-1.75954,-0.98525,1.73125,-0.24341
+0.58285,1.27566,-1.39152,-1.75925,-0.98530,1.73148,-0.24377
+0.58508,1.27525,-1.39182,-1.75896,-0.98534,1.73171,-0.24413
+0.58732,1.27484,-1.39211,-1.75867,-0.98539,1.73194,-0.24447
+0.58955,1.27444,-1.39240,-1.75839,-0.98543,1.73216,-0.24482
+0.59178,1.27418,-1.39258,-1.75822,-0.98546,1.73230,-0.24503
+0.59402,1.27361,-1.39297,-1.75786,-0.98550,1.73261,-0.24552
+0.59625,1.27305,-1.39335,-1.75750,-0.98555,1.73292,-0.24600
+0.59848,1.27249,-1.39373,-1.75716,-0.98559,1.73322,-0.24647
+0.60071,1.27195,-1.39410,-1.75681,-0.98564,1.73351,-0.24693
+0.60295,1.27142,-1.39446,-1.75648,-0.98568,1.73381,-0.24739
+0.60518,1.27089,-1.39482,-1.75614,-0.98573,1.73409,-0.24783
+0.60741,1.27038,-1.39517,-1.75582,-0.98577,1.73437,-0.24827
+0.60965,1.26987,-1.39552,-1.75549,-0.98582,1.73465,-0.24870
+0.61188,1.26938,-1.39585,-1.75518,-0.98586,1.73492,-0.24912
+0.61411,1.26889,-1.39619,-1.75486,-0.98591,1.73519,-0.24954
+0.61635,1.26841,-1.39652,-1.75455,-0.98595,1.73545,-0.24995
+0.61858,1.26794,-1.39684,-1.75425,-0.98599,1.73571,-0.25035
+0.62081,1.26748,-1.39716,-1.75395,-0.98603,1.73596,-0.25074
+0.62305,1.26702,-1.39747,-1.75366,-0.98608,1.73621,-0.25113
+0.62528,1.26657,-1.39778,-1.75337,-0.98612,1.73645,-0.25151
+0.62751,1.26614,-1.39808,-1.75309,-0.98616,1.73669,-0.25188
+0.62975,1.26571,-1.39838,-1.75281,-0.98620,1.73693,-0.25225
+0.63198,1.26528,-1.39867,-1.75253,-0.98624,1.73716,-0.25261
+0.63421,1.26487,-1.39895,-1.75226,-0.98629,1.73739,-0.25297
+0.63644,1.26446,-1.39924,-1.75199,-0.98633,1.73761,-0.25331
+0.63868,1.26406,-1.39951,-1.75173,-0.98637,1.73783,-0.25366
+0.64091,1.26397,-1.39958,-1.75167,-0.98637,1.73788,-0.25373
+0.64314,1.26347,-1.39991,-1.75136,-0.98642,1.73815,-0.25416
+0.64538,1.26297,-1.40024,-1.75105,-0.98646,1.73842,-0.25458
+0.64761,1.26249,-1.40057,-1.75075,-0.98650,1.73869,-0.25499
+0.64984,1.26201,-1.40089,-1.75045,-0.98654,1.73895,-0.25540
+0.65208,1.26155,-1.40121,-1.75016,-0.98658,1.73920,-0.25580
+0.65431,1.26109,-1.40152,-1.74987,-0.98662,1.73945,-0.25619
+0.65654,1.26064,-1.40182,-1.74959,-0.98666,1.73970,-0.25657
+0.65878,1.26020,-1.40212,-1.74931,-0.98670,1.73994,-0.25695
+0.66101,1.25976,-1.40242,-1.74904,-0.98674,1.74018,-0.25732
+0.66324,1.25933,-1.40271,-1.74877,-0.98678,1.74041,-0.25769
+0.66548,1.25891,-1.40299,-1.74850,-0.98682,1.74064,-0.25805
+0.66771,1.25850,-1.40327,-1.74824,-0.98686,1.74086,-0.25840
+0.66994,1.25810,-1.40355,-1.74798,-0.98690,1.74109,-0.25874
+0.67218,1.25785,-1.40372,-1.74782,-0.98692,1.74122,-0.25895
+0.67441,1.25739,-1.40404,-1.74751,-0.98697,1.74147,-0.25935
+0.67664,1.25694,-1.40436,-1.74721,-0.98702,1.74172,-0.25973
+0.67887,1.25649,-1.40468,-1.74691,-0.98707,1.74196,-0.26011
+0.68111,1.25606,-1.40498,-1.74662,-0.98711,1.74220,-0.26048
+0.68334,1.25563,-1.40529,-1.74633,-0.98716,1.74243,-0.26085
+0.68557,1.25521,-1.40559,-1.74604,-0.98720,1.74266,-0.26121
+0.68781,1.25479,-1.40588,-1.74576,-0.98725,1.74289,-0.26156
+0.69004,1.25439,-1.40617,-1.74548,-0.98729,1.74311,-0.26191
+0.69227,1.25399,-1.40645,-1.74521,-0.98734,1.74333,-0.26225
+0.69451,1.25369,-1.40667,-1.74501,-0.98737,1.74349,-0.26251
+0.69674,1.25301,-1.40712,-1.74460,-0.98742,1.74386,-0.26309
+0.69897,1.25235,-1.40756,-1.74420,-0.98747,1.74422,-0.26365
+0.70121,1.25169,-1.40800,-1.74380,-0.98752,1.74457,-0.26420
+0.70344,1.25105,-1.40843,-1.74341,-0.98757,1.74492,-0.26475
+0.70567,1.25043,-1.40885,-1.74302,-0.98762,1.74526,-0.26528
+0.70791,1.24981,-1.40927,-1.74265,-0.98767,1.74559,-0.26581
+0.71014,1.24920,-1.40968,-1.74227,-0.98772,1.74592,-0.26633
+0.71237,1.24861,-1.41008,-1.74191,-0.98777,1.74624,-0.26683
+0.71460,1.24802,-1.41048,-1.74154,-0.98782,1.74656,-0.26733
+0.71684,1.24745,-1.41087,-1.74119,-0.98787,1.74687,-0.26782
+0.71907,1.24688,-1.41125,-1.74084,-0.98792,1.74717,-0.26830
+0.72130,1.24633,-1.41162,-1.74049,-0.98797,1.74747,-0.26878
+0.72354,1.24579,-1.41199,-1.74015,-0.98802,1.74777,-0.26924
+0.72577,1.24525,-1.41236,-1.73982,-0.98807,1.74806,-0.26970
+0.72800,1.24473,-1.41272,-1.73949,-0.98811,1.74834,-0.27015
+0.73024,1.24421,-1.41307,-1.73916,-0.98816,1.74862,-0.27059
+0.73247,1.24371,-1.41341,-1.73884,-0.98821,1.74890,-0.27102
+0.73470,1.24321,-1.41375,-1.73853,-0.98826,1.74917,-0.27144
+0.73694,1.24272,-1.41409,-1.73822,-0.98830,1.74943,-0.27186
+0.73917,1.24224,-1.41442,-1.73791,-0.98835,1.74969,-0.27227
+0.74140,1.24177,-1.41474,-1.73761,-0.98840,1.74995,-0.27267
+0.74364,1.24131,-1.41506,-1.73731,-0.98844,1.75020,-0.27307
+0.74587,1.24085,-1.41537,-1.73702,-0.98849,1.75045,-0.27346
+0.74810,1.24041,-1.41568,-1.73673,-0.98853,1.75069,-0.27384
+0.75033,1.23997,-1.41598,-1.73645,-0.98858,1.75093,-0.27422
+0.75257,1.23954,-1.41628,-1.73617,-0.98862,1.75116,-0.27459
+0.75480,1.23911,-1.41657,-1.73590,-0.98867,1.75139,-0.27495
+0.75703,1.23870,-1.41686,-1.73563,-0.98871,1.75162,-0.27530
+0.75927,1.23829,-1.41714,-1.73536,-0.98875,1.75184,-0.27565
+0.76150,1.23789,-1.41742,-1.73510,-0.98880,1.75206,-0.27600
+0.76373,1.23753,-1.41767,-1.73487,-0.98884,1.75225,-0.27631
+0.76597,1.23709,-1.41797,-1.73459,-0.98888,1.75249,-0.27668
+0.76820,1.23666,-1.41827,-1.73431,-0.98892,1.75273,-0.27706
+0.77043,1.23623,-1.41856,-1.73404,-0.98897,1.75296,-0.27742
+0.77267,1.23581,-1.41885,-1.73377,-0.98901,1.75318,-0.27778
+0.77490,1.23540,-1.41913,-1.73350,-0.98906,1.75341,-0.27813
+0.77713,1.23500,-1.41941,-1.73324,-0.98910,1.75363,-0.27848
+0.77937,1.23460,-1.41968,-1.73299,-0.98914,1.75384,-0.27882
+0.78160,1.23451,-1.41975,-1.73292,-0.98915,1.75389,-0.27890
+0.78383,1.23394,-1.42018,-1.73250,-0.98922,1.75420,-0.27938
+0.78607,1.23339,-1.42061,-1.73209,-0.98930,1.75450,-0.27985
+0.78830,1.23284,-1.42102,-1.73168,-0.98937,1.75479,-0.28032
+0.79053,1.23231,-1.42143,-1.73128,-0.98944,1.75508,-0.28078
+0.79276,1.23178,-1.42183,-1.73089,-0.98951,1.75536,-0.28123
+0.79500,1.23127,-1.42223,-1.73050,-0.98957,1.75564,-0.28167
+0.79723,1.23076,-1.42262,-1.73012,-0.98964,1.75592,-0.28210
+0.79946,1.23026,-1.42300,-1.72975,-0.98971,1.75619,-0.28253
+0.80170,1.22978,-1.42337,-1.72938,-0.98978,1.75645,-0.28295
+0.80393,1.22930,-1.42374,-1.72902,-0.98985,1.75671,-0.28336
+0.80616,1.22882,-1.42411,-1.72866,-0.98991,1.75697,-0.28376
+0.80840,1.22836,-1.42446,-1.72831,-0.98998,1.75722,-0.28416
+0.81063,1.22791,-1.42482,-1.72796,-0.99004,1.75746,-0.28455
+0.81286,1.22746,-1.42516,-1.72762,-0.99011,1.75770,-0.28494
+0.81510,1.22702,-1.42550,-1.72728,-0.99017,1.75794,-0.28531
+0.81733,1.22659,-1.42583,-1.72695,-0.99023,1.75817,-0.28568
+0.81956,1.22617,-1.42616,-1.72662,-0.99030,1.75840,-0.28605
+0.82180,1.22575,-1.42648,-1.72630,-0.99036,1.75863,-0.28640
+0.82403,1.22534,-1.42680,-1.72599,-0.99042,1.75885,-0.28675
+0.82626,1.22494,-1.42711,-1.72568,-0.99048,1.75907,-0.28710
+0.82849,1.22455,-1.42742,-1.72537,-0.99054,1.75928,-0.28744
+0.83073,1.22416,-1.42772,-1.72507,-0.99060,1.75949,-0.28777
+0.83296,1.22378,-1.42802,-1.72478,-0.99066,1.75970,-0.28810
+0.83519,1.22359,-1.42816,-1.72463,-0.99069,1.75980,-0.28826
+0.83743,1.22321,-1.42846,-1.72433,-0.99075,1.76001,-0.28859
+0.83966,1.22282,-1.42876,-1.72404,-0.99081,1.76022,-0.28892
+0.84189,1.22263,-1.42891,-1.72389,-0.99083,1.76032,-0.28908
+0.84413,1.22223,-1.42922,-1.72358,-0.99089,1.76054,-0.28943
+0.84636,1.22183,-1.42952,-1.72328,-0.99095,1.76076,-0.28978
+0.84859,1.22144,-1.42982,-1.72298,-0.99101,1.76097,-0.29011
+0.85083,1.22105,-1.43012,-1.72269,-0.99107,1.76118,-0.29044
+0.85306,1.22071,-1.43038,-1.72243,-0.99112,1.76136,-0.29074
+0.85529,1.22029,-1.43070,-1.72212,-0.99118,1.76159,-0.29110
+0.85753,1.21987,-1.43101,-1.72181,-0.99124,1.76182,-0.29146
+0.85976,1.21946,-1.43132,-1.72151,-0.99129,1.76204,-0.29181
+0.86199,1.21906,-1.43163,-1.72121,-0.99135,1.76225,-0.29216
+0.86423,1.21866,-1.43192,-1.72092,-0.99141,1.76247,-0.29250
+0.86646,1.21828,-1.43222,-1.72063,-0.99146,1.76268,-0.29283
+0.86869,1.21790,-1.43251,-1.72035,-0.99152,1.76288,-0.29316
+0.87092,1.21782,-1.43257,-1.72029,-0.99153,1.76293,-0.29323
+0.87316,1.21744,-1.43287,-1.71998,-0.99160,1.76313,-0.29356
+0.87539,1.21706,-1.43317,-1.71967,-0.99166,1.76334,-0.29388
+0.87762,1.21675,-1.43342,-1.71943,-0.99171,1.76351,-0.29415
+0.87986,1.21623,-1.43382,-1.71904,-0.99178,1.76379,-0.29460
+0.88209,1.21571,-1.43420,-1.71867,-0.99185,1.76406,-0.29504
+0.88432,1.21521,-1.43459,-1.71830,-0.99192,1.76433,-0.29547
+0.88656,1.21472,-1.43496,-1.71793,-0.99198,1.76460,-0.29589
+0.88879,1.21423,-1.43533,-1.71757,-0.99205,1.76486,-0.29631
+0.89102,1.21376,-1.43569,-1.71722,-0.99212,1.76511,-0.29672
+0.89326,1.21329,-1.43605,-1.71687,-0.99218,1.76537,-0.29712
+0.89549,1.21283,-1.43640,-1.71653,-0.99225,1.76561,-0.29752
+0.89772,1.21238,-1.43674,-1.71619,-0.99231,1.76586,-0.29790
+0.89996,1.21193,-1.43708,-1.71586,-0.99238,1.76610,-0.29829
+0.90219,1.21150,-1.43742,-1.71553,-0.99244,1.76633,-0.29866
+0.90442,1.21107,-1.43774,-1.71521,-0.99251,1.76656,-0.29903
+0.90665,1.21065,-1.43807,-1.71489,-0.99257,1.76679,-0.29939
+0.90889,1.21024,-1.43838,-1.71458,-0.99263,1.76701,-0.29975
+0.91112,1.20983,-1.43869,-1.71427,-0.99269,1.76723,-0.30009
+0.91335,1.20944,-1.43900,-1.71397,-0.99275,1.76744,-0.30044
+0.91559,1.20904,-1.43930,-1.71367,-0.99281,1.76765,-0.30077
+0.91782,1.20866,-1.43960,-1.71338,-0.99287,1.76786,-0.30111
+0.92005,1.20828,-1.43989,-1.71309,-0.99293,1.76806,-0.30143
+0.92229,1.20817,-1.43998,-1.71300,-0.99295,1.76813,-0.30153
+0.92452,1.20778,-1.44027,-1.71271,-0.99301,1.76833,-0.30186
+0.92675,1.20741,-1.44056,-1.71242,-0.99307,1.76854,-0.30219
+0.92899,1.20721,-1.44072,-1.71227,-0.99310,1.76864,-0.30236
+0.93122,1.20675,-1.44109,-1.71189,-0.99318,1.76889,-0.30275
+0.93345,1.20630,-1.44146,-1.71151,-0.99326,1.76913,-0.30314
+0.93569,1.20586,-1.44183,-1.71114,-0.99333,1.76937,-0.30352
+0.93792,1.20542,-1.44219,-1.71078,-0.99341,1.76961,-0.30390
+0.94015,1.20499,-1.44254,-1.71042,-0.99349,1.76984,-0.30427
+0.94238,1.20457,-1.44289,-1.71006,-0.99356,1.77006,-0.30463
+0.94462,1.20416,-1.44323,-1.70972,-0.99364,1.77028,-0.30498
+0.94685,1.20376,-1.44357,-1.70937,-0.99371,1.77050,-0.30533
+0.94908,1.20336,-1.44389,-1.70904,-0.99378,1.77072,-0.30568
+0.95132,1.20297,-1.44422,-1.70870,-0.99386,1.77093,-0.30601
+0.95355,1.20258,-1.44454,-1.70838,-0.99393,1.77113,-0.30635
+0.95578,1.20221,-1.44485,-1.70806,-0.99400,1.77134,-0.30667
+0.95802,1.20184,-1.44516,-1.70774,-0.99407,1.77154,-0.30699
+0.96025,1.20147,-1.44546,-1.70743,-0.99414,1.77173,-0.30730
+0.96248,1.20144,-1.44549,-1.70740,-0.99414,1.77175,-0.30734
+0.96472,1.20106,-1.44580,-1.70708,-0.99421,1.77195,-0.30766
+0.96695,1.20070,-1.44610,-1.70677,-0.99428,1.77215,-0.30798
+0.96918,1.20051,-1.44625,-1.70661,-0.99432,1.77225,-0.30813
+0.97142,1.20040,-1.44641,-1.70643,-0.99437,1.77231,-0.30823
+0.97365,1.20067,-1.44667,-1.70591,-0.99458,1.77217,-0.30801
+0.97588,1.20093,-1.44692,-1.70540,-0.99479,1.77204,-0.30779
+0.97812,1.20119,-1.44718,-1.70490,-0.99500,1.77191,-0.30757
+0.98035,1.20145,-1.44743,-1.70440,-0.99520,1.77178,-0.30736
+0.98258,1.20169,-1.44767,-1.70392,-0.99540,1.77165,-0.30715
+0.98481,1.20194,-1.44791,-1.70344,-0.99560,1.77153,-0.30695
+0.98705,1.20218,-1.44815,-1.70297,-0.99579,1.77141,-0.30675
+0.98928,1.20241,-1.44838,-1.70251,-0.99598,1.77129,-0.30656
+0.99151,1.20264,-1.44861,-1.70205,-0.99617,1.77117,-0.30636
+0.99375,1.20287,-1.44883,-1.70161,-0.99635,1.77105,-0.30618
+0.99598,1.20309,-1.44905,-1.70117,-0.99653,1.77094,-0.30599
+0.99821,1.20326,-1.44918,-1.70089,-0.99665,1.77085,-0.30585
+1.00045,1.20388,-1.44938,-1.70032,-0.99692,1.77053,-0.30533
+1.00268,1.20448,-1.44957,-1.69975,-0.99719,1.77022,-0.30482
+1.00491,1.20507,-1.44977,-1.69920,-0.99746,1.76991,-0.30432
+1.00715,1.20566,-1.44995,-1.69865,-0.99772,1.76961,-0.30383
+1.00938,1.20623,-1.45014,-1.69812,-0.99797,1.76931,-0.30334
+1.01161,1.20679,-1.45033,-1.69759,-0.99822,1.76902,-0.30287
+1.01385,1.20734,-1.45051,-1.69707,-0.99847,1.76873,-0.30241
+1.01608,1.20788,-1.45068,-1.69656,-0.99871,1.76845,-0.30195
+1.01831,1.20841,-1.45086,-1.69606,-0.99895,1.76817,-0.30150
+1.02054,1.20893,-1.45103,-1.69557,-0.99919,1.76790,-0.30106
+1.02278,1.20944,-1.45120,-1.69508,-0.99942,1.76763,-0.30063
+1.02501,1.20994,-1.45137,-1.69461,-0.99965,1.76737,-0.30021
+1.02724,1.21043,-1.45153,-1.69414,-0.99987,1.76711,-0.29980
+1.02948,1.21091,-1.45170,-1.69368,-1.00009,1.76686,-0.29939
+1.03171,1.21138,-1.45186,-1.69323,-1.00031,1.76661,-0.29899
+1.03394,1.21185,-1.45201,-1.69278,-1.00052,1.76637,-0.29860
+1.03618,1.21230,-1.45217,-1.69234,-1.00073,1.76613,-0.29821
+1.03841,1.21275,-1.45232,-1.69191,-1.00094,1.76590,-0.29783
+1.04064,1.21319,-1.45247,-1.69149,-1.00114,1.76567,-0.29746
+1.04288,1.21362,-1.45261,-1.69108,-1.00134,1.76544,-0.29710
+1.04511,1.21404,-1.45276,-1.69067,-1.00154,1.76522,-0.29674
+1.04734,1.21445,-1.45290,-1.69027,-1.00173,1.76500,-0.29639
+1.04958,1.21486,-1.45304,-1.68987,-1.00192,1.76479,-0.29605
+1.05181,1.21526,-1.45318,-1.68948,-1.00211,1.76458,-0.29571
+1.05404,1.21565,-1.45331,-1.68910,-1.00230,1.76437,-0.29538
+1.05628,1.21604,-1.45345,-1.68873,-1.00248,1.76417,-0.29505
+1.05851,1.21642,-1.45358,-1.68836,-1.00265,1.76397,-0.29473
+1.06074,1.21679,-1.45371,-1.68800,-1.00283,1.76377,-0.29442
+1.06297,1.21715,-1.45383,-1.68764,-1.00300,1.76358,-0.29411
+1.06521,1.21751,-1.45396,-1.68729,-1.00317,1.76339,-0.29381
+1.06744,1.21786,-1.45408,-1.68695,-1.00334,1.76321,-0.29351
+1.06967,1.21820,-1.45420,-1.68661,-1.00350,1.76303,-0.29322
+1.07191,1.21854,-1.45432,-1.68628,-1.00366,1.76285,-0.29294
+1.07414,1.21887,-1.45444,-1.68595,-1.00382,1.76267,-0.29266
+1.07637,1.21920,-1.45455,-1.68563,-1.00398,1.76250,-0.29238
+1.07861,1.21951,-1.45467,-1.68531,-1.00413,1.76233,-0.29211
+1.08084,1.21968,-1.45472,-1.68515,-1.00421,1.76224,-0.29197
+1.08307,1.22008,-1.45484,-1.68480,-1.00439,1.76203,-0.29163
+1.08531,1.22048,-1.45496,-1.68445,-1.00456,1.76182,-0.29129
+1.08754,1.22087,-1.45507,-1.68410,-1.00473,1.76162,-0.29096
+1.08977,1.22125,-1.45518,-1.68376,-1.00490,1.76141,-0.29064
+1.09201,1.22162,-1.45529,-1.68343,-1.00507,1.76122,-0.29033
+1.09424,1.22199,-1.45540,-1.68310,-1.00523,1.76102,-0.29002
+1.09647,1.22235,-1.45550,-1.68278,-1.00539,1.76083,-0.28971
+1.09870,1.22270,-1.45561,-1.68247,-1.00555,1.76064,-0.28941
+1.10094,1.22305,-1.45571,-1.68216,-1.00570,1.76046,-0.28912
+1.10317,1.22339,-1.45581,-1.68185,-1.00585,1.76028,-0.28883
+1.10540,1.22372,-1.45591,-1.68155,-1.00600,1.76010,-0.28855
+1.10764,1.22405,-1.45601,-1.68125,-1.00615,1.75993,-0.28827
+1.10987,1.22412,-1.45603,-1.68119,-1.00618,1.75989,-0.28821
+1.11210,1.22452,-1.45615,-1.68084,-1.00635,1.75968,-0.28787
+1.11434,1.22491,-1.45626,-1.68050,-1.00652,1.75947,-0.28754
+1.11657,1.22529,-1.45637,-1.68016,-1.00669,1.75927,-0.28722
+1.11880,1.22566,-1.45648,-1.67983,-1.00685,1.75907,-0.28690
+1.12104,1.22603,-1.45659,-1.67951,-1.00702,1.75887,-0.28659
+1.12327,1.22639,-1.45669,-1.67919,-1.00718,1.75868,-0.28628
+1.12550,1.22674,-1.45680,-1.67888,-1.00733,1.75849,-0.28598
+1.12774,1.22709,-1.45690,-1.67857,-1.00749,1.75831,-0.28569
+1.12997,1.22743,-1.45700,-1.67826,-1.00764,1.75813,-0.28540
+1.13220,1.22777,-1.45710,-1.67797,-1.00778,1.75795,-0.28512
+1.13444,1.22810,-1.45719,-1.67767,-1.00793,1.75777,-0.28484
+1.13667,1.22816,-1.45721,-1.67763,-1.00796,1.75774,-0.28478
+1.13890,1.22880,-1.45733,-1.67717,-1.00819,1.75740,-0.28424
+1.14113,1.22944,-1.45745,-1.67671,-1.00843,1.75706,-0.28370
+1.14337,1.23006,-1.45757,-1.67626,-1.00866,1.75673,-0.28318
+1.14560,1.23066,-1.45769,-1.67583,-1.00889,1.75641,-0.28266
+1.14783,1.23126,-1.45781,-1.67539,-1.00911,1.75609,-0.28216
+1.15007,1.23185,-1.45793,-1.67497,-1.00933,1.75578,-0.28166
+1.15230,1.23242,-1.45804,-1.67455,-1.00955,1.75547,-0.28117
+1.15453,1.23299,-1.45815,-1.67414,-1.00976,1.75517,-0.28069
+1.15677,1.23354,-1.45826,-1.67374,-1.00997,1.75487,-0.28022
+1.15900,1.23409,-1.45837,-1.67334,-1.01018,1.75458,-0.27976
+1.16123,1.23462,-1.45848,-1.67295,-1.01038,1.75430,-0.27931
+1.16347,1.23514,-1.45858,-1.67257,-1.01058,1.75402,-0.27887
+1.16570,1.23566,-1.45869,-1.67219,-1.01078,1.75374,-0.27843
+1.16793,1.23616,-1.45879,-1.67182,-1.01097,1.75347,-0.27800
+1.17017,1.23666,-1.45889,-1.67145,-1.01116,1.75321,-0.27758
+1.17240,1.23715,-1.45899,-1.67110,-1.01135,1.75295,-0.27717
+1.17463,1.23762,-1.45909,-1.67074,-1.01153,1.75269,-0.27676
+1.17686,1.23809,-1.45918,-1.67040,-1.01171,1.75244,-0.27637
+1.17910,1.23855,-1.45928,-1.67006,-1.01189,1.75219,-0.27598
+1.18133,1.23900,-1.45937,-1.66972,-1.01207,1.75195,-0.27559
+1.18356,1.23945,-1.45946,-1.66939,-1.01224,1.75171,-0.27522
+1.18580,1.23988,-1.45956,-1.66907,-1.01241,1.75148,-0.27485
+1.18803,1.24031,-1.45964,-1.66875,-1.01257,1.75125,-0.27449
+1.19026,1.24073,-1.45973,-1.66844,-1.01274,1.75102,-0.27413
+1.19250,1.24114,-1.45982,-1.66813,-1.01290,1.75080,-0.27378
+1.19473,1.24155,-1.45990,-1.66783,-1.01306,1.75059,-0.27344
+1.19696,1.24194,-1.45999,-1.66754,-1.01321,1.75037,-0.27310
+1.19920,1.24233,-1.46007,-1.66724,-1.01337,1.75016,-0.27277
+1.20143,1.24271,-1.46015,-1.66696,-1.01352,1.74996,-0.27245
+1.20366,1.24309,-1.46023,-1.66668,-1.01366,1.74976,-0.27213
+1.20590,1.24346,-1.46031,-1.66640,-1.01381,1.74956,-0.27182
+1.20813,1.24382,-1.46039,-1.66613,-1.01395,1.74936,-0.27151
+1.21036,1.24417,-1.46046,-1.66586,-1.01409,1.74917,-0.27121
+1.21259,1.24452,-1.46054,-1.66560,-1.01423,1.74898,-0.27091
+1.21483,1.24477,-1.46059,-1.66541,-1.01433,1.74885,-0.27070
+1.21706,1.24515,-1.46067,-1.66513,-1.01448,1.74864,-0.27038
+1.21929,1.24553,-1.46075,-1.66486,-1.01462,1.74844,-0.27006
+1.22153,1.24590,-1.46082,-1.66458,-1.01477,1.74824,-0.26975
+1.22376,1.24626,-1.46090,-1.66432,-1.01491,1.74805,-0.26944
+1.22599,1.24661,-1.46097,-1.66405,-1.01505,1.74786,-0.26914
+1.22823,1.24696,-1.46104,-1.66380,-1.01518,1.74767,-0.26884
+1.23046,1.24714,-1.46108,-1.66367,-1.01525,1.74757,-0.26869
+1.23269,1.24753,-1.46115,-1.66339,-1.01540,1.74736,-0.26836
+1.23493,1.24790,-1.46123,-1.66312,-1.01555,1.74716,-0.26804
+1.23716,1.24828,-1.46130,-1.66285,-1.01569,1.74696,-0.26773
+1.23939,1.24864,-1.46137,-1.66259,-1.01583,1.74676,-0.26742
+1.24163,1.24900,-1.46144,-1.66233,-1.01597,1.74657,-0.26711
+1.24386,1.24935,-1.46151,-1.66207,-1.01610,1.74638,-0.26682
+1.24609,1.24953,-1.46154,-1.66194,-1.01617,1.74628,-0.26666
+1.24833,1.24996,-1.46161,-1.66167,-1.01632,1.74605,-0.26630
+1.25056,1.25038,-1.46167,-1.66139,-1.01647,1.74582,-0.26594
+1.25279,1.25079,-1.46174,-1.66113,-1.01662,1.74560,-0.26560
+1.25502,1.25119,-1.46180,-1.66086,-1.01677,1.74538,-0.26525
+1.25726,1.25159,-1.46186,-1.66060,-1.01691,1.74517,-0.26492
+1.25949,1.25198,-1.46192,-1.66035,-1.01705,1.74496,-0.26459
+1.26172,1.25236,-1.46198,-1.66010,-1.01719,1.74475,-0.26426
+1.26396,1.25274,-1.46204,-1.65985,-1.01732,1.74455,-0.26394
+1.26619,1.25311,-1.46210,-1.65961,-1.01745,1.74435,-0.26363
+1.26842,1.25347,-1.46215,-1.65937,-1.01759,1.74416,-0.26332
+1.27066,1.25381,-1.46221,-1.65914,-1.01771,1.74397,-0.26303
+1.27289,1.25439,-1.46235,-1.65870,-1.01793,1.74366,-0.26255
+1.27512,1.25495,-1.46248,-1.65827,-1.01815,1.74336,-0.26207
+1.27736,1.25550,-1.46261,-1.65785,-1.01837,1.74306,-0.26160
+1.27959,1.25605,-1.46274,-1.65743,-1.01858,1.74277,-0.26114
+1.28182,1.25658,-1.46286,-1.65702,-1.01879,1.74248,-0.26069
+1.28406,1.25711,-1.46298,-1.65662,-1.01899,1.74220,-0.26025
+1.28629,1.25762,-1.46311,-1.65623,-1.01919,1.74192,-0.25981
+1.28852,1.25813,-1.46323,-1.65584,-1.01939,1.74165,-0.25939
+1.29075,1.25862,-1.46335,-1.65546,-1.01959,1.74138,-0.25897
+1.29299,1.25911,-1.46346,-1.65508,-1.01978,1.74112,-0.25855
+1.29522,1.25958,-1.46358,-1.65471,-1.01997,1.74086,-0.25815
+1.29745,1.26005,-1.46369,-1.65435,-1.02016,1.74061,-0.25775
+1.29969,1.26051,-1.46380,-1.65399,-1.02034,1.74036,-0.25737
+1.30192,1.26096,-1.46391,-1.65364,-1.02052,1.74011,-0.25698
+1.30415,1.26141,-1.46402,-1.65329,-1.02069,1.73987,-0.25661
+1.30639,1.26184,-1.46412,-1.65295,-1.02087,1.73964,-0.25624
+1.30862,1.26227,-1.46423,-1.65262,-1.02104,1.73941,-0.25588
+1.31085,1.26269,-1.46433,-1.65229,-1.02121,1.73918,-0.25552
+1.31309,1.26310,-1.46443,-1.65197,-1.02137,1.73896,-0.25518
+1.31532,1.26350,-1.46453,-1.65165,-1.02154,1.73874,-0.25483
+1.31755,1.26390,-1.46463,-1.65134,-1.02170,1.73852,-0.25450
+1.31979,1.26429,-1.46473,-1.65104,-1.02185,1.73831,-0.25417
+1.32202,1.26467,-1.46482,-1.65074,-1.02201,1.73810,-0.25385
+1.32425,1.26504,-1.46491,-1.65044,-1.02216,1.73790,-0.25353
+1.32649,1.26541,-1.46500,-1.65015,-1.02231,1.73770,-0.25322
+1.32872,1.26577,-1.46510,-1.64986,-1.02246,1.73750,-0.25291
+1.33095,1.26613,-1.46518,-1.64958,-1.02260,1.73731,-0.25261
+1.33318,1.26648,-1.46527,-1.64931,-1.02275,1.73712,-0.25232
+1.33542,1.26682,-1.46536,-1.64903,-1.02289,1.73694,-0.25203
+1.33765,1.26697,-1.46540,-1.64891,-1.02295,1.73685,-0.25190
+1.33988,1.26782,-1.46560,-1.64826,-1.02328,1.73640,-0.25118
+1.34212,1.26865,-1.46581,-1.64762,-1.02360,1.73595,-0.25048
+1.34435,1.26947,-1.46601,-1.64699,-1.02392,1.73551,-0.24979
+1.34658,1.27028,-1.46621,-1.64637,-1.02423,1.73507,-0.24911
+1.34882,1.27106,-1.46641,-1.64576,-1.02454,1.73465,-0.24845
+1.35105,1.27184,-1.46660,-1.64516,-1.02484,1.73423,-0.24780
+1.35328,1.27260,-1.46679,-1.64456,-1.02514,1.73382,-0.24716
+1.35552,1.27334,-1.46698,-1.64398,-1.02543,1.73342,-0.24653
+1.35775,1.27407,-1.46717,-1.64341,-1.02572,1.73302,-0.24591
+1.35998,1.27479,-1.46735,-1.64285,-1.02600,1.73264,-0.24531
+1.36222,1.27549,-1.46753,-1.64230,-1.02628,1.73226,-0.24472
+1.36445,1.27619,-1.46771,-1.64175,-1.02656,1.73188,-0.24413
+1.36668,1.27686,-1.46788,-1.64122,-1.02683,1.73151,-0.24356
+1.36891,1.27753,-1.46806,-1.64069,-1.02710,1.73115,-0.24300
+1.37115,1.27818,-1.46823,-1.64017,-1.02736,1.73080,-0.24245
+1.37338,1.27882,-1.46840,-1.63966,-1.02762,1.73045,-0.24191
+1.37561,1.27945,-1.46856,-1.63916,-1.02787,1.73011,-0.24138
+1.37785,1.28007,-1.46872,-1.63867,-1.02812,1.72978,-0.24086
+1.38008,1.28068,-1.46888,-1.63819,-1.02836,1.72945,-0.24035
+1.38231,1.28127,-1.46904,-1.63771,-1.02861,1.72913,-0.23985
+1.38455,1.28185,-1.46920,-1.63724,-1.02884,1.72881,-0.23936
+1.38678,1.28243,-1.46935,-1.63678,-1.02908,1.72850,-0.23887
+1.38901,1.28299,-1.46950,-1.63633,-1.02931,1.72819,-0.23840
+1.39125,1.28354,-1.46965,-1.63588,-1.02953,1.72789,-0.23793
+1.39348,1.28408,-1.46980,-1.63545,-1.02976,1.72760,-0.23748
+1.39571,1.28461,-1.46994,-1.63502,-1.02998,1.72731,-0.23703
+1.39795,1.28513,-1.47008,-1.63459,-1.03019,1.72702,-0.23659
+1.40018,1.28565,-1.47022,-1.63418,-1.03040,1.72674,-0.23616
+1.40241,1.28615,-1.47036,-1.63377,-1.03061,1.72647,-0.23573
+1.40464,1.28664,-1.47050,-1.63337,-1.03082,1.72620,-0.23532
+1.40688,1.28712,-1.47063,-1.63297,-1.03102,1.72594,-0.23491
+1.40911,1.28760,-1.47076,-1.63258,-1.03122,1.72568,-0.23451
+1.41134,1.28807,-1.47089,-1.63220,-1.03142,1.72542,-0.23412
+1.41358,1.28852,-1.47102,-1.63182,-1.03161,1.72517,-0.23373
+1.41581,1.28897,-1.47114,-1.63145,-1.03180,1.72493,-0.23335
+1.41804,1.28941,-1.47127,-1.63109,-1.03198,1.72469,-0.23298
+1.42028,1.28984,-1.47139,-1.63073,-1.03217,1.72445,-0.23261
+1.42251,1.29027,-1.47151,-1.63038,-1.03235,1.72422,-0.23226
+1.42474,1.29069,-1.47162,-1.63004,-1.03252,1.72399,-0.23190
+1.42698,1.29110,-1.47174,-1.62970,-1.03270,1.72377,-0.23156
+1.42921,1.29150,-1.47185,-1.62936,-1.03287,1.72355,-0.23122
+1.43144,1.29189,-1.47196,-1.62904,-1.03304,1.72333,-0.23089
+1.43368,1.29228,-1.47207,-1.62871,-1.03320,1.72312,-0.23056
+1.43591,1.29266,-1.47218,-1.62840,-1.03337,1.72291,-0.23024
+1.43814,1.29303,-1.47229,-1.62809,-1.03353,1.72271,-0.22992
+1.44038,1.29339,-1.47239,-1.62778,-1.03369,1.72251,-0.22962
+1.44261,1.29375,-1.47250,-1.62748,-1.03384,1.72231,-0.22931
+1.44484,1.29411,-1.47260,-1.62718,-1.03400,1.72212,-0.22901
+1.44707,1.29445,-1.47270,-1.62689,-1.03415,1.72193,-0.22872
+1.44931,1.29479,-1.47280,-1.62660,-1.03429,1.72174,-0.22844
+1.45154,1.29513,-1.47290,-1.62632,-1.03444,1.72155,-0.22815
+1.45377,1.29551,-1.47301,-1.62599,-1.03461,1.72135,-0.22783
+1.45601,1.29587,-1.47313,-1.62567,-1.03477,1.72115,-0.22752
+1.45824,1.29624,-1.47324,-1.62535,-1.03493,1.72095,-0.22721
+1.46047,1.29659,-1.47335,-1.62504,-1.03509,1.72075,-0.22691
+1.46271,1.29694,-1.47346,-1.62473,-1.03525,1.72056,-0.22662
+1.46494,1.29728,-1.47357,-1.62443,-1.03540,1.72037,-0.22633
+1.46717,1.29762,-1.47368,-1.62414,-1.03555,1.72019,-0.22605
+1.46941,1.29795,-1.47378,-1.62384,-1.03570,1.72001,-0.22577
+1.47164,1.29803,-1.47381,-1.62377,-1.03574,1.71996,-0.22570
+1.47387,1.29848,-1.47397,-1.62335,-1.03594,1.71972,-0.22533
+1.47611,1.29892,-1.47413,-1.62293,-1.03615,1.71948,-0.22496
+1.47834,1.29935,-1.47429,-1.62252,-1.03635,1.71924,-0.22459
+1.48057,1.29977,-1.47445,-1.62211,-1.03655,1.71901,-0.22424
+1.48280,1.30019,-1.47460,-1.62172,-1.03674,1.71878,-0.22389
+1.48504,1.30059,-1.47475,-1.62132,-1.03693,1.71856,-0.22354
+1.48727,1.30099,-1.47490,-1.62094,-1.03712,1.71834,-0.22321
+1.48950,1.30139,-1.47505,-1.62056,-1.03731,1.71813,-0.22288
+1.49174,1.30177,-1.47519,-1.62019,-1.03749,1.71792,-0.22255
+1.49397,1.30215,-1.47533,-1.61983,-1.03767,1.71771,-0.22223
+1.49620,1.30252,-1.47547,-1.61947,-1.03784,1.71750,-0.22192
+1.49844,1.30288,-1.47561,-1.61911,-1.03802,1.71731,-0.22161
+1.50067,1.30324,-1.47575,-1.61877,-1.03819,1.71711,-0.22131
+1.50290,1.30359,-1.47588,-1.61842,-1.03836,1.71692,-0.22102
+1.50514,1.30394,-1.47601,-1.61809,-1.03852,1.71673,-0.22073
+1.50737,1.30427,-1.47614,-1.61776,-1.03869,1.71654,-0.22044
+1.50960,1.30461,-1.47626,-1.61743,-1.03885,1.71636,-0.22016
+1.51184,1.30493,-1.47639,-1.61712,-1.03900,1.71618,-0.21989
+1.51407,1.30525,-1.47651,-1.61680,-1.03916,1.71600,-0.21962
+1.51630,1.30538,-1.47656,-1.61668,-1.03922,1.71593,-0.21951
+1.51854,1.30571,-1.47668,-1.61636,-1.03938,1.71575,-0.21923
+1.52077,1.30604,-1.47680,-1.61604,-1.03954,1.71557,-0.21896
+1.52300,1.30636,-1.47692,-1.61573,-1.03969,1.71540,-0.21868
+1.52523,1.30646,-1.47696,-1.61563,-1.03974,1.71534,-0.21860
+1.52747,1.30680,-1.47711,-1.61527,-1.03991,1.71515,-0.21831
+1.52970,1.30714,-1.47726,-1.61491,-1.04008,1.71497,-0.21803
+1.53193,1.30747,-1.47740,-1.61456,-1.04025,1.71478,-0.21775
+1.53417,1.30780,-1.47754,-1.61422,-1.04042,1.71461,-0.21747
+1.53640,1.30812,-1.47768,-1.61388,-1.04058,1.71443,-0.21721
+1.53863,1.30843,-1.47782,-1.61354,-1.04075,1.71426,-0.21694
+1.54087,1.30874,-1.47796,-1.61321,-1.04090,1.71409,-0.21668
+1.54310,1.30877,-1.47797,-1.61318,-1.04092,1.71407,-0.21665
+1.54533,1.30912,-1.47813,-1.61280,-1.04110,1.71388,-0.21636
+1.54757,1.30947,-1.47828,-1.61243,-1.04128,1.71369,-0.21607
+1.54980,1.30980,-1.47843,-1.61207,-1.04145,1.71350,-0.21579
+1.55203,1.31013,-1.47858,-1.61171,-1.04162,1.71332,-0.21551
+1.55427,1.31046,-1.47872,-1.61136,-1.04179,1.71314,-0.21523
+1.55650,1.31078,-1.47887,-1.61102,-1.04196,1.71297,-0.21497
+1.55873,1.31109,-1.47901,-1.61068,-1.04212,1.71280,-0.21470
+1.56096,1.31140,-1.47914,-1.61035,-1.04228,1.71263,-0.21445
+1.56320,1.31146,-1.47917,-1.61028,-1.04231,1.71259,-0.21439
+1.56543,1.31176,-1.47932,-1.60993,-1.04248,1.71243,-0.21414
+1.56766,1.31206,-1.47947,-1.60959,-1.04264,1.71226,-0.21389
+1.56990,1.31210,-1.47949,-1.60954,-1.04266,1.71224,-0.21386
+1.57213,1.31246,-1.47972,-1.60906,-1.04288,1.71204,-0.21355
+1.57436,1.31281,-1.47994,-1.60858,-1.04309,1.71185,-0.21326
+1.57660,1.31315,-1.48015,-1.60812,-1.04330,1.71166,-0.21297
+1.57883,1.31349,-1.48036,-1.60766,-1.04351,1.71148,-0.21268
+1.58106,1.31383,-1.48057,-1.60721,-1.04371,1.71129,-0.21240
+1.58330,1.31415,-1.48078,-1.60677,-1.04391,1.71111,-0.21213
+1.58553,1.31447,-1.48098,-1.60633,-1.04411,1.71094,-0.21186
+1.58776,1.31479,-1.48118,-1.60590,-1.04431,1.71077,-0.21160
+1.59000,1.31509,-1.48138,-1.60548,-1.04450,1.71060,-0.21134
+1.59223,1.31540,-1.48157,-1.60507,-1.04468,1.71043,-0.21108
+1.59446,1.31569,-1.48176,-1.60466,-1.04487,1.71027,-0.21084
+1.59669,1.31598,-1.48194,-1.60426,-1.04505,1.71011,-0.21059
+1.59893,1.31627,-1.48213,-1.60387,-1.04523,1.70995,-0.21035
+1.60116,1.31655,-1.48230,-1.60348,-1.04541,1.70979,-0.21011
+1.60339,1.31683,-1.48248,-1.60310,-1.04558,1.70964,-0.20988
+1.60563,1.31691,-1.48254,-1.60299,-1.04563,1.70960,-0.20981
+1.60786,1.31718,-1.48272,-1.60259,-1.04581,1.70945,-0.20959
+1.61009,1.31745,-1.48291,-1.60220,-1.04599,1.70930,-0.20936
+1.61233,1.31748,-1.48293,-1.60215,-1.04601,1.70928,-0.20934
+1.61456,1.31777,-1.48321,-1.60160,-1.04624,1.70912,-0.20909
+1.61679,1.31806,-1.48349,-1.60107,-1.04647,1.70896,-0.20885
+1.61903,1.31834,-1.48376,-1.60054,-1.04669,1.70881,-0.20861
+1.62126,1.31862,-1.48402,-1.60002,-1.04691,1.70866,-0.20838
+1.62349,1.31889,-1.48428,-1.59952,-1.04713,1.70851,-0.20815
+1.62573,1.31915,-1.48454,-1.59902,-1.04734,1.70836,-0.20793
+1.62796,1.31941,-1.48479,-1.59852,-1.04755,1.70822,-0.20771
+1.63019,1.31967,-1.48504,-1.59804,-1.04776,1.70808,-0.20750
+1.63243,1.31992,-1.48528,-1.59756,-1.04797,1.70794,-0.20729
+1.63466,1.32017,-1.48552,-1.59710,-1.04817,1.70780,-0.20708
+1.63689,1.32041,-1.48576,-1.59664,-1.04836,1.70767,-0.20688
+1.63912,1.32065,-1.48599,-1.59619,-1.04856,1.70754,-0.20668
+1.64136,1.32088,-1.48622,-1.59574,-1.04875,1.70741,-0.20648
+1.64359,1.32111,-1.48644,-1.59530,-1.04894,1.70728,-0.20629
+1.64582,1.32115,-1.48649,-1.59521,-1.04898,1.70726,-0.20625
+1.64806,1.32139,-1.48677,-1.59469,-1.04920,1.70713,-0.20605
+1.65029,1.32163,-1.48704,-1.59417,-1.04941,1.70700,-0.20585
+1.65252,1.32186,-1.48731,-1.59367,-1.04963,1.70687,-0.20566
+1.65476,1.32209,-1.48757,-1.59317,-1.04983,1.70674,-0.20547
+1.65699,1.32231,-1.48783,-1.59269,-1.05004,1.70662,-0.20528
+1.65922,1.32253,-1.48808,-1.59221,-1.05024,1.70650,-0.20510
+1.66146,1.32274,-1.48833,-1.59173,-1.05044,1.70638,-0.20492
+1.66369,1.32295,-1.48857,-1.59127,-1.05064,1.70627,-0.20475
+1.66592,1.32312,-1.48882,-1.59081,-1.05083,1.70617,-0.20460
+1.66816,1.32321,-1.48942,-1.58985,-1.05118,1.70612,-0.20453
+1.67039,1.32330,-1.49001,-1.58890,-1.05152,1.70607,-0.20445
+1.67262,1.32338,-1.49058,-1.58798,-1.05186,1.70602,-0.20438
+1.67485,1.32346,-1.49115,-1.58706,-1.05220,1.70597,-0.20431
+1.67709,1.32355,-1.49170,-1.58616,-1.05253,1.70593,-0.20425
+1.67932,1.32362,-1.49225,-1.58528,-1.05286,1.70588,-0.20418
+1.68155,1.32370,-1.49279,-1.58441,-1.05318,1.70584,-0.20412
+1.68379,1.32378,-1.49331,-1.58355,-1.05349,1.70580,-0.20405
+1.68602,1.32385,-1.49383,-1.58271,-1.05381,1.70576,-0.20399
+1.68825,1.32392,-1.49434,-1.58188,-1.05411,1.70571,-0.20393
+1.69049,1.32399,-1.49484,-1.58107,-1.05442,1.70567,-0.20387
+1.69272,1.32406,-1.49533,-1.58027,-1.05472,1.70564,-0.20382
+1.69495,1.32413,-1.49582,-1.57948,-1.05501,1.70560,-0.20376
+1.69719,1.32419,-1.49629,-1.57871,-1.05530,1.70556,-0.20371
+1.69942,1.32426,-1.49676,-1.57795,-1.05558,1.70552,-0.20366
+1.70165,1.32432,-1.49722,-1.57720,-1.05587,1.70549,-0.20360
+1.70389,1.32438,-1.49767,-1.57646,-1.05614,1.70545,-0.20355
+1.70612,1.32444,-1.49812,-1.57574,-1.05642,1.70542,-0.20350
+1.70835,1.32450,-1.49855,-1.57502,-1.05668,1.70539,-0.20346
+1.71059,1.32455,-1.49898,-1.57432,-1.05695,1.70536,-0.20341
+1.71282,1.32461,-1.49940,-1.57363,-1.05721,1.70532,-0.20336
+1.71505,1.32466,-1.49982,-1.57295,-1.05747,1.70529,-0.20332
+1.71728,1.32471,-1.50022,-1.57229,-1.05772,1.70526,-0.20327
+1.71952,1.32477,-1.50062,-1.57163,-1.05797,1.70523,-0.20323
+1.72175,1.32482,-1.50102,-1.57099,-1.05822,1.70520,-0.20319
+1.72398,1.32487,-1.50140,-1.57035,-1.05846,1.70518,-0.20315
+1.72622,1.32491,-1.50178,-1.56973,-1.05870,1.70515,-0.20311
+1.72845,1.32496,-1.50216,-1.56911,-1.05893,1.70512,-0.20307
+1.73068,1.32501,-1.50252,-1.56851,-1.05917,1.70510,-0.20303
+1.73292,1.32505,-1.50289,-1.56792,-1.05939,1.70507,-0.20300
+1.73515,1.32509,-1.50324,-1.56733,-1.05962,1.70505,-0.20296
+1.73738,1.32514,-1.50359,-1.56676,-1.05984,1.70502,-0.20293
+1.73962,1.32518,-1.50393,-1.56619,-1.06006,1.70500,-0.20289
+1.74185,1.32519,-1.50408,-1.56596,-1.06015,1.70499,-0.20288
+1.74408,1.32518,-1.50450,-1.56528,-1.06040,1.70500,-0.20289
+1.74632,1.32517,-1.50493,-1.56461,-1.06065,1.70500,-0.20290
+1.74855,1.32515,-1.50534,-1.56395,-1.06089,1.70501,-0.20291
+1.75078,1.32514,-1.50575,-1.56330,-1.06113,1.70501,-0.20292
+1.75301,1.32513,-1.50615,-1.56267,-1.06137,1.70502,-0.20293
+1.75525,1.32512,-1.50654,-1.56204,-1.06160,1.70502,-0.20295
+1.75748,1.32511,-1.50693,-1.56143,-1.06183,1.70503,-0.20296
+1.75971,1.32509,-1.50731,-1.56082,-1.06206,1.70504,-0.20297
+1.76195,1.32508,-1.50768,-1.56023,-1.06228,1.70504,-0.20298
+1.76418,1.32507,-1.50805,-1.55964,-1.06250,1.70505,-0.20299
+1.76641,1.32506,-1.50841,-1.55906,-1.06272,1.70505,-0.20300
+1.76865,1.32505,-1.50852,-1.55888,-1.06279,1.70506,-0.20301
+1.77088,1.32499,-1.50897,-1.55819,-1.06304,1.70509,-0.20306
+1.77311,1.32492,-1.50941,-1.55751,-1.06329,1.70512,-0.20311
+1.77535,1.32486,-1.50984,-1.55684,-1.06353,1.70516,-0.20316
+1.77758,1.32480,-1.51026,-1.55618,-1.06377,1.70519,-0.20322
+1.77981,1.32474,-1.51068,-1.55553,-1.06401,1.70522,-0.20327
+1.78205,1.32468,-1.51109,-1.55490,-1.06424,1.70525,-0.20332
+1.78428,1.32462,-1.51149,-1.55427,-1.06447,1.70528,-0.20337
+1.78651,1.32457,-1.51189,-1.55365,-1.06470,1.70531,-0.20342
+1.78874,1.32451,-1.51228,-1.55305,-1.06492,1.70534,-0.20346
+1.79098,1.32445,-1.51266,-1.55245,-1.06514,1.70537,-0.20351
+1.79321,1.32440,-1.51303,-1.55186,-1.06536,1.70540,-0.20356
+1.79544,1.32435,-1.51340,-1.55129,-1.06557,1.70543,-0.20360
+1.79768,1.32432,-1.51348,-1.55117,-1.06561,1.70544,-0.20362
+1.79991,1.32409,-1.51425,-1.55003,-1.06600,1.70557,-0.20382
+1.80214,1.32387,-1.51501,-1.54890,-1.06639,1.70569,-0.20401
+1.80438,1.32365,-1.51576,-1.54780,-1.06677,1.70581,-0.20419
+1.80661,1.32343,-1.51649,-1.54671,-1.06714,1.70592,-0.20438
+1.80884,1.32322,-1.51721,-1.54564,-1.06751,1.70604,-0.20456
+1.81108,1.32301,-1.51792,-1.54458,-1.06787,1.70615,-0.20473
+1.81331,1.32280,-1.51862,-1.54355,-1.06823,1.70626,-0.20491
+1.81554,1.32260,-1.51930,-1.54253,-1.06859,1.70637,-0.20508
+1.81778,1.32240,-1.51998,-1.54152,-1.06894,1.70648,-0.20525
+1.82001,1.32221,-1.52064,-1.54053,-1.06928,1.70659,-0.20541
+1.82224,1.32202,-1.52129,-1.53956,-1.06962,1.70669,-0.20557
+1.82448,1.32183,-1.52193,-1.53861,-1.06996,1.70679,-0.20573
+1.82671,1.32164,-1.52255,-1.53767,-1.07029,1.70689,-0.20589
+1.82894,1.32146,-1.52317,-1.53674,-1.07062,1.70699,-0.20605
+1.83117,1.32128,-1.52378,-1.53583,-1.07094,1.70709,-0.20620
+1.83341,1.32110,-1.52437,-1.53493,-1.07125,1.70719,-0.20635
+1.83564,1.32093,-1.52496,-1.53405,-1.07157,1.70728,-0.20649
+1.83787,1.32076,-1.52554,-1.53318,-1.07188,1.70737,-0.20664
+1.84011,1.32059,-1.52610,-1.53233,-1.07218,1.70747,-0.20678
+1.84234,1.32043,-1.52666,-1.53149,-1.07248,1.70755,-0.20692
+1.84457,1.32027,-1.52721,-1.53066,-1.07278,1.70764,-0.20706
+1.84681,1.32011,-1.52775,-1.52985,-1.07307,1.70773,-0.20719
+1.84904,1.31995,-1.52827,-1.52905,-1.07335,1.70782,-0.20733
+1.85127,1.31980,-1.52879,-1.52826,-1.07364,1.70790,-0.20746
+1.85351,1.31965,-1.52930,-1.52749,-1.07392,1.70798,-0.20759
+1.85574,1.31950,-1.52981,-1.52673,-1.07419,1.70806,-0.20771
+1.85797,1.31935,-1.53030,-1.52598,-1.07447,1.70814,-0.20784
+1.86021,1.31921,-1.53079,-1.52524,-1.07473,1.70822,-0.20796
+1.86244,1.31907,-1.53126,-1.52452,-1.07500,1.70830,-0.20808
+1.86467,1.31893,-1.53173,-1.52380,-1.07526,1.70837,-0.20820
+1.86690,1.31879,-1.53219,-1.52310,-1.07551,1.70845,-0.20831
+1.86914,1.31866,-1.53265,-1.52241,-1.07577,1.70852,-0.20843
+1.87137,1.31852,-1.53309,-1.52173,-1.07602,1.70860,-0.20854
+1.87360,1.31839,-1.53353,-1.52106,-1.07626,1.70867,-0.20865
+1.87584,1.31827,-1.53396,-1.52040,-1.07650,1.70874,-0.20876
+1.87807,1.31814,-1.53438,-1.51976,-1.07674,1.70881,-0.20887
+1.88030,1.31802,-1.53480,-1.51912,-1.07698,1.70887,-0.20897
+1.88254,1.31790,-1.53521,-1.51849,-1.07721,1.70894,-0.20908
+1.88477,1.31778,-1.53561,-1.51788,-1.07744,1.70901,-0.20918
+1.88700,1.31766,-1.53600,-1.51727,-1.07766,1.70907,-0.20928
+1.88924,1.31755,-1.53639,-1.51668,-1.07789,1.70913,-0.20938
+1.89147,1.31743,-1.53677,-1.51609,-1.07811,1.70920,-0.20948
+1.89370,1.31732,-1.53715,-1.51551,-1.07832,1.70926,-0.20957
+1.89594,1.31730,-1.53719,-1.51544,-1.07835,1.70927,-0.20958
+1.89817,1.31715,-1.53766,-1.51474,-1.07860,1.70935,-0.20972
+1.90040,1.31699,-1.53811,-1.51406,-1.07885,1.70944,-0.20985
+1.90264,1.31684,-1.53856,-1.51338,-1.07909,1.70952,-0.20998
+1.90487,1.31668,-1.53900,-1.51272,-1.07934,1.70961,-0.21011
+1.90710,1.31654,-1.53943,-1.51206,-1.07958,1.70969,-0.21024
+1.90933,1.31639,-1.53985,-1.51142,-1.07981,1.70977,-0.21037
+1.91157,1.31625,-1.54027,-1.51079,-1.08004,1.70985,-0.21049
+1.91380,1.31611,-1.54068,-1.51017,-1.08027,1.70993,-0.21061
+1.91603,1.31597,-1.54108,-1.50955,-1.08050,1.71000,-0.21073
+1.91827,1.31583,-1.54148,-1.50895,-1.08072,1.71008,-0.21084
+1.92050,1.31570,-1.54187,-1.50836,-1.08094,1.71015,-0.21096
+1.92273,1.31556,-1.54225,-1.50777,-1.08116,1.71022,-0.21107
+1.92497,1.31543,-1.54263,-1.50720,-1.08137,1.71029,-0.21118
+1.92720,1.31540,-1.54271,-1.50708,-1.08141,1.71031,-0.21121
+1.92943,1.31518,-1.54316,-1.50641,-1.08165,1.71043,-0.21140
+1.93167,1.31497,-1.54361,-1.50576,-1.08188,1.71055,-0.21158
+1.93390,1.31476,-1.54405,-1.50512,-1.08211,1.71067,-0.21176
+1.93613,1.31455,-1.54448,-1.50449,-1.08233,1.71078,-0.21193
+1.93837,1.31435,-1.54490,-1.50387,-1.08255,1.71089,-0.21210
+1.94060,1.31415,-1.54532,-1.50326,-1.08277,1.71100,-0.21227
+1.94283,1.31395,-1.54573,-1.50266,-1.08299,1.71111,-0.21244
+1.94506,1.31376,-1.54613,-1.50206,-1.08320,1.71121,-0.21260
+1.94730,1.31357,-1.54652,-1.50148,-1.08341,1.71132,-0.21276
+1.94953,1.31338,-1.54691,-1.50091,-1.08362,1.71142,-0.21292
+1.95176,1.31320,-1.54729,-1.50035,-1.08382,1.71152,-0.21308
+1.95400,1.31302,-1.54767,-1.49979,-1.08402,1.71162,-0.21323
+1.95623,1.31293,-1.54786,-1.49950,-1.08413,1.71167,-0.21331
+1.95846,1.31271,-1.54834,-1.49880,-1.08437,1.71179,-0.21350
+1.96070,1.31249,-1.54880,-1.49812,-1.08462,1.71191,-0.21368
+1.96293,1.31228,-1.54926,-1.49744,-1.08486,1.71202,-0.21386
+1.96516,1.31207,-1.54971,-1.49678,-1.08510,1.71214,-0.21404
+1.96740,1.31187,-1.55016,-1.49613,-1.08533,1.71225,-0.21421
+1.96963,1.31167,-1.55059,-1.49548,-1.08556,1.71236,-0.21438
+1.97186,1.31147,-1.55102,-1.49485,-1.08579,1.71247,-0.21455
+1.97410,1.31128,-1.55144,-1.49423,-1.08601,1.71257,-0.21471
+1.97633,1.31108,-1.55186,-1.49361,-1.08623,1.71268,-0.21488
+1.97856,1.31090,-1.55226,-1.49301,-1.08645,1.71278,-0.21504
+1.98079,1.31071,-1.55266,-1.49242,-1.08666,1.71288,-0.21519
+1.98303,1.31053,-1.55306,-1.49184,-1.08688,1.71298,-0.21535
+1.98526,1.31036,-1.55344,-1.49126,-1.08709,1.71308,-0.21550
+1.98749,1.31018,-1.55382,-1.49070,-1.08729,1.71318,-0.21565
+1.98973,1.31001,-1.55420,-1.49014,-1.08749,1.71327,-0.21579
+1.99196,1.30998,-1.55424,-1.49007,-1.08752,1.71328,-0.21582
+1.99419,1.30973,-1.55471,-1.48940,-1.08775,1.71342,-0.21603
+1.99643,1.30948,-1.55516,-1.48874,-1.08799,1.71356,-0.21624
+1.99866,1.30924,-1.55561,-1.48809,-1.08821,1.71369,-0.21645
+2.00089,1.30899,-1.55606,-1.48745,-1.08844,1.71383,-0.21666
+2.00313,1.30876,-1.55649,-1.48682,-1.08866,1.71396,-0.21686
+2.00536,1.30853,-1.55692,-1.48620,-1.08888,1.71408,-0.21705
+2.00759,1.30830,-1.55734,-1.48559,-1.08910,1.71421,-0.21725
+2.00983,1.30807,-1.55775,-1.48499,-1.08931,1.71433,-0.21744
+2.01206,1.30785,-1.55816,-1.48440,-1.08952,1.71445,-0.21762
+2.01429,1.30764,-1.55856,-1.48382,-1.08973,1.71457,-0.21781
+2.01653,1.30743,-1.55895,-1.48325,-1.08994,1.71469,-0.21799
+2.01876,1.30722,-1.55933,-1.48268,-1.09014,1.71480,-0.21817
+2.02099,1.30701,-1.55971,-1.48213,-1.09034,1.71491,-0.21834
+2.02322,1.30681,-1.56009,-1.48159,-1.09053,1.71502,-0.21851
+2.02546,1.30664,-1.56041,-1.48111,-1.09070,1.71512,-0.21866
+2.02769,1.30629,-1.56108,-1.48015,-1.09103,1.71531,-0.21896
+2.02992,1.30594,-1.56174,-1.47921,-1.09136,1.71550,-0.21925
+2.03216,1.30560,-1.56238,-1.47828,-1.09168,1.71568,-0.21954
+2.03439,1.30527,-1.56302,-1.47736,-1.09200,1.71587,-0.21982
+2.03662,1.30494,-1.56364,-1.47646,-1.09231,1.71604,-0.22010
+2.03886,1.30462,-1.56426,-1.47557,-1.09262,1.71622,-0.22037
+2.04109,1.30431,-1.56486,-1.47470,-1.09292,1.71639,-0.22064
+2.04332,1.30400,-1.56545,-1.47384,-1.09322,1.71656,-0.22090
+2.04556,1.30370,-1.56604,-1.47299,-1.09352,1.71673,-0.22116
+2.04779,1.30340,-1.56661,-1.47216,-1.09381,1.71689,-0.22141
+2.05002,1.30310,-1.56717,-1.47134,-1.09410,1.71705,-0.22166
+2.05226,1.30282,-1.56773,-1.47054,-1.09438,1.71721,-0.22190
+2.05449,1.30253,-1.56827,-1.46974,-1.09466,1.71736,-0.22214
+2.05672,1.30226,-1.56881,-1.46896,-1.09494,1.71752,-0.22238
+2.05895,1.30198,-1.56934,-1.46819,-1.09521,1.71766,-0.22261
+2.06119,1.30172,-1.56985,-1.46744,-1.09548,1.71781,-0.22284
+2.06342,1.30145,-1.57036,-1.46669,-1.09575,1.71796,-0.22306
+2.06565,1.30120,-1.57086,-1.46596,-1.09601,1.71810,-0.22328
+2.06789,1.30094,-1.57136,-1.46524,-1.09627,1.71824,-0.22350
+2.07012,1.30069,-1.57184,-1.46453,-1.09652,1.71837,-0.22371
+2.07235,1.30045,-1.57232,-1.46383,-1.09678,1.71851,-0.22392
+2.07459,1.30021,-1.57278,-1.46314,-1.09702,1.71864,-0.22412
+2.07682,1.29997,-1.57324,-1.46247,-1.09727,1.71877,-0.22433
+2.07905,1.29974,-1.57370,-1.46180,-1.09751,1.71890,-0.22452
+2.08129,1.29951,-1.57414,-1.46115,-1.09775,1.71902,-0.22472
+2.08352,1.29929,-1.57458,-1.46050,-1.09798,1.71914,-0.22491
+2.08575,1.29907,-1.57501,-1.45987,-1.09822,1.71927,-0.22510
+2.08799,1.29886,-1.57543,-1.45924,-1.09844,1.71938,-0.22528
+2.09022,1.29864,-1.57585,-1.45863,-1.09867,1.71950,-0.22546
+2.09245,1.29844,-1.57625,-1.45802,-1.09889,1.71962,-0.22564
+2.09469,1.29823,-1.57666,-1.45743,-1.09911,1.71973,-0.22582
+2.09692,1.29803,-1.57705,-1.45684,-1.09933,1.71984,-0.22599
+2.09915,1.29783,-1.57744,-1.45627,-1.09954,1.71995,-0.22616
+2.10138,1.29764,-1.57782,-1.45570,-1.09975,1.72006,-0.22632
+2.10362,1.29745,-1.57820,-1.45514,-1.09996,1.72016,-0.22649
+2.10585,1.29728,-1.57853,-1.45464,-1.10014,1.72026,-0.22663
+2.10808,1.29705,-1.57896,-1.45402,-1.10037,1.72038,-0.22682
+2.11032,1.29683,-1.57937,-1.45341,-1.10059,1.72050,-0.22701
+2.11255,1.29662,-1.57977,-1.45281,-1.10081,1.72062,-0.22720
+2.11478,1.29641,-1.58017,-1.45222,-1.10103,1.72074,-0.22738
+2.11702,1.29620,-1.58057,-1.45164,-1.10124,1.72085,-0.22755
+2.11925,1.29600,-1.58095,-1.45107,-1.10145,1.72096,-0.22773
+2.12148,1.29579,-1.58133,-1.45051,-1.10166,1.72107,-0.22790
+2.12372,1.29560,-1.58171,-1.44996,-1.10186,1.72118,-0.22807
+2.12595,1.29543,-1.58201,-1.44950,-1.10203,1.72127,-0.22821
+2.12818,1.29513,-1.58252,-1.44877,-1.10229,1.72144,-0.22847
+2.13042,1.29484,-1.58302,-1.44805,-1.10254,1.72160,-0.22871
+2.13265,1.29456,-1.58351,-1.44734,-1.10280,1.72175,-0.22896
+2.13488,1.29427,-1.58400,-1.44664,-1.10305,1.72191,-0.22920
+2.13711,1.29400,-1.58447,-1.44596,-1.10329,1.72206,-0.22943
+2.13935,1.29373,-1.58494,-1.44528,-1.10353,1.72221,-0.22966
+2.14158,1.29346,-1.58540,-1.44461,-1.10377,1.72235,-0.22989
+2.14381,1.29320,-1.58585,-1.44396,-1.10401,1.72250,-0.23012
+2.14605,1.29294,-1.58630,-1.44331,-1.10424,1.72264,-0.23033
+2.14828,1.29269,-1.58673,-1.44268,-1.10447,1.72278,-0.23055
+2.15051,1.29244,-1.58716,-1.44205,-1.10470,1.72291,-0.23076
+2.15275,1.29220,-1.58758,-1.44144,-1.10492,1.72305,-0.23097
+2.15498,1.29196,-1.58800,-1.44083,-1.10514,1.72318,-0.23117
+2.15721,1.29172,-1.58841,-1.44023,-1.10536,1.72331,-0.23137
+2.15945,1.29149,-1.58881,-1.43965,-1.10557,1.72343,-0.23157
+2.16168,1.29127,-1.58920,-1.43907,-1.10578,1.72356,-0.23177
+2.16391,1.29104,-1.58959,-1.43850,-1.10599,1.72368,-0.23196
+2.16615,1.29082,-1.58997,-1.43794,-1.10620,1.72380,-0.23214
+2.16838,1.29061,-1.59035,-1.43739,-1.10640,1.72392,-0.23233
+2.17061,1.29040,-1.59072,-1.43685,-1.10660,1.72404,-0.23251
+2.17285,1.29023,-1.59100,-1.43645,-1.10675,1.72413,-0.23265
+2.17508,1.28983,-1.59157,-1.43564,-1.10702,1.72435,-0.23299
+2.17731,1.28944,-1.59214,-1.43485,-1.10730,1.72456,-0.23332
+2.17954,1.28905,-1.59270,-1.43407,-1.10757,1.72477,-0.23365
+2.18178,1.28868,-1.59324,-1.43330,-1.10783,1.72498,-0.23397
+2.18401,1.28830,-1.59378,-1.43255,-1.10809,1.72518,-0.23429
+2.18624,1.28794,-1.59431,-1.43180,-1.10835,1.72538,-0.23460
+2.18848,1.28758,-1.59483,-1.43107,-1.10861,1.72558,-0.23490
+2.19071,1.28723,-1.59535,-1.43035,-1.10886,1.72577,-0.23520
+2.19294,1.28688,-1.59585,-1.42964,-1.10911,1.72596,-0.23550
+2.19518,1.28654,-1.59635,-1.42894,-1.10936,1.72614,-0.23579
+2.19741,1.28621,-1.59683,-1.42825,-1.10960,1.72632,-0.23607
+2.19964,1.28588,-1.59731,-1.42758,-1.10984,1.72650,-0.23635
+2.20188,1.28556,-1.59778,-1.42691,-1.11007,1.72668,-0.23662
+2.20411,1.28524,-1.59825,-1.42625,-1.11031,1.72685,-0.23689
+2.20634,1.28493,-1.59870,-1.42561,-1.11054,1.72702,-0.23716
+2.20858,1.28463,-1.59915,-1.42497,-1.11076,1.72719,-0.23742
+2.21081,1.28433,-1.59959,-1.42435,-1.11099,1.72735,-0.23767
+2.21304,1.28404,-1.60002,-1.42373,-1.11121,1.72751,-0.23792
+2.21527,1.28375,-1.60045,-1.42312,-1.11143,1.72767,-0.23817
+2.21751,1.28347,-1.60087,-1.42253,-1.11164,1.72782,-0.23841
+2.21974,1.28319,-1.60128,-1.42194,-1.11185,1.72798,-0.23865
+2.22197,1.28292,-1.60169,-1.42136,-1.11206,1.72813,-0.23888
+2.22421,1.28265,-1.60208,-1.42079,-1.11227,1.72827,-0.23911
+2.22644,1.28239,-1.60248,-1.42023,-1.11247,1.72842,-0.23933
+2.22867,1.28213,-1.60286,-1.41968,-1.11267,1.72856,-0.23955
+2.23091,1.28188,-1.60324,-1.41913,-1.11287,1.72870,-0.23977
+2.23314,1.28163,-1.60361,-1.41860,-1.11307,1.72884,-0.23998
+2.23537,1.28138,-1.60398,-1.41807,-1.11326,1.72897,-0.24019
+2.23761,1.28114,-1.60434,-1.41755,-1.11345,1.72910,-0.24040
+2.23984,1.28091,-1.60469,-1.41704,-1.11364,1.72923,-0.24060
+2.24207,1.28088,-1.60473,-1.41699,-1.11366,1.72925,-0.24062
+2.24431,1.28062,-1.60509,-1.41647,-1.11385,1.72939,-0.24085
+2.24654,1.28036,-1.60546,-1.41596,-1.11403,1.72953,-0.24107
+2.24877,1.28011,-1.60581,-1.41546,-1.11421,1.72967,-0.24129
+2.25100,1.27986,-1.60616,-1.41496,-1.11440,1.72981,-0.24150
+2.25324,1.27981,-1.60623,-1.41486,-1.11443,1.72984,-0.24154
+2.25547,1.27953,-1.60659,-1.41435,-1.11461,1.72999,-0.24178
+2.25770,1.27926,-1.60695,-1.41386,-1.11479,1.73013,-0.24201
+2.25994,1.27900,-1.60729,-1.41337,-1.11497,1.73028,-0.24223
+2.26217,1.27874,-1.60764,-1.41288,-1.11514,1.73042,-0.24246
+2.26440,1.27865,-1.60775,-1.41273,-1.11520,1.73047,-0.24253
+2.26664,1.27829,-1.60818,-1.41214,-1.11540,1.73066,-0.24283
+2.26887,1.27795,-1.60860,-1.41156,-1.11561,1.73085,-0.24313
+2.27110,1.27760,-1.60902,-1.41099,-1.11580,1.73104,-0.24342
+2.27334,1.27727,-1.60943,-1.41043,-1.11600,1.73122,-0.24371
+2.27557,1.27694,-1.60983,-1.40987,-1.11619,1.73140,-0.24399
+2.27780,1.27662,-1.61023,-1.40933,-1.11639,1.73158,-0.24426
+2.28004,1.27630,-1.61062,-1.40879,-1.11657,1.73175,-0.24453
+2.28227,1.27599,-1.61100,-1.40826,-1.11676,1.73192,-0.24480
+2.28450,1.27568,-1.61138,-1.40774,-1.11694,1.73209,-0.24506
+2.28674,1.27538,-1.61175,-1.40723,-1.11713,1.73225,-0.24532
+2.28897,1.27509,-1.61212,-1.40673,-1.11730,1.73242,-0.24557
+2.29120,1.27480,-1.61248,-1.40623,-1.11748,1.73257,-0.24582
+2.29343,1.27451,-1.61283,-1.40574,-1.11766,1.73273,-0.24606
+2.29567,1.27423,-1.61318,-1.40526,-1.11783,1.73288,-0.24630
+2.29790,1.27396,-1.61352,-1.40479,-1.11800,1.73303,-0.24653
+2.30013,1.27369,-1.61385,-1.40432,-1.11816,1.73318,-0.24676
+2.30237,1.27363,-1.61392,-1.40422,-1.11820,1.73321,-0.24681
+2.30460,1.27333,-1.61430,-1.40371,-1.11838,1.73338,-0.24707
+2.30683,1.27303,-1.61466,-1.40321,-1.11856,1.73354,-0.24733
+2.30907,1.27273,-1.61502,-1.40271,-1.11873,1.73370,-0.24758
+2.31130,1.27244,-1.61537,-1.40222,-1.11891,1.73386,-0.24783
+2.31353,1.27216,-1.61572,-1.40174,-1.11908,1.73402,-0.24807
+2.31577,1.27188,-1.61606,-1.40127,-1.11925,1.73417,-0.24831
+2.31800,1.27161,-1.61640,-1.40081,-1.11941,1.73432,-0.24855
+2.32023,1.27140,-1.61665,-1.40046,-1.11954,1.73443,-0.24872
+2.32247,1.27096,-1.61713,-1.39982,-1.11975,1.73467,-0.24909
+2.32470,1.27053,-1.61761,-1.39919,-1.11996,1.73490,-0.24946
+2.32693,1.27011,-1.61808,-1.39856,-1.12018,1.73513,-0.24982
+2.32916,1.26970,-1.61854,-1.39795,-1.12038,1.73536,-0.25017
+2.33140,1.26929,-1.61900,-1.39734,-1.12059,1.73558,-0.25052
+2.33363,1.26889,-1.61945,-1.39674,-1.12079,1.73580,-0.25086
+2.33586,1.26850,-1.61988,-1.39616,-1.12099,1.73601,-0.25119
+2.33810,1.26811,-1.62032,-1.39558,-1.12119,1.73622,-0.25152
+2.34033,1.26774,-1.62074,-1.39501,-1.12139,1.73642,-0.25184
+2.34256,1.26736,-1.62116,-1.39445,-1.12158,1.73663,-0.25216
+2.34480,1.26700,-1.62157,-1.39389,-1.12177,1.73683,-0.25247
+2.34703,1.26664,-1.62198,-1.39335,-1.12196,1.73702,-0.25277
+2.34926,1.26629,-1.62237,-1.39282,-1.12214,1.73721,-0.25307
+2.35150,1.26595,-1.62276,-1.39229,-1.12233,1.73740,-0.25337
+2.35373,1.26561,-1.62315,-1.39177,-1.12251,1.73758,-0.25366
+2.35596,1.26528,-1.62353,-1.39126,-1.12269,1.73776,-0.25394
+2.35820,1.26495,-1.62390,-1.39075,-1.12286,1.73794,-0.25422
+2.36043,1.26463,-1.62426,-1.39026,-1.12304,1.73812,-0.25449
+2.36266,1.26432,-1.62462,-1.38977,-1.12321,1.73829,-0.25476
+2.36490,1.26401,-1.62498,-1.38929,-1.12338,1.73846,-0.25502
+2.36713,1.26371,-1.62533,-1.38882,-1.12355,1.73862,-0.25528
+2.36936,1.26341,-1.62567,-1.38835,-1.12371,1.73878,-0.25554
+2.37159,1.26312,-1.62600,-1.38789,-1.12388,1.73894,-0.25579
+2.37383,1.26283,-1.62634,-1.38744,-1.12404,1.73910,-0.25603
+2.37606,1.26255,-1.62666,-1.38700,-1.12420,1.73925,-0.25627
+2.37829,1.26247,-1.62676,-1.38686,-1.12425,1.73930,-0.25635
+2.38053,1.26218,-1.62710,-1.38639,-1.12441,1.73946,-0.25659
+2.38276,1.26190,-1.62744,-1.38593,-1.12458,1.73961,-0.25683
+2.38499,1.26163,-1.62777,-1.38547,-1.12474,1.73976,-0.25707
+2.38723,1.26154,-1.62787,-1.38533,-1.12479,1.73981,-0.25714
+2.38946,1.26123,-1.62823,-1.38485,-1.12496,1.73998,-0.25741
+2.39169,1.26092,-1.62857,-1.38438,-1.12513,1.74015,-0.25767
+2.39393,1.26061,-1.62892,-1.38392,-1.12529,1.74031,-0.25793
+2.39616,1.26032,-1.62925,-1.38347,-1.12545,1.74047,-0.25819
+2.39839,1.26002,-1.62958,-1.38302,-1.12561,1.74063,-0.25844
+2.40063,1.25974,-1.62991,-1.38258,-1.12577,1.74079,-0.25869
+2.40286,1.25951,-1.63017,-1.38223,-1.12589,1.74092,-0.25888
+2.40509,1.25920,-1.63050,-1.38178,-1.12605,1.74108,-0.25915
+2.40732,1.25890,-1.63083,-1.38133,-1.12621,1.74125,-0.25940
+2.40956,1.25860,-1.63115,-1.38090,-1.12636,1.74141,-0.25966
+2.41179,1.25831,-1.63147,-1.38047,-1.12651,1.74157,-0.25991
+2.41402,1.25813,-1.63167,-1.38021,-1.12660,1.74167,-0.26007
+2.41626,1.25774,-1.63205,-1.37972,-1.12677,1.74188,-0.26040
+2.41849,1.25735,-1.63242,-1.37924,-1.12693,1.74209,-0.26073
+2.42072,1.25698,-1.63279,-1.37877,-1.12709,1.74230,-0.26105
+2.42296,1.25661,-1.63315,-1.37830,-1.12724,1.74250,-0.26136
+2.42519,1.25624,-1.63350,-1.37784,-1.12740,1.74269,-0.26167
+2.42742,1.25589,-1.63385,-1.37739,-1.12755,1.74289,-0.26198
+2.42966,1.25554,-1.63420,-1.37694,-1.12771,1.74308,-0.26228
+2.43189,1.25520,-1.63453,-1.37651,-1.12786,1.74326,-0.26257
+2.43412,1.25486,-1.63487,-1.37607,-1.12800,1.74345,-0.26286
+2.43636,1.25453,-1.63519,-1.37565,-1.12815,1.74363,-0.26314
+2.43859,1.25420,-1.63551,-1.37523,-1.12830,1.74380,-0.26342
+2.44082,1.25388,-1.63583,-1.37482,-1.12844,1.74398,-0.26369
+2.44305,1.25357,-1.63614,-1.37441,-1.12858,1.74415,-0.26396
+2.44529,1.25327,-1.63645,-1.37401,-1.12872,1.74431,-0.26422
+2.44752,1.25299,-1.63672,-1.37365,-1.12884,1.74446,-0.26446
+2.44975,1.25266,-1.63708,-1.37318,-1.12901,1.74465,-0.26474
+2.45199,1.25233,-1.63743,-1.37272,-1.12917,1.74482,-0.26502
+2.45422,1.25201,-1.63777,-1.37226,-1.12933,1.74500,-0.26530
+2.45645,1.25170,-1.63811,-1.37181,-1.12948,1.74517,-0.26557
+2.45869,1.25139,-1.63844,-1.37137,-1.12964,1.74534,-0.26583
+2.46092,1.25108,-1.63876,-1.37094,-1.12979,1.74550,-0.26609
+2.46315,1.25079,-1.63908,-1.37051,-1.12994,1.74566,-0.26635
+2.46539,1.25049,-1.63940,-1.37009,-1.13009,1.74582,-0.26660
+2.46762,1.25038,-1.63952,-1.36992,-1.13015,1.74589,-0.26670
+2.46985,1.25006,-1.63985,-1.36949,-1.13030,1.74606,-0.26697
+2.47209,1.24975,-1.64017,-1.36906,-1.13045,1.74623,-0.26724
+2.47432,1.24945,-1.64049,-1.36864,-1.13060,1.74639,-0.26750
+2.47655,1.24915,-1.64080,-1.36823,-1.13074,1.74656,-0.26775
+2.47879,1.24893,-1.64102,-1.36794,-1.13084,1.74667,-0.26794
+2.48102,1.24855,-1.64139,-1.36747,-1.13100,1.74688,-0.26826
+2.48325,1.24818,-1.64174,-1.36702,-1.13115,1.74708,-0.26858
+2.48548,1.24782,-1.64210,-1.36657,-1.13130,1.74728,-0.26889
+2.48772,1.24746,-1.64244,-1.36612,-1.13145,1.74748,-0.26920
+2.48995,1.24710,-1.64278,-1.36569,-1.13160,1.74767,-0.26950
+2.49218,1.24676,-1.64311,-1.36526,-1.13175,1.74785,-0.26980
+2.49442,1.24642,-1.64344,-1.36484,-1.13189,1.74804,-0.27009
+2.49665,1.24608,-1.64377,-1.36442,-1.13203,1.74822,-0.27038
+2.49888,1.24576,-1.64408,-1.36401,-1.13218,1.74840,-0.27066
+2.50112,1.24543,-1.64440,-1.36360,-1.13231,1.74857,-0.27094
+2.50335,1.24512,-1.64470,-1.36321,-1.13245,1.74875,-0.27121
+2.50558,1.24481,-1.64501,-1.36281,-1.13259,1.74891,-0.27147
+2.50782,1.24450,-1.64530,-1.36243,-1.13272,1.74908,-0.27173
+2.51005,1.24447,-1.64534,-1.36239,-1.13274,1.74910,-0.27176
+2.51228,1.24413,-1.64566,-1.36198,-1.13288,1.74928,-0.27206
+2.51452,1.24379,-1.64597,-1.36157,-1.13301,1.74947,-0.27235
+2.51675,1.24346,-1.64629,-1.36117,-1.13315,1.74965,-0.27263
+2.51898,1.24313,-1.64659,-1.36078,-1.13328,1.74982,-0.27291
+2.52121,1.24281,-1.64689,-1.36040,-1.13342,1.75000,-0.27318
+2.52345,1.24250,-1.64719,-1.36002,-1.13355,1.75017,-0.27345
+2.52568,1.24219,-1.64749,-1.35964,-1.13368,1.75034,-0.27372
+2.52791,1.24181,-1.64782,-1.35922,-1.13382,1.75054,-0.27404
+2.53015,1.24144,-1.64815,-1.35880,-1.13395,1.75074,-0.27436
+2.53238,1.24107,-1.64848,-1.35839,-1.13409,1.75094,-0.27467
+2.53461,1.24072,-1.64880,-1.35799,-1.13423,1.75113,-0.27498
+2.53685,1.24037,-1.64912,-1.35759,-1.13436,1.75132,-0.27528
+2.53908,1.24002,-1.64943,-1.35720,-1.13449,1.75151,-0.27557
+2.54131,1.23969,-1.64973,-1.35682,-1.13462,1.75169,-0.27586
+2.54355,1.23936,-1.65003,-1.35644,-1.13475,1.75187,-0.27615
+2.54578,1.23903,-1.65033,-1.35607,-1.13488,1.75205,-0.27643
+2.54801,1.23871,-1.65062,-1.35570,-1.13500,1.75222,-0.27670
+2.55025,1.23840,-1.65090,-1.35534,-1.13512,1.75239,-0.27697
+2.55248,1.23833,-1.65096,-1.35526,-1.13515,1.75243,-0.27703
+2.55471,1.23796,-1.65128,-1.35487,-1.13528,1.75263,-0.27734
+2.55695,1.23760,-1.65160,-1.35448,-1.13541,1.75282,-0.27765
+2.55918,1.23725,-1.65191,-1.35409,-1.13554,1.75301,-0.27795
+2.56141,1.23690,-1.65221,-1.35371,-1.13567,1.75320,-0.27825
+2.56364,1.23656,-1.65251,-1.35334,-1.13579,1.75339,-0.27854
+2.56588,1.23623,-1.65281,-1.35297,-1.13592,1.75357,-0.27883
+2.56811,1.23590,-1.65310,-1.35261,-1.13604,1.75374,-0.27911
+2.57034,1.23558,-1.65338,-1.35225,-1.13616,1.75392,-0.27939
+2.57258,1.23527,-1.65366,-1.35190,-1.13628,1.75409,-0.27966
+2.57481,1.23519,-1.65373,-1.35182,-1.13630,1.75413,-0.27972
+2.57704,1.23480,-1.65406,-1.35142,-1.13644,1.75434,-0.28006
+2.57928,1.23440,-1.65439,-1.35101,-1.13657,1.75456,-0.28040
+2.58151,1.23402,-1.65472,-1.35062,-1.13670,1.75476,-0.28073
+2.58374,1.23364,-1.65504,-1.35023,-1.13683,1.75497,-0.28105
+2.58598,1.23327,-1.65535,-1.34984,-1.13695,1.75517,-0.28137
+2.58821,1.23291,-1.65566,-1.34947,-1.13708,1.75536,-0.28168
+2.59044,1.23255,-1.65596,-1.34909,-1.13720,1.75556,-0.28198
+2.59268,1.23220,-1.65626,-1.34872,-1.13732,1.75575,-0.28229
+2.59491,1.23186,-1.65656,-1.34836,-1.13744,1.75593,-0.28258
+2.59714,1.23152,-1.65685,-1.34801,-1.13756,1.75612,-0.28287
+2.59937,1.23119,-1.65713,-1.34765,-1.13768,1.75629,-0.28315
+2.60161,1.23087,-1.65741,-1.34731,-1.13780,1.75647,-0.28343
+2.60384,1.23055,-1.65769,-1.34697,-1.13791,1.75664,-0.28371
+2.60607,1.23042,-1.65778,-1.34685,-1.13795,1.75671,-0.28382
+2.60831,1.22977,-1.65821,-1.34640,-1.13807,1.75706,-0.28437
+2.61054,1.22914,-1.65863,-1.34595,-1.13820,1.75740,-0.28491
+2.61277,1.22852,-1.65905,-1.34551,-1.13832,1.75773,-0.28544
+2.61501,1.22791,-1.65945,-1.34507,-1.13844,1.75806,-0.28596
+2.61724,1.22732,-1.65986,-1.34464,-1.13856,1.75838,-0.28647
+2.61947,1.22673,-1.66025,-1.34421,-1.13868,1.75869,-0.28697
+2.62171,1.22615,-1.66064,-1.34380,-1.13880,1.75900,-0.28746
+2.62394,1.22559,-1.66102,-1.34338,-1.13892,1.75930,-0.28794
+2.62617,1.22504,-1.66140,-1.34298,-1.13904,1.75960,-0.28842
+2.62841,1.22449,-1.66177,-1.34258,-1.13915,1.75989,-0.28888
+2.63064,1.22396,-1.66213,-1.34218,-1.13927,1.76018,-0.28934
+2.63287,1.22343,-1.66249,-1.34179,-1.13938,1.76046,-0.28979
+2.63510,1.22292,-1.66284,-1.34141,-1.13950,1.76074,-0.29023
+2.63734,1.22242,-1.66319,-1.34103,-1.13961,1.76101,-0.29066
+2.63957,1.22192,-1.66353,-1.34065,-1.13972,1.76128,-0.29109
+2.64180,1.22144,-1.66386,-1.34028,-1.13983,1.76154,-0.29150
+2.64404,1.22096,-1.66419,-1.33992,-1.13994,1.76180,-0.29191
+2.64627,1.22049,-1.66452,-1.33956,-1.14004,1.76205,-0.29232
+2.64850,1.22003,-1.66484,-1.33921,-1.14015,1.76229,-0.29271
+2.65074,1.21958,-1.66515,-1.33886,-1.14025,1.76254,-0.29310
+2.65297,1.21914,-1.66546,-1.33852,-1.14036,1.76278,-0.29348
+2.65520,1.21870,-1.66577,-1.33818,-1.14046,1.76301,-0.29385
+2.65744,1.21828,-1.66607,-1.33785,-1.14056,1.76324,-0.29422
+2.65967,1.21786,-1.66636,-1.33752,-1.14066,1.76347,-0.29458
+2.66190,1.21745,-1.66665,-1.33720,-1.14076,1.76369,-0.29493
+2.66414,1.21704,-1.66693,-1.33688,-1.14086,1.76390,-0.29528
+2.66637,1.21665,-1.66721,-1.33657,-1.14096,1.76412,-0.29562
+2.66860,1.21626,-1.66749,-1.33626,-1.14106,1.76433,-0.29595
+2.67084,1.21588,-1.66776,-1.33595,-1.14115,1.76453,-0.29628
+2.67307,1.21550,-1.66803,-1.33565,-1.14125,1.76474,-0.29661
+2.67530,1.21514,-1.66829,-1.33536,-1.14134,1.76493,-0.29692
+2.67753,1.21478,-1.66855,-1.33506,-1.14143,1.76513,-0.29723
+2.67977,1.21442,-1.66880,-1.33478,-1.14152,1.76532,-0.29754
+2.68200,1.21407,-1.66905,-1.33449,-1.14162,1.76551,-0.29784
+2.68423,1.21373,-1.66930,-1.33421,-1.14170,1.76569,-0.29813
+2.68647,1.21340,-1.66954,-1.33394,-1.14179,1.76587,-0.29842
+2.68870,1.21325,-1.66964,-1.33383,-1.14183,1.76595,-0.29855
+2.69093,1.21282,-1.66992,-1.33353,-1.14191,1.76619,-0.29892
+2.69317,1.21238,-1.67020,-1.33324,-1.14200,1.76642,-0.29929
+2.69540,1.21196,-1.67047,-1.33295,-1.14208,1.76665,-0.29966
+2.69763,1.21155,-1.67074,-1.33267,-1.14217,1.76687,-0.30002
+2.69987,1.21114,-1.67100,-1.33239,-1.14225,1.76709,-0.30037
+2.70210,1.21074,-1.67126,-1.33211,-1.14233,1.76731,-0.30071
+2.70433,1.21035,-1.67152,-1.33184,-1.14241,1.76752,-0.30105
+2.70657,1.20996,-1.67177,-1.33157,-1.14249,1.76772,-0.30138
+2.70880,1.20958,-1.67202,-1.33131,-1.14257,1.76793,-0.30171
+2.71103,1.20921,-1.67226,-1.33105,-1.14265,1.76813,-0.30203
+2.71326,1.20885,-1.67250,-1.33079,-1.14273,1.76832,-0.30234
+2.71550,1.20849,-1.67273,-1.33054,-1.14281,1.76852,-0.30265
+2.71773,1.20814,-1.67296,-1.33029,-1.14288,1.76871,-0.30296
+2.71996,1.20779,-1.67319,-1.33005,-1.14296,1.76889,-0.30325
+2.72220,1.20745,-1.67342,-1.32981,-1.14303,1.76908,-0.30355
+2.72443,1.20741,-1.67344,-1.32978,-1.14304,1.76910,-0.30358
+2.72666,1.20702,-1.67369,-1.32952,-1.14311,1.76931,-0.30392
+2.72890,1.20663,-1.67393,-1.32927,-1.14319,1.76952,-0.30425
+2.73113,1.20625,-1.67417,-1.32902,-1.14326,1.76972,-0.30458
+2.73336,1.20588,-1.67441,-1.32877,-1.14333,1.76992,-0.30491
+2.73560,1.20551,-1.67464,-1.32853,-1.14341,1.77012,-0.30522
+2.73783,1.20515,-1.67487,-1.32829,-1.14348,1.77032,-0.30553
+2.74006,1.20480,-1.67510,-1.32805,-1.14355,1.77051,-0.30584
+2.74230,1.20445,-1.67532,-1.32782,-1.14362,1.77069,-0.30614
+2.74453,1.20411,-1.67553,-1.32759,-1.14369,1.77088,-0.30643
+2.74676,1.20403,-1.67558,-1.32754,-1.14370,1.77092,-0.30650
+2.74900,1.20360,-1.67587,-1.32724,-1.14379,1.77115,-0.30687
+2.75123,1.20317,-1.67615,-1.32694,-1.14388,1.77138,-0.30724
+2.75346,1.20275,-1.67643,-1.32664,-1.14397,1.77160,-0.30760
+2.75569,1.20234,-1.67671,-1.32635,-1.14405,1.77182,-0.30796
+2.75793,1.20194,-1.67697,-1.32607,-1.14414,1.77204,-0.30830
+2.76016,1.20154,-1.67724,-1.32578,-1.14422,1.77225,-0.30864
+2.76239,1.20116,-1.67750,-1.32551,-1.14430,1.77246,-0.30898
+2.76463,1.20077,-1.67776,-1.32523,-1.14439,1.77267,-0.30931
+2.76686,1.20040,-1.67801,-1.32496,-1.14447,1.77287,-0.30963
+2.76909,1.20003,-1.67826,-1.32469,-1.14455,1.77307,-0.30995
+2.77133,1.19967,-1.67850,-1.32443,-1.14463,1.77326,-0.31026
+2.77356,1.19932,-1.67874,-1.32417,-1.14471,1.77345,-0.31057
+2.77579,1.19897,-1.67898,-1.32392,-1.14479,1.77364,-0.31087
+2.77803,1.19863,-1.67921,-1.32367,-1.14486,1.77382,-0.31116
+2.78026,1.19825,-1.67946,-1.32341,-1.14494,1.77402,-0.31149
+2.78249,1.19746,-1.67988,-1.32304,-1.14502,1.77444,-0.31217
+2.78473,1.19668,-1.68029,-1.32267,-1.14510,1.77486,-0.31284
+2.78696,1.19592,-1.68070,-1.32231,-1.14517,1.77526,-0.31349
+2.78919,1.19517,-1.68111,-1.32196,-1.14525,1.77566,-0.31413
+2.79142,1.19444,-1.68151,-1.32161,-1.14533,1.77605,-0.31476
+2.79366,1.19372,-1.68190,-1.32126,-1.14541,1.77643,-0.31538
+2.79589,1.19302,-1.68228,-1.32092,-1.14548,1.77681,-0.31599
+2.79812,1.19232,-1.68266,-1.32058,-1.14556,1.77717,-0.31658
+2.80036,1.19164,-1.68303,-1.32025,-1.14564,1.77754,-0.31717
+2.80259,1.19098,-1.68340,-1.31992,-1.14571,1.77789,-0.31774
+2.80482,1.19032,-1.68376,-1.31959,-1.14579,1.77824,-0.31830
+2.80706,1.18968,-1.68412,-1.31927,-1.14586,1.77858,-0.31886
+2.80929,1.18905,-1.68447,-1.31896,-1.14594,1.77892,-0.31940
+2.81152,1.18843,-1.68481,-1.31864,-1.14601,1.77925,-0.31993
+2.81376,1.18783,-1.68515,-1.31834,-1.14609,1.77957,-0.32046
+2.81599,1.18723,-1.68549,-1.31803,-1.14616,1.77989,-0.32097
+2.81822,1.18665,-1.68581,-1.31773,-1.14623,1.78020,-0.32148
+2.82046,1.18607,-1.68614,-1.31743,-1.14631,1.78050,-0.32197
+2.82269,1.18551,-1.68646,-1.31714,-1.14638,1.78080,-0.32246
+2.82492,1.18496,-1.68677,-1.31685,-1.14645,1.78110,-0.32293
+2.82715,1.18442,-1.68708,-1.31657,-1.14652,1.78139,-0.32340
+2.82939,1.18388,-1.68738,-1.31629,-1.14660,1.78167,-0.32386
+2.83162,1.18336,-1.68768,-1.31601,-1.14667,1.78195,-0.32431
+2.83385,1.18285,-1.68797,-1.31574,-1.14674,1.78222,-0.32476
+2.83609,1.18235,-1.68826,-1.31547,-1.14681,1.78249,-0.32519
+2.83832,1.18185,-1.68854,-1.31520,-1.14688,1.78276,-0.32562
+2.84055,1.18137,-1.68882,-1.31494,-1.14695,1.78301,-0.32604
+2.84279,1.18089,-1.68910,-1.31468,-1.14702,1.78327,-0.32645
+2.84502,1.18043,-1.68937,-1.31442,-1.14708,1.78352,-0.32686
+2.84725,1.17997,-1.68964,-1.31417,-1.14715,1.78376,-0.32725
+2.84949,1.17952,-1.68990,-1.31392,-1.14722,1.78400,-0.32764
+2.85172,1.17908,-1.69016,-1.31368,-1.14729,1.78424,-0.32803
+2.85395,1.17864,-1.69041,-1.31343,-1.14735,1.78447,-0.32840
+2.85619,1.17822,-1.69066,-1.31319,-1.14742,1.78470,-0.32877
+2.85842,1.17780,-1.69090,-1.31296,-1.14748,1.78492,-0.32913
+2.86065,1.17739,-1.69115,-1.31273,-1.14755,1.78514,-0.32949
+2.86289,1.17699,-1.69138,-1.31250,-1.14761,1.78535,-0.32984
+2.86512,1.17660,-1.69162,-1.31227,-1.14767,1.78556,-0.33018
+2.86735,1.17621,-1.69185,-1.31205,-1.14774,1.78577,-0.33052
+2.86958,1.17583,-1.69207,-1.31183,-1.14780,1.78597,-0.33085
+2.87182,1.17546,-1.69230,-1.31161,-1.14786,1.78617,-0.33117
+2.87405,1.17509,-1.69251,-1.31140,-1.14792,1.78637,-0.33149
+2.87628,1.17473,-1.69273,-1.31119,-1.14798,1.78656,-0.33180
+2.87852,1.17438,-1.69294,-1.31098,-1.14805,1.78675,-0.33211
+2.88075,1.17404,-1.69315,-1.31077,-1.14811,1.78694,-0.33241
+2.88298,1.17370,-1.69335,-1.31057,-1.14816,1.78712,-0.33270
+2.88522,1.17362,-1.69340,-1.31053,-1.14818,1.78716,-0.33277
+2.88745,1.17319,-1.69364,-1.31031,-1.14823,1.78739,-0.33314
+2.88968,1.17277,-1.69387,-1.31010,-1.14829,1.78761,-0.33351
+2.89192,1.17236,-1.69411,-1.30988,-1.14835,1.78783,-0.33387
+2.89415,1.17195,-1.69434,-1.30967,-1.14840,1.78805,-0.33422
+2.89638,1.17156,-1.69456,-1.30947,-1.14846,1.78826,-0.33456
+2.89862,1.17117,-1.69478,-1.30926,-1.14851,1.78847,-0.33490
+2.90085,1.17078,-1.69500,-1.30906,-1.14857,1.78867,-0.33524
+2.90308,1.17041,-1.69521,-1.30886,-1.14862,1.78887,-0.33556
+2.90531,1.17004,-1.69542,-1.30866,-1.14868,1.78907,-0.33588
+2.90755,1.16968,-1.69563,-1.30847,-1.14873,1.78926,-0.33620
+2.90978,1.16932,-1.69583,-1.30828,-1.14878,1.78945,-0.33651
+2.91201,1.16897,-1.69603,-1.30809,-1.14883,1.78964,-0.33681
+2.91425,1.16863,-1.69623,-1.30791,-1.14889,1.78982,-0.33711
+2.91648,1.16846,-1.69633,-1.30781,-1.14891,1.78992,-0.33726
+2.91871,1.16808,-1.69656,-1.30759,-1.14898,1.79012,-0.33759
+2.92095,1.16772,-1.69678,-1.30738,-1.14904,1.79031,-0.33791
+2.92318,1.16735,-1.69700,-1.30717,-1.14910,1.79050,-0.33822
+2.92541,1.16700,-1.69721,-1.30696,-1.14916,1.79069,-0.33853
+2.92765,1.16665,-1.69742,-1.30675,-1.14922,1.79088,-0.33883
+2.92988,1.16631,-1.69763,-1.30655,-1.14927,1.79106,-0.33913
+2.93211,1.16602,-1.69780,-1.30639,-1.14932,1.79122,-0.33939
+2.93435,1.16546,-1.69809,-1.30615,-1.14937,1.79151,-0.33987
+2.93658,1.16492,-1.69838,-1.30591,-1.14942,1.79180,-0.34034
+2.93881,1.16438,-1.69866,-1.30568,-1.14947,1.79208,-0.34080
+2.94105,1.16386,-1.69893,-1.30545,-1.14953,1.79236,-0.34126
+2.94328,1.16334,-1.69920,-1.30522,-1.14958,1.79263,-0.34171
+2.94551,1.16284,-1.69947,-1.30500,-1.14963,1.79290,-0.34214
+2.94774,1.16234,-1.69973,-1.30478,-1.14968,1.79316,-0.34258
+2.94998,1.16186,-1.69999,-1.30456,-1.14973,1.79342,-0.34300
+2.95221,1.16138,-1.70025,-1.30434,-1.14978,1.79368,-0.34341
+2.95444,1.16091,-1.70050,-1.30413,-1.14983,1.79392,-0.34382
+2.95668,1.16045,-1.70074,-1.30392,-1.14988,1.79417,-0.34422
+2.95891,1.16000,-1.70098,-1.30371,-1.14993,1.79441,-0.34461
+2.96114,1.15955,-1.70122,-1.30351,-1.14998,1.79464,-0.34500
+2.96338,1.15912,-1.70146,-1.30331,-1.15003,1.79487,-0.34538
+2.96561,1.15869,-1.70169,-1.30311,-1.15008,1.79510,-0.34575
+2.96784,1.15827,-1.70192,-1.30291,-1.15013,1.79532,-0.34612
+2.97008,1.15786,-1.70214,-1.30272,-1.15018,1.79554,-0.34647
+2.97231,1.15746,-1.70236,-1.30253,-1.15022,1.79576,-0.34683
+2.97454,1.15706,-1.70257,-1.30234,-1.15027,1.79597,-0.34717
+2.97678,1.15667,-1.70279,-1.30215,-1.15032,1.79617,-0.34751
+2.97901,1.15629,-1.70300,-1.30197,-1.15037,1.79638,-0.34784
+2.98124,1.15592,-1.70320,-1.30178,-1.15041,1.79657,-0.34817
+2.98347,1.15555,-1.70341,-1.30161,-1.15046,1.79677,-0.34849
+2.98571,1.15519,-1.70360,-1.30143,-1.15051,1.79696,-0.34881
+2.98794,1.15483,-1.70380,-1.30125,-1.15055,1.79715,-0.34912
+2.99017,1.15449,-1.70399,-1.30108,-1.15060,1.79734,-0.34942
+2.99241,1.15415,-1.70418,-1.30091,-1.15064,1.79752,-0.34972
+2.99464,1.15401,-1.70426,-1.30084,-1.15066,1.79759,-0.34984
+2.99687,1.15363,-1.70448,-1.30064,-1.15072,1.79779,-0.35016
+2.99911,1.15327,-1.70470,-1.30044,-1.15077,1.79798,-0.35049
+3.00134,1.15291,-1.70491,-1.30024,-1.15083,1.79818,-0.35080
+3.00357,1.15255,-1.70512,-1.30005,-1.15088,1.79836,-0.35111
+3.00581,1.15220,-1.70532,-1.29986,-1.15094,1.79855,-0.35141
+3.00804,1.15186,-1.70552,-1.29967,-1.15099,1.79873,-0.35171
+3.01027,1.15159,-1.70568,-1.29952,-1.15103,1.79887,-0.35195
+3.01251,1.15121,-1.70589,-1.29935,-1.15107,1.79908,-0.35228
+3.01474,1.15083,-1.70609,-1.29918,-1.15111,1.79928,-0.35261
+3.01697,1.15046,-1.70628,-1.29901,-1.15116,1.79947,-0.35293
+3.01921,1.15010,-1.70648,-1.29885,-1.15120,1.79966,-0.35325
+3.02144,1.14975,-1.70667,-1.29869,-1.15124,1.79985,-0.35356
+3.02367,1.14940,-1.70685,-1.29853,-1.15128,1.80004,-0.35386
+3.02590,1.14906,-1.70704,-1.29837,-1.15132,1.80022,-0.35416
+3.02814,1.14887,-1.70713,-1.29828,-1.15134,1.80031,-0.35432
+3.03037,1.14841,-1.70739,-1.29807,-1.15139,1.80056,-0.35473
+3.03260,1.14795,-1.70764,-1.29786,-1.15144,1.80080,-0.35513
+3.03484,1.14749,-1.70789,-1.29765,-1.15149,1.80104,-0.35553
+3.03707,1.14705,-1.70813,-1.29744,-1.15154,1.80128,-0.35591
+3.03930,1.14662,-1.70837,-1.29724,-1.15159,1.80151,-0.35629
+3.04154,1.14619,-1.70860,-1.29703,-1.15164,1.80173,-0.35666
+3.04377,1.14577,-1.70883,-1.29684,-1.15169,1.80195,-0.35703
+3.04600,1.14536,-1.70906,-1.29664,-1.15174,1.80217,-0.35739
+3.04824,1.14496,-1.70928,-1.29645,-1.15179,1.80238,-0.35774
+3.05047,1.14456,-1.70950,-1.29626,-1.15184,1.80259,-0.35809
+3.05270,1.14417,-1.70972,-1.29607,-1.15188,1.80280,-0.35843
+3.05494,1.14379,-1.70993,-1.29588,-1.15193,1.80300,-0.35876
+3.05717,1.14342,-1.71014,-1.29570,-1.15198,1.80320,-0.35909
+3.05940,1.14305,-1.71035,-1.29552,-1.15203,1.80339,-0.35941
+3.06163,1.14269,-1.71055,-1.29534,-1.15207,1.80358,-0.35972
+3.06387,1.14233,-1.71075,-1.29516,-1.15212,1.80377,-0.36003
+3.06610,1.14199,-1.71095,-1.29499,-1.15217,1.80395,-0.36034
+3.06833,1.14165,-1.71114,-1.29482,-1.15221,1.80413,-0.36064
+3.07057,1.14138,-1.71129,-1.29468,-1.15225,1.80428,-0.36087
+3.07280,1.14103,-1.71149,-1.29450,-1.15230,1.80446,-0.36117
+3.07503,1.14070,-1.71169,-1.29432,-1.15235,1.80464,-0.36147
+3.07727,1.14059,-1.71175,-1.29427,-1.15236,1.80469,-0.36156
+3.07950,1.14021,-1.71194,-1.29411,-1.15240,1.80489,-0.36190
+3.08173,1.13983,-1.71214,-1.29395,-1.15243,1.80509,-0.36222
+3.08397,1.13947,-1.71233,-1.29379,-1.15247,1.80529,-0.36255
+3.08620,1.13910,-1.71252,-1.29364,-1.15251,1.80548,-0.36286
+3.08843,1.13875,-1.71271,-1.29349,-1.15255,1.80566,-0.36317
+3.09067,1.13840,-1.71289,-1.29334,-1.15258,1.80585,-0.36348
+3.09290,1.13806,-1.71307,-1.29319,-1.15262,1.80603,-0.36378
+3.09513,1.13785,-1.71319,-1.29309,-1.15264,1.80614,-0.36396
+3.09736,1.13741,-1.71341,-1.29291,-1.15268,1.80637,-0.36435
+3.09960,1.13698,-1.71364,-1.29273,-1.15273,1.80660,-0.36472
+3.10183,1.13655,-1.71386,-1.29255,-1.15277,1.80682,-0.36509
+3.10406,1.13614,-1.71408,-1.29237,-1.15281,1.80704,-0.36545
+3.10630,1.13573,-1.71430,-1.29220,-1.15285,1.80725,-0.36581
+3.10853,1.13533,-1.71451,-1.29203,-1.15289,1.80746,-0.36616
+3.11076,1.13494,-1.71472,-1.29186,-1.15293,1.80767,-0.36650
+3.11300,1.13456,-1.71492,-1.29169,-1.15297,1.80787,-0.36684
+3.11523,1.13418,-1.71512,-1.29153,-1.15301,1.80807,-0.36717
+3.11746,1.13381,-1.71532,-1.29136,-1.15305,1.80827,-0.36750
+3.11970,1.13344,-1.71552,-1.29120,-1.15309,1.80846,-0.36782
+3.12193,1.13308,-1.71571,-1.29104,-1.15313,1.80865,-0.36813
+3.12416,1.13273,-1.71590,-1.29089,-1.15316,1.80883,-0.36844
+3.12640,1.13239,-1.71608,-1.29073,-1.15320,1.80902,-0.36874
+3.12863,1.13205,-1.71626,-1.29058,-1.15324,1.80919,-0.36904
+3.13086,1.13195,-1.71632,-1.29053,-1.15325,1.80925,-0.36913
+3.13310,1.13161,-1.71651,-1.29037,-1.15330,1.80943,-0.36943
+3.13533,1.13127,-1.71670,-1.29021,-1.15334,1.80961,-0.36972
+3.13756,1.13117,-1.71675,-1.29016,-1.15335,1.80966,-0.36981
+3.13979,1.13081,-1.71695,-1.29000,-1.15339,1.80985,-0.37013
+3.14203,1.13045,-1.71714,-1.28985,-1.15343,1.81004,-0.37044
+3.14426,1.13010,-1.71732,-1.28969,-1.15346,1.81022,-0.37075
+3.14649,1.12976,-1.71751,-1.28954,-1.15350,1.81040,-0.37105
+3.14873,1.12942,-1.71769,-1.28939,-1.15354,1.81058,-0.37134
+3.15096,1.12939,-1.71771,-1.28938,-1.15354,1.81060,-0.37138
+3.15319,1.12902,-1.71788,-1.28926,-1.15356,1.81079,-0.37170
+3.15543,1.12866,-1.71805,-1.28913,-1.15359,1.81098,-0.37202
+3.15766,1.12830,-1.71822,-1.28901,-1.15361,1.81117,-0.37233
+3.15989,1.12795,-1.71839,-1.28890,-1.15364,1.81135,-0.37263
+3.16213,1.12761,-1.71855,-1.28878,-1.15366,1.81153,-0.37293
+3.16436,1.12740,-1.71865,-1.28871,-1.15367,1.81164,-0.37312
+3.16659,1.12703,-1.71883,-1.28858,-1.15370,1.81184,-0.37345
+3.16883,1.12665,-1.71901,-1.28845,-1.15372,1.81204,-0.37377
+3.17106,1.12629,-1.71918,-1.28833,-1.15375,1.81223,-0.37409
+3.17329,1.12593,-1.71935,-1.28820,-1.15377,1.81241,-0.37441
+3.17552,1.12558,-1.71952,-1.28808,-1.15380,1.81260,-0.37472
+3.17776,1.12524,-1.71969,-1.28796,-1.15382,1.81278,-0.37502
+3.17999,1.12490,-1.71985,-1.28784,-1.15385,1.81296,-0.37532
+3.18222,1.12486,-1.71987,-1.28783,-1.15385,1.81298,-0.37535
+3.18446,1.12451,-1.72003,-1.28773,-1.15387,1.81316,-0.37565
+3.18669,1.12417,-1.72019,-1.28762,-1.15388,1.81334,-0.37596
+3.18892,1.12383,-1.72034,-1.28752,-1.15390,1.81352,-0.37626
+3.19116,1.12347,-1.72049,-1.28743,-1.15391,1.81371,-0.37656
+3.19339,1.12313,-1.72064,-1.28735,-1.15393,1.81389,-0.37687
+3.19562,1.12278,-1.72078,-1.28726,-1.15393,1.81407,-0.37717
+3.19786,1.12237,-1.72092,-1.28723,-1.15392,1.81428,-0.37753
+3.20009,1.12197,-1.72106,-1.28719,-1.15391,1.81449,-0.37789
+3.20232,1.12157,-1.72119,-1.28715,-1.15389,1.81470,-0.37823
+3.20456,1.12119,-1.72132,-1.28712,-1.15388,1.81491,-0.37857
+3.20679,1.12080,-1.72145,-1.28708,-1.15387,1.81510,-0.37891
+3.20902,1.12043,-1.72158,-1.28704,-1.15386,1.81530,-0.37924
+3.21126,1.12006,-1.72170,-1.28700,-1.15385,1.81549,-0.37956
+3.21349,1.11970,-1.72183,-1.28697,-1.15383,1.81568,-0.37987
+3.21572,1.11935,-1.72195,-1.28693,-1.15382,1.81587,-0.38019
+3.21795,1.11900,-1.72207,-1.28690,-1.15381,1.81605,-0.38049
+3.22019,1.11866,-1.72218,-1.28686,-1.15381,1.81623,-0.38079
+3.22242,1.11859,-1.72221,-1.28685,-1.15380,1.81626,-0.38085
+3.22465,1.11825,-1.72231,-1.28684,-1.15378,1.81644,-0.38115
+3.22689,1.11822,-1.72231,-1.28685,-1.15378,1.81646,-0.38118
+3.22912,1.11785,-1.72239,-1.28690,-1.15373,1.81665,-0.38150
+3.23135,1.11750,-1.72246,-1.28695,-1.15369,1.81684,-0.38181
+3.23359,1.11715,-1.72253,-1.28700,-1.15364,1.81702,-0.38212
+3.23582,1.11680,-1.72260,-1.28704,-1.15360,1.81720,-0.38242
+3.23805,1.11646,-1.72267,-1.28709,-1.15356,1.81738,-0.38272
+3.24029,1.11636,-1.72269,-1.28711,-1.15355,1.81743,-0.38281
+3.24252,1.11603,-1.72274,-1.28717,-1.15350,1.81761,-0.38311
+3.24475,1.11592,-1.72275,-1.28721,-1.15347,1.81766,-0.38320
+3.24699,1.11553,-1.72275,-1.28740,-1.15337,1.81787,-0.38354
+3.24922,1.11514,-1.72275,-1.28759,-1.15327,1.81807,-0.38388
+3.25145,1.11477,-1.72275,-1.28777,-1.15317,1.81827,-0.38421
+3.25368,1.11440,-1.72275,-1.28795,-1.15307,1.81846,-0.38454
+3.25592,1.11403,-1.72275,-1.28813,-1.15297,1.81865,-0.38486
+3.25815,1.11368,-1.72274,-1.28830,-1.15288,1.81884,-0.38517
+3.26038,1.11333,-1.72274,-1.28847,-1.15278,1.81902,-0.38548
+3.26262,1.11298,-1.72274,-1.28864,-1.15269,1.81920,-0.38578
+3.26485,1.11264,-1.72274,-1.28880,-1.15260,1.81937,-0.38608
+3.26708,1.11231,-1.72274,-1.28897,-1.15251,1.81955,-0.38637
+3.26932,1.11199,-1.72274,-1.28913,-1.15242,1.81972,-0.38665
+3.27155,1.11186,-1.72274,-1.28919,-1.15239,1.81979,-0.38677
+3.27378,1.11152,-1.72274,-1.28936,-1.15230,1.81996,-0.38706
+3.27602,1.11119,-1.72274,-1.28952,-1.15221,1.82013,-0.38735
+3.27825,1.11087,-1.72274,-1.28968,-1.15212,1.82030,-0.38764
+3.28048,1.11077,-1.72273,-1.28973,-1.15209,1.82035,-0.38772
+3.28272,1.11044,-1.72271,-1.28994,-1.15198,1.82053,-0.38801
+3.28495,1.11012,-1.72268,-1.29014,-1.15188,1.82069,-0.38830
+3.28718,1.10981,-1.72265,-1.29034,-1.15177,1.82086,-0.38857
+3.28941,1.10970,-1.72264,-1.29041,-1.15174,1.82091,-0.38866
+3.29165,1.10931,-1.72256,-1.29074,-1.15157,1.82112,-0.38901
+3.29388,1.10893,-1.72248,-1.29107,-1.15141,1.82132,-0.38935
+3.29611,1.10855,-1.72240,-1.29138,-1.15126,1.82151,-0.38968
+3.29835,1.10818,-1.72233,-1.29170,-1.15110,1.82171,-0.39000
+3.30058,1.10781,-1.72225,-1.29200,-1.15095,1.82190,-0.39032
+3.30281,1.10745,-1.72218,-1.29230,-1.15080,1.82208,-0.39064
+3.30505,1.10710,-1.72211,-1.29260,-1.15066,1.82227,-0.39095
+3.30728,1.10676,-1.72204,-1.29289,-1.15051,1.82245,-0.39125
+3.30951,1.10642,-1.72197,-1.29318,-1.15037,1.82262,-0.39155
+3.31175,1.10609,-1.72190,-1.29346,-1.15023,1.82279,-0.39184
+3.31398,1.10576,-1.72183,-1.29374,-1.15009,1.82296,-0.39212
+3.31621,1.10545,-1.72177,-1.29401,-1.14996,1.82313,-0.39240
+3.31845,1.10513,-1.72170,-1.29427,-1.14983,1.82329,-0.39268
+3.32068,1.10482,-1.72164,-1.29454,-1.14970,1.82345,-0.39295
+3.32291,1.10452,-1.72157,-1.29479,-1.14957,1.82361,-0.39322
+3.32515,1.10446,-1.72156,-1.29485,-1.14954,1.82364,-0.39327
+3.32738,1.10415,-1.72150,-1.29511,-1.14941,1.82381,-0.39355
+3.32961,1.10384,-1.72144,-1.29537,-1.14928,1.82397,-0.39382
+3.33184,1.10354,-1.72138,-1.29563,-1.14915,1.82413,-0.39409
+3.33408,1.10344,-1.72136,-1.29571,-1.14911,1.82417,-0.39417
+3.33631,1.10313,-1.72126,-1.29603,-1.14896,1.82434,-0.39444
+3.33854,1.10282,-1.72116,-1.29635,-1.14880,1.82450,-0.39472
+3.34078,1.10252,-1.72107,-1.29666,-1.14865,1.82466,-0.39498
+3.34301,1.10222,-1.72098,-1.29697,-1.14850,1.82481,-0.39524
+3.34524,1.10193,-1.72089,-1.29727,-1.14836,1.82496,-0.39550
+3.34748,1.10171,-1.72081,-1.29751,-1.14824,1.82508,-0.39569
+3.34971,1.10125,-1.72060,-1.29809,-1.14797,1.82531,-0.39610
+3.35194,1.10080,-1.72040,-1.29867,-1.14770,1.82555,-0.39649
+3.35418,1.10036,-1.72020,-1.29923,-1.14744,1.82577,-0.39688
+3.35641,1.09993,-1.72000,-1.29979,-1.14718,1.82600,-0.39726
+3.35864,1.09950,-1.71981,-1.30033,-1.14692,1.82622,-0.39763
+3.36088,1.09908,-1.71962,-1.30087,-1.14667,1.82643,-0.39800
+3.36311,1.09868,-1.71943,-1.30139,-1.14642,1.82665,-0.39836
+3.36534,1.09827,-1.71925,-1.30191,-1.14618,1.82685,-0.39871
+3.36757,1.09788,-1.71907,-1.30242,-1.14594,1.82706,-0.39906
+3.36981,1.09749,-1.71889,-1.30292,-1.14571,1.82726,-0.39939
+3.37204,1.09711,-1.71872,-1.30341,-1.14547,1.82745,-0.39973
+3.37427,1.09674,-1.71855,-1.30390,-1.14525,1.82765,-0.40006
+3.37651,1.09637,-1.71838,-1.30437,-1.14502,1.82784,-0.40038
+3.37874,1.09602,-1.71821,-1.30484,-1.14480,1.82802,-0.40069
+3.38097,1.09566,-1.71805,-1.30530,-1.14458,1.82821,-0.40100
+3.38321,1.09532,-1.71789,-1.30575,-1.14437,1.82838,-0.40131
+3.38544,1.09498,-1.71773,-1.30619,-1.14416,1.82856,-0.40160
+3.38767,1.09465,-1.71758,-1.30663,-1.14395,1.82873,-0.40190
+3.38991,1.09432,-1.71743,-1.30706,-1.14375,1.82890,-0.40218
+3.39214,1.09400,-1.71728,-1.30748,-1.14355,1.82907,-0.40247
+3.39437,1.09369,-1.71713,-1.30789,-1.14335,1.82923,-0.40274
+3.39661,1.09338,-1.71699,-1.30830,-1.14316,1.82939,-0.40302
+3.39884,1.09307,-1.71684,-1.30870,-1.14297,1.82955,-0.40328
+3.40107,1.09278,-1.71670,-1.30910,-1.14278,1.82970,-0.40354
+3.40331,1.09249,-1.71657,-1.30948,-1.14260,1.82985,-0.40380
+3.40554,1.09220,-1.71643,-1.30987,-1.14241,1.83000,-0.40405
+3.40777,1.09192,-1.71630,-1.31024,-1.14224,1.83015,-0.40430
+3.41000,1.09164,-1.71617,-1.31061,-1.14206,1.83029,-0.40454
+3.41224,1.09137,-1.71604,-1.31097,-1.14189,1.83043,-0.40478
+3.41447,1.09118,-1.71595,-1.31123,-1.14176,1.83053,-0.40495
+3.41670,1.09085,-1.71576,-1.31173,-1.14153,1.83070,-0.40525
+3.41894,1.09052,-1.71557,-1.31222,-1.14130,1.83087,-0.40553
+3.42117,1.09020,-1.71539,-1.31270,-1.14108,1.83104,-0.40582
+3.42340,1.08988,-1.71521,-1.31317,-1.14086,1.83120,-0.40609
+3.42564,1.08957,-1.71504,-1.31363,-1.14064,1.83136,-0.40637
+3.42787,1.08927,-1.71486,-1.31409,-1.14043,1.83152,-0.40663
+3.43010,1.08897,-1.71469,-1.31454,-1.14022,1.83167,-0.40690
+3.43234,1.08868,-1.71453,-1.31498,-1.14001,1.83182,-0.40715
+3.43457,1.08839,-1.71436,-1.31541,-1.13980,1.83197,-0.40741
+3.43680,1.08811,-1.71420,-1.31584,-1.13960,1.83212,-0.40766
+3.43904,1.08783,-1.71404,-1.31625,-1.13941,1.83226,-0.40790
+3.44127,1.08756,-1.71389,-1.31667,-1.13921,1.83240,-0.40814
+3.44350,1.08730,-1.71373,-1.31707,-1.13902,1.83254,-0.40837
+3.44573,1.08704,-1.71358,-1.31747,-1.13883,1.83267,-0.40860
+3.44797,1.08678,-1.71343,-1.31786,-1.13865,1.83281,-0.40883
+3.45020,1.08665,-1.71335,-1.31807,-1.13855,1.83288,-0.40895
+3.45243,1.08633,-1.71316,-1.31857,-1.13832,1.83304,-0.40922
+3.45467,1.08602,-1.71297,-1.31906,-1.13809,1.83320,-0.40950
+3.45690,1.08572,-1.71278,-1.31954,-1.13786,1.83335,-0.40976
+3.45913,1.08542,-1.71259,-1.32002,-1.13764,1.83351,-0.41002
+3.46137,1.08513,-1.71241,-1.32049,-1.13742,1.83366,-0.41028
+3.46360,1.08484,-1.71223,-1.32095,-1.13721,1.83381,-0.41053
+3.46583,1.08456,-1.71205,-1.32140,-1.13700,1.83395,-0.41078
+3.46807,1.08429,-1.71188,-1.32184,-1.13679,1.83409,-0.41102
+3.47030,1.08402,-1.71171,-1.32228,-1.13658,1.83423,-0.41126
+3.47253,1.08375,-1.71154,-1.32271,-1.13638,1.83437,-0.41150
+3.47477,1.08349,-1.71138,-1.32313,-1.13618,1.83451,-0.41173
+3.47700,1.08324,-1.71122,-1.32355,-1.13599,1.83464,-0.41195
+3.47923,1.08298,-1.71106,-1.32396,-1.13579,1.83477,-0.41217
+3.48146,1.08277,-1.71092,-1.32430,-1.13563,1.83488,-0.41236
+3.48370,1.08241,-1.71068,-1.32491,-1.13535,1.83506,-0.41268
+3.48593,1.08205,-1.71044,-1.32551,-1.13507,1.83525,-0.41300
+3.48816,1.08169,-1.71021,-1.32610,-1.13480,1.83543,-0.41331
+3.49040,1.08134,-1.70998,-1.32668,-1.13453,1.83561,-0.41362
+3.49263,1.08100,-1.70975,-1.32725,-1.13427,1.83579,-0.41392
+3.49486,1.08067,-1.70953,-1.32780,-1.13401,1.83596,-0.41421
+3.49710,1.08034,-1.70931,-1.32835,-1.13375,1.83613,-0.41450
+3.49933,1.08002,-1.70910,-1.32890,-1.13350,1.83629,-0.41479
+3.50156,1.07970,-1.70889,-1.32943,-1.13325,1.83646,-0.41507
+3.50380,1.07939,-1.70868,-1.32995,-1.13301,1.83661,-0.41534
+3.50603,1.07908,-1.70848,-1.33046,-1.13277,1.83677,-0.41561
+3.50826,1.07879,-1.70828,-1.33097,-1.13253,1.83693,-0.41587
+3.51050,1.07849,-1.70808,-1.33147,-1.13230,1.83708,-0.41613
+3.51273,1.07820,-1.70789,-1.33195,-1.13207,1.83722,-0.41638
+3.51496,1.07792,-1.70770,-1.33243,-1.13185,1.83737,-0.41663
+3.51720,1.07764,-1.70751,-1.33291,-1.13163,1.83751,-0.41688
+3.51943,1.07737,-1.70732,-1.33337,-1.13141,1.83765,-0.41712
+3.52166,1.07711,-1.70714,-1.33383,-1.13119,1.83779,-0.41735
+3.52389,1.07684,-1.70697,-1.33428,-1.13098,1.83792,-0.41758
+3.52613,1.07659,-1.70679,-1.33472,-1.13077,1.83806,-0.41781
+3.52836,1.07633,-1.70662,-1.33515,-1.13057,1.83819,-0.41803
+3.53059,1.07609,-1.70645,-1.33558,-1.13037,1.83831,-0.41825
+3.53283,1.07584,-1.70628,-1.33600,-1.13017,1.83844,-0.41847
+3.53506,1.07572,-1.70620,-1.33621,-1.13007,1.83850,-0.41858
+3.53729,1.07544,-1.70600,-1.33671,-1.12984,1.83864,-0.41882
+3.53953,1.07517,-1.70580,-1.33719,-1.12962,1.83878,-0.41906
+3.54176,1.07491,-1.70561,-1.33766,-1.12939,1.83892,-0.41929
+3.54399,1.07465,-1.70542,-1.33813,-1.12918,1.83905,-0.41952
+3.54623,1.07439,-1.70524,-1.33859,-1.12896,1.83919,-0.41975
+3.54846,1.07414,-1.70505,-1.33904,-1.12875,1.83931,-0.41997
+3.55069,1.07389,-1.70487,-1.33949,-1.12854,1.83944,-0.42019
+3.55293,1.07365,-1.70470,-1.33992,-1.12834,1.83957,-0.42040
+3.55516,1.07342,-1.70452,-1.34035,-1.12813,1.83969,-0.42061
+3.55739,1.07330,-1.70444,-1.34057,-1.12803,1.83975,-0.42071
+3.55962,1.07306,-1.70425,-1.34101,-1.12783,1.83987,-0.42092
+3.56186,1.07283,-1.70408,-1.34145,-1.12762,1.83999,-0.42113
+3.56409,1.07273,-1.70400,-1.34164,-1.12753,1.84004,-0.42122
+3.56632,1.07239,-1.70374,-1.34226,-1.12725,1.84021,-0.42151
+3.56856,1.07207,-1.70348,-1.34288,-1.12697,1.84038,-0.42180
+3.57079,1.07174,-1.70323,-1.34348,-1.12669,1.84054,-0.42209
+3.57302,1.07143,-1.70299,-1.34407,-1.12642,1.84071,-0.42236
+3.57526,1.07112,-1.70274,-1.34465,-1.12615,1.84086,-0.42264
+3.57749,1.07082,-1.70251,-1.34523,-1.12589,1.84102,-0.42290
+3.57972,1.07052,-1.70227,-1.34579,-1.12563,1.84117,-0.42317
+3.58196,1.07023,-1.70204,-1.34634,-1.12537,1.84132,-0.42342
+3.58419,1.06994,-1.70182,-1.34689,-1.12512,1.84147,-0.42368
+3.58642,1.06966,-1.70159,-1.34742,-1.12487,1.84161,-0.42393
+3.58866,1.06938,-1.70138,-1.34795,-1.12463,1.84175,-0.42417
+3.59089,1.06911,-1.70116,-1.34847,-1.12439,1.84189,-0.42441
+3.59312,1.06885,-1.70095,-1.34898,-1.12415,1.84203,-0.42464
+3.59536,1.06859,-1.70074,-1.34948,-1.12392,1.84216,-0.42487
+3.59759,1.06833,-1.70054,-1.34997,-1.12369,1.84229,-0.42510
+3.59982,1.06808,-1.70034,-1.35045,-1.12347,1.84242,-0.42532
+3.60205,1.06783,-1.70014,-1.35093,-1.12324,1.84255,-0.42554
+3.60429,1.06759,-1.69995,-1.35140,-1.12303,1.84267,-0.42575
+3.60652,1.06735,-1.69976,-1.35186,-1.12281,1.84279,-0.42596
+3.60875,1.06712,-1.69957,-1.35231,-1.12260,1.84291,-0.42617
+3.61099,1.06689,-1.69938,-1.35275,-1.12239,1.84303,-0.42637
+3.61322,1.06678,-1.69929,-1.35298,-1.12229,1.84309,-0.42647
+3.61545,1.06654,-1.69907,-1.35349,-1.12206,1.84321,-0.42668
+3.61769,1.06630,-1.69886,-1.35398,-1.12183,1.84333,-0.42689
+3.61992,1.06606,-1.69865,-1.35447,-1.12160,1.84345,-0.42710
+3.62215,1.06584,-1.69845,-1.35495,-1.12138,1.84357,-0.42730
+3.62439,1.06561,-1.69825,-1.35542,-1.12116,1.84369,-0.42750
+3.62662,1.06539,-1.69805,-1.35589,-1.12095,1.84380,-0.42770
+3.62885,1.06517,-1.69785,-1.35635,-1.12073,1.84391,-0.42789
+3.63109,1.06494,-1.69762,-1.35687,-1.12050,1.84403,-0.42809
+3.63332,1.06471,-1.69740,-1.35738,-1.12026,1.84415,-0.42829
+3.63555,1.06449,-1.69718,-1.35788,-1.12003,1.84426,-0.42849
+3.63778,1.06427,-1.69696,-1.35838,-1.11981,1.84437,-0.42869
+3.64002,1.06405,-1.69675,-1.35886,-1.11959,1.84448,-0.42888
+3.64225,1.06384,-1.69654,-1.35934,-1.11937,1.84459,-0.42906
+3.64448,1.06362,-1.69631,-1.35986,-1.11913,1.84471,-0.42926
+3.64672,1.06323,-1.69589,-1.36077,-1.11873,1.84490,-0.42961
+3.64895,1.06285,-1.69548,-1.36168,-1.11833,1.84510,-0.42994
+3.65118,1.06248,-1.69508,-1.36256,-1.11793,1.84529,-0.43027
+3.65342,1.06211,-1.69469,-1.36343,-1.11755,1.84547,-0.43059
+3.65565,1.06175,-1.69430,-1.36429,-1.11717,1.84565,-0.43091
+3.65788,1.06140,-1.69391,-1.36513,-1.11679,1.84583,-0.43122
+3.66012,1.06105,-1.69354,-1.36596,-1.11643,1.84601,-0.43152
+3.66235,1.06071,-1.69317,-1.36677,-1.11606,1.84618,-0.43182
+3.66458,1.06038,-1.69281,-1.36757,-1.11571,1.84635,-0.43212
+3.66682,1.06005,-1.69245,-1.36836,-1.11536,1.84652,-0.43241
+3.66905,1.05973,-1.69210,-1.36913,-1.11501,1.84668,-0.43269
+3.67128,1.05942,-1.69176,-1.36989,-1.11467,1.84684,-0.43297
+3.67351,1.05911,-1.69142,-1.37064,-1.11434,1.84700,-0.43324
+3.67575,1.05881,-1.69109,-1.37138,-1.11401,1.84715,-0.43351
+3.67798,1.05851,-1.69076,-1.37210,-1.11368,1.84730,-0.43377
+3.68021,1.05822,-1.69044,-1.37281,-1.11337,1.84745,-0.43403
+3.68245,1.05793,-1.69012,-1.37351,-1.11305,1.84759,-0.43428
+3.68468,1.05765,-1.68981,-1.37419,-1.11274,1.84774,-0.43453
+3.68691,1.05738,-1.68950,-1.37487,-1.11244,1.84788,-0.43477
+3.68915,1.05711,-1.68920,-1.37553,-1.11214,1.84801,-0.43501
+3.69138,1.05684,-1.68891,-1.37619,-1.11185,1.84815,-0.43524
+3.69361,1.05658,-1.68862,-1.37683,-1.11156,1.84828,-0.43547
+3.69585,1.05633,-1.68833,-1.37746,-1.11127,1.84841,-0.43570
+3.69808,1.05608,-1.68805,-1.37808,-1.11099,1.84854,-0.43592
+3.70031,1.05583,-1.68778,-1.37869,-1.11072,1.84866,-0.43614
+3.70255,1.05559,-1.68751,-1.37929,-1.11044,1.84879,-0.43635
+3.70478,1.05535,-1.68724,-1.37988,-1.11018,1.84891,-0.43656
+3.70701,1.05512,-1.68698,-1.38046,-1.10991,1.84902,-0.43676
+3.70925,1.05489,-1.68672,-1.38103,-1.10965,1.84914,-0.43697
+3.71148,1.05467,-1.68647,-1.38159,-1.10940,1.84925,-0.43716
+3.71371,1.05445,-1.68622,-1.38214,-1.10915,1.84937,-0.43736
+3.71594,1.05424,-1.68597,-1.38268,-1.10890,1.84948,-0.43755
+3.71818,1.05403,-1.68573,-1.38322,-1.10866,1.84958,-0.43773
+3.72041,1.05382,-1.68550,-1.38374,-1.10842,1.84969,-0.43792
+3.72264,1.05362,-1.68527,-1.38426,-1.10818,1.84979,-0.43810
+3.72488,1.05342,-1.68504,-1.38476,-1.10795,1.84989,-0.43827
+3.72711,1.05322,-1.68481,-1.38526,-1.10772,1.84999,-0.43844
+3.72934,1.05303,-1.68459,-1.38576,-1.10750,1.85009,-0.43862
+3.73158,1.05282,-1.68434,-1.38631,-1.10725,1.85020,-0.43880
+3.73381,1.05262,-1.68409,-1.38685,-1.10700,1.85030,-0.43898
+3.73604,1.05241,-1.68384,-1.38739,-1.10676,1.85040,-0.43916
+3.73828,1.05222,-1.68360,-1.38791,-1.10652,1.85050,-0.43933
+3.74051,1.05202,-1.68337,-1.38843,-1.10629,1.85060,-0.43951
+3.74274,1.05183,-1.68314,-1.38893,-1.10606,1.85070,-0.43967
+3.74498,1.05165,-1.68291,-1.38943,-1.10583,1.85080,-0.43984
+3.74721,1.05161,-1.68286,-1.38953,-1.10578,1.85081,-0.43987
+3.74944,1.05141,-1.68261,-1.39007,-1.10554,1.85091,-0.44005
+3.75167,1.05122,-1.68237,-1.39060,-1.10530,1.85101,-0.44022
+3.75391,1.05103,-1.68213,-1.39111,-1.10507,1.85111,-0.44038
+3.75614,1.05085,-1.68190,-1.39162,-1.10484,1.85120,-0.44055
+3.75837,1.05068,-1.68169,-1.39208,-1.10463,1.85129,-0.44069
+3.76061,1.05048,-1.68142,-1.39264,-1.10438,1.85139,-0.44087
+3.76284,1.05029,-1.68117,-1.39319,-1.10413,1.85149,-0.44104
+3.76507,1.05009,-1.68091,-1.39374,-1.10389,1.85159,-0.44121
+3.76731,1.04991,-1.68066,-1.39427,-1.10365,1.85168,-0.44138
+3.76954,1.04972,-1.68042,-1.39480,-1.10341,1.85178,-0.44154
+3.77177,1.04954,-1.68018,-1.39531,-1.10318,1.85187,-0.44170
+3.77401,1.04936,-1.67994,-1.39582,-1.10295,1.85196,-0.44186
+3.77624,1.04932,-1.67989,-1.39594,-1.10289,1.85198,-0.44190
+3.77847,1.04910,-1.67957,-1.39660,-1.10260,1.85209,-0.44209
+3.78071,1.04888,-1.67926,-1.39725,-1.10232,1.85220,-0.44229
+3.78294,1.04867,-1.67896,-1.39788,-1.10203,1.85231,-0.44248
+3.78517,1.04845,-1.67866,-1.39851,-1.10176,1.85242,-0.44266
+3.78741,1.04825,-1.67837,-1.39913,-1.10148,1.85252,-0.44285
+3.78964,1.04804,-1.67808,-1.39973,-1.10121,1.85263,-0.44303
+3.79187,1.04785,-1.67780,-1.40033,-1.10095,1.85273,-0.44320
+3.79410,1.04765,-1.67752,-1.40092,-1.10069,1.85283,-0.44338
+3.79634,1.04746,-1.67725,-1.40149,-1.10043,1.85292,-0.44354
+3.79857,1.04727,-1.67698,-1.40206,-1.10018,1.85302,-0.44371
+3.80080,1.04709,-1.67672,-1.40262,-1.09993,1.85311,-0.44387
+3.80304,1.04691,-1.67646,-1.40316,-1.09968,1.85320,-0.44403
+3.80527,1.04673,-1.67620,-1.40370,-1.09944,1.85329,-0.44419
+3.80750,1.04656,-1.67595,-1.40423,-1.09921,1.85338,-0.44434
+3.80974,1.04639,-1.67570,-1.40475,-1.09897,1.85347,-0.44449
+3.81197,1.04627,-1.67553,-1.40512,-1.09881,1.85353,-0.44460
+3.81420,1.04609,-1.67527,-1.40567,-1.09856,1.85362,-0.44476
+3.81644,1.04591,-1.67501,-1.40621,-1.09832,1.85371,-0.44491
+3.81867,1.04574,-1.67475,-1.40675,-1.09808,1.85380,-0.44507
+3.82090,1.04557,-1.67450,-1.40727,-1.09785,1.85388,-0.44522
+3.82314,1.04541,-1.67427,-1.40776,-1.09763,1.85396,-0.44536
+3.82537,1.04517,-1.67390,-1.40852,-1.09730,1.85408,-0.44557
+3.82760,1.04493,-1.67354,-1.40927,-1.09697,1.85420,-0.44578
+3.82983,1.04470,-1.67318,-1.41001,-1.09665,1.85432,-0.44598
+3.83207,1.04447,-1.67283,-1.41073,-1.09634,1.85443,-0.44619
+3.83430,1.04425,-1.67249,-1.41144,-1.09603,1.85455,-0.44638
+3.83653,1.04403,-1.67215,-1.41214,-1.09572,1.85466,-0.44658
+3.83877,1.04381,-1.67181,-1.41283,-1.09542,1.85477,-0.44677
+3.84100,1.04360,-1.67149,-1.41350,-1.09512,1.85487,-0.44696
+3.84323,1.04340,-1.67116,-1.41417,-1.09483,1.85498,-0.44714
+3.84547,1.04319,-1.67085,-1.41482,-1.09454,1.85508,-0.44732
+3.84770,1.04299,-1.67054,-1.41546,-1.09426,1.85518,-0.44749
+3.84993,1.04280,-1.67023,-1.41609,-1.09398,1.85528,-0.44767
+3.85217,1.04261,-1.66993,-1.41671,-1.09371,1.85538,-0.44784
+3.85440,1.04242,-1.66964,-1.41732,-1.09344,1.85547,-0.44800
+3.85663,1.04223,-1.66935,-1.41792,-1.09317,1.85557,-0.44817
+3.85887,1.04205,-1.66906,-1.41851,-1.09291,1.85566,-0.44833
+3.86110,1.04188,-1.66878,-1.41909,-1.09266,1.85575,-0.44848
+3.86333,1.04170,-1.66850,-1.41966,-1.09240,1.85583,-0.44864
+3.86556,1.04153,-1.66823,-1.42023,-1.09216,1.85592,-0.44879
+3.86780,1.04136,-1.66797,-1.42078,-1.09191,1.85601,-0.44894
+3.87003,1.04120,-1.66770,-1.42132,-1.09167,1.85609,-0.44908
+3.87226,1.04104,-1.66745,-1.42185,-1.09143,1.85617,-0.44923
+3.87450,1.04088,-1.66719,-1.42238,-1.09120,1.85625,-0.44937
+3.87673,1.04086,-1.66717,-1.42243,-1.09117,1.85626,-0.44938
+3.87896,1.04070,-1.66691,-1.42297,-1.09094,1.85634,-0.44952
+3.88120,1.04054,-1.66665,-1.42350,-1.09070,1.85642,-0.44966
+3.88343,1.04046,-1.66652,-1.42376,-1.09058,1.85646,-0.44973
+3.88566,1.04029,-1.66625,-1.42432,-1.09033,1.85655,-0.44988
+3.88790,1.04013,-1.66598,-1.42488,-1.09009,1.85663,-0.45003
+3.89013,1.03997,-1.66572,-1.42542,-1.08985,1.85671,-0.45017
+3.89236,1.03981,-1.66546,-1.42595,-1.08961,1.85679,-0.45031
+3.89460,1.03965,-1.66520,-1.42649,-1.08938,1.85687,-0.45046
+3.89683,1.03945,-1.66488,-1.42714,-1.08909,1.85697,-0.45063
+3.89906,1.03926,-1.66457,-1.42778,-1.08881,1.85707,-0.45080
+3.90130,1.03907,-1.66426,-1.42841,-1.08853,1.85716,-0.45097
+3.90353,1.03888,-1.66396,-1.42903,-1.08826,1.85726,-0.45113
+3.90576,1.03870,-1.66366,-1.42964,-1.08800,1.85735,-0.45129
+3.90799,1.03852,-1.66337,-1.43024,-1.08773,1.85744,-0.45145
+3.91023,1.03835,-1.66309,-1.43083,-1.08747,1.85753,-0.45161
+3.91246,1.03818,-1.66280,-1.43140,-1.08722,1.85761,-0.45176
+3.91469,1.03801,-1.66253,-1.43197,-1.08697,1.85770,-0.45191
+3.91693,1.03784,-1.66225,-1.43253,-1.08672,1.85778,-0.45205
+3.91916,1.03768,-1.66199,-1.43308,-1.08648,1.85786,-0.45220
+3.92139,1.03752,-1.66172,-1.43362,-1.08624,1.85794,-0.45234
+3.92363,1.03737,-1.66146,-1.43416,-1.08600,1.85802,-0.45247
+3.92586,1.03725,-1.66125,-1.43458,-1.08582,1.85808,-0.45258
+3.92809,1.03703,-1.66070,-1.43563,-1.08538,1.85819,-0.45277
+3.93033,1.03682,-1.66015,-1.43666,-1.08495,1.85830,-0.45296
+3.93256,1.03661,-1.65961,-1.43767,-1.08453,1.85840,-0.45314
+3.93479,1.03641,-1.65909,-1.43867,-1.08411,1.85850,-0.45332
+3.93703,1.03621,-1.65857,-1.43965,-1.08371,1.85860,-0.45350
+3.93926,1.03601,-1.65806,-1.44062,-1.08330,1.85870,-0.45367
+3.94149,1.03582,-1.65756,-1.44157,-1.08291,1.85880,-0.45384
+3.94372,1.03563,-1.65707,-1.44250,-1.08251,1.85889,-0.45401
+3.94596,1.03545,-1.65658,-1.44341,-1.08213,1.85899,-0.45417
+3.94819,1.03526,-1.65611,-1.44431,-1.08175,1.85908,-0.45433
+3.95042,1.03509,-1.65564,-1.44520,-1.08138,1.85917,-0.45449
+3.95266,1.03491,-1.65518,-1.44607,-1.08101,1.85925,-0.45464
+3.95489,1.03474,-1.65473,-1.44693,-1.08065,1.85934,-0.45479
+3.95712,1.03457,-1.65428,-1.44777,-1.08030,1.85942,-0.45494
+3.95936,1.03441,-1.65385,-1.44860,-1.07995,1.85951,-0.45509
+3.96159,1.03425,-1.65342,-1.44941,-1.07960,1.85959,-0.45523
+3.96382,1.03409,-1.65300,-1.45021,-1.07927,1.85967,-0.45537
+3.96606,1.03393,-1.65258,-1.45100,-1.07893,1.85974,-0.45551
+3.96829,1.03378,-1.65217,-1.45177,-1.07861,1.85982,-0.45564
+3.97052,1.03363,-1.65177,-1.45253,-1.07828,1.85990,-0.45577
+3.97276,1.03349,-1.65138,-1.45328,-1.07796,1.85997,-0.45590
+3.97499,1.03334,-1.65099,-1.45401,-1.07765,1.86004,-0.45603
+3.97722,1.03320,-1.65061,-1.45474,-1.07734,1.86011,-0.45615
+3.97946,1.03307,-1.65024,-1.45545,-1.07704,1.86018,-0.45627
+3.98169,1.03293,-1.64987,-1.45615,-1.07674,1.86025,-0.45639
+3.98392,1.03280,-1.64951,-1.45683,-1.07645,1.86031,-0.45651
+3.98615,1.03267,-1.64916,-1.45751,-1.07616,1.86038,-0.45662
+3.98839,1.03254,-1.64881,-1.45817,-1.07588,1.86044,-0.45673
+3.99062,1.03242,-1.64846,-1.45882,-1.07560,1.86051,-0.45684
+3.99285,1.03230,-1.64813,-1.45947,-1.07532,1.86057,-0.45695
+3.99509,1.03218,-1.64780,-1.46010,-1.07505,1.86063,-0.45706
+3.99732,1.03206,-1.64747,-1.46072,-1.07478,1.86069,-0.45716
+3.99955,1.03194,-1.64715,-1.46133,-1.07452,1.86074,-0.45726
+4.00179,1.03183,-1.64684,-1.46193,-1.07426,1.86080,-0.45736
+4.00402,1.03172,-1.64653,-1.46252,-1.07401,1.86086,-0.45746
+4.00625,1.03161,-1.64622,-1.46310,-1.07376,1.86091,-0.45755
+4.00849,1.03151,-1.64592,-1.46367,-1.07351,1.86096,-0.45765
+4.01072,1.03140,-1.64563,-1.46423,-1.07327,1.86102,-0.45774
+4.01295,1.03139,-1.64560,-1.46429,-1.07324,1.86102,-0.45775
+4.01519,1.03128,-1.64526,-1.46492,-1.07297,1.86108,-0.45784
+4.01742,1.03117,-1.64493,-1.46554,-1.07271,1.86113,-0.45794
+4.01965,1.03107,-1.64461,-1.46615,-1.07244,1.86119,-0.45803
+4.02188,1.03096,-1.64429,-1.46675,-1.07219,1.86124,-0.45812
+4.02412,1.03086,-1.64398,-1.46734,-1.07194,1.86129,-0.45821
+4.02635,1.03076,-1.64367,-1.46792,-1.07169,1.86134,-0.45830
+4.02858,1.03066,-1.64337,-1.46849,-1.07144,1.86139,-0.45839
+4.03082,1.03059,-1.64315,-1.46890,-1.07127,1.86142,-0.45845
+4.03305,1.03048,-1.64276,-1.46962,-1.07097,1.86148,-0.45855
+4.03528,1.03037,-1.64239,-1.47032,-1.07067,1.86153,-0.45864
+4.03752,1.03026,-1.64201,-1.47101,-1.07038,1.86159,-0.45874
+4.03975,1.03016,-1.64165,-1.47169,-1.07009,1.86164,-0.45883
+4.04198,1.03005,-1.64128,-1.47236,-1.06981,1.86169,-0.45892
+4.04422,1.02995,-1.64093,-1.47301,-1.06954,1.86174,-0.45901
+4.04645,1.02985,-1.64058,-1.47366,-1.06926,1.86179,-0.45910
+4.04868,1.02976,-1.64024,-1.47429,-1.06899,1.86184,-0.45919
+4.05092,1.02966,-1.63990,-1.47492,-1.06873,1.86189,-0.45927
+4.05315,1.02957,-1.63957,-1.47553,-1.06847,1.86194,-0.45935
+4.05538,1.02948,-1.63925,-1.47613,-1.06821,1.86198,-0.45943
+4.05762,1.02939,-1.63893,-1.47673,-1.06796,1.86203,-0.45951
+4.05985,1.02930,-1.63861,-1.47731,-1.06771,1.86207,-0.45959
+4.06208,1.02921,-1.63830,-1.47788,-1.06747,1.86211,-0.45966
+4.06431,1.02917,-1.63812,-1.47821,-1.06733,1.86214,-0.45970
+4.06655,1.02905,-1.63754,-1.47924,-1.06691,1.86220,-0.45981
+4.06878,1.02894,-1.63697,-1.48025,-1.06650,1.86225,-0.45991
+4.07101,1.02882,-1.63641,-1.48125,-1.06610,1.86231,-0.46000
+4.07325,1.02871,-1.63586,-1.48223,-1.06570,1.86236,-0.46010
+4.07548,1.02861,-1.63532,-1.48319,-1.06531,1.86242,-0.46019
+4.07771,1.02850,-1.63479,-1.48413,-1.06493,1.86247,-0.46028
+4.07995,1.02840,-1.63426,-1.48506,-1.06455,1.86252,-0.46037
+4.08218,1.02830,-1.63375,-1.48598,-1.06418,1.86257,-0.46046
+4.08441,1.02820,-1.63324,-1.48687,-1.06381,1.86262,-0.46055
+4.08665,1.02810,-1.63275,-1.48776,-1.06345,1.86267,-0.46063
+4.08888,1.02801,-1.63226,-1.48862,-1.06310,1.86271,-0.46071
+4.09111,1.02792,-1.63178,-1.48948,-1.06275,1.86276,-0.46080
+4.09335,1.02783,-1.63131,-1.49032,-1.06240,1.86280,-0.46087
+4.09558,1.02774,-1.63084,-1.49114,-1.06206,1.86285,-0.46095
+4.09781,1.02765,-1.63039,-1.49195,-1.06173,1.86289,-0.46103
+4.10004,1.02757,-1.62994,-1.49275,-1.06140,1.86293,-0.46110
+4.10228,1.02749,-1.62950,-1.49353,-1.06108,1.86297,-0.46117
+4.10451,1.02740,-1.62907,-1.49430,-1.06076,1.86301,-0.46124
+4.10674,1.02733,-1.62864,-1.49506,-1.06045,1.86305,-0.46131
+4.10898,1.02725,-1.62822,-1.49581,-1.06014,1.86309,-0.46138
+4.11121,1.02717,-1.62781,-1.49654,-1.05984,1.86313,-0.46145
+4.11344,1.02710,-1.62741,-1.49726,-1.05954,1.86317,-0.46151
+4.11568,1.02702,-1.62701,-1.49797,-1.05925,1.86320,-0.46157
+4.11791,1.02695,-1.62662,-1.49866,-1.05896,1.86324,-0.46164
+4.12014,1.02688,-1.62624,-1.49935,-1.05867,1.86327,-0.46170
+4.12238,1.02682,-1.62586,-1.50002,-1.05839,1.86331,-0.46175
+4.12461,1.02675,-1.62549,-1.50068,-1.05812,1.86334,-0.46181
+4.12684,1.02668,-1.62513,-1.50133,-1.05785,1.86337,-0.46187
+4.12908,1.02662,-1.62477,-1.50197,-1.05758,1.86340,-0.46192
+4.13131,1.02656,-1.62442,-1.50260,-1.05732,1.86344,-0.46198
+4.13354,1.02650,-1.62407,-1.50322,-1.05706,1.86347,-0.46203
+4.13577,1.02644,-1.62373,-1.50383,-1.05680,1.86350,-0.46208
+4.13801,1.02638,-1.62340,-1.50443,-1.05655,1.86352,-0.46213
+4.14024,1.02632,-1.62307,-1.50501,-1.05630,1.86355,-0.46218
+4.14247,1.02626,-1.62275,-1.50559,-1.05606,1.86358,-0.46223
+4.14471,1.02625,-1.62267,-1.50572,-1.05601,1.86359,-0.46224
+4.14694,1.02617,-1.62225,-1.50647,-1.05570,1.86363,-0.46231
+4.14917,1.02609,-1.62184,-1.50720,-1.05540,1.86367,-0.46238
+4.15141,1.02601,-1.62144,-1.50792,-1.05510,1.86370,-0.46245
+4.15364,1.02594,-1.62104,-1.50863,-1.05481,1.86374,-0.46251
+4.15587,1.02587,-1.62065,-1.50933,-1.05452,1.86378,-0.46258
+4.15811,1.02579,-1.62026,-1.51001,-1.05424,1.86381,-0.46264
+4.16034,1.02572,-1.61988,-1.51069,-1.05396,1.86385,-0.46270
+4.16257,1.02565,-1.61951,-1.51135,-1.05368,1.86388,-0.46276
+4.16481,1.02559,-1.61915,-1.51200,-1.05341,1.86392,-0.46282
+4.16704,1.02552,-1.61879,-1.51264,-1.05315,1.86395,-0.46288
+4.16927,1.02546,-1.61844,-1.51327,-1.05288,1.86398,-0.46293
+4.17151,1.02539,-1.61809,-1.51389,-1.05263,1.86401,-0.46299
+4.17374,1.02533,-1.61775,-1.51450,-1.05237,1.86404,-0.46304
+4.17597,1.02527,-1.61742,-1.51510,-1.05212,1.86407,-0.46309
+4.17820,1.02521,-1.61709,-1.51568,-1.05188,1.86410,-0.46315
+4.18044,1.02515,-1.61676,-1.51626,-1.05164,1.86413,-0.46320
+4.18267,1.02512,-1.61657,-1.51661,-1.05149,1.86415,-0.46323
+4.18490,1.02505,-1.61621,-1.51725,-1.05122,1.86418,-0.46328
+4.18714,1.02499,-1.61585,-1.51788,-1.05096,1.86421,-0.46334
+4.18937,1.02492,-1.61550,-1.51850,-1.05071,1.86424,-0.46339
+4.19160,1.02486,-1.61516,-1.51911,-1.05045,1.86427,-0.46344
+4.19384,1.02480,-1.61483,-1.51971,-1.05020,1.86430,-0.46350
+4.19607,1.02474,-1.61450,-1.52030,-1.04996,1.86433,-0.46355
+4.19830,1.02469,-1.61417,-1.52088,-1.04972,1.86436,-0.46360
+4.20054,1.02465,-1.61393,-1.52130,-1.04954,1.86438,-0.46363
+4.20277,1.02462,-1.61346,-1.52210,-1.04922,1.86439,-0.46365
+4.20500,1.02460,-1.61300,-1.52288,-1.04891,1.86440,-0.46367
+4.20724,1.02457,-1.61254,-1.52365,-1.04861,1.86442,-0.46369
+4.20947,1.02455,-1.61210,-1.52440,-1.04830,1.86443,-0.46371
+4.21170,1.02452,-1.61166,-1.52514,-1.04801,1.86444,-0.46373
+4.21393,1.02450,-1.61122,-1.52587,-1.04771,1.86445,-0.46375
+4.21617,1.02448,-1.61080,-1.52659,-1.04743,1.86446,-0.46377
+4.21840,1.02446,-1.61038,-1.52730,-1.04714,1.86447,-0.46379
+4.22063,1.02444,-1.60997,-1.52799,-1.04686,1.86448,-0.46380
+4.22287,1.02442,-1.60957,-1.52867,-1.04659,1.86449,-0.46382
+4.22510,1.02440,-1.60918,-1.52934,-1.04632,1.86450,-0.46383
+4.22733,1.02438,-1.60879,-1.53000,-1.04605,1.86451,-0.46385
+4.22957,1.02436,-1.60840,-1.53065,-1.04579,1.86452,-0.46386
+4.23180,1.02434,-1.60803,-1.53129,-1.04553,1.86453,-0.46388
+4.23403,1.02432,-1.60766,-1.53192,-1.04528,1.86454,-0.46389
+4.23627,1.02431,-1.60730,-1.53253,-1.04503,1.86455,-0.46391
+4.23850,1.02429,-1.60694,-1.53314,-1.04478,1.86455,-0.46392
+4.24073,1.02427,-1.60659,-1.53373,-1.04454,1.86456,-0.46393
+4.24297,1.02426,-1.60624,-1.53432,-1.04430,1.86457,-0.46394
+4.24520,1.02425,-1.60602,-1.53470,-1.04415,1.86457,-0.46395
+4.24743,1.02422,-1.60550,-1.53557,-1.04380,1.86459,-0.46398
+4.24967,1.02419,-1.60499,-1.53643,-1.04346,1.86460,-0.46400
+4.25190,1.02416,-1.60449,-1.53727,-1.04313,1.86462,-0.46402
+4.25413,1.02413,-1.60399,-1.53810,-1.04280,1.86463,-0.46405
+4.25636,1.02410,-1.60351,-1.53892,-1.04248,1.86464,-0.46407
+4.25860,1.02408,-1.60303,-1.53972,-1.04216,1.86466,-0.46409
+4.26083,1.02405,-1.60256,-1.54051,-1.04185,1.86467,-0.46411
+4.26306,1.02403,-1.60210,-1.54128,-1.04154,1.86468,-0.46413
+4.26530,1.02400,-1.60165,-1.54205,-1.04124,1.86469,-0.46415
+4.26753,1.02398,-1.60120,-1.54280,-1.04094,1.86470,-0.46417
+4.26976,1.02396,-1.60076,-1.54353,-1.04064,1.86471,-0.46419
+4.27200,1.02394,-1.60033,-1.54426,-1.04036,1.86472,-0.46420
+4.27423,1.02392,-1.59991,-1.54497,-1.04007,1.86473,-0.46422
+4.27646,1.02389,-1.59949,-1.54567,-1.03979,1.86474,-0.46424
+4.27870,1.02387,-1.59909,-1.54636,-1.03952,1.86475,-0.46425
+4.28093,1.02386,-1.59869,-1.54703,-1.03924,1.86476,-0.46427
+4.28316,1.02384,-1.59829,-1.54770,-1.03898,1.86477,-0.46428
+4.28540,1.02382,-1.59790,-1.54835,-1.03871,1.86478,-0.46430
+4.28763,1.02380,-1.59752,-1.54899,-1.03846,1.86479,-0.46431
+4.28986,1.02378,-1.59715,-1.54963,-1.03820,1.86479,-0.46432
+4.29209,1.02377,-1.59678,-1.55025,-1.03795,1.86480,-0.46433
+4.29433,1.02375,-1.59642,-1.55086,-1.03770,1.86481,-0.46435
+4.29656,1.02374,-1.59606,-1.55146,-1.03746,1.86482,-0.46436
+4.29879,1.02372,-1.59571,-1.55205,-1.03722,1.86482,-0.46437
+4.30103,1.02371,-1.59537,-1.55263,-1.03699,1.86483,-0.46438
+4.30326,1.02370,-1.59523,-1.55287,-1.03689,1.86483,-0.46438
+4.30549,1.02369,-1.59480,-1.55359,-1.03660,1.86484,-0.46439
+4.30773,1.02368,-1.59438,-1.55429,-1.03633,1.86484,-0.46440
+4.30996,1.02367,-1.59396,-1.55498,-1.03605,1.86485,-0.46440
+4.31219,1.02366,-1.59355,-1.55566,-1.03578,1.86485,-0.46441
+4.31443,1.02365,-1.59315,-1.55632,-1.03552,1.86485,-0.46442
+4.31666,1.02365,-1.59276,-1.55698,-1.03526,1.86486,-0.46442
+4.31889,1.02364,-1.59238,-1.55762,-1.03500,1.86486,-0.46443
+4.32113,1.02363,-1.59200,-1.55826,-1.03475,1.86486,-0.46443
+4.32336,1.02362,-1.59162,-1.55888,-1.03450,1.86487,-0.46444
+4.32559,1.02361,-1.59126,-1.55949,-1.03425,1.86487,-0.46444
+4.32782,1.02361,-1.59090,-1.56009,-1.03401,1.86487,-0.46444
+4.33006,1.02360,-1.59054,-1.56068,-1.03377,1.86488,-0.46445
+4.33229,1.02360,-1.59019,-1.56127,-1.03354,1.86488,-0.46445
+4.33452,1.02359,-1.58998,-1.56162,-1.03340,1.86488,-0.46445
+4.33676,1.02359,-1.58958,-1.56228,-1.03314,1.86488,-0.46445
+4.33899,1.02359,-1.58919,-1.56292,-1.03288,1.86488,-0.46445
+4.34122,1.02359,-1.58881,-1.56356,-1.03263,1.86488,-0.46445
+4.34346,1.02359,-1.58843,-1.56418,-1.03238,1.86488,-0.46445
+4.34569,1.02359,-1.58806,-1.56479,-1.03214,1.86488,-0.46444
+4.34792,1.02359,-1.58770,-1.56540,-1.03190,1.86488,-0.46444
+4.35016,1.02359,-1.58734,-1.56599,-1.03166,1.86488,-0.46444
+4.35239,1.02359,-1.58699,-1.56657,-1.03143,1.86487,-0.46444
+4.35462,1.02360,-1.58668,-1.56708,-1.03123,1.86487,-0.46443
+4.35686,1.02361,-1.58600,-1.56818,-1.03081,1.86486,-0.46442
+4.35909,1.02362,-1.58533,-1.56925,-1.03041,1.86486,-0.46440
+4.36132,1.02364,-1.58467,-1.57031,-1.03001,1.86485,-0.46439
+4.36356,1.02365,-1.58403,-1.57135,-1.02961,1.86484,-0.46437
+4.36579,1.02367,-1.58339,-1.57237,-1.02923,1.86483,-0.46436
+4.36802,1.02368,-1.58277,-1.57337,-1.02884,1.86483,-0.46434
+4.37025,1.02370,-1.58215,-1.57435,-1.02847,1.86482,-0.46432
+4.37249,1.02371,-1.58155,-1.57532,-1.02810,1.86481,-0.46431
+4.37472,1.02373,-1.58096,-1.57628,-1.02774,1.86480,-0.46429
+4.37695,1.02374,-1.58038,-1.57721,-1.02738,1.86479,-0.46428
+4.37919,1.02376,-1.57981,-1.57813,-1.02703,1.86478,-0.46426
+4.38142,1.02377,-1.57925,-1.57904,-1.02668,1.86477,-0.46424
+4.38365,1.02379,-1.57869,-1.57993,-1.02634,1.86477,-0.46423
+4.38589,1.02380,-1.57815,-1.58080,-1.02600,1.86476,-0.46421
+4.38812,1.02382,-1.57762,-1.58166,-1.02567,1.86475,-0.46419
+4.39035,1.02384,-1.57710,-1.58251,-1.02535,1.86474,-0.46418
+4.39259,1.02385,-1.57658,-1.58334,-1.02503,1.86473,-0.46416
+4.39482,1.02387,-1.57607,-1.58415,-1.02471,1.86472,-0.46414
+4.39705,1.02389,-1.57558,-1.58495,-1.02440,1.86471,-0.46413
+4.39929,1.02390,-1.57509,-1.58574,-1.02410,1.86470,-0.46411
+4.40152,1.02392,-1.57461,-1.58652,-1.02380,1.86469,-0.46409
+4.40375,1.02393,-1.57414,-1.58728,-1.02350,1.86469,-0.46407
+4.40598,1.02395,-1.57367,-1.58803,-1.02321,1.86468,-0.46406
+4.40822,1.02397,-1.57322,-1.58877,-1.02293,1.86467,-0.46404
+4.41045,1.02398,-1.57277,-1.58949,-1.02265,1.86466,-0.46402
+4.41268,1.02400,-1.57233,-1.59020,-1.02237,1.86465,-0.46401
+4.41492,1.02402,-1.57190,-1.59090,-1.02210,1.86464,-0.46399
+4.41715,1.02403,-1.57147,-1.59159,-1.02183,1.86463,-0.46397
+4.41938,1.02405,-1.57105,-1.59227,-1.02156,1.86462,-0.46395
+4.42162,1.02407,-1.57064,-1.59293,-1.02130,1.86461,-0.46394
+4.42385,1.02408,-1.57024,-1.59359,-1.02105,1.86460,-0.46392
+4.42608,1.02410,-1.56984,-1.59423,-1.02079,1.86459,-0.46390
+4.42832,1.02412,-1.56945,-1.59486,-1.02055,1.86459,-0.46388
+4.43055,1.02413,-1.56907,-1.59548,-1.02030,1.86458,-0.46387
+4.43278,1.02415,-1.56870,-1.59609,-1.02006,1.86457,-0.46385
+4.43502,1.02416,-1.56833,-1.59669,-1.01983,1.86456,-0.46383
+4.43725,1.02418,-1.56796,-1.59728,-1.01959,1.86455,-0.46382
+4.43948,1.02420,-1.56760,-1.59786,-1.01936,1.86454,-0.46380
+4.44172,1.02421,-1.56725,-1.59844,-1.01913,1.86453,-0.46378
+4.44395,1.02421,-1.56685,-1.59910,-1.01888,1.86453,-0.46378
+4.44618,1.02421,-1.56645,-1.59975,-1.01862,1.86453,-0.46378
+4.44841,1.02421,-1.56607,-1.60038,-1.01837,1.86453,-0.46378
+4.45065,1.02421,-1.56569,-1.60101,-1.01813,1.86453,-0.46378
+4.45288,1.02421,-1.56531,-1.60162,-1.01789,1.86453,-0.46377
+4.45511,1.02421,-1.56494,-1.60222,-1.01765,1.86453,-0.46377
+4.45735,1.02421,-1.56458,-1.60282,-1.01741,1.86453,-0.46377
+4.45958,1.02421,-1.56423,-1.60340,-1.01718,1.86453,-0.46377
+4.46181,1.02421,-1.56388,-1.60397,-1.01696,1.86452,-0.46376
+4.46405,1.02421,-1.56365,-1.60435,-1.01681,1.86452,-0.46376
+4.46628,1.02425,-1.56306,-1.60528,-1.01646,1.86450,-0.46373
+4.46851,1.02428,-1.56248,-1.60619,-1.01612,1.86449,-0.46369
+4.47075,1.02431,-1.56192,-1.60708,-1.01578,1.86447,-0.46366
+4.47298,1.02435,-1.56136,-1.60796,-1.01545,1.86445,-0.46363
+4.47521,1.02438,-1.56081,-1.60883,-1.01513,1.86444,-0.46360
+4.47745,1.02441,-1.56028,-1.60968,-1.01481,1.86442,-0.46356
+4.47968,1.02444,-1.55975,-1.61051,-1.01449,1.86440,-0.46353
+4.48191,1.02448,-1.55923,-1.61133,-1.01418,1.86438,-0.46350
+4.48414,1.02451,-1.55872,-1.61214,-1.01388,1.86437,-0.46347
+4.48638,1.02454,-1.55822,-1.61294,-1.01358,1.86435,-0.46344
+4.48861,1.02457,-1.55772,-1.61372,-1.01328,1.86433,-0.46341
+4.49084,1.02460,-1.55724,-1.61448,-1.01299,1.86432,-0.46338
+4.49308,1.02464,-1.55676,-1.61524,-1.01270,1.86430,-0.46335
+4.49531,1.02467,-1.55629,-1.61598,-1.01242,1.86428,-0.46332
+4.49754,1.02470,-1.55583,-1.61671,-1.01215,1.86427,-0.46329
+4.49978,1.02473,-1.55538,-1.61742,-1.01187,1.86425,-0.46326
+4.50201,1.02476,-1.55494,-1.61813,-1.01160,1.86424,-0.46323
+4.50424,1.02479,-1.55450,-1.61882,-1.01134,1.86422,-0.46320
+4.50648,1.02482,-1.55407,-1.61950,-1.01108,1.86420,-0.46317
+4.50871,1.02485,-1.55365,-1.62017,-1.01082,1.86419,-0.46314
+4.51094,1.02488,-1.55324,-1.62082,-1.01057,1.86417,-0.46311
+4.51318,1.02491,-1.55283,-1.62147,-1.01032,1.86416,-0.46308
+4.51541,1.02493,-1.55243,-1.62210,-1.01008,1.86414,-0.46305
+4.51764,1.02496,-1.55204,-1.62273,-1.00984,1.86413,-0.46303
+4.51987,1.02499,-1.55165,-1.62334,-1.00960,1.86411,-0.46300
+4.52211,1.02502,-1.55127,-1.62395,-1.00937,1.86410,-0.46297
+4.52434,1.02505,-1.55090,-1.62454,-1.00914,1.86408,-0.46294
+4.52657,1.02508,-1.55053,-1.62512,-1.00891,1.86407,-0.46292
+4.52881,1.02510,-1.55017,-1.62570,-1.00869,1.86405,-0.46289
+4.53104,1.02513,-1.54985,-1.62621,-1.00849,1.86404,-0.46286
+4.53327,1.02518,-1.54946,-1.62681,-1.00826,1.86401,-0.46282
+4.53551,1.02522,-1.54908,-1.62740,-1.00804,1.86399,-0.46277
+4.53774,1.02527,-1.54871,-1.62798,-1.00782,1.86396,-0.46273
+4.53997,1.02532,-1.54835,-1.62855,-1.00760,1.86394,-0.46269
+4.54221,1.02536,-1.54802,-1.62907,-1.00740,1.86392,-0.46265
+4.54444,1.02539,-1.54762,-1.62969,-1.00716,1.86390,-0.46261
+4.54667,1.02543,-1.54723,-1.63031,-1.00693,1.86388,-0.46258
+4.54891,1.02546,-1.54684,-1.63092,-1.00669,1.86386,-0.46255
+4.55114,1.02550,-1.54646,-1.63152,-1.00647,1.86385,-0.46251
+4.55337,1.02553,-1.54609,-1.63210,-1.00624,1.86383,-0.46248
+4.55561,1.02556,-1.54572,-1.63268,-1.00602,1.86381,-0.46245
+4.55784,1.02560,-1.54536,-1.63325,-1.00580,1.86379,-0.46242
+4.56007,1.02561,-1.54518,-1.63353,-1.00570,1.86378,-0.46240
+4.56230,1.02565,-1.54481,-1.63412,-1.00547,1.86376,-0.46236
+4.56454,1.02569,-1.54444,-1.63469,-1.00525,1.86374,-0.46232
+4.56677,1.02573,-1.54408,-1.63526,-1.00504,1.86372,-0.46229
+4.56900,1.02575,-1.54390,-1.63554,-1.00493,1.86371,-0.46227
+4.57124,1.02579,-1.54352,-1.63613,-1.00471,1.86369,-0.46223
+4.57347,1.02584,-1.54315,-1.63670,-1.00449,1.86367,-0.46219
+4.57570,1.02588,-1.54279,-1.63727,-1.00427,1.86364,-0.46215
+4.57794,1.02590,-1.54261,-1.63755,-1.00416,1.86363,-0.46213
+4.58017,1.02594,-1.54224,-1.63812,-1.00395,1.86362,-0.46209
+4.58240,1.02597,-1.54189,-1.63868,-1.00373,1.86360,-0.46206
+4.58464,1.02598,-1.54181,-1.63880,-1.00369,1.86359,-0.46205
+4.58687,1.02603,-1.54145,-1.63936,-1.00348,1.86357,-0.46201
+4.58910,1.02604,-1.54130,-1.63959,-1.00339,1.86356,-0.46199
+4.59134,1.02608,-1.54094,-1.64016,-1.00317,1.86354,-0.46195
+4.59357,1.02612,-1.54058,-1.64072,-1.00296,1.86352,-0.46192
+4.59580,1.02608,-1.54059,-1.64072,-1.00295,1.86354,-0.46195
+4.59803,1.02586,-1.54069,-1.64071,-1.00292,1.86365,-0.46215
+4.60027,1.02545,-1.54088,-1.64067,-1.00287,1.86385,-0.46251
+4.60250,1.02505,-1.54107,-1.64062,-1.00281,1.86404,-0.46286
+4.60473,1.02466,-1.54125,-1.64058,-1.00276,1.86424,-0.46321
+4.60697,1.02428,-1.54144,-1.64054,-1.00272,1.86443,-0.46355
+4.60920,1.02390,-1.54161,-1.64050,-1.00267,1.86461,-0.46388
+4.61143,1.02353,-1.54179,-1.64046,-1.00262,1.86480,-0.46421
+4.61367,1.02349,-1.54181,-1.64045,-1.00262,1.86482,-0.46425
+4.61590,1.02308,-1.54202,-1.64037,-1.00258,1.86502,-0.46461
+4.61813,1.02268,-1.54223,-1.64029,-1.00255,1.86521,-0.46496
+4.62037,1.02229,-1.54244,-1.64021,-1.00251,1.86541,-0.46531
+4.62260,1.02190,-1.54264,-1.64013,-1.00248,1.86560,-0.46565
+4.62483,1.02153,-1.54284,-1.64006,-1.00245,1.86578,-0.46599
+4.62707,1.02116,-1.54304,-1.63998,-1.00242,1.86597,-0.46632
+4.62930,1.02104,-1.54310,-1.63996,-1.00241,1.86602,-0.46642
+4.63153,1.02067,-1.54330,-1.63987,-1.00238,1.86621,-0.46675
+4.63377,1.02030,-1.54350,-1.63978,-1.00235,1.86639,-0.46708
+4.63600,1.02021,-1.54356,-1.63975,-1.00235,1.86643,-0.46716
+4.63823,1.01971,-1.54393,-1.63948,-1.00238,1.86668,-0.46761
+4.64046,1.01921,-1.54429,-1.63921,-1.00240,1.86693,-0.46805
+4.64270,1.01873,-1.54464,-1.63895,-1.00242,1.86717,-0.46848
+4.64493,1.01825,-1.54499,-1.63870,-1.00245,1.86740,-0.46890
+4.64716,1.01779,-1.54533,-1.63844,-1.00247,1.86763,-0.46932
+4.64940,1.01733,-1.54567,-1.63819,-1.00249,1.86786,-0.46973
+4.65163,1.01688,-1.54600,-1.63795,-1.00252,1.86808,-0.47013
+4.65386,1.01644,-1.54633,-1.63770,-1.00254,1.86830,-0.47053
+4.65610,1.01600,-1.54665,-1.63746,-1.00257,1.86851,-0.47091
+4.65833,1.01558,-1.54696,-1.63723,-1.00259,1.86872,-0.47129
+4.66056,1.01516,-1.54727,-1.63700,-1.00262,1.86893,-0.47167
+4.66280,1.01475,-1.54757,-1.63677,-1.00264,1.86914,-0.47203
+4.66503,1.01435,-1.54787,-1.63654,-1.00267,1.86933,-0.47239
+4.66726,1.01395,-1.54816,-1.63632,-1.00270,1.86953,-0.47275
+4.66950,1.01356,-1.54845,-1.63610,-1.00272,1.86972,-0.47310
+4.67173,1.01318,-1.54874,-1.63589,-1.00275,1.86991,-0.47344
+4.67396,1.01281,-1.54902,-1.63567,-1.00277,1.87010,-0.47377
+4.67619,1.01244,-1.54929,-1.63546,-1.00280,1.87028,-0.47410
+4.67843,1.01208,-1.54956,-1.63526,-1.00282,1.87046,-0.47443
+4.68066,1.01172,-1.54982,-1.63506,-1.00285,1.87063,-0.47474
+4.68289,1.01155,-1.54996,-1.63495,-1.00286,1.87072,-0.47490
+4.68513,1.01116,-1.55026,-1.63471,-1.00290,1.87092,-0.47525
+4.68736,1.01078,-1.55055,-1.63448,-1.00293,1.87110,-0.47559
+4.68959,1.01041,-1.55084,-1.63425,-1.00297,1.87129,-0.47593
+4.69183,1.01004,-1.55112,-1.63402,-1.00300,1.87147,-0.47626
+4.69406,1.00968,-1.55140,-1.63380,-1.00304,1.87165,-0.47658
+4.69629,1.00933,-1.55168,-1.63358,-1.00307,1.87182,-0.47690
+4.69853,1.00901,-1.55192,-1.63337,-1.00311,1.87198,-0.47718
+4.70076,1.00866,-1.55224,-1.63309,-1.00316,1.87216,-0.47750
+4.70299,1.00831,-1.55254,-1.63281,-1.00322,1.87233,-0.47781
+4.70523,1.00797,-1.55285,-1.63254,-1.00327,1.87250,-0.47811
+4.70746,1.00764,-1.55314,-1.63227,-1.00333,1.87266,-0.47841
+4.70969,1.00757,-1.55321,-1.63222,-1.00334,1.87270,-0.47848
+4.71192,1.00720,-1.55354,-1.63191,-1.00341,1.87288,-0.47881
+4.71416,1.00684,-1.55386,-1.63161,-1.00347,1.87306,-0.47914
+4.71639,1.00648,-1.55418,-1.63132,-1.00353,1.87324,-0.47946
+4.71862,1.00613,-1.55450,-1.63103,-1.00359,1.87341,-0.47977
+4.72086,1.00579,-1.55481,-1.63074,-1.00366,1.87358,-0.48008
+4.72309,1.00545,-1.55511,-1.63046,-1.00372,1.87375,-0.48038
+4.72532,1.00512,-1.55541,-1.63019,-1.00378,1.87391,-0.48068
+4.72756,1.00508,-1.55545,-1.63015,-1.00379,1.87393,-0.48072
+4.72979,1.00466,-1.55584,-1.62979,-1.00387,1.87414,-0.48110
+4.73202,1.00424,-1.55622,-1.62943,-1.00395,1.87435,-0.48147
+4.73426,1.00384,-1.55660,-1.62907,-1.00403,1.87455,-0.48184
+4.73649,1.00344,-1.55697,-1.62873,-1.00411,1.87475,-0.48220
+4.73872,1.00305,-1.55733,-1.62838,-1.00419,1.87494,-0.48255
+4.74096,1.00266,-1.55769,-1.62805,-1.00427,1.87514,-0.48290
+4.74319,1.00228,-1.55804,-1.62771,-1.00435,1.87532,-0.48324
+4.74542,1.00191,-1.55839,-1.62739,-1.00442,1.87551,-0.48358
+4.74766,1.00155,-1.55872,-1.62706,-1.00450,1.87569,-0.48391
+4.74989,1.00119,-1.55906,-1.62675,-1.00458,1.87587,-0.48423
+4.75212,1.00084,-1.55938,-1.62644,-1.00465,1.87604,-0.48455
+4.75435,1.00049,-1.55971,-1.62613,-1.00473,1.87621,-0.48486
+4.75659,1.00015,-1.56002,-1.62583,-1.00480,1.87638,-0.48517
+4.75882,0.99982,-1.56033,-1.62553,-1.00487,1.87655,-0.48547
+4.76105,0.99950,-1.56064,-1.62524,-1.00494,1.87671,-0.48576
+4.76329,0.99940,-1.56073,-1.62514,-1.00497,1.87676,-0.48585
+4.76552,0.99905,-1.56109,-1.62477,-1.00507,1.87693,-0.48616
+4.76775,0.99871,-1.56145,-1.62441,-1.00516,1.87710,-0.48647
+4.76999,0.99838,-1.56180,-1.62405,-1.00526,1.87726,-0.48677
+4.77222,0.99806,-1.56214,-1.62370,-1.00535,1.87742,-0.48707
+4.77445,0.99774,-1.56247,-1.62335,-1.00544,1.87758,-0.48735
+4.77669,0.99742,-1.56280,-1.62301,-1.00553,1.87774,-0.48764
+4.77892,0.99712,-1.56313,-1.62268,-1.00562,1.87789,-0.48792
+4.78115,0.99705,-1.56320,-1.62261,-1.00564,1.87792,-0.48798
+4.78339,0.99671,-1.56355,-1.62224,-1.00574,1.87809,-0.48829
+4.78562,0.99637,-1.56391,-1.62188,-1.00584,1.87826,-0.48859
+4.78785,0.99604,-1.56425,-1.62152,-1.00594,1.87843,-0.48890
+4.79008,0.99571,-1.56459,-1.62117,-1.00603,1.87859,-0.48919
+4.79232,0.99540,-1.56493,-1.62082,-1.00613,1.87875,-0.48948
+4.79455,0.99508,-1.56526,-1.62048,-1.00622,1.87890,-0.48976
+4.79678,0.99478,-1.56558,-1.62015,-1.00632,1.87906,-0.49004
+4.79902,0.99474,-1.56562,-1.62011,-1.00632,1.87907,-0.49007
+4.80125,0.99443,-1.56595,-1.61977,-1.00642,1.87923,-0.49036
+4.80348,0.99412,-1.56627,-1.61943,-1.00651,1.87938,-0.49064
+4.80572,0.99395,-1.56645,-1.61924,-1.00657,1.87946,-0.49079
+4.80795,0.99353,-1.56692,-1.61874,-1.00671,1.87967,-0.49117
+4.81018,0.99312,-1.56739,-1.61824,-1.00685,1.87988,-0.49155
+4.81242,0.99271,-1.56785,-1.61775,-1.00698,1.88008,-0.49192
+4.81465,0.99231,-1.56830,-1.61727,-1.00712,1.88028,-0.49228
+4.81688,0.99192,-1.56874,-1.61679,-1.00726,1.88047,-0.49264
+4.81912,0.99153,-1.56918,-1.61633,-1.00739,1.88066,-0.49299
+4.82135,0.99115,-1.56960,-1.61587,-1.00752,1.88085,-0.49333
+4.82358,0.99078,-1.57002,-1.61541,-1.00765,1.88104,-0.49367
+4.82582,0.99042,-1.57044,-1.61497,-1.00778,1.88122,-0.49400
+4.82805,0.99006,-1.57084,-1.61453,-1.00791,1.88139,-0.49433
+4.83028,0.98971,-1.57124,-1.61410,-1.00803,1.88157,-0.49465
+4.83251,0.98936,-1.57163,-1.61367,-1.00816,1.88174,-0.49496
+4.83475,0.98902,-1.57202,-1.61326,-1.00828,1.88191,-0.49527
+4.83698,0.98869,-1.57240,-1.61284,-1.00840,1.88207,-0.49557
+4.83921,0.98836,-1.57277,-1.61244,-1.00852,1.88224,-0.49587
+4.84145,0.98804,-1.57313,-1.61204,-1.00864,1.88239,-0.49616
+4.84368,0.98773,-1.57349,-1.61165,-1.00876,1.88255,-0.49645
+4.84591,0.98742,-1.57385,-1.61126,-1.00888,1.88271,-0.49673
+4.84815,0.98711,-1.57419,-1.61088,-1.00899,1.88286,-0.49701
+4.85038,0.98682,-1.57454,-1.61051,-1.00910,1.88300,-0.49728
+4.85261,0.98652,-1.57487,-1.61014,-1.00922,1.88315,-0.49755
+4.85485,0.98643,-1.57497,-1.61003,-1.00925,1.88319,-0.49763
+4.85708,0.98611,-1.57534,-1.60962,-1.00937,1.88336,-0.49793
+4.85931,0.98579,-1.57571,-1.60923,-1.00949,1.88352,-0.49822
+4.86155,0.98547,-1.57606,-1.60884,-1.00961,1.88367,-0.49851
+4.86378,0.98516,-1.57641,-1.60846,-1.00972,1.88383,-0.49879
+4.86601,0.98486,-1.57676,-1.60808,-1.00984,1.88398,-0.49907
+4.86824,0.98456,-1.57710,-1.60771,-1.00995,1.88413,-0.49934
+4.87048,0.98427,-1.57743,-1.60734,-1.01006,1.88427,-0.49961
+4.87271,0.98421,-1.57750,-1.60727,-1.01008,1.88430,-0.49966
+4.87494,0.98391,-1.57783,-1.60690,-1.01020,1.88445,-0.49994
+4.87718,0.98361,-1.57817,-1.60653,-1.01031,1.88460,-0.50021
+4.87941,0.98349,-1.57831,-1.60638,-1.01036,1.88465,-0.50032
+4.88164,0.98318,-1.57869,-1.60594,-1.01050,1.88481,-0.50060
+4.88388,0.98288,-1.57907,-1.60551,-1.01063,1.88496,-0.50088
+4.88611,0.98258,-1.57945,-1.60508,-1.01076,1.88511,-0.50115
+4.88834,0.98228,-1.57982,-1.60466,-1.01090,1.88526,-0.50142
+4.89058,0.98199,-1.58018,-1.60425,-1.01103,1.88540,-0.50169
+4.89281,0.98171,-1.58053,-1.60384,-1.01115,1.88554,-0.50195
+4.89504,0.98143,-1.58088,-1.60344,-1.01128,1.88568,-0.50221
+4.89728,0.98120,-1.58116,-1.60312,-1.01138,1.88579,-0.50241
+4.89951,0.98085,-1.58158,-1.60265,-1.01153,1.88597,-0.50273
+4.90174,0.98051,-1.58200,-1.60218,-1.01167,1.88614,-0.50305
+4.90397,0.98017,-1.58240,-1.60173,-1.01182,1.88630,-0.50336
+4.90621,0.97984,-1.58280,-1.60128,-1.01196,1.88647,-0.50366
+4.90844,0.97951,-1.58320,-1.60084,-1.01209,1.88663,-0.50396
+4.91067,0.97919,-1.58358,-1.60040,-1.01223,1.88679,-0.50425
+4.91291,0.97887,-1.58396,-1.59997,-1.01236,1.88694,-0.50454
+4.91514,0.97857,-1.58434,-1.59955,-1.01250,1.88710,-0.50483
+4.91737,0.97826,-1.58470,-1.59914,-1.01263,1.88725,-0.50510
+4.91961,0.97796,-1.58506,-1.59873,-1.01276,1.88739,-0.50538
+4.92184,0.97767,-1.58542,-1.59833,-1.01289,1.88754,-0.50564
+4.92407,0.97739,-1.58576,-1.59793,-1.01302,1.88768,-0.50591
+4.92631,0.97710,-1.58611,-1.59754,-1.01314,1.88782,-0.50617
+4.92854,0.97696,-1.58628,-1.59735,-1.01320,1.88789,-0.50630
+4.93077,0.97668,-1.58662,-1.59696,-1.01333,1.88803,-0.50656
+4.93301,0.97639,-1.58696,-1.59657,-1.01345,1.88817,-0.50682
+4.93524,0.97628,-1.58710,-1.59641,-1.01350,1.88823,-0.50692
+4.93747,0.97599,-1.58745,-1.59602,-1.01363,1.88837,-0.50719
+4.93971,0.97571,-1.58779,-1.59563,-1.01375,1.88851,-0.50745
+4.94194,0.97557,-1.58796,-1.59544,-1.01382,1.88858,-0.50758
+4.94417,0.97529,-1.58831,-1.59503,-1.01395,1.88872,-0.50783
+4.94640,0.97501,-1.58866,-1.59462,-1.01408,1.88886,-0.50809
+4.94864,0.97477,-1.58897,-1.59426,-1.01420,1.88898,-0.50831
+4.95087,0.97449,-1.58932,-1.59386,-1.01433,1.88912,-0.50857
+4.95310,0.97421,-1.58967,-1.59346,-1.01447,1.88926,-0.50882
+4.95534,0.97407,-1.58984,-1.59326,-1.01453,1.88932,-0.50895
+4.95757,0.97379,-1.59019,-1.59285,-1.01466,1.88946,-0.50921
+4.95980,0.97352,-1.59054,-1.59245,-1.01479,1.88960,-0.50946
+4.96204,0.97341,-1.59068,-1.59229,-1.01485,1.88965,-0.50956
+4.96427,0.97313,-1.59103,-1.59189,-1.01498,1.88979,-0.50982
+4.96650,0.97285,-1.59137,-1.59149,-1.01511,1.88993,-0.51007
+4.96874,0.97271,-1.59154,-1.59130,-1.01517,1.89000,-0.51020
+4.97097,0.97243,-1.59189,-1.59089,-1.01530,1.89014,-0.51046
+4.97320,0.97215,-1.59224,-1.59050,-1.01543,1.89028,-0.51072
+4.97544,0.97201,-1.59241,-1.59030,-1.01550,1.89034,-0.51084
+4.97767,0.97173,-1.59275,-1.58990,-1.01563,1.89048,-0.51110
+4.97990,0.97145,-1.59310,-1.58951,-1.01576,1.89062,-0.51136
+4.98213,0.97131,-1.59327,-1.58931,-1.01582,1.89069,-0.51149
+4.98437,0.97103,-1.59362,-1.58891,-1.01595,1.89083,-0.51175
+4.98660,0.97075,-1.59396,-1.58852,-1.01608,1.89097,-0.51201
+4.98883,0.97064,-1.59409,-1.58836,-1.01613,1.89102,-0.51211
+4.99107,0.97035,-1.59444,-1.58797,-1.01626,1.89116,-0.51237
+4.99330,0.97007,-1.59478,-1.58758,-1.01639,1.89130,-0.51263
+4.99553,0.96993,-1.59495,-1.58738,-1.01646,1.89137,-0.51276
+4.99777,0.96965,-1.59530,-1.58699,-1.01659,1.89151,-0.51302
+5.00000,0.96937,-1.59564,-1.58660,-1.01672,1.89165,-0.51328
diff --git a/python/examples/path_in_pixels.csv b/python/examples/path_in_pixels.csv
index b236f1c7ea4ba6cb25001db54716627cbcfc1171..dd8348d4969d3c8b0ffbe86316541aa85328a492 100644
--- a/python/examples/path_in_pixels.csv
+++ b/python/examples/path_in_pixels.csv
@@ -1,41 +1,197 @@
-0.16240,0.57914
-0.16389,0.57914
-0.16537,0.57914
-0.19359,0.58663
-0.27228,0.59862
-0.32574,0.60311
-0.34801,0.60311
-0.38661,0.60311
-0.42819,0.60311
-0.47273,0.60311
-0.50986,0.59862
-0.55292,0.58963
-0.58261,0.58064
-0.58558,0.57764
-0.58558,0.57914
-0.57964,0.57465
-0.57073,0.57315
-0.56925,0.57315
-0.56776,0.57315
-0.56479,0.57315
-0.55589,0.57315
-0.54698,0.57764
-0.54549,0.58064
-0.53064,0.59113
-0.51579,0.60011
-0.50689,0.60760
-0.50540,0.60760
-0.49501,0.61210
-0.48610,0.61959
-0.48610,0.62108
-0.48610,0.62258
-0.50540,0.64655
-0.58261,0.68699
-0.62122,0.70497
-0.68655,0.73643
-0.72516,0.75140
-0.74743,0.75740
-0.81128,0.77837
-0.82910,0.78436
-0.83355,0.78436
-0.83355,0.78436
+0.10362,0.20547
+0.10511,0.20547
+0.10511,0.20697
+0.10808,0.20697
+0.10957,0.20697
+0.12297,0.20997
+0.12743,0.20997
+0.12892,0.20997
+0.14529,0.20997
+0.14827,0.20997
+0.15273,0.20997
+0.16910,0.21447
+0.17357,0.21447
+0.17803,0.21447
+0.19143,0.21447
+0.19589,0.21447
+0.19887,0.21447
+0.20929,0.21447
+0.21375,0.21447
+0.21673,0.21447
+0.22119,0.21597
+0.23161,0.21597
+0.23608,0.21597
+0.24054,0.21597
+0.26286,0.22048
+0.27328,0.22048
+0.31644,0.22799
+0.33132,0.22799
+0.34025,0.22799
+0.34621,0.22949
+0.37002,0.22949
+0.37448,0.22949
+0.39085,0.23399
+0.39234,0.23399
+0.39532,0.23399
+0.39978,0.23399
+0.40127,0.23549
+0.41467,0.23549
+0.41616,0.23549
+0.42508,0.23850
+0.42657,0.23850
+0.42657,0.24000
+0.42508,0.24300
+0.41913,0.24600
+0.40127,0.26102
+0.39681,0.26552
+0.38490,0.27303
+0.35811,0.29555
+0.35216,0.30155
+0.34770,0.30756
+0.32686,0.32858
+0.32388,0.33158
+0.32091,0.33458
+0.31495,0.33909
+0.30156,0.35861
+0.26882,0.39764
+0.26584,0.40215
+0.25840,0.41416
+0.25691,0.41566
+0.25542,0.42016
+0.25245,0.42467
+0.25245,0.42617
+0.24947,0.43668
+0.24947,0.43818
+0.24947,0.44869
+0.24947,0.45470
+0.26584,0.48172
+0.27179,0.48773
+0.27775,0.49373
+0.30007,0.52226
+0.30602,0.52826
+0.31495,0.53127
+0.32091,0.53877
+0.32984,0.54328
+0.34918,0.56280
+0.35365,0.56580
+0.36555,0.57331
+0.38639,0.58231
+0.38937,0.58231
+0.39234,0.58231
+0.40276,0.58532
+0.40723,0.58682
+0.42508,0.59132
+0.42657,0.59282
+0.43104,0.59282
+0.43401,0.59282
+0.44443,0.59282
+0.44890,0.59583
+0.45187,0.59583
+0.46080,0.59583
+0.46527,0.59583
+0.47271,0.59583
+0.47866,0.59583
+0.48759,0.59583
+0.51885,0.58982
+0.52926,0.58682
+0.53522,0.58532
+0.54563,0.58532
+0.58879,0.57331
+0.59772,0.57030
+0.60219,0.57030
+0.62302,0.56280
+0.62749,0.56280
+0.63195,0.55979
+0.64535,0.55679
+0.64684,0.55679
+0.65130,0.55379
+0.66172,0.55078
+0.66321,0.55078
+0.66618,0.54928
+0.66916,0.54628
+0.67362,0.54478
+0.67511,0.54328
+0.67660,0.54178
+0.68255,0.53577
+0.68255,0.53427
+0.68404,0.52977
+0.68404,0.52826
+0.68702,0.51926
+0.68851,0.51775
+0.68851,0.51475
+0.69297,0.50424
+0.69446,0.50274
+0.69446,0.49824
+0.70339,0.47572
+0.70637,0.46521
+0.70934,0.45620
+0.71530,0.43968
+0.71678,0.43368
+0.71678,0.43217
+0.72125,0.41716
+0.72125,0.41266
+0.72125,0.40815
+0.72571,0.37662
+0.72571,0.37212
+0.72571,0.36912
+0.72571,0.36461
+0.72571,0.35410
+0.72571,0.35110
+0.72571,0.33458
+0.72571,0.33308
+0.72571,0.33008
+0.72571,0.32107
+0.71678,0.29104
+0.71530,0.28654
+0.71232,0.27753
+0.70190,0.25201
+0.69892,0.24150
+0.69744,0.23699
+0.68851,0.22648
+0.68107,0.20997
+0.67660,0.20246
+0.67362,0.19796
+0.65725,0.17093
+0.65577,0.16493
+0.64237,0.14691
+0.63939,0.14541
+0.63791,0.14091
+0.63642,0.13940
+0.63493,0.13790
+0.63493,0.13640
+0.63344,0.13640
+0.63344,0.13490
+0.63791,0.13490
+0.63939,0.13790
+0.64832,0.13790
+0.66172,0.13940
+0.66767,0.14091
+0.68107,0.14541
+0.68553,0.14541
+0.69000,0.14541
+0.69148,0.14541
+0.70785,0.14841
+0.71232,0.14841
+0.71530,0.15142
+0.71976,0.15142
+0.73018,0.15142
+0.73464,0.15442
+0.73911,0.15442
+0.74060,0.15442
+0.75548,0.15742
+0.75994,0.15742
+0.76143,0.15742
+0.76590,0.16042
+0.77483,0.16042
+0.77631,0.16042
+0.77780,0.16042
+0.77929,0.16192
+0.78078,0.16192
+0.78227,0.16192
+0.78376,0.16192
+0.78524,0.16192
+0.78673,0.16192
+0.78822,0.16192
+0.78971,0.16192
+0.79120,0.16192
+0.79120,0.16192
diff --git a/python/ur_simple_control/.managers.py.swp b/python/ur_simple_control/.managers.py.swp
new file mode 100644
index 0000000000000000000000000000000000000000..0ef38c10b8c6a2b53dce0c51730b4c598d115d1d
Binary files /dev/null and b/python/ur_simple_control/.managers.py.swp differ
diff --git a/python/ur_simple_control/__pycache__/managers.cpython-310.pyc b/python/ur_simple_control/__pycache__/managers.cpython-310.pyc
index 82676cbf4c37426f13dd04a2b2699f68f9ee3f24..c10725690a79e90b18d13c2a9bb6da1853d04ae0 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/clik/.clik_point_to_point.py.swp b/python/ur_simple_control/clik/.clik_point_to_point.py.swp
deleted file mode 100644
index a49da600dc00a345bd81c6a1d2409732714750a6..0000000000000000000000000000000000000000
Binary files a/python/ur_simple_control/clik/.clik_point_to_point.py.swp and /dev/null differ
diff --git a/python/ur_simple_control/clik/.clik_trajectory_following.py.swp b/python/ur_simple_control/clik/.clik_trajectory_following.py.swp
index 3cc7c72825cf0cd7f429c698dc4ced2dd40f36f5..ed64e06e4253d21eae569753ab3276d0282b66b2 100644
Binary files a/python/ur_simple_control/clik/.clik_trajectory_following.py.swp and b/python/ur_simple_control/clik/.clik_trajectory_following.py.swp 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 0dfee1861238ee36321ba4d1ea3b45c06492a33d..35180bad01703e847b6908f23e4ac77c45afb34b 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_trajectory_following.cpython-310.pyc b/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-310.pyc
new file mode 100644
index 0000000000000000000000000000000000000000..291588f9bd393e2ee55972ae03feea53f3844d50
Binary files /dev/null and b/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-310.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 d5ce006a6150affd24a4f07af2af03af32727e9f..a85c17654827d05f1528c7c78cfcedb1d9ad324c 100644
--- a/python/ur_simple_control/clik/clik_point_to_point.py
+++ b/python/ur_simple_control/clik/clik_point_to_point.py
@@ -5,9 +5,7 @@ import argparse
 from functools import partial
 from ur_simple_control.managers import ControlLoopManager, RobotManager
 
-# TODO move actually using this (main file and arguments to an example file).
-# but do make assertions that certain arguments have to exist.
-# this is good, just not separated the way it should be, like dmp is for example.
+
 
 """
 Every imaginable magic number, flag and setting is put in here.
@@ -18,8 +16,11 @@ All the sane defaults are here, and you can change any number of them as an argu
 when running your program. If you want to change a drastic amount of them, and
 not have to run a super long commands, just copy-paste this function and put your
 own parameters as default ones.
-NOTE: the args object obtained from args = parser.get_args()
+NOTE1: the args object obtained from args = parser.get_args()
 is pushed all around the rest of the code (because it's tidy), so don't change their names.
+NOTE2: that you need to copy-paste and add aguments you need
+to the script you will be writing. This is kept here 
+only as a convenient reference point.
 """
 def get_args():
     parser = argparse.ArgumentParser(description='Run closed loop inverse kinematics \
@@ -64,6 +65,19 @@ def get_args():
 #######################################################################
 #                             controllers                             #
 #######################################################################
+"""
+controllers general
+-----------------------
+really trully just the equation you are running.
+ideally, everything else is a placeholder,
+meaning you can swap these at will.
+if a controller has some additional arguments,
+those are put in via functools.partial in getClikController,
+so that you don't have to worry about how your controller is handled in
+the actual control loop after you've put it in getClikController,
+which constructs the controller from an argument to the file.
+"""
+
 def dampedPseudoinverse(tiknonov_damp, J, err_vector):
     qd = J.T @ np.linalg.inv(J @ J.T + np.eye(J.shape[0], J.shape[0]) * tiknonov_damp) @ err_vector
     return qd
@@ -73,6 +87,8 @@ def jacobianTranspose(J, err_vector):
     return qd
 
 """
+getClikController
+-----------------
 A string argument is used to select one of these.
 It's a bit ugly, bit totally functional and OK solution.
 we want all of theme to accept the same arguments, i.e. the jacobian and the error vector.
@@ -108,6 +124,13 @@ def getClikController(args):
 # modularity yo
 # past data to comply with the API
 # TODO make this a kwarg or whatever to be more lax with this
+"""
+controlLoopClik
+---------------
+generic control loop for clik (handling error to final point etc).
+in some version of the universe this could be extended to a generic
+point-to-point motion control loop.
+"""
 def controlLoopClik(robot, clik_controller, i, past_data):
     breakFlag = False
     save_past_dict = {}
diff --git a/python/ur_simple_control/clik/clik_trajectory_following.py b/python/ur_simple_control/clik/clik_trajectory_following.py
index 141b90d6ecb38c964b8f3e739911751062cb0bdd..cf25427a54257f96ae8bd0e14069bae3483b8ff6 100644
--- a/python/ur_simple_control/clik/clik_trajectory_following.py
+++ b/python/ur_simple_control/clik/clik_trajectory_following.py
@@ -8,8 +8,7 @@
 
 import numpy as np
 import pinocchio as pin
-import os
-import sys
+import copy
 
 #######################################################################
 #                    map the pixels to a 3D plane                     #
@@ -17,6 +16,8 @@ import sys
 """
 map2DPathTo3DPlane
 --------------------
+TODO: THINK AND FINALIZE THE FRAME
+TODO: WRITE PRINT ABOUT THE FRAME TO THE USER
 assumptions:
 - origin in top-left corner (natual for western latin script writing)
 - x goes right (from TCP)
@@ -29,16 +30,16 @@ Returns a 3D path appropriately scaled, and placed into the first quadrant
 of the x-y plane of the body-frame (TODO: what is the body frame if we're general?)
 """
 def map2DPathTo3DPlane(path_2D, width, height):
-    z = np.zeros((len(path),1))
-    path_3D = np.hstack((path,z))
+    z = np.zeros((len(path_2D),1))
+    path_3D = np.hstack((path_2D,z))
     # scale the path to m
-    path[:,0] = path[:,0] * width
-    path[:,1] = path[:,1] * height
+    path_3D[:,0] = path_3D[:,0] * width
+    path_3D[:,1] = path_3D[:,1] * height
     # in the new coordinate system we're going in the -y direction
     # TODO this is a demo specific hack, 
     # make it general for a future release
-    path[:,1] = -1 * path[:,1] + args.height
-    return path
+    path_3D[:,1] = -1 * path_3D[:,1] + height
+    return path_3D
 
 
 """
@@ -78,8 +79,10 @@ TODO: make this a kwarg with a neural transform as default.
      so this makes perfect sense to ensure correctness
 """
 def clikCartesianPathIntoJointPath(path, args, robot, \
-        clikController, q_init, transf_body_task_frame):
+        clikController, q_init, R, p):
+
     transf_body_to_task_frame = pin.SE3(R, p)
+    q = copy.deepcopy(q_init)
 
     for i in range(len(path)):
         path[i] = transf_body_to_task_frame.act(path[i])
@@ -108,18 +111,18 @@ def clikCartesianPathIntoJointPath(path, args, robot, \
             SEerror = robot.data.oMi[robot.JOINT_ID].actInv(Mgoal)
             err_vector = pin.log6(SEerror).vector 
             if np.linalg.norm(err_vector) < args.clik_goal_error:
-                if not n_iter == args.args.max_init_clik_iterations:
+                if not n_iter == args.max_init_clik_iterations:
                     print("converged in", i)
                     break
             J = pin.computeJointJacobian(robot.model, robot.data, q, robot.JOINT_ID)
             qd = clikController(J, err_vector)
             # we're integrating this fully offline of course
-            q = pin.integrate(robot.model, q, qd * dt)
-            if (not n_iter == args.args.max_init_clik_iterations) and (i % 10 == 0):
+            q = pin.integrate(robot.model, q, qd * robot.dt)
+            if (not n_iter == args.max_init_clik_iterations) and (i % 10 == 0):
                 qs.append(q[:6])
 
         # just skipping the first run with one stone
-        if n_iter == args.args.max_init_clik_iterations:
+        if n_iter == args.max_init_clik_iterations:
             n_iter = args.max_running_clik_iterations
         else:
             if i == args.max_running_clik_iterations - 1:
@@ -136,7 +139,7 @@ def clikCartesianPathIntoJointPath(path, args, robot, \
     joint_trajectory = np.hstack((t, qs))
     # TODO handle saving more consistently/intentionally
     # (although this definitely works right now and isn't bad, just mid)
-    np.savetxt("./new_traj.csv", joint_trajectory, delimiter=',', fmt='%.5f')
+    np.savetxt("./joint_trajectory.csv", joint_trajectory, delimiter=',', fmt='%.5f')
     return joint_trajectory
 
 
diff --git a/python/ur_simple_control/dmp/__pycache__/dmp.cpython-310.pyc b/python/ur_simple_control/dmp/__pycache__/dmp.cpython-310.pyc
index e35c4b88f393d22f12a90e35d11ca47eef6680e6..0f8c0ab2560a9677153f22c766fe22fa96a859c8 100644
Binary files a/python/ur_simple_control/dmp/__pycache__/dmp.cpython-310.pyc and b/python/ur_simple_control/dmp/__pycache__/dmp.cpython-310.pyc differ
diff --git a/python/ur_simple_control/dmp/dmp.py b/python/ur_simple_control/dmp/dmp.py
index 2e6c7343c3ae5f14c9c196218a4dca77b5651ea9..2741bd47abbf7bb8cc6f4c5a1ee051d44760b4ee 100644
--- a/python/ur_simple_control/dmp/dmp.py
+++ b/python/ur_simple_control/dmp/dmp.py
@@ -61,17 +61,16 @@ class DMP:
 
     def load_trajectory_from_file(self, file_path):
         # load trajectory.  this is just joint positions.
-        data = np.genfromtxt(file_path, delimiter=',')
-        self.time = data[:, 0]
+        trajectory = np.genfromtxt(file_path, delimiter=',')
+        self.time = trajectory [:, 0]
         self.time = self.time.reshape(1, len(self.time))
-        self.y = np.array(data[:, 1:]).T
+        self.y = np.array(trajectory[:, 1:]).T
 
     def load_trajectory(self, trajectory):
         # load trajectory.  this is just joint positions.
-        data = np.genfromtxt(file_path, delimiter=',')
-        self.time = data[:, 0]
+        self.time = trajectory[:, 0]
         self.time = self.time.reshape(1, len(self.time))
-        self.y = np.array(data[:, 1:]).T
+        self.y = np.array(trajectory[:, 1:]).T
 
     def reset(self):
         self.x = np.vstack((np.zeros((self.n, 1)), self.y0, 1.))
diff --git a/python/ur_simple_control/managers.py b/python/ur_simple_control/managers.py
index c7f17cfac856e0881e5fa5cbf8bbcf7073934819..b7868937584f0cbe19d899c6ce0061d8a3ba066c 100644
--- a/python/ur_simple_control/managers.py
+++ b/python/ur_simple_control/managers.py
@@ -128,7 +128,7 @@ class ControlLoopManager:
         for i in range(100):
             vel_cmd = np.zeros(6)
             self.robot_manager.rtde_control.speedJ(vel_cmd, 0.1, 1.0 / 500)
-        exit()
+        #exit()
 
     """
     run
@@ -154,6 +154,8 @@ class ControlLoopManager:
                 self.past_data[key].append(latest_to_save_dict[key])
             
             # log the data
+            for key in log_entry_dict:
+                self.log_dict[key][i] = log_entry_dict[key]
 
             # break if done
             if breakFlag:
@@ -246,6 +248,9 @@ class RobotManager:
             self.rtde_io = RTDEIOInterface("127.0.0.1")
 
         # ur specific magic numbers 
+        # TODO: this is 8 in pinocchio and that's what you actually use 
+        # if we're being real lmao
+        # the TODO here is make this consistent obviously
         self.n_joints = 6
         # last joint because pinocchio adds base frame as 0th joint.
         # and since this is unintuitive, we add the other variable too
@@ -259,18 +264,31 @@ class RobotManager:
         # we're not saying it's qdd because it isn't directly (apparently)
         # TODO: check that again
         self.acceleration = args.acceleration
+        assert args.speed_slider <= 1.0 and args.acceleration > 0.0
+        self.speed_slider = args.speed_slider
         if not args.pinocchio_only:
             self.rtde_io.setSpeedSlider(args.speed_slider)
         self.max_iterations = args.max_iterations
         # TODO: these are almost certainly higher
         # maybe you want to have them high and cap the rest with speed slider?
         # idk really, but it's better to have this low and burried for safety and robot longevity reasons
-        self.max_qdd = 1.7
+        self.max_qdd = 1.7 * args.speed_slider
         # NOTE: i had this thing at 2 in other code
-        self.max_qd = 0.5
+        self.max_qd = 0.5 * args.speed_slider
         # error limit 
         # TODO this is clik specific, put it in a better place
         self.goal_error = args.goal_error
+
+    """
+    setSpeedSlider
+    ---------------
+    update in all places
+    """
+    def setSpeedSlider(self, value):
+        assert value <= 1.0 and value > 0.0
+        if not self.args.pinocchio_only:
+            self.rtde_io.setSpeedSlider(value)
+        self.speed_slider = value
         
     """
     getQ
@@ -327,12 +345,13 @@ class RobotManager:
                 # the /255 is to get it dimensionless
                 # the gap is 5cm
                 # thus half the gap is 0.025m and we only do si units here
-                q.append(self.gripper_vel)
-                q.append(self.gripper_vel)
+                # no need to deepcopy because only literals are passed
+                qd.append(self.gripper_vel)
+                qd.append(self.gripper_vel)
             else:
                 # just fill it with zeros otherwise
-                q.append(0.0)
-                q.append(0.0)
+                qd.append(0.0)
+                qd.append(0.0)
         # let's just have both options for getting q, it's just a 8d float list
         # readability is a somewhat subjective quality after all
             qd = np.array(qd)
diff --git a/python/ur_simple_control/util/.calib_board_hacks.py.swp b/python/ur_simple_control/util/.calib_board_hacks.py.swp
new file mode 100644
index 0000000000000000000000000000000000000000..ac3783692611d57bcdac238caeaf173dd2429adf
Binary files /dev/null and b/python/ur_simple_control/util/.calib_board_hacks.py.swp 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
new file mode 100644
index 0000000000000000000000000000000000000000..984653c2a30827fec2c4c0d25253583930002d57
Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/calib_board_hacks.cpython-310.pyc differ
diff --git a/python/ur_simple_control/util/__pycache__/draw_path.cpython-310.pyc b/python/ur_simple_control/util/__pycache__/draw_path.cpython-310.pyc
index 4e8050f7d0467e3e6bb82fad86dbd2b2d79b9265..f0a5d1e7903972505b217535a151be83e1115c63 100644
Binary files a/python/ur_simple_control/util/__pycache__/draw_path.cpython-310.pyc and b/python/ur_simple_control/util/__pycache__/draw_path.cpython-310.pyc differ
diff --git a/python/ur_simple_control/util/__pycache__/freedrive.cpython-310.pyc b/python/ur_simple_control/util/__pycache__/freedrive.cpython-310.pyc
new file mode 100644
index 0000000000000000000000000000000000000000..c2ca7a5fb770db91952c5fc6e1ccd4911a035ba4
Binary files /dev/null and b/python/ur_simple_control/util/__pycache__/freedrive.cpython-310.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 0d8acd5a5daacbf59c470dfb5fa698a953f28525..286ed50a44785a09a86ae21d15345ce4dc9fa29a 100644
--- a/python/ur_simple_control/util/calib_board_hacks.py
+++ b/python/ur_simple_control/util/calib_board_hacks.py
@@ -3,11 +3,12 @@
 
 import pinocchio as pin
 import numpy as np
-import sys
 import time
 import copy
 from ur_simple_control.managers import RobotManager
 from ur_simple_control.util.freedrive import freedrive
+# used to deal with freedrive's infinite while loop
+import threading
 
 """
 general
@@ -37,6 +38,7 @@ def fitNormalVector(positions):
     print("if the following give you roughly the same number, it worked")
     for p in positions:
         print("cdot", p @ n)
+    return n
 
 """
 constructFrameFromNormalVector
@@ -83,40 +85,85 @@ handleUserToHandleTCPPose
 4. release the freedrive and then start doing the calibration process
 """
 def handleUserToHandleTCPPose(robot):
-    print("Whatever code you ran wants you to calibrate the plane on which you will be doing\
-            your things. Put the end-effector at the top left corner of the plane \
-            where you'll be doing said things. \n
-            Make sure the orientation is reasonably correct as that will be \
-            used as the initial estimate of the orientation, \
-            which is what you will get as an output from this calibration procedure.\
-            The end-effector will go down (it's TCP z pozitive direction) and touch the thing\
-            the number of times you specified (if you are not aware of this, check the\
-            arguments of the program you ran.\n \
-            The robot will now enter freedrive mode so that you can manually put\
-            the end-effector where it's supposed to be.\n \
-            When you did it, press 'Y', or press 'n' to exit.")
+    print("""
+    Whatever code you ran wants you to calibrate the plane on which you will be doing
+    your things. Put the end-effector at the top left corner SOMEWHAT ABOVE of the plane 
+    where you'll be doing said things. \n
+    Make sure the orientation is reasonably correct as that will be 
+    used as the initial estimate of the orientation, 
+    which is what you will get as an output from this calibration procedure.
+    The end-effector will go down (it's TCP z pozitive direction) and touch the thing
+    the number of times you specified (if you are not aware of this, check the
+    arguments of the program you ran.\n 
+    The robot will now enter freedrive mode so that you can manually put
+    the end-effector where it's supposed to be.\n 
+    When you did it, press 'Y', or press 'n' to exit.
+    """)
     while True:
         answer = input("Ready to calibrate or exit? [Y/n]")
         if answer == 'n' or answer == 'N':
-            print("The whole program will exit. Change the argument to --no-calibrate or \
-                    change code that lead you here.")
+            print("""
+    The whole program will exit. Change the argument to --no-calibrate or 
+    change code that lead you here.
+            """)
             exit()
         elif answer == 'y' or answer == 'Y':
-            print("The robot will now enter freedrive mode. Put the end-effector to the \
-                    top left corner of your plane and mind the orientation.")
+            print("""
+    The robot will now enter freedrive mode. Put the end-effector to the 
+    top left corner of your plane and mind the orientation.
+                    """)
             break
         else:
             print("Whatever you typed in is neither 'Y' nor 'n'. Give it to me straight cheif!")
             continue
-    freedrive()
+    print("""
+    Entering freedrive. 
+    Put the end-effector to the top left corner of your plane and mind the orientation.
+    Press Enter to stop freedrive.
+    """)
+    time.sleep(2)
+    # it is necessary both to have freedrive as an infinite loop,
+    # and to run it in another thread to stop it.
+    # TODO: make this pretty (redefine freedrive or something, idc,
+    # just don't have it here)
+    def freedriveThreadFunction(robot, stop_event):
+        robot.rtde_control.freedriveMode()
+        while not stop_event.is_set():
+            q = robot.rtde_receive.getActualQ()
+            q.append(0.0)
+            q.append(0.0)
+            pin.forwardKinematics(robot.model, robot.data, np.array(q))
+            print(robot.data.oMi[6])
+            print("pin:", *robot.data.oMi[6].translation.round(4), \
+                    *pin.rpy.matrixToRpy(robot.data.oMi[6].rotation).round(4))
+            print("ur5:", *np.array(robot.rtde_receive.getActualTCPPose()).round(4))
+            print("q:", *np.array(q).round(4))
+            time.sleep(0.005)
+
+    # Create a stop event
+    stop_event = threading.Event()
+
+    # Start freedrive in a separate thread
+    freedrive_thread = threading.Thread(target=freedriveThreadFunction, args=(robot, stop_event,))
+    freedrive_thread.start()
+
+    input("Press Enter to stop...")
+    stop_event.set()
+
+    # join child thread (standard practise)
+    freedrive_thread.join()
+
     while True:
-        answer = input("You got the end-effector in the correct pose and are ready \
-                to start calibrating or do you want to exit? [Y/n]")
+        answer = input("""
+    I am assuming you got the end-effector in the correct pose. \n
+    Are you ready to start calibrating or do you want to exit? [Y/n]
+    """)
         if answer == 'n' or answer == 'N':
             print("The whole program will exit. Goodbye!")
             exit()
         elif answer == 'y' or answer == 'Y':
             print("Calibration about to start. Have your hand on the big red stop button!")
+            time.sleep(2)
             break
         else:
             print("Whatever you typed in is neither 'Y' nor 'n'. Give it to me straight cheif!")
@@ -125,14 +172,19 @@ def handleUserToHandleTCPPose(robot):
 
 
 def calibratePlane(robot, n_tests):
+    # i don't care which speed slider you have,
+    # because 0.4 is the only reasonable one here
+    old_speed_slider = robot.speed_slider
+    robot.setSpeedSlider(0.4)
     handleUserToHandleTCPPose(robot)
+    q_init = copy.deepcopy(robot.getQ())
 
     init_pose = robot.rtde_receive.getActualTCPPose()
     new_pose = copy.deepcopy(init_pose)
 
     # TODO change this, i just shoved the pen through the board
     # the point is go up, but the frame is the TCP frame
-    speed = [0, 0, -0.3, 0, 0, 0]
+    speed = [0, 0, -0.1, 0, 0, 0]
     n_tests = 10
     # TODO: for the love of god please actually read this when you begin
     # instead of having this horror here
@@ -147,7 +199,6 @@ def calibratePlane(robot, n_tests):
     pin.forwardKinematics(robot.model, robot.data, q)
     # this apsolutely has to be deepcopied aka copy-constructed
     R_initial_estimate = copy.deepcopy(robot.data.oMi[robot.JOINT_ID].rotation)
-    translation = copy.deepcopy(robot.data.oMi[robot.JOINT_ID].translation)
 
     positions = []
     for i in range(n_tests):
@@ -159,6 +210,12 @@ def calibratePlane(robot, n_tests):
         print("pin:", *robot.data.oMi[6].translation.round(4), \
                 *pin.rpy.matrixToRpy(robot.data.oMi[6].rotation).round(4))
         print("ur5:", *np.array(robot.rtde_receive.getActualTCPPose()).round(4))
+
+        # the first contact point is the translation vector 
+        # --> this is how the whole program is set up
+        if i == 0:
+            translation = copy.deepcopy(robot.data.oMi[robot.JOINT_ID].translation)
+
         positions.append(copy.deepcopy(robot.data.oMi[6].translation))
         if i < n_tests -1:
             current_pose = robot.rtde_receive.getActualTCPPose()
@@ -166,6 +223,7 @@ def calibratePlane(robot, n_tests):
             # go back up (assuming top-left is highest incline)
             # TODO: make this assumption an argument, or print it at least
             new_pose[2] = init_pose[2]
+            # TODO make these moveLs slower, they're way too fast
             robot.rtde_control.moveL(new_pose)
             new_pose[0] = init_pose[0] + np.random.random() * 0.3
             new_pose[1] = init_pose[1] - np.random.random() * 0.2
@@ -183,14 +241,16 @@ def calibratePlane(robot, n_tests):
         n = fitNormalVector(positions)
         R = constructFrameFromNormalVector(R_initial_estimate, n)
 
-    current_pose = rtde_receive.getActualTCPPose()
+    current_pose = robot.rtde_receive.getActualTCPPose()
     new_pose = copy.deepcopy(current_pose)
     new_pose[2] = init_pose[2]
     robot.rtde_control.moveL(new_pose)
     robot.rtde_control.moveL(init_pose)
     
+    # put the speed slider back to its previous value
+    robot.setSpeedSlider(old_speed_slider)
     print('also, the translation vector is:', translation)
-    return R, translation
+    return R, translation, q_init
 
 if __name__ == "__main__":
     robot = RobotManager()
diff --git a/python/ur_simple_control/util/draw_path.py b/python/ur_simple_control/util/draw_path.py
index b93166fab79ef350cb20d4d57323d83dec2e0e54..0fa950d844b57782611bfcf0dcb3b19552cb1311 100644
--- a/python/ur_simple_control/util/draw_path.py
+++ b/python/ur_simple_control/util/draw_path.py
@@ -40,7 +40,7 @@ class DrawPathManager:
     # made to save and exit
     def accept(self, event):
         if event.key == "enter":
-            print("path points:")
+            print("pixel path:")
             print(self.path)
             self.disconnect()
             # TODO: ensure this runs fine after packaging
diff --git a/python/ur_simple_control/util/freedrive.py b/python/ur_simple_control/util/freedrive.py
index 7c89d701c31e87193b01127d667a2529638170b5..552333abc013b9f1f99eeedcd512c8d2b7e88176 100644
--- a/python/ur_simple_control/util/freedrive.py
+++ b/python/ur_simple_control/util/freedrive.py
@@ -11,10 +11,11 @@ def freedrive(robot):
         q.append(0.0)
         q.append(0.0)
         pin.forwardKinematics(robot.model, robot.data, np.array(q))
-        print(robot.data.oMi[6])
-        print("pin:", *robot.data.oMi[6].translation.round(4), \
-                *pin.rpy.matrixToRpy(robot.data.oMi[6].rotation).round(4))
-        print("ur5:", *np.array(robot.rtde_receive.getActualTCPPose()).round(4))
+    #    print(robot.data.oMi[6])
+    #    print("pin:", *robot.data.oMi[6].translation.round(4), \
+    #            *pin.rpy.matrixToRpy(robot.data.oMi[6].rotation).round(4))
+    #    print("ur5:", *np.array(robot.rtde_receive.getActualTCPPose()).round(4))
+    #    print("q:", *np.array(q).round(4))
         time.sleep(0.005)
 
 if __name__ == "__main__":
diff --git a/python/ur_simple_control/visualize/__pycache__/visualize.cpython-310.pyc b/python/ur_simple_control/visualize/__pycache__/visualize.cpython-310.pyc
index 68ca46ae7f81ca421c192f85191a01c73b82c31f..f4f3e5fc87b29baec3f22e19efb26294ddcf7091 100644
Binary files a/python/ur_simple_control/visualize/__pycache__/visualize.cpython-310.pyc and b/python/ur_simple_control/visualize/__pycache__/visualize.cpython-310.pyc differ
diff --git a/python/ur_simple_control/visualize/visualize.py b/python/ur_simple_control/visualize/visualize.py
index a1cb99723b48825efaf99d7615bf824b08b9e2d3..ccee92a3c92e458720304dcb1c464e7413d65845 100644
--- a/python/ur_simple_control/visualize/visualize.py
+++ b/python/ur_simple_control/visualize/visualize.py
@@ -6,6 +6,7 @@ import matplotlib.pyplot as plt
 # every key is one subplot, and it's value
 # is what you plot
 def plotFromDict(plot_data, 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
@@ -19,10 +20,8 @@ def plotFromDict(plot_data, args):
     # 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):
-        ax_dict[data_key] = plt.subplot(subplot_col_row + str(i))
-        for j in range(len(plot_data[data_key])):
-            ax_dict[data_key].plot(t, plot_data[data_key][:,j], color=colors[i], label=day_key)
-        # TODO maybe write a hack for getting the legend to work (all lines are the same color so 
-        # we're not using it as intended
+        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].legend()
     plt.show()