diff --git a/python/convenience_tool_box/check_tcp_payload b/convenience_tool_box/check_tcp_payload
similarity index 100%
rename from python/convenience_tool_box/check_tcp_payload
rename to convenience_tool_box/check_tcp_payload
diff --git a/python/convenience_tool_box/currents.png b/convenience_tool_box/currents.png
similarity index 100%
rename from python/convenience_tool_box/currents.png
rename to convenience_tool_box/currents.png
diff --git a/python/convenience_tool_box/frame_validation.py b/convenience_tool_box/frame_validation.py
similarity index 100%
rename from python/convenience_tool_box/frame_validation.py
rename to convenience_tool_box/frame_validation.py
diff --git a/python/convenience_tool_box/freedrive.py b/convenience_tool_box/freedrive.py
similarity index 100%
rename from python/convenience_tool_box/freedrive.py
rename to convenience_tool_box/freedrive.py
diff --git a/python/convenience_tool_box/freedrive_v2.0.py b/convenience_tool_box/freedrive_v2.0.py
similarity index 100%
rename from python/convenience_tool_box/freedrive_v2.0.py
rename to convenience_tool_box/freedrive_v2.0.py
diff --git a/python/convenience_tool_box/ft_readings.py b/convenience_tool_box/ft_readings.py
similarity index 100%
rename from python/convenience_tool_box/ft_readings.py
rename to convenience_tool_box/ft_readings.py
diff --git a/python/convenience_tool_box/fts.png b/convenience_tool_box/fts.png
similarity index 100%
rename from python/convenience_tool_box/fts.png
rename to convenience_tool_box/fts.png
diff --git a/python/convenience_tool_box/jog_example b/convenience_tool_box/jog_example
similarity index 100%
rename from python/convenience_tool_box/jog_example
rename to convenience_tool_box/jog_example
diff --git a/python/convenience_tool_box/measuring_stick.py b/convenience_tool_box/measuring_stick.py
similarity index 100%
rename from python/convenience_tool_box/measuring_stick.py
rename to convenience_tool_box/measuring_stick.py
diff --git a/python/convenience_tool_box/notes.md b/convenience_tool_box/notes.md
similarity index 100%
rename from python/convenience_tool_box/notes.md
rename to convenience_tool_box/notes.md
diff --git a/python/convenience_tool_box/open_close_gripper.py b/convenience_tool_box/open_close_gripper.py
similarity index 100%
rename from python/convenience_tool_box/open_close_gripper.py
rename to convenience_tool_box/open_close_gripper.py
diff --git a/python/convenience_tool_box/taus.png b/convenience_tool_box/taus.png
similarity index 100%
rename from python/convenience_tool_box/taus.png
rename to convenience_tool_box/taus.png
diff --git a/development_plan.toml b/development_plan.toml
index b39b40a65c252a70b8445f0c0ee9e1519bbfcb09..8c4361b4572fc1934bff8669b6098c41ed7344cb 100644
--- a/development_plan.toml
+++ b/development_plan.toml
@@ -77,7 +77,7 @@ dependencies = []
 purpose = """making typing possible - easier code writting and debugging, making library professional-grade"""
 # -1 means it should be a sum over sub-items
 hours_required = 10
-is_done = false
+is_done = true
 
 
 [[project_plan.action_items.action_items]]
@@ -107,6 +107,8 @@ for the pinocchio-only option.
 these can be done via ifs in those functions because 1 if is ok.
 
 various things are to be implemented with interfaces (like 2 arms, which just gives you more functions, but which only make sense if the robot has two arms). interfaces don't exist in python, but you can do multiple inheritance. these extra functions should thus be made available by inheriting stuff like TwoArmsRobot etc. have one such class for simulated robots as they all use the same getq etc.
+
+UPDATE: BTW, this took more like 3 full days than 4 hours. getting OOP right is hard and i have 0 real experience with it. i'm not even sure i got the design right. also, setting the scope was hella difficult. this required both seba's help and chatgpt
 """
 priority = 1
 deadline = 2025-01-31
@@ -114,7 +116,7 @@ dependencies = []
 purpose = """making codebase usable"""
 # -1 means it should be a sum over sub-items
 hours_required = 4
-is_done = false
+is_done = true
 
 
 [[project_plan.action_items.action_items]]
@@ -242,7 +244,7 @@ with some different parameters - finish that. this checks whether anything runs,
 and whether things converge. probably a good idea to run some of these multiple times
 in the case they are not supposed to converge every time (if you have crazy init conditions etc).
 """
-priority = 1
+priority = 2
 deadline = ["before going to vasteros", 2025-02-10]
 dependencies = ["smc refactor"]
 purpose = """makes you sleep safe at night, saves a lot of time after writing of a feature -
diff --git a/examples/cart_pulling/behavior_tree.py b/examples/cart_pulling/behavior_tree.py
new file mode 100644
index 0000000000000000000000000000000000000000..f5305d1e392b2ba8150dc1010c25dbb4bc57a5c7
--- /dev/null
+++ b/examples/cart_pulling/behavior_tree.py
@@ -0,0 +1,76 @@
+import pinocchio as pin
+import numpy as np
+
+
+################################################################
+#             STATE TRANSITION CONDITIONS
+################################################################
+def isGraspOK(args, robot, grasp_pose):
+    isOK = False
+    SEerror = robot.T_w_e().actInv(grasp_pose)
+    err_vector = pin.log6(SEerror).vector
+    # TODO: figure this out
+    # it seems you have to use just the arm to get to finish with this precision
+    # if np.linalg.norm(err_vector) < robot.args.goal_error:
+    if np.linalg.norm(err_vector) < 2 * 1e-1:
+        isOK = True
+    return not isOK
+
+
+def isGripperRelativeToBaseOK(args, robot):
+    isOK = False
+    # we want to be in the back of the base (x-axis) and on handlebar height
+    T_w_base = robot.data.oMi[1]
+    # rotation for the gripper is base with z flipped to point into the ground
+    rotate = pin.SE3(pin.rpy.rpyToMatrix(np.pi, 0.0, 0.0), np.zeros(3))
+    # translation is prefered distance from base
+    translate = pin.SE3(
+        np.eye(3),
+        np.array(
+            [args.base_to_handlebar_preferred_distance, 0.0, args.handlebar_height]
+        ),
+    )
+    # grasp_pose = T_w_base.act(rotate.act(translate))
+    grasp_pose = T_w_base.act(translate.act(rotate))
+    SEerror = robot.T_w_e().actInv(grasp_pose)
+    err_vector = pin.log6(SEerror).vector
+    # TODO: figure this out
+    # it seems you have to use just the arm to get to finish with this precision
+    # if np.linalg.norm(err_vector) < robot.args.goal_error:
+    if np.linalg.norm(err_vector) < 2 * 1e-1:
+        isOK = True
+    return isOK, grasp_pose
+
+
+def areDualGrippersRelativeToBaseOK(args, goal_transform, robot):
+    isOK = False
+    # we want to be in the back of the base (x-axis) and on handlebar height
+    T_w_base = robot.data.oMi[1]
+    # rotation for the gripper is base with z flipped to point into the ground
+    rotate = pin.SE3(pin.rpy.rpyToMatrix(np.pi, 0.0, 0.0), np.zeros(3))
+    # translation is prefered distance from base
+    translate = pin.SE3(
+        np.eye(3),
+        np.array(
+            [args.base_to_handlebar_preferred_distance, 0.0, args.handlebar_height]
+        ),
+    )
+    # grasp_pose = T_w_base.act(rotate.act(translate))
+    grasp_pose = T_w_base.act(translate.act(rotate))
+
+    grasp_pose_left = goal_transform.act(grasp_pose)
+    grasp_pose_right = goal_transform.inverse().act(grasp_pose)
+
+    T_w_e_left, T_w_e_right = robot.T_w_e()
+    SEerror_left = T_w_e_left.actInv(grasp_pose_left)
+    SEerror_right = T_w_e_right.actInv(grasp_pose_right)
+    err_vector_left = pin.log6(SEerror_left).vector
+    err_vector_right = pin.log6(SEerror_right).vector
+    # TODO: figure this out
+    # it seems you have to use just the arm to get to finish with this precision
+    # if np.linalg.norm(err_vector) < robot.args.goal_error:
+    if (np.linalg.norm(err_vector_left) < 2 * 1e-1) and (
+        np.linalg.norm(err_vector_right) < 2 * 1e-1
+    ):
+        isOK = True
+    return isOK, grasp_pose, grasp_pose_left, grasp_pose_right
diff --git a/python/examples/cart_pulling/cart_pulling.py b/examples/cart_pulling/cart_pulling.py
similarity index 70%
rename from python/examples/cart_pulling/cart_pulling.py
rename to examples/cart_pulling/cart_pulling.py
index 2687ca8e4601aaf12e5f16874c44914f211ed8ce..6ed8beddd3f5955f509d04c62cc94220600df12d 100644
--- a/python/examples/cart_pulling/cart_pulling.py
+++ b/examples/cart_pulling/cart_pulling.py
@@ -1,21 +1,10 @@
-# PYTHON_ARGCOMPLETE_OK
-import numpy as np
-import time
-import argparse, argcomplete
-from functools import partial
-from smc.managers import (
-    getMinimalArgParser,
-    ControlLoopManager,
-    RobotManager,
-    ProcessManager,
-)
-from smc.optimal_control.get_ocp_args import get_OCP_args
-from smc.optimal_control.crocoddyl_optimal_control import *
-from smc.optimal_control.crocoddyl_mpc import *
-from smc.basics.basics import followKinematicJointTrajP
-from smc.util.logging_utils import LogManager
-from smc.visualize.visualize import plotFromDict
-from smc.clik.clik import (
+from behavior_tree import *
+from smc.path_generation.maps.premade_maps import createSampleStaticMap
+from smc.path_generation.planner import starPlanner, getPlanningArgs
+from smc import getMinimalArgParser, getRobotFromArgs
+from smc.util.define_random_goal import getRandomlyGeneratedGoal
+from smc.control.optimal_control import *
+from smc.control.cartesian_space import (
     getClikArgs,
     cartesianPathFollowingWithPlanner,
     controlLoopClik,
@@ -25,11 +14,11 @@ from smc.clik.clik import (
     controlLoopClikDualArmsOnly,
 )
 import pinocchio as pin
+import numpy as np
 import crocoddyl
 from functools import partial
-import importlib.util
-from smc.path_generation.planner import starPlanner, getPlanningArgs, createMap
 import yaml
+import time
 
 # TODO:
 # - make reference step size in path_generator an argument here
@@ -53,7 +42,6 @@ def get_args():
         default=0.7,
         help="prefered path arclength from mobile base position to handlebar",
     )
-    argcomplete.autocomplete(parser)
     args = parser.parse_args()
     # TODO TODO TODO: REMOVE PRESET HACKS
     robot_type = "Unicycle"
@@ -68,77 +56,6 @@ def get_args():
     return args
 
 
-def isGraspOK(args, robot, grasp_pose):
-    isOK = False
-    SEerror = robot.getT_w_e().actInv(grasp_pose)
-    err_vector = pin.log6(SEerror).vector
-    # TODO: figure this out
-    # it seems you have to use just the arm to get to finish with this precision
-    # if np.linalg.norm(err_vector) < robot.args.goal_error:
-    if np.linalg.norm(err_vector) < 2 * 1e-1:
-        isOK = True
-    return not isOK
-
-
-def isGripperRelativeToBaseOK(args, robot):
-    isOK = False
-    # we want to be in the back of the base (x-axis) and on handlebar height
-    T_w_base = robot.data.oMi[1]
-    # rotation for the gripper is base with z flipped to point into the ground
-    rotate = pin.SE3(pin.rpy.rpyToMatrix(np.pi, 0.0, 0.0), np.zeros(3))
-    # translation is prefered distance from base
-    translate = pin.SE3(
-        np.eye(3),
-        np.array(
-            [args.base_to_handlebar_preferred_distance, 0.0, args.handlebar_height]
-        ),
-    )
-    # grasp_pose = T_w_base.act(rotate.act(translate))
-    grasp_pose = T_w_base.act(translate.act(rotate))
-    SEerror = robot.getT_w_e().actInv(grasp_pose)
-    err_vector = pin.log6(SEerror).vector
-    # TODO: figure this out
-    # it seems you have to use just the arm to get to finish with this precision
-    # if np.linalg.norm(err_vector) < robot.args.goal_error:
-    if np.linalg.norm(err_vector) < 2 * 1e-1:
-        isOK = True
-    return isOK, grasp_pose
-
-
-def areDualGrippersRelativeToBaseOK(args, goal_transform, robot):
-    isOK = False
-    # we want to be in the back of the base (x-axis) and on handlebar height
-    T_w_base = robot.data.oMi[1]
-    # rotation for the gripper is base with z flipped to point into the ground
-    rotate = pin.SE3(pin.rpy.rpyToMatrix(np.pi, 0.0, 0.0), np.zeros(3))
-    # translation is prefered distance from base
-    translate = pin.SE3(
-        np.eye(3),
-        np.array(
-            [args.base_to_handlebar_preferred_distance, 0.0, args.handlebar_height]
-        ),
-    )
-    # grasp_pose = T_w_base.act(rotate.act(translate))
-    grasp_pose = T_w_base.act(translate.act(rotate))
-
-    grasp_pose_left = goal_transform.act(grasp_pose)
-    grasp_pose_right = goal_transform.inverse().act(grasp_pose)
-
-    T_w_e_left, T_w_e_right = robot.getT_w_e()
-    SEerror_left = T_w_e_left.actInv(grasp_pose_left)
-    SEerror_right = T_w_e_right.actInv(grasp_pose_right)
-    err_vector_left = pin.log6(SEerror_left).vector
-    err_vector_right = pin.log6(SEerror_right).vector
-    # TODO: figure this out
-    # it seems you have to use just the arm to get to finish with this precision
-    # if np.linalg.norm(err_vector) < robot.args.goal_error:
-    if (np.linalg.norm(err_vector_left) < 2 * 1e-1) and (
-        np.linalg.norm(err_vector_right) < 2 * 1e-1
-    ):
-        isOK = True
-    return isOK, grasp_pose, grasp_pose_left, grasp_pose_right
-
-
 def cartPullingControlLoop(
     args,
     robot: RobotManager,
@@ -159,11 +76,11 @@ def cartPullingControlLoop(
     4) ? always true (or do nothing is always true, whatever)
     """
 
-    q = robot.getQ()
+    q = robot.q
     if robot.robot_name != "yumi":
-        T_w_e = robot.getT_w_e()
+        T_w_e = robot.T_w_e
     else:
-        T_w_e_left, T_w_e_right = robot.getT_w_e()
+        T_w_e_left, T_w_e_right = robot.T_w_e
 
     # we use binary as string representation (i don't want to deal with python's binary representation).
     # the reason for this is that then we don't have disgusting nested ifs
@@ -305,7 +222,7 @@ def cartPullingControlLoop(
     # TODO plot priority register out
     # log_item['prio_reg'] = ...
     log_item["qs"] = q.reshape((robot.model.nq,))
-    log_item["dqs"] = robot.getQd().reshape((robot.model.nv,))
+    log_item["dqs"] = robot.v.reshape((robot.model.nv,))
     print(priority_register)
     return breakFlag, save_past_item, log_item
 
@@ -321,7 +238,7 @@ def cartPulling(args, robot: RobotManager, goal, path_planner):
     ############################
     #  setup cart-pulling mpc  #
     ############################
-    x0 = np.concatenate([robot.getQ(), robot.getQd()])
+    x0 = np.concatenate([robot.q, robot.v])
     problem_pulling = createBaseAndEEPathFollowingOCP(args, robot, x0)
     if args.solver == "boxfddp":
         solver_pulling = crocoddyl.SolverBoxFDDP(problem_pulling)
@@ -335,7 +252,7 @@ def cartPulling(args, robot: RobotManager, goal, path_planner):
     #  setup point-to-point handlebar grasping  #
     # TODO: have option to swith this for clik  #
     #############################################
-    grasp_pose = robot.getT_w_e()
+    grasp_pose = robot.T_w_e()
     problem_grasp = createCrocoIKOCP(args, robot, x0, grasp_pose)
     if args.solver == "boxfddp":
         solver_grasp = crocoddyl.SolverBoxFDDP(problem_grasp)
@@ -357,13 +274,13 @@ def cartPulling(args, robot: RobotManager, goal, path_planner):
     )
 
     log_item = {}
-    q = robot.getQ()
+    q = robot.q
     if robot.robot_name != "yumi":
-        T_w_e = robot.getT_w_e()
+        T_w_e = robot.T_w_e()
     else:
-        T_w_e_l, T_w_e_right = robot.getT_w_e()
+        T_w_e_l, T_w_e_right = robot.T_w_e()
     log_item["qs"] = q.reshape((robot.model.nq,))
-    log_item["dqs"] = robot.getQd().reshape((robot.model.nv,))
+    log_item["dqs"] = robot.v.reshape((robot.model.nv,))
     # T_base = self.robot_manager.data.oMi[1]
     # NOTE: why the fuck was the past path defined from the end-effector?????
     # save_past_item = {'path2D_untimed' : T_w_e.translation[:2],
@@ -376,46 +293,29 @@ def cartPulling(args, robot: RobotManager, goal, path_planner):
 
 if __name__ == "__main__":
     args = get_args()
-    if importlib.util.find_spec("mim_solvers"):
-        import mim_solvers
-    robot = RobotManager(args)
-    robot.q[0] = 9.0
-    robot.q[1] = 4.0
+    robot = getRobotFromArgs(args)
+    # TODO: here you have to exit unless the robot has a mobile base interface
+    robot._q[0] = 9.0
+    robot._q[1] = 4.0
 
-    x0 = np.concatenate([robot.getQ(), robot.getQd()])
+    x0 = np.concatenate([robot.q, robot.v])
     robot._step()
     goal = np.array([0.5, 5.5])
 
     ###########################
     #  visualizing obstacles  #
     ###########################
-    _, map_as_list = createMap()
+    _, map_as_list = createSampleStaticMap()
     # we're assuming rectangles here
     # be my guest and implement other options
-    if args.visualize_manipulator:
-        for obstacle in map_as_list:
-            length = obstacle[1][0] - obstacle[0][0]
-            width = obstacle[3][1] - obstacle[0][1]
-            height = 0.4  # doesn't matter because plan because planning is 2D
-            pose = pin.SE3(
-                np.eye(3),
-                np.array(
-                    [
-                        obstacle[0][0] + (obstacle[1][0] - obstacle[0][0]) / 2,
-                        obstacle[0][1] + (obstacle[3][1] - obstacle[0][1]) / 2,
-                        0.0,
-                    ]
-                ),
-            )
-            dims = [length, width, height]
-            command = {"obstacle": [pose, dims]}
-            robot.visualizer_manager.sendCommand(command)
+    if args.visualizer:
+        robot.sendRectangular2DMapToVisualizer(map_as_list)
 
     planning_function = partial(starPlanner, goal)
     # TODO: ensure alignment in orientation between planner and actual robot
     path_planner = ProcessManager(args, planning_function, robot.q[:2], 3, None)
     # wait for meshcat to initialize
-    if args.visualize_manipulator:
+    if args.visualizer:
         time.sleep(5)
     # clik version
     # cartesianPathFollowingWithPlanner(args, robot, path_planner)
@@ -427,18 +327,15 @@ if __name__ == "__main__":
     # atm this is just mobile base tracking
     cartPulling(args, robot, goal, path_planner)
     print("final position:")
-    print(robot.getT_w_e())
+    print(robot.T_w_e)
     path_planner.terminateProcess()
 
     if args.save_log:
-        robot.log_manager.plotAllControlLoops()
+        robot._log_manager.saveLog()
+        robot._log_manager.plotAllControlLoops()
 
     if not args.pinocchio_only:
         robot.stopRobot()
 
-    if args.visualize_manipulator:
+    if args.visualizer:
         robot.killManipulatorVisualizer()
-
-    if args.save_log:
-        robot.log_manager.saveLog()
-    # loop_manager.stopHandler(None, None)
diff --git a/examples/cart_pulling/cart_pulling_notes.md b/examples/cart_pulling/cart_pulling_notes.md
new file mode 100644
index 0000000000000000000000000000000000000000..95fe861a8f701e20a69c7a2dbcf069332f625155
--- /dev/null
+++ b/examples/cart_pulling/cart_pulling_notes.md
@@ -0,0 +1,93 @@
+# stuff to try
+--------------
+once the the basic version of the control is done you can try putting in something extra to the objective function of the ocp maybe?
+
+# a thing to take care of
+-------------------------
+if the end-effector is not at the starting point of the path, it goes to shit. it can't make the path because the path is constantly changing.
+there are 3 different ways to solve the problem:
+1) don't update the path until the end-effector is close enough
+2) run a behavior tree where you don't do path following unless you are at the path, and have a different controller get you to the point (this should be just initialization)
+3) transform the path differently so that it goes to the desired height, i.e. change the path to make it followable
+
+discussion.
+1) is not a good idea because we want the path planner to run on the side and do it's thing. it is resposible for the path, control is responsible to follow the path. the path is guaranteed to exist, and it is our duty to deal with non-linearity to get us on the path.
+2) a totally valid solution and makes sense in the final version. does add some complexity because you then need to make sure you designed the state transitions well.
+3) just a bit of math, can't fail. does not fuck with the path planner, introduces no new concepts - it's just a different transformation of the 2D path. once put in place there is no reason for it not to work.
+
+conclusion:
+we go with option 2) because option 2) is false! it does not account for orientation! we want a fixed orientation which changes along the path. this makes interpolating to the 6d path weird. hence we need to swap to a clik if the initial error is too big.
+you could also try "freezing" the first point tbh
+
+
+
+
+# the desided joint space position
+name:
+- myumi_001_yumi_robr_joint_1
+- myumi_001_yumi_robr_joint_2
+- myumi_001_yumi_robr_joint_3
+- myumi_001_yumi_robr_joint_4
+- myumi_001_yumi_robr_joint_5
+- myumi_001_yumi_robr_joint_6
+- myumi_001_yumi_robr_joint_7
+- myumi_001_yumi_robl_joint_1
+- myumi_001_yumi_robl_joint_2
+- myumi_001_yumi_robl_joint_3
+- myumi_001_yumi_robl_joint_4
+- myumi_001_yumi_robl_joint_5
+- myumi_001_yumi_robl_joint_6
+- myumi_001_yumi_robl_joint_7
+position:
+- 1.1781062998438787
+- -0.000595335227562165
+- -1.749208945070357
+- 0.4106104712156747
+- -2.060408639509931
+- 0.3044975499507672
+- 1.7246295661055797
+- -0.7019778380440242
+- 0.0394624047824147
+- 1.1381740635109037
+- 0.40438559848372346
+- 1.5945463973962233
+- 0.3724310942226761
+- -1.3882579393586854
+velocity: []
+effort: []
+
+# better
+name:
+- myumi_001_yumi_robr_joint_1
+- myumi_001_yumi_robr_joint_2
+- myumi_001_yumi_robr_joint_3
+- myumi_001_yumi_robr_joint_4
+- myumi_001_yumi_robr_joint_5
+- myumi_001_yumi_robr_joint_6
+- myumi_001_yumi_robr_joint_7
+- myumi_001_yumi_robl_joint_1
+- myumi_001_yumi_robl_joint_2
+- myumi_001_yumi_robl_joint_3
+- myumi_001_yumi_robl_joint_4
+- myumi_001_yumi_robl_joint_5
+- myumi_001_yumi_robl_joint_6
+- myumi_001_yumi_robl_joint_7
+position:
+- 1.177726666230488
+- -0.0014802503425588292
+- -1.7605729197578341
+- 0.4215065284996249
+- -1.9415690706067803
+- 0.2803584248036936
+- 1.6919710884998835
+- -0.7879804975484437
+- 0.22470208644656367
+- 1.3406988091378869
+- 0.35854547216754384
+- 1.7128065956042273
+- 0.22850344929702915
+- -1.5302555581528383
+velocity: []
+effort: []
+
+
diff --git a/examples/cart_pulling/dual_arm_path_following.py b/examples/cart_pulling/dual_arm_path_following.py
new file mode 100644
index 0000000000000000000000000000000000000000..2b0e218d566aeeec6a3ec796ff5269ccaef262a1
--- /dev/null
+++ b/examples/cart_pulling/dual_arm_path_following.py
@@ -0,0 +1,2 @@
+# same as path_following_mpc in a circle, just use a dual arm instead.
+# the reference is still a single 6D path, but now with dual arms
diff --git a/examples/cart_pulling/path_following_from_planner.py b/examples/cart_pulling/path_following_from_planner.py
new file mode 100644
index 0000000000000000000000000000000000000000..54581b9e40eaf4a228611c772d1bac20a3b1506e
--- /dev/null
+++ b/examples/cart_pulling/path_following_from_planner.py
@@ -0,0 +1,60 @@
+from smc import getRobotFromArgs
+from smc import getMinimalArgParser
+from smc.path_generation.maps.premade_maps import createSampleStaticMap
+from smc.control.optimal_control.util import get_OCP_args
+from smc.control.cartesian_space import getClikArgs
+from smc.path_generation.planner import starPlanner, getPlanningArgs
+from smc.control.optimal_control.croco_mpc_path_following import (
+    CrocoEndEffectorPathFollowingMPC,
+)
+from smc.multiprocessing import ProcessManager
+
+import time
+import numpy as np
+from functools import partial
+
+
+def get_args():
+    parser = getMinimalArgParser()
+    parser = get_OCP_args(parser)
+    parser = getClikArgs(parser)  # literally just for goal error
+    parser = getPlanningArgs(parser)
+    parser.add_argument(
+        "--handlebar-height",
+        type=float,
+        default=0.5,
+        help="heigh of handlebar of the cart to be pulled",
+    )
+    args = parser.parse_args()
+    return args
+
+
+if __name__ == "__main__":
+    args = get_args()
+    robot = getRobotFromArgs(args)
+    robot._q[0] = 9.0
+    robot._q[1] = 4.0
+    robot._step()
+    x0 = np.concatenate([robot.q, robot.v])
+    goal = np.array([0.5, 5.5])
+
+    planning_function = partial(starPlanner, goal)
+    # TODO: ensure alignment in orientation between planner and actual robot
+    path_planner = ProcessManager(args, planning_function, robot.q[:2], 3, None)
+    _, map_as_list = createSampleStaticMap()
+    if args.visualizer:
+        robot.sendRectangular2DMapToVisualizer(map_as_list)
+        time.sleep(5)
+    CrocoEndEffectorPathFollowingMPC(args, robot, x0, path_planner)
+
+    print("final position:", robot.T_w_e)
+
+    if args.real:
+        robot.stopRobot()
+
+    if args.save_log:
+        robot._log_manager.saveLog()
+        robot._log_manager.plotAllControlLoops()
+
+    if args.visualizer:
+        robot.killManipulatorVisualizer()
diff --git a/examples/cart_pulling/pose_initialization.py b/examples/cart_pulling/pose_initialization.py
new file mode 100644
index 0000000000000000000000000000000000000000..f73a16029b9bc0ee549e5b38ad88c28f1c2dd2ea
--- /dev/null
+++ b/examples/cart_pulling/pose_initialization.py
@@ -0,0 +1,3 @@
+# whatever control you use to get to the starting point for cart pulling.
+# in the past this might have been clik, but we can run with p2p mpc honestly.
+# that too needs to be dual-arm compatible though
diff --git a/python/examples/cart_pulling/starify_nav2_map.py b/examples/cart_pulling/starify_nav2_map.py
similarity index 100%
rename from python/examples/cart_pulling/starify_nav2_map.py
rename to examples/cart_pulling/starify_nav2_map.py
diff --git a/examples/cart_pulling/trajectory_following_mpc.py b/examples/cart_pulling/trajectory_following_mpc.py
new file mode 100644
index 0000000000000000000000000000000000000000..d7a53935e5b3d0bbfcf2812a1d90043e351a9565
--- /dev/null
+++ b/examples/cart_pulling/trajectory_following_mpc.py
@@ -0,0 +1 @@
+# same as dual_arm_path_following, but with the trajectory math in it
diff --git a/python/examples/cartesian_space/clik.py b/examples/cartesian_space/clik.py
similarity index 97%
rename from python/examples/cartesian_space/clik.py
rename to examples/cartesian_space/clik.py
index 9383a64b82e57e556441321d9b6ccc0cf2c1ce32..b1a8b8482befe3c34e1e258836247a7b141ee0b3 100644
--- a/python/examples/cartesian_space/clik.py
+++ b/examples/cartesian_space/clik.py
@@ -1,13 +1,10 @@
-# PYTHON_ARGCOMPLETE_OK
 from smc import getMinimalArgParser, getRobotFromArgs
-from smc.control.cartesian_space import getClikArgs
 from smc.util.define_random_goal import getRandomlyGeneratedGoal
+from smc.control.cartesian_space import getClikArgs
 from smc.robots.utils import defineGoalPointCLI
 from smc.control.cartesian_space.cartesian_space_point_to_point import moveL
 
 import numpy as np
-
-# import pinocchio as pin
 import argparse
 
 
diff --git a/python/examples/data/from_writing_to_handover.pickle_save b/examples/data/from_writing_to_handover.pickle_save
similarity index 100%
rename from python/examples/data/from_writing_to_handover.pickle_save
rename to examples/data/from_writing_to_handover.pickle_save
diff --git a/python/examples/data/fts.png b/examples/data/fts.png
similarity index 100%
rename from python/examples/data/fts.png
rename to examples/data/fts.png
diff --git a/python/examples/data/latest_run b/examples/data/latest_run
similarity index 100%
rename from python/examples/data/latest_run
rename to examples/data/latest_run
diff --git a/python/examples/data/latest_run_0 b/examples/data/latest_run_0
similarity index 100%
rename from python/examples/data/latest_run_0
rename to examples/data/latest_run_0
diff --git a/python/examples/drawing/drawing_from_input_drawing.py b/examples/drawing/drawing_from_input_drawing.py
similarity index 100%
rename from python/examples/drawing/drawing_from_input_drawing.py
rename to examples/drawing/drawing_from_input_drawing.py
diff --git a/python/examples/drawing/plane_pose.pickle_save b/examples/drawing/plane_pose.pickle_save
similarity index 100%
rename from python/examples/drawing/plane_pose.pickle_save
rename to examples/drawing/plane_pose.pickle_save
diff --git a/python/examples/drawing/wiping_path.csv_save b/examples/drawing/wiping_path.csv_save
similarity index 100%
rename from python/examples/drawing/wiping_path.csv_save
rename to examples/drawing/wiping_path.csv_save
diff --git a/python/examples/graz/cartesian_pose_command_server.py b/examples/graz/cartesian_pose_command_server.py
similarity index 100%
rename from python/examples/graz/cartesian_pose_command_server.py
rename to examples/graz/cartesian_pose_command_server.py
diff --git a/python/examples/graz/clik_client.py b/examples/graz/clik_client.py
similarity index 100%
rename from python/examples/graz/clik_client.py
rename to examples/graz/clik_client.py
diff --git a/python/examples/graz/clik_m.py b/examples/graz/clik_m.py
similarity index 100%
rename from python/examples/graz/clik_m.py
rename to examples/graz/clik_m.py
diff --git a/python/examples/graz/joint_copier_client.py b/examples/graz/joint_copier_client.py
similarity index 100%
rename from python/examples/graz/joint_copier_client.py
rename to examples/graz/joint_copier_client.py
diff --git a/python/examples/graz/message_specs_pb2.py b/examples/graz/message_specs_pb2.py
similarity index 100%
rename from python/examples/graz/message_specs_pb2.py
rename to examples/graz/message_specs_pb2.py
diff --git a/python/examples/graz/point_impedance_server.py b/examples/graz/point_impedance_server.py
similarity index 100%
rename from python/examples/graz/point_impedance_server.py
rename to examples/graz/point_impedance_server.py
diff --git a/python/examples/graz/protobuf_ros1_bridge.py b/examples/graz/protobuf_ros1_bridge.py
similarity index 100%
rename from python/examples/graz/protobuf_ros1_bridge.py
rename to examples/graz/protobuf_ros1_bridge.py
diff --git a/python/examples/graz/protobuf_to_ros1.py b/examples/graz/protobuf_to_ros1.py
similarity index 100%
rename from python/examples/graz/protobuf_to_ros1.py
rename to examples/graz/protobuf_to_ros1.py
diff --git a/python/examples/graz/ros1_to_protobuf.py b/examples/graz/ros1_to_protobuf.py
similarity index 100%
rename from python/examples/graz/ros1_to_protobuf.py
rename to examples/graz/ros1_to_protobuf.py
diff --git a/python/examples/graz/to_install_on_ubuntu18.md b/examples/graz/to_install_on_ubuntu18.md
similarity index 100%
rename from python/examples/graz/to_install_on_ubuntu18.md
rename to examples/graz/to_install_on_ubuntu18.md
diff --git a/python/examples/graz/traiettoria.m b/examples/graz/traiettoria.m
similarity index 100%
rename from python/examples/graz/traiettoria.m
rename to examples/graz/traiettoria.m
diff --git a/python/examples/impedance/point_impedance_control.py b/examples/impedance/point_impedance_control.py
similarity index 100%
rename from python/examples/impedance/point_impedance_control.py
rename to examples/impedance/point_impedance_control.py
diff --git a/python/examples/log_analysis/comparing_logs_example.py b/examples/log_analysis/comparing_logs_example.py
similarity index 100%
rename from python/examples/log_analysis/comparing_logs_example.py
rename to examples/log_analysis/comparing_logs_example.py
diff --git a/python/examples/log_analysis/log_analysis_example.py b/examples/log_analysis/log_analysis_example.py
similarity index 100%
rename from python/examples/log_analysis/log_analysis_example.py
rename to examples/log_analysis/log_analysis_example.py
diff --git a/python/examples/old_or_experimental/clik_old.py b/examples/old_or_experimental/clik_old.py
similarity index 100%
rename from python/examples/old_or_experimental/clik_old.py
rename to examples/old_or_experimental/clik_old.py
diff --git a/python/examples/old_or_experimental/force_control/force_control_test.py b/examples/old_or_experimental/force_control/force_control_test.py
similarity index 100%
rename from python/examples/old_or_experimental/force_control/force_control_test.py
rename to examples/old_or_experimental/force_control/force_control_test.py
diff --git a/python/examples/old_or_experimental/force_control/force_mode_api.py b/examples/old_or_experimental/force_control/force_mode_api.py
similarity index 100%
rename from python/examples/old_or_experimental/force_control/force_mode_api.py
rename to examples/old_or_experimental/force_control/force_mode_api.py
diff --git a/python/examples/old_or_experimental/force_control/forcemode_example.py b/examples/old_or_experimental/force_control/forcemode_example.py
similarity index 100%
rename from python/examples/old_or_experimental/force_control/forcemode_example.py
rename to examples/old_or_experimental/force_control/forcemode_example.py
diff --git a/python/examples/old_or_experimental/force_control/point_force_control.py b/examples/old_or_experimental/force_control/point_force_control.py
similarity index 100%
rename from python/examples/old_or_experimental/force_control/point_force_control.py
rename to examples/old_or_experimental/force_control/point_force_control.py
diff --git a/python/examples/old_or_experimental/ft_calibration_via_amperes_test.py b/examples/old_or_experimental/ft_calibration_via_amperes_test.py
similarity index 100%
rename from python/examples/old_or_experimental/ft_calibration_via_amperes_test.py
rename to examples/old_or_experimental/ft_calibration_via_amperes_test.py
diff --git a/python/examples/old_or_experimental/test_crocoddyl_opt_ctrl.py b/examples/old_or_experimental/test_crocoddyl_opt_ctrl.py
similarity index 100%
rename from python/examples/old_or_experimental/test_crocoddyl_opt_ctrl.py
rename to examples/old_or_experimental/test_crocoddyl_opt_ctrl.py
diff --git a/python/examples/old_or_experimental/test_gripper.py b/examples/old_or_experimental/test_gripper.py
similarity index 100%
rename from python/examples/old_or_experimental/test_gripper.py
rename to examples/old_or_experimental/test_gripper.py
diff --git a/python/examples/old_or_experimental/test_traj_w_movej.py b/examples/old_or_experimental/test_traj_w_movej.py
similarity index 100%
rename from python/examples/old_or_experimental/test_traj_w_movej.py
rename to examples/old_or_experimental/test_traj_w_movej.py
diff --git a/python/examples/old_or_experimental/test_traj_w_speedj.py b/examples/old_or_experimental/test_traj_w_speedj.py
similarity index 100%
rename from python/examples/old_or_experimental/test_traj_w_speedj.py
rename to examples/old_or_experimental/test_traj_w_speedj.py
diff --git a/python/examples/optimal_control/casadi_ocp_collision_avoidance.py b/examples/optimal_control/casadi_ocp_collision_avoidance.py
similarity index 100%
rename from python/examples/optimal_control/casadi_ocp_collision_avoidance.py
rename to examples/optimal_control/casadi_ocp_collision_avoidance.py
diff --git a/python/examples/optimal_control/croco_ik_mpc.py b/examples/optimal_control/croco_ik_mpc.py
similarity index 100%
rename from python/examples/optimal_control/croco_ik_mpc.py
rename to examples/optimal_control/croco_ik_mpc.py
diff --git a/python/examples/optimal_control/croco_ik_ocp.py b/examples/optimal_control/croco_ik_ocp.py
similarity index 100%
rename from python/examples/optimal_control/croco_ik_ocp.py
rename to examples/optimal_control/croco_ik_ocp.py
diff --git a/examples/optimal_control/path_following_mpc.py b/examples/optimal_control/path_following_mpc.py
new file mode 100644
index 0000000000000000000000000000000000000000..439352518beb563d076069f21bb3597cdd607b68
--- /dev/null
+++ b/examples/optimal_control/path_following_mpc.py
@@ -0,0 +1,53 @@
+from smc import getRobotFromArgs
+from smc import getMinimalArgParser
+from smc.control.optimal_control.util import get_OCP_args
+from smc.control.cartesian_space import getClikArgs
+from smc.control.optimal_control.croco_mpc_path_following import (
+    CrocoEndEffectorPathFollowingMPC,
+)
+import numpy as np
+
+
+def path(T_w_e, i):
+    # 2) do T_mobile_base_ee_pos to get
+    # end-effector reference frame(s)
+
+    # generate bullshit just to see it works
+    path = []
+    t = i * robot.dt
+    for i in range(args.n_knots):
+        t += 0.01
+        new = T_w_e.copy()
+        translation = 2 * np.array([np.cos(t / 20), np.sin(t / 20), 0.3])
+        new.translation = translation
+        path.append(new)
+    return path
+
+
+def get_args():
+    parser = getMinimalArgParser()
+    parser = get_OCP_args(parser)
+    parser = getClikArgs(parser)  # literally just for goal error
+    args = parser.parse_args()
+    return args
+
+
+if __name__ == "__main__":
+    args = get_args()
+    robot = getRobotFromArgs(args)
+    x0 = np.concatenate([robot.q, robot.v])
+    robot._step()
+
+    CrocoEndEffectorPathFollowingMPC(args, robot, x0, path)
+
+    print("final position:", robot.T_w_e)
+
+    if args.real:
+        robot.stopRobot()
+
+    if args.save_log:
+        robot._log_manager.saveLog()
+        robot._log_manager.plotAllControlLoops()
+
+    if args.visualizer:
+        robot.killManipulatorVisualizer()
diff --git a/python/examples/path6d_from_path2d.py b/examples/path6d_from_path2d.py
similarity index 75%
rename from python/examples/path6d_from_path2d.py
rename to examples/path6d_from_path2d.py
index 11334efce7186bcbb346c82cc7992f6acbc016b6..a2636e2f0dbb84c01ee982a9c7efeff03f339791 100644
--- a/python/examples/path6d_from_path2d.py
+++ b/examples/path6d_from_path2d.py
@@ -1,43 +1,19 @@
-# PYTHON_ARGCOMPLETE_OK
 import numpy as np
 import time
-import argparse, argcomplete
 from functools import partial
-from smc.managers import (
-    getMinimalArgParser,
-    ControlLoopManager,
-    RobotManager,
-    ProcessManager,
-)
-from smc.optimal_control.get_ocp_args import get_OCP_args
-from smc.optimal_control.crocoddyl_optimal_control import *
-from smc.optimal_control.crocoddyl_mpc import *
-from smc.basics.basics import followKinematicJointTrajP
-from smc.util.logging_utils import LogManager
-from smc.visualize.visualize import plotFromDict
-from smc.clik.clik import (
-    getClikArgs,
-    cartesianPathFollowingWithPlanner,
-    controlLoopClik,
-    invKinmQP,
-    dampedPseudoinverse,
-)
-import pinocchio as pin
-import crocoddyl
+from smc import getMinimalArgParser
+from smc.multiprocessing.process_manager import ProcessManager
+from smc.control.cartesian_space import getClikArgs
 from functools import partial
-import importlib.util
-from smc.path_generation.planner import starPlanner, getPlanningArgs, createMap
+from smc.path_generation.planner import getPlanningArgs
 import yaml
 import numpy as np
 from functools import partial
-from smc.managers import ProcessManager, getMinimalArgParser
-from smc.util.get_model import heron_approximation
-from smc.visualize.visualize import plotFromDict, realTimePlotter, manipulatorVisualizer
-from smc.path_generation.planner import (
-    path2D_timed,
-    pathPointFromPathParam,
-    path2D_to_SE3,
-)
+from smc.robots.implementations.heron import heron_approximation
+from smc.visualization.visualizer import manipulatorVisualizer
+from smc.path_generation.path_math.path2d_to_6d import path2D_to_SE3_fixed
+from smc.path_generation.path_math.path_to_trajectory import path2D_timed
+from smc.control.optimal_control.util import get_OCP_args
 
 
 def get_args():
@@ -57,7 +33,6 @@ def get_args():
         default=0.7,
         help="prefered path arclength from mobile base position to handlebar",
     )
-    argcomplete.autocomplete(parser)
     args = parser.parse_args()
     # TODO TODO TODO: REMOVE PRESET HACKS
     robot_type = "Unicycle"
@@ -112,7 +87,7 @@ path2D_untimed_base = np.array(path2D_untimed_base).reshape((-1, 2))
 # ideally should be precomputed somewhere
 # base just needs timing on the path,
 # and it's of height 0 (i.e. the height of base's planar joint)
-path_base = path2D_timed(args, None, path2D_untimed_base, max_base_v, 0.0)
+# path_base = path2D_timed(args, None, path2D_untimed_base, max_base_v, 0.0)
 
 path_arclength = np.linalg.norm(p - past_data["path2D_untimed"])
 handlebar_path_index = -1
@@ -137,7 +112,7 @@ path2D_handlebar_1 = np.hstack(
 )
 
 # TODO: combine with base for maximum correctness
-pathSE3_handlebar = path2D_to_SE3(path2D_handlebar_1, args.handlebar_height)
+pathSE3_handlebar = path2D_to_SE3_fixed(path2D_handlebar_1, args.handlebar_height)
 for p in pathSE3_handlebar:
     print(p)
 
diff --git a/python/examples/pinocchio_math_understanding/pin_contact3d.py b/examples/pinocchio_math_understanding/pin_contact3d.py
similarity index 100%
rename from python/examples/pinocchio_math_understanding/pin_contact3d.py
rename to examples/pinocchio_math_understanding/pin_contact3d.py
diff --git a/python/examples/pushing_via_friction_cones.py b/examples/pushing_via_friction_cones.py
similarity index 100%
rename from python/examples/pushing_via_friction_cones.py
rename to examples/pushing_via_friction_cones.py
diff --git a/python/examples/ros/dummy_cmds_pub.py b/examples/ros/dummy_cmds_pub.py
similarity index 100%
rename from python/examples/ros/dummy_cmds_pub.py
rename to examples/ros/dummy_cmds_pub.py
diff --git a/python/examples/ros/ros2_clik.py b/examples/ros/ros2_clik.py
similarity index 100%
rename from python/examples/ros/ros2_clik.py
rename to examples/ros/ros2_clik.py
diff --git a/python/examples/ros/smc_node.py b/examples/ros/smc_node.py
similarity index 100%
rename from python/examples/ros/smc_node.py
rename to examples/ros/smc_node.py
diff --git a/python/examples/ros/smc_yumi_challenge.py b/examples/ros/smc_yumi_challenge.py
similarity index 100%
rename from python/examples/ros/smc_yumi_challenge.py
rename to examples/ros/smc_yumi_challenge.py
diff --git a/python/examples/test_by_running.sh b/examples/test_by_running.sh
similarity index 100%
rename from python/examples/test_by_running.sh
rename to examples/test_by_running.sh
diff --git a/python/examples/vision/camera_no_lag.py b/examples/vision/camera_no_lag.py
similarity index 100%
rename from python/examples/vision/camera_no_lag.py
rename to examples/vision/camera_no_lag.py
diff --git a/python/convenience_tool_box/__pycache__/give_me_the_calibrated_model.cpython-310.pyc b/python/convenience_tool_box/__pycache__/give_me_the_calibrated_model.cpython-310.pyc
deleted file mode 100644
index cfab0f627e61c0c5f90ce585743a40adb0c59558..0000000000000000000000000000000000000000
Binary files a/python/convenience_tool_box/__pycache__/give_me_the_calibrated_model.cpython-310.pyc and /dev/null differ
diff --git a/python/convenience_tool_box/__pycache__/robotiq_gripper.cpython-310.pyc b/python/convenience_tool_box/__pycache__/robotiq_gripper.cpython-310.pyc
deleted file mode 100644
index ac782a856b3b0b90466cb9e690e68066a36e398b..0000000000000000000000000000000000000000
Binary files a/python/convenience_tool_box/__pycache__/robotiq_gripper.cpython-310.pyc and /dev/null differ
diff --git a/python/examples/cart_pulling/cart_pulling_notes.md b/python/examples/cart_pulling/cart_pulling_notes.md
deleted file mode 100644
index 928c8c4b3cef3c4d3865fd4814bc587e91cab462..0000000000000000000000000000000000000000
--- a/python/examples/cart_pulling/cart_pulling_notes.md
+++ /dev/null
@@ -1,67 +0,0 @@
-# the desided joint space position
-name:
-- myumi_001_yumi_robr_joint_1
-- myumi_001_yumi_robr_joint_2
-- myumi_001_yumi_robr_joint_3
-- myumi_001_yumi_robr_joint_4
-- myumi_001_yumi_robr_joint_5
-- myumi_001_yumi_robr_joint_6
-- myumi_001_yumi_robr_joint_7
-- myumi_001_yumi_robl_joint_1
-- myumi_001_yumi_robl_joint_2
-- myumi_001_yumi_robl_joint_3
-- myumi_001_yumi_robl_joint_4
-- myumi_001_yumi_robl_joint_5
-- myumi_001_yumi_robl_joint_6
-- myumi_001_yumi_robl_joint_7
-position:
-- 1.1781062998438787
-- -0.000595335227562165
-- -1.749208945070357
-- 0.4106104712156747
-- -2.060408639509931
-- 0.3044975499507672
-- 1.7246295661055797
-- -0.7019778380440242
-- 0.0394624047824147
-- 1.1381740635109037
-- 0.40438559848372346
-- 1.5945463973962233
-- 0.3724310942226761
-- -1.3882579393586854
-velocity: []
-effort: []
-
-# better
-name:
-- myumi_001_yumi_robr_joint_1
-- myumi_001_yumi_robr_joint_2
-- myumi_001_yumi_robr_joint_3
-- myumi_001_yumi_robr_joint_4
-- myumi_001_yumi_robr_joint_5
-- myumi_001_yumi_robr_joint_6
-- myumi_001_yumi_robr_joint_7
-- myumi_001_yumi_robl_joint_1
-- myumi_001_yumi_robl_joint_2
-- myumi_001_yumi_robl_joint_3
-- myumi_001_yumi_robl_joint_4
-- myumi_001_yumi_robl_joint_5
-- myumi_001_yumi_robl_joint_6
-- myumi_001_yumi_robl_joint_7
-position:
-- 1.177726666230488
-- -0.0014802503425588292
-- -1.7605729197578341
-- 0.4215065284996249
-- -1.9415690706067803
-- 0.2803584248036936
-- 1.6919710884998835
-- -0.7879804975484437
-- 0.22470208644656367
-- 1.3406988091378869
-- 0.35854547216754384
-- 1.7128065956042273
-- 0.22850344929702915
-- -1.5302555581528383
-velocity: []
-effort: []
diff --git a/python/examples/data/clik_comparison_0.pickle b/python/examples/data/clik_comparison_0.pickle
deleted file mode 100644
index 32e22f561c64f552da9018fdfb46aec3f3b0ca90..0000000000000000000000000000000000000000
Binary files a/python/examples/data/clik_comparison_0.pickle and /dev/null differ
diff --git a/python/examples/data/clik_comparison_1.pickle b/python/examples/data/clik_comparison_1.pickle
deleted file mode 100644
index 0ceb878e17283c30b70f44b5c1e00c57f3c633c7..0000000000000000000000000000000000000000
Binary files a/python/examples/data/clik_comparison_1.pickle and /dev/null differ
diff --git a/python/examples/data/joint_trajectory.csv b/python/examples/data/joint_trajectory.csv
deleted file mode 100644
index 582ecca5fbd8ce5ddab3131d4801cd2f201d314f..0000000000000000000000000000000000000000
--- a/python/examples/data/joint_trajectory.csv
+++ /dev/null
@@ -1,8412 +0,0 @@
-0.00000,1.45545,-0.97542,-1.41192,-0.75829,1.68980,0.00258
-0.00119,1.45341,-0.97604,-1.41187,-0.75772,1.69174,0.00257
-0.00238,1.45135,-0.97666,-1.41182,-0.75716,1.69369,0.00257
-0.00357,1.44928,-0.97728,-1.41176,-0.75660,1.69565,0.00256
-0.00476,1.44721,-0.97790,-1.41170,-0.75603,1.69761,0.00255
-0.00594,1.44514,-0.97853,-1.41165,-0.75546,1.69959,0.00255
-0.00713,1.44305,-0.97916,-1.41159,-0.75490,1.70157,0.00254
-0.00832,1.44096,-0.97979,-1.41152,-0.75433,1.70357,0.00254
-0.00951,1.43887,-0.98043,-1.41146,-0.75376,1.70557,0.00253
-0.01070,1.43676,-0.98106,-1.41139,-0.75320,1.70758,0.00252
-0.01189,1.43465,-0.98170,-1.41132,-0.75263,1.70960,0.00252
-0.01308,1.43254,-0.98234,-1.41125,-0.75206,1.71162,0.00251
-0.01427,1.43042,-0.98298,-1.41118,-0.75149,1.71366,0.00250
-0.01546,1.42829,-0.98363,-1.41111,-0.75092,1.71570,0.00250
-0.01664,1.42616,-0.98427,-1.41104,-0.75035,1.71775,0.00249
-0.01783,1.42402,-0.98492,-1.41096,-0.74978,1.71981,0.00248
-0.01902,1.42187,-0.98557,-1.41088,-0.74920,1.72187,0.00248
-0.02021,1.41973,-0.98622,-1.41080,-0.74863,1.72394,0.00247
-0.02140,1.41757,-0.98688,-1.41072,-0.74806,1.72602,0.00246
-0.02259,1.41541,-0.98753,-1.41064,-0.74749,1.72811,0.00246
-0.02378,1.41325,-0.98819,-1.41055,-0.74691,1.73020,0.00245
-0.02497,1.41108,-0.98885,-1.41046,-0.74634,1.73229,0.00244
-0.02616,1.40891,-0.98951,-1.41038,-0.74577,1.73440,0.00244
-0.02735,1.40673,-0.99018,-1.41029,-0.74519,1.73651,0.00243
-0.02853,1.40455,-0.99084,-1.41019,-0.74462,1.73862,0.00242
-0.02972,1.40236,-0.99151,-1.41010,-0.74405,1.74074,0.00242
-0.03091,1.40017,-0.99217,-1.41001,-0.74347,1.74287,0.00241
-0.03210,1.39798,-0.99284,-1.40991,-0.74290,1.74500,0.00240
-0.03329,1.39578,-0.99352,-1.40981,-0.74232,1.74714,0.00240
-0.03448,1.39358,-0.99419,-1.40971,-0.74175,1.74928,0.00239
-0.03567,1.39138,-0.99486,-1.40961,-0.74118,1.75143,0.00238
-0.03686,1.38917,-0.99554,-1.40951,-0.74060,1.75358,0.00238
-0.03805,1.38696,-0.99621,-1.40941,-0.74003,1.75574,0.00237
-0.03923,1.38475,-0.99689,-1.40930,-0.73945,1.75790,0.00236
-0.04042,1.38253,-0.99757,-1.40919,-0.73888,1.76006,0.00235
-0.04161,1.38032,-0.99825,-1.40908,-0.73831,1.76223,0.00235
-0.04280,1.37810,-0.99893,-1.40897,-0.73773,1.76440,0.00234
-0.04399,1.37587,-0.99962,-1.40886,-0.73716,1.76657,0.00233
-0.04518,1.37365,-1.00030,-1.40875,-0.73659,1.76875,0.00233
-0.04637,1.37142,-1.00099,-1.40864,-0.73601,1.77093,0.00232
-0.04756,1.36920,-1.00167,-1.40852,-0.73544,1.77312,0.00231
-0.04875,1.36697,-1.00236,-1.40840,-0.73487,1.77530,0.00231
-0.04993,1.36474,-1.00305,-1.40828,-0.73430,1.77749,0.00230
-0.05112,1.36251,-1.00374,-1.40816,-0.73373,1.77968,0.00229
-0.05231,1.36027,-1.00442,-1.40804,-0.73316,1.78188,0.00229
-0.05350,1.35804,-1.00512,-1.40792,-0.73259,1.78407,0.00228
-0.05469,1.35581,-1.00581,-1.40780,-0.73202,1.78627,0.00227
-0.05588,1.35357,-1.00650,-1.40767,-0.73145,1.78847,0.00226
-0.05707,1.35134,-1.00719,-1.40754,-0.73088,1.79067,0.00226
-0.05826,1.34910,-1.00788,-1.40742,-0.73031,1.79287,0.00225
-0.05945,1.34687,-1.00857,-1.40729,-0.72975,1.79507,0.00224
-0.06063,1.34463,-1.00927,-1.40716,-0.72918,1.79727,0.00224
-0.06182,1.34240,-1.00996,-1.40703,-0.72862,1.79948,0.00223
-0.06301,1.34016,-1.01066,-1.40689,-0.72805,1.80168,0.00222
-0.06420,1.33793,-1.01135,-1.40676,-0.72749,1.80389,0.00222
-0.06539,1.33569,-1.01205,-1.40662,-0.72693,1.80609,0.00221
-0.06658,1.33346,-1.01274,-1.40649,-0.72637,1.80830,0.00220
-0.06777,1.33123,-1.01344,-1.40635,-0.72580,1.81050,0.00219
-0.06896,1.32900,-1.01413,-1.40621,-0.72525,1.81270,0.00219
-0.07015,1.32677,-1.01483,-1.40607,-0.72469,1.81491,0.00218
-0.07134,1.32455,-1.01552,-1.40593,-0.72413,1.81711,0.00217
-0.07252,1.32232,-1.01622,-1.40579,-0.72357,1.81931,0.00217
-0.07371,1.32010,-1.01691,-1.40564,-0.72302,1.82151,0.00216
-0.07490,1.31788,-1.01761,-1.40550,-0.72246,1.82371,0.00215
-0.07609,1.31566,-1.01830,-1.40535,-0.72191,1.82591,0.00215
-0.07728,1.31345,-1.01899,-1.40521,-0.72136,1.82811,0.00214
-0.07847,1.31123,-1.01969,-1.40506,-0.72081,1.83030,0.00213
-0.07966,1.30902,-1.02038,-1.40491,-0.72026,1.83249,0.00213
-0.08085,1.30682,-1.02107,-1.40476,-0.71971,1.83468,0.00212
-0.08204,1.30461,-1.02177,-1.40461,-0.71917,1.83687,0.00211
-0.08322,1.30241,-1.02246,-1.40446,-0.71862,1.83906,0.00211
-0.08441,1.30021,-1.02315,-1.40431,-0.71808,1.84124,0.00210
-0.08560,1.29802,-1.02384,-1.40416,-0.71754,1.84342,0.00209
-0.08679,1.29583,-1.02453,-1.40400,-0.71700,1.84560,0.00209
-0.08798,1.29364,-1.02522,-1.40385,-0.71646,1.84777,0.00208
-0.08917,1.29146,-1.02591,-1.40369,-0.71592,1.84994,0.00207
-0.09036,1.28928,-1.02660,-1.40353,-0.71539,1.85211,0.00207
-0.09155,1.28710,-1.02728,-1.40338,-0.71486,1.85427,0.00206
-0.09274,1.28493,-1.02797,-1.40322,-0.71432,1.85643,0.00205
-0.09392,1.28277,-1.02865,-1.40306,-0.71379,1.85859,0.00205
-0.09511,1.28061,-1.02934,-1.40290,-0.71326,1.86074,0.00204
-0.09630,1.27845,-1.03002,-1.40274,-0.71274,1.86289,0.00203
-0.09749,1.27630,-1.03070,-1.40258,-0.71221,1.86503,0.00203
-0.09868,1.27415,-1.03138,-1.40242,-0.71169,1.86717,0.00202
-0.09987,1.27201,-1.03206,-1.40225,-0.71117,1.86930,0.00201
-0.10106,1.26987,-1.03274,-1.40209,-0.71065,1.87143,0.00201
-0.10225,1.26774,-1.03342,-1.40193,-0.71013,1.87356,0.00200
-0.10344,1.26562,-1.03409,-1.40176,-0.70962,1.87568,0.00200
-0.10462,1.26350,-1.03477,-1.40160,-0.70910,1.87779,0.00199
-0.10581,1.26139,-1.03544,-1.40143,-0.70859,1.87990,0.00198
-0.10700,1.25928,-1.03611,-1.40127,-0.70808,1.88200,0.00198
-0.10819,1.25718,-1.03678,-1.40110,-0.70758,1.88410,0.00197
-0.10938,1.25508,-1.03745,-1.40093,-0.70707,1.88620,0.00196
-0.11057,1.25299,-1.03812,-1.40076,-0.70657,1.88828,0.00196
-0.11176,1.25091,-1.03878,-1.40060,-0.70607,1.89036,0.00195
-0.11295,1.24883,-1.03944,-1.40043,-0.70557,1.89244,0.00195
-0.11414,1.24676,-1.04011,-1.40026,-0.70507,1.89451,0.00194
-0.11533,1.24470,-1.04077,-1.40009,-0.70457,1.89657,0.00193
-0.11651,1.24264,-1.04142,-1.39992,-0.70408,1.89863,0.00193
-0.11770,1.24059,-1.04208,-1.39975,-0.70359,1.90068,0.00192
-0.11889,1.23843,-1.04278,-1.39957,-0.70306,1.90283,0.00191
-0.12008,1.23525,-1.04390,-1.39932,-0.70219,1.90598,0.00190
-0.12127,1.23207,-1.04502,-1.39908,-0.70132,1.90912,0.00189
-0.12246,1.22890,-1.04613,-1.39883,-0.70045,1.91225,0.00188
-0.12365,1.22574,-1.04725,-1.39857,-0.69959,1.91538,0.00187
-0.12484,1.22259,-1.04836,-1.39832,-0.69873,1.91849,0.00186
-0.12603,1.21945,-1.04947,-1.39806,-0.69788,1.92160,0.00185
-0.12721,1.21631,-1.05057,-1.39780,-0.69703,1.92470,0.00184
-0.12840,1.21319,-1.05168,-1.39753,-0.69619,1.92780,0.00183
-0.12959,1.21008,-1.05278,-1.39727,-0.69535,1.93088,0.00182
-0.13078,1.20698,-1.05388,-1.39700,-0.69451,1.93395,0.00181
-0.13197,1.20389,-1.05497,-1.39673,-0.69368,1.93702,0.00180
-0.13316,1.20082,-1.05607,-1.39646,-0.69286,1.94007,0.00179
-0.13435,1.19775,-1.05716,-1.39619,-0.69204,1.94311,0.00178
-0.13554,1.19470,-1.05824,-1.39592,-0.69122,1.94614,0.00177
-0.13673,1.19166,-1.05933,-1.39564,-0.69041,1.94916,0.00176
-0.13791,1.18863,-1.06041,-1.39536,-0.68961,1.95217,0.00175
-0.13910,1.18561,-1.06148,-1.39508,-0.68881,1.95517,0.00174
-0.14029,1.18261,-1.06256,-1.39480,-0.68801,1.95815,0.00173
-0.14148,1.17963,-1.06362,-1.39452,-0.68722,1.96112,0.00172
-0.14267,1.17665,-1.06469,-1.39423,-0.68644,1.96408,0.00171
-0.14386,1.17369,-1.06575,-1.39395,-0.68566,1.96703,0.00171
-0.14505,1.17075,-1.06681,-1.39366,-0.68488,1.96996,0.00170
-0.14624,1.16781,-1.06786,-1.39337,-0.68412,1.97288,0.00169
-0.14743,1.16490,-1.06891,-1.39308,-0.68335,1.97579,0.00168
-0.14861,1.16200,-1.06995,-1.39279,-0.68260,1.97868,0.00167
-0.14980,1.15911,-1.07099,-1.39250,-0.68184,1.98156,0.00166
-0.15099,1.15624,-1.07203,-1.39221,-0.68110,1.98442,0.00165
-0.15218,1.15338,-1.07306,-1.39191,-0.68035,1.98727,0.00164
-0.15337,1.15054,-1.07408,-1.39162,-0.67962,1.99010,0.00163
-0.15456,1.14772,-1.07511,-1.39132,-0.67889,1.99292,0.00162
-0.15575,1.14491,-1.07612,-1.39103,-0.67816,1.99572,0.00162
-0.15694,1.14212,-1.07713,-1.39073,-0.67744,1.99851,0.00161
-0.15813,1.13934,-1.07814,-1.39043,-0.67673,2.00128,0.00160
-0.15932,1.13658,-1.07914,-1.39014,-0.67602,2.00404,0.00159
-0.16050,1.13384,-1.08014,-1.38984,-0.67532,2.00678,0.00158
-0.16169,1.13112,-1.08113,-1.38954,-0.67462,2.00951,0.00157
-0.16288,1.12841,-1.08212,-1.38924,-0.67393,2.01222,0.00156
-0.16407,1.12571,-1.08310,-1.38894,-0.67324,2.01491,0.00156
-0.16526,1.12304,-1.08407,-1.38864,-0.67256,2.01759,0.00155
-0.16645,1.12038,-1.08504,-1.38834,-0.67189,2.02025,0.00154
-0.16764,1.11774,-1.08601,-1.38804,-0.67122,2.02289,0.00153
-0.16883,1.11512,-1.08697,-1.38774,-0.67055,2.02552,0.00153
-0.17002,1.11251,-1.08792,-1.38744,-0.66990,2.02813,0.00152
-0.17120,1.10992,-1.08887,-1.38714,-0.66924,2.03072,0.00151
-0.17239,1.10735,-1.08981,-1.38683,-0.66860,2.03330,0.00150
-0.17358,1.10480,-1.09075,-1.38653,-0.66795,2.03586,0.00149
-0.17477,1.10226,-1.09168,-1.38623,-0.66732,2.03840,0.00149
-0.17596,1.09974,-1.09261,-1.38593,-0.66669,2.04092,0.00148
-0.17715,1.09724,-1.09353,-1.38563,-0.66606,2.04343,0.00147
-0.17834,1.09476,-1.09444,-1.38533,-0.66545,2.04592,0.00147
-0.17953,1.09229,-1.09535,-1.38503,-0.66483,2.04840,0.00146
-0.18072,1.08984,-1.09625,-1.38473,-0.66422,2.05085,0.00145
-0.18190,1.08741,-1.09715,-1.38443,-0.66362,2.05329,0.00144
-0.18309,1.08500,-1.09804,-1.38413,-0.66303,2.05571,0.00144
-0.18428,1.08261,-1.09892,-1.38383,-0.66243,2.05812,0.00143
-0.18547,1.08023,-1.09980,-1.38353,-0.66185,2.06050,0.00142
-0.18666,1.07787,-1.10067,-1.38324,-0.66127,2.06287,0.00142
-0.18785,1.07553,-1.10154,-1.38294,-0.66069,2.06522,0.00141
-0.18904,1.07321,-1.10240,-1.38264,-0.66012,2.06756,0.00141
-0.19023,1.07091,-1.10325,-1.38235,-0.65956,2.06988,0.00140
-0.19142,1.06862,-1.10410,-1.38205,-0.65900,2.07217,0.00139
-0.19260,1.06635,-1.10494,-1.38176,-0.65845,2.07446,0.00139
-0.19379,1.06410,-1.10578,-1.38146,-0.65790,2.07672,0.00138
-0.19498,1.06187,-1.10661,-1.38117,-0.65736,2.07897,0.00137
-0.19617,1.05965,-1.10743,-1.38088,-0.65682,2.08120,0.00137
-0.19736,1.05745,-1.10825,-1.38058,-0.65629,2.08341,0.00136
-0.19855,1.05527,-1.10906,-1.38029,-0.65576,2.08560,0.00136
-0.19974,1.05311,-1.10987,-1.38000,-0.65524,2.08778,0.00135
-0.20093,1.05097,-1.11067,-1.37971,-0.65472,2.08994,0.00135
-0.20212,1.04884,-1.11146,-1.37943,-0.65421,2.09208,0.00134
-0.20331,1.04673,-1.11225,-1.37914,-0.65371,2.09421,0.00133
-0.20449,1.04464,-1.11303,-1.37885,-0.65321,2.09631,0.00133
-0.20568,1.04256,-1.11380,-1.37857,-0.65271,2.09840,0.00132
-0.20687,1.04050,-1.11457,-1.37828,-0.65222,2.10048,0.00132
-0.20806,1.03846,-1.11534,-1.37800,-0.65173,2.10253,0.00131
-0.20925,1.03644,-1.11609,-1.37772,-0.65125,2.10457,0.00131
-0.21044,1.03443,-1.11684,-1.37744,-0.65078,2.10660,0.00130
-0.21163,1.03245,-1.11759,-1.37716,-0.65031,2.10860,0.00130
-0.21282,1.03047,-1.11833,-1.37688,-0.64984,2.11059,0.00129
-0.21401,1.02852,-1.11906,-1.37660,-0.64938,2.11256,0.00129
-0.21519,1.02658,-1.11978,-1.37633,-0.64892,2.11452,0.00128
-0.21638,1.02466,-1.12050,-1.37605,-0.64847,2.11646,0.00128
-0.21757,1.02276,-1.12122,-1.37578,-0.64802,2.11838,0.00128
-0.21876,1.02087,-1.12193,-1.37551,-0.64758,2.12028,0.00127
-0.21995,1.01900,-1.12263,-1.37524,-0.64715,2.12217,0.00127
-0.22114,1.01714,-1.12333,-1.37497,-0.64671,2.12405,0.00126
-0.22233,1.01531,-1.12402,-1.37470,-0.64628,2.12590,0.00126
-0.22352,1.01348,-1.12470,-1.37443,-0.64586,2.12774,0.00125
-0.22471,1.01168,-1.12538,-1.37416,-0.64544,2.12957,0.00125
-0.22589,1.00989,-1.12605,-1.37390,-0.64503,2.13137,0.00125
-0.22708,1.00812,-1.12672,-1.37364,-0.64462,2.13316,0.00124
-0.22827,1.00636,-1.12738,-1.37338,-0.64421,2.13494,0.00124
-0.22946,1.00462,-1.12803,-1.37312,-0.64381,2.13670,0.00123
-0.23065,1.00289,-1.12868,-1.37286,-0.64342,2.13844,0.00123
-0.23184,1.00118,-1.12933,-1.37260,-0.64302,2.14017,0.00123
-0.23303,0.99949,-1.12996,-1.37234,-0.64264,2.14189,0.00122
-0.23422,0.99781,-1.13060,-1.37209,-0.64225,2.14358,0.00122
-0.23541,0.99615,-1.13122,-1.37184,-0.64187,2.14527,0.00122
-0.23659,0.99450,-1.13184,-1.37159,-0.64150,2.14693,0.00121
-0.23778,0.99278,-1.13251,-1.37132,-0.64110,2.14866,0.00121
-0.23897,0.99035,-1.13359,-1.37088,-0.64044,2.15110,0.00120
-0.24016,0.98794,-1.13467,-1.37045,-0.63979,2.15350,0.00119
-0.24135,0.98555,-1.13574,-1.37002,-0.63915,2.15589,0.00119
-0.24254,0.98319,-1.13679,-1.36960,-0.63852,2.15825,0.00118
-0.24373,0.98085,-1.13784,-1.36917,-0.63790,2.16059,0.00117
-0.24492,0.97853,-1.13887,-1.36875,-0.63728,2.16291,0.00116
-0.24611,0.97624,-1.13990,-1.36833,-0.63668,2.16520,0.00116
-0.24730,0.97397,-1.14091,-1.36791,-0.63608,2.16748,0.00115
-0.24848,0.97172,-1.14192,-1.36749,-0.63548,2.16973,0.00114
-0.24967,0.96950,-1.14291,-1.36708,-0.63490,2.17196,0.00113
-0.25086,0.96729,-1.14390,-1.36667,-0.63432,2.17416,0.00113
-0.25205,0.96511,-1.14487,-1.36626,-0.63375,2.17635,0.00112
-0.25324,0.96295,-1.14584,-1.36585,-0.63319,2.17851,0.00112
-0.25443,0.96082,-1.14679,-1.36545,-0.63264,2.18065,0.00111
-0.25562,0.95870,-1.14773,-1.36505,-0.63209,2.18277,0.00110
-0.25681,0.95661,-1.14867,-1.36465,-0.63155,2.18487,0.00110
-0.25800,0.95454,-1.14959,-1.36425,-0.63102,2.18695,0.00109
-0.25918,0.95249,-1.15051,-1.36386,-0.63049,2.18901,0.00109
-0.26037,0.95046,-1.15142,-1.36347,-0.62997,2.19104,0.00108
-0.26156,0.94846,-1.15231,-1.36308,-0.62946,2.19306,0.00107
-0.26275,0.94647,-1.15320,-1.36269,-0.62896,2.19505,0.00107
-0.26394,0.94450,-1.15408,-1.36231,-0.62846,2.19703,0.00106
-0.26513,0.94256,-1.15494,-1.36193,-0.62797,2.19898,0.00106
-0.26632,0.94064,-1.15580,-1.36155,-0.62748,2.20092,0.00105
-0.26751,0.93873,-1.15665,-1.36117,-0.62700,2.20283,0.00105
-0.26870,0.93685,-1.15749,-1.36080,-0.62653,2.20472,0.00104
-0.26988,0.93499,-1.15832,-1.36043,-0.62607,2.20660,0.00104
-0.27107,0.93314,-1.15915,-1.36006,-0.62561,2.20845,0.00103
-0.27226,0.93132,-1.15996,-1.35970,-0.62515,2.21029,0.00103
-0.27345,0.92951,-1.16077,-1.35933,-0.62471,2.21210,0.00102
-0.27464,0.92773,-1.16156,-1.35897,-0.62427,2.21390,0.00102
-0.27583,0.92596,-1.16235,-1.35862,-0.62383,2.21568,0.00102
-0.27702,0.92422,-1.16313,-1.35826,-0.62340,2.21744,0.00101
-0.27821,0.92249,-1.16390,-1.35791,-0.62298,2.21918,0.00101
-0.27940,0.92078,-1.16466,-1.35756,-0.62256,2.22090,0.00100
-0.28058,0.91909,-1.16541,-1.35722,-0.62215,2.22260,0.00100
-0.28177,0.91742,-1.16615,-1.35687,-0.62174,2.22429,0.00100
-0.28296,0.91577,-1.16689,-1.35653,-0.62134,2.22595,0.00099
-0.28415,0.91413,-1.16762,-1.35619,-0.62095,2.22760,0.00099
-0.28534,0.91251,-1.16834,-1.35586,-0.62056,2.22923,0.00098
-0.28653,0.91091,-1.16905,-1.35553,-0.62018,2.23085,0.00098
-0.28772,0.90933,-1.16975,-1.35520,-0.61980,2.23244,0.00098
-0.28891,0.90776,-1.17045,-1.35487,-0.61942,2.23402,0.00097
-0.29010,0.90622,-1.17114,-1.35455,-0.61906,2.23559,0.00097
-0.29129,0.90469,-1.17182,-1.35422,-0.61869,2.23713,0.00097
-0.29247,0.90317,-1.17249,-1.35390,-0.61833,2.23866,0.00097
-0.29366,0.90168,-1.17315,-1.35359,-0.61798,2.24017,0.00096
-0.29485,0.90020,-1.17381,-1.35327,-0.61763,2.24167,0.00096
-0.29604,0.89873,-1.17446,-1.35296,-0.61729,2.24315,0.00096
-0.29723,0.89728,-1.17510,-1.35266,-0.61695,2.24461,0.00095
-0.29842,0.89585,-1.17573,-1.35235,-0.61662,2.24605,0.00095
-0.29961,0.89444,-1.17636,-1.35205,-0.61629,2.24749,0.00095
-0.30080,0.89304,-1.17698,-1.35175,-0.61596,2.24890,0.00095
-0.30199,0.89165,-1.17759,-1.35145,-0.61564,2.25030,0.00094
-0.30317,0.89028,-1.17820,-1.35116,-0.61532,2.25168,0.00094
-0.30436,0.88893,-1.17880,-1.35086,-0.61501,2.25305,0.00094
-0.30555,0.88759,-1.17939,-1.35057,-0.61471,2.25441,0.00094
-0.30674,0.88627,-1.17997,-1.35029,-0.61440,2.25574,0.00094
-0.30793,0.88496,-1.18055,-1.35000,-0.61410,2.25707,0.00093
-0.30912,0.88367,-1.18112,-1.34972,-0.61381,2.25838,0.00093
-0.31031,0.88239,-1.18169,-1.34944,-0.61352,2.25967,0.00093
-0.31150,0.88112,-1.18224,-1.34917,-0.61323,2.26095,0.00093
-0.31269,0.87987,-1.18279,-1.34889,-0.61295,2.26222,0.00093
-0.31387,0.87864,-1.18334,-1.34862,-0.61267,2.26347,0.00092
-0.31506,0.87742,-1.18388,-1.34835,-0.61240,2.26471,0.00092
-0.31625,0.87621,-1.18441,-1.34808,-0.61213,2.26593,0.00092
-0.31744,0.87501,-1.18493,-1.34782,-0.61186,2.26714,0.00092
-0.31863,0.87383,-1.18545,-1.34756,-0.61160,2.26834,0.00092
-0.31982,0.87266,-1.18596,-1.34730,-0.61134,2.26952,0.00092
-0.32101,0.87151,-1.18647,-1.34704,-0.61108,2.27069,0.00091
-0.32220,0.87037,-1.18697,-1.34679,-0.61083,2.27185,0.00091
-0.32339,0.86924,-1.18747,-1.34654,-0.61058,2.27299,0.00091
-0.32457,0.86813,-1.18796,-1.34629,-0.61034,2.27412,0.00091
-0.32576,0.86702,-1.18844,-1.34604,-0.61010,2.27524,0.00091
-0.32695,0.86593,-1.18892,-1.34580,-0.60986,2.27634,0.00091
-0.32814,0.86486,-1.18939,-1.34556,-0.60963,2.27744,0.00091
-0.32933,0.86379,-1.18985,-1.34532,-0.60939,2.27852,0.00091
-0.33052,0.86274,-1.19031,-1.34508,-0.60917,2.27959,0.00090
-0.33171,0.86170,-1.19077,-1.34485,-0.60894,2.28064,0.00090
-0.33290,0.86067,-1.19122,-1.34461,-0.60872,2.28169,0.00090
-0.33409,0.85965,-1.19166,-1.34438,-0.60850,2.28272,0.00090
-0.33528,0.85864,-1.19210,-1.34416,-0.60829,2.28374,0.00090
-0.33646,0.85765,-1.19253,-1.34393,-0.60807,2.28475,0.00090
-0.33765,0.85667,-1.19296,-1.34371,-0.60786,2.28575,0.00090
-0.33884,0.85570,-1.19338,-1.34349,-0.60766,2.28673,0.00090
-0.34003,0.85474,-1.19380,-1.34327,-0.60745,2.28771,0.00090
-0.34122,0.85379,-1.19421,-1.34305,-0.60725,2.28867,0.00090
-0.34241,0.85285,-1.19462,-1.34284,-0.60706,2.28963,0.00090
-0.34360,0.85192,-1.19502,-1.34262,-0.60686,2.29057,0.00089
-0.34479,0.85101,-1.19542,-1.34241,-0.60667,2.29150,0.00089
-0.34598,0.85010,-1.19581,-1.34221,-0.60648,2.29242,0.00089
-0.34716,0.84920,-1.19620,-1.34200,-0.60629,2.29333,0.00089
-0.34835,0.84832,-1.19658,-1.34180,-0.60611,2.29423,0.00089
-0.34954,0.84744,-1.19696,-1.34160,-0.60593,2.29512,0.00089
-0.35073,0.84658,-1.19733,-1.34140,-0.60575,2.29600,0.00089
-0.35192,0.84572,-1.19770,-1.34120,-0.60557,2.29687,0.00089
-0.35311,0.84488,-1.19806,-1.34100,-0.60540,2.29773,0.00089
-0.35430,0.84404,-1.19842,-1.34081,-0.60523,2.29858,0.00089
-0.35549,0.84322,-1.19878,-1.34062,-0.60506,2.29942,0.00089
-0.35668,0.84237,-1.19915,-1.34042,-0.60488,2.30028,0.00089
-0.35786,0.84128,-1.19971,-1.34014,-0.60461,2.30137,0.00089
-0.35905,0.84021,-1.20025,-1.33985,-0.60434,2.30245,0.00088
-0.36024,0.83915,-1.20079,-1.33958,-0.60407,2.30352,0.00088
-0.36143,0.83810,-1.20133,-1.33930,-0.60381,2.30458,0.00088
-0.36262,0.83706,-1.20185,-1.33903,-0.60356,2.30563,0.00088
-0.36381,0.83604,-1.20237,-1.33876,-0.60330,2.30666,0.00088
-0.36500,0.83502,-1.20289,-1.33849,-0.60306,2.30768,0.00087
-0.36619,0.83402,-1.20339,-1.33822,-0.60281,2.30869,0.00087
-0.36738,0.83303,-1.20389,-1.33796,-0.60257,2.30968,0.00087
-0.36856,0.83206,-1.20439,-1.33770,-0.60233,2.31067,0.00087
-0.36975,0.83109,-1.20487,-1.33745,-0.60210,2.31164,0.00087
-0.37094,0.83014,-1.20535,-1.33719,-0.60187,2.31261,0.00086
-0.37213,0.82920,-1.20583,-1.33694,-0.60164,2.31356,0.00086
-0.37332,0.82827,-1.20629,-1.33670,-0.60142,2.31450,0.00086
-0.37451,0.82735,-1.20675,-1.33645,-0.60120,2.31542,0.00086
-0.37570,0.82644,-1.20721,-1.33621,-0.60099,2.31634,0.00086
-0.37689,0.82554,-1.20766,-1.33597,-0.60077,2.31725,0.00086
-0.37808,0.82465,-1.20810,-1.33573,-0.60056,2.31815,0.00086
-0.37927,0.82377,-1.20854,-1.33550,-0.60036,2.31903,0.00085
-0.38045,0.82291,-1.20897,-1.33526,-0.60016,2.31991,0.00085
-0.38164,0.82205,-1.20940,-1.33503,-0.59996,2.32077,0.00085
-0.38283,0.82121,-1.20982,-1.33481,-0.59976,2.32162,0.00085
-0.38402,0.82037,-1.21023,-1.33458,-0.59957,2.32247,0.00085
-0.38521,0.81955,-1.21064,-1.33436,-0.59938,2.32330,0.00085
-0.38640,0.81873,-1.21104,-1.33414,-0.59919,2.32413,0.00085
-0.38759,0.81793,-1.21144,-1.33392,-0.59900,2.32494,0.00085
-0.38878,0.81713,-1.21184,-1.33371,-0.59882,2.32575,0.00085
-0.38997,0.81634,-1.21222,-1.33349,-0.59864,2.32654,0.00084
-0.39115,0.81557,-1.21261,-1.33328,-0.59847,2.32733,0.00084
-0.39234,0.81480,-1.21298,-1.33308,-0.59829,2.32811,0.00084
-0.39353,0.81404,-1.21336,-1.33287,-0.59812,2.32887,0.00084
-0.39472,0.81329,-1.21372,-1.33267,-0.59795,2.32963,0.00084
-0.39591,0.81255,-1.21409,-1.33247,-0.59779,2.33038,0.00084
-0.39710,0.81182,-1.21445,-1.33227,-0.59763,2.33112,0.00084
-0.39829,0.81110,-1.21480,-1.33207,-0.59747,2.33185,0.00084
-0.39948,0.81039,-1.21515,-1.33188,-0.59731,2.33258,0.00084
-0.40067,0.80968,-1.21549,-1.33169,-0.59715,2.33329,0.00084
-0.40185,0.80898,-1.21583,-1.33150,-0.59700,2.33400,0.00084
-0.40304,0.80830,-1.21616,-1.33131,-0.59685,2.33469,0.00084
-0.40423,0.80762,-1.21650,-1.33112,-0.59670,2.33538,0.00084
-0.40542,0.80694,-1.21682,-1.33094,-0.59655,2.33606,0.00084
-0.40661,0.80628,-1.21714,-1.33076,-0.59641,2.33674,0.00084
-0.40780,0.80562,-1.21746,-1.33058,-0.59627,2.33740,0.00084
-0.40899,0.80498,-1.21777,-1.33040,-0.59613,2.33806,0.00084
-0.41018,0.80434,-1.21808,-1.33023,-0.59599,2.33871,0.00084
-0.41137,0.80370,-1.21839,-1.33006,-0.59586,2.33935,0.00084
-0.41255,0.80308,-1.21869,-1.32988,-0.59572,2.33998,0.00084
-0.41374,0.80250,-1.21897,-1.32972,-0.59560,2.34057,0.00083
-0.41493,0.80167,-1.21945,-1.32947,-0.59538,2.34141,0.00083
-0.41612,0.80084,-1.21991,-1.32922,-0.59516,2.34224,0.00083
-0.41731,0.80002,-1.22037,-1.32897,-0.59495,2.34306,0.00083
-0.41850,0.79922,-1.22082,-1.32872,-0.59474,2.34387,0.00083
-0.41969,0.79842,-1.22127,-1.32847,-0.59454,2.34467,0.00082
-0.42088,0.79763,-1.22171,-1.32823,-0.59434,2.34546,0.00082
-0.42207,0.79686,-1.22215,-1.32799,-0.59414,2.34624,0.00082
-0.42326,0.79609,-1.22258,-1.32776,-0.59394,2.34702,0.00082
-0.42444,0.79533,-1.22300,-1.32753,-0.59375,2.34778,0.00082
-0.42563,0.79458,-1.22341,-1.32729,-0.59357,2.34853,0.00082
-0.42682,0.79384,-1.22382,-1.32707,-0.59338,2.34927,0.00082
-0.42801,0.79311,-1.22423,-1.32684,-0.59320,2.35001,0.00081
-0.42920,0.79239,-1.22463,-1.32662,-0.59302,2.35074,0.00081
-0.43039,0.79168,-1.22502,-1.32640,-0.59284,2.35145,0.00081
-0.43158,0.79098,-1.22541,-1.32618,-0.59267,2.35216,0.00081
-0.43277,0.79028,-1.22579,-1.32597,-0.59250,2.35286,0.00081
-0.43396,0.78960,-1.22617,-1.32576,-0.59233,2.35355,0.00081
-0.43514,0.78892,-1.22654,-1.32555,-0.59217,2.35424,0.00081
-0.43633,0.78825,-1.22691,-1.32534,-0.59200,2.35491,0.00081
-0.43752,0.78759,-1.22727,-1.32513,-0.59184,2.35558,0.00081
-0.43871,0.78694,-1.22763,-1.32493,-0.59169,2.35623,0.00080
-0.43990,0.78630,-1.22798,-1.32473,-0.59153,2.35688,0.00080
-0.44109,0.78566,-1.22833,-1.32453,-0.59138,2.35753,0.00080
-0.44228,0.78503,-1.22867,-1.32434,-0.59123,2.35816,0.00080
-0.44347,0.78441,-1.22901,-1.32415,-0.59108,2.35879,0.00080
-0.44466,0.78380,-1.22934,-1.32396,-0.59094,2.35941,0.00080
-0.44584,0.78319,-1.22967,-1.32377,-0.59080,2.36002,0.00080
-0.44703,0.78259,-1.22999,-1.32358,-0.59066,2.36062,0.00080
-0.44822,0.78197,-1.23034,-1.32338,-0.59051,2.36125,0.00080
-0.44941,0.78102,-1.23096,-1.32302,-0.59025,2.36219,0.00079
-0.45060,0.78009,-1.23157,-1.32267,-0.58999,2.36312,0.00079
-0.45179,0.77917,-1.23217,-1.32232,-0.58974,2.36404,0.00079
-0.45298,0.77827,-1.23277,-1.32197,-0.58949,2.36495,0.00078
-0.45417,0.77737,-1.23335,-1.32163,-0.58925,2.36584,0.00078
-0.45536,0.77649,-1.23393,-1.32129,-0.58901,2.36672,0.00078
-0.45655,0.77562,-1.23450,-1.32096,-0.58877,2.36759,0.00078
-0.45773,0.77476,-1.23506,-1.32062,-0.58854,2.36845,0.00077
-0.45892,0.77391,-1.23561,-1.32030,-0.58832,2.36930,0.00077
-0.46011,0.77307,-1.23615,-1.31998,-0.58809,2.37014,0.00077
-0.46130,0.77224,-1.23669,-1.31966,-0.58788,2.37097,0.00077
-0.46249,0.77142,-1.23721,-1.31934,-0.58766,2.37179,0.00076
-0.46368,0.77062,-1.23773,-1.31903,-0.58745,2.37260,0.00076
-0.46487,0.76982,-1.23825,-1.31873,-0.58724,2.37340,0.00076
-0.46606,0.76903,-1.23875,-1.31842,-0.58704,2.37418,0.00076
-0.46725,0.76826,-1.23925,-1.31812,-0.58684,2.37496,0.00075
-0.46843,0.76749,-1.23974,-1.31783,-0.58664,2.37573,0.00075
-0.46962,0.76673,-1.24022,-1.31754,-0.58645,2.37649,0.00075
-0.47081,0.76599,-1.24070,-1.31725,-0.58626,2.37724,0.00075
-0.47200,0.76525,-1.24117,-1.31696,-0.58607,2.37797,0.00075
-0.47319,0.76452,-1.24163,-1.31668,-0.58589,2.37870,0.00074
-0.47438,0.76381,-1.24209,-1.31641,-0.58571,2.37943,0.00074
-0.47557,0.76310,-1.24254,-1.31613,-0.58554,2.38014,0.00074
-0.47676,0.76240,-1.24298,-1.31586,-0.58536,2.38084,0.00074
-0.47795,0.76171,-1.24341,-1.31559,-0.58519,2.38153,0.00074
-0.47913,0.76102,-1.24384,-1.31533,-0.58502,2.38222,0.00074
-0.48032,0.76035,-1.24427,-1.31507,-0.58486,2.38289,0.00074
-0.48151,0.75969,-1.24468,-1.31481,-0.58470,2.38356,0.00074
-0.48270,0.75903,-1.24509,-1.31455,-0.58454,2.38422,0.00073
-0.48389,0.75838,-1.24550,-1.31430,-0.58438,2.38487,0.00073
-0.48508,0.75774,-1.24590,-1.31406,-0.58423,2.38551,0.00073
-0.48627,0.75711,-1.24629,-1.31381,-0.58408,2.38615,0.00073
-0.48746,0.75649,-1.24668,-1.31357,-0.58393,2.38677,0.00073
-0.48865,0.75588,-1.24706,-1.31333,-0.58379,2.38739,0.00073
-0.48983,0.75527,-1.24744,-1.31309,-0.58364,2.38800,0.00073
-0.49102,0.75467,-1.24781,-1.31286,-0.58350,2.38861,0.00073
-0.49221,0.75408,-1.24817,-1.31263,-0.58337,2.38920,0.00073
-0.49340,0.75350,-1.24853,-1.31240,-0.58323,2.38979,0.00073
-0.49459,0.75292,-1.24889,-1.31218,-0.58310,2.39037,0.00073
-0.49578,0.75235,-1.24924,-1.31196,-0.58297,2.39094,0.00073
-0.49697,0.75179,-1.24958,-1.31174,-0.58284,2.39151,0.00072
-0.49816,0.75149,-1.24977,-1.31162,-0.58277,2.39181,0.00072
-0.49935,0.75071,-1.25032,-1.31127,-0.58257,2.39259,0.00072
-0.50054,0.74994,-1.25086,-1.31093,-0.58237,2.39336,0.00072
-0.50172,0.74918,-1.25139,-1.31059,-0.58218,2.39412,0.00072
-0.50291,0.74843,-1.25191,-1.31025,-0.58199,2.39487,0.00071
-0.50410,0.74769,-1.25243,-1.30992,-0.58181,2.39560,0.00071
-0.50529,0.74697,-1.25293,-1.30960,-0.58162,2.39633,0.00071
-0.50648,0.74625,-1.25343,-1.30928,-0.58145,2.39705,0.00071
-0.50767,0.74554,-1.25392,-1.30896,-0.58127,2.39776,0.00071
-0.50886,0.74484,-1.25441,-1.30864,-0.58110,2.39847,0.00070
-0.51005,0.74415,-1.25488,-1.30833,-0.58093,2.39916,0.00070
-0.51124,0.74346,-1.25535,-1.30803,-0.58076,2.39984,0.00070
-0.51242,0.74279,-1.25582,-1.30773,-0.58060,2.40052,0.00070
-0.51361,0.74213,-1.25627,-1.30743,-0.58044,2.40118,0.00070
-0.51480,0.74147,-1.25672,-1.30713,-0.58028,2.40184,0.00070
-0.51599,0.74082,-1.25717,-1.30684,-0.58013,2.40249,0.00070
-0.51718,0.74019,-1.25760,-1.30656,-0.57998,2.40313,0.00069
-0.51837,0.73956,-1.25803,-1.30627,-0.57983,2.40376,0.00069
-0.51956,0.73893,-1.25845,-1.30599,-0.57969,2.40438,0.00069
-0.52075,0.73832,-1.25887,-1.30572,-0.57954,2.40500,0.00069
-0.52194,0.73771,-1.25928,-1.30545,-0.57940,2.40561,0.00069
-0.52312,0.73712,-1.25969,-1.30518,-0.57926,2.40621,0.00069
-0.52431,0.73653,-1.26008,-1.30491,-0.57913,2.40680,0.00069
-0.52550,0.73595,-1.26048,-1.30465,-0.57900,2.40738,0.00069
-0.52669,0.73537,-1.26086,-1.30439,-0.57887,2.40796,0.00069
-0.52788,0.73481,-1.26124,-1.30414,-0.57874,2.40853,0.00068
-0.52907,0.73425,-1.26162,-1.30389,-0.57861,2.40909,0.00068
-0.53026,0.73369,-1.26199,-1.30364,-0.57849,2.40965,0.00068
-0.53145,0.73315,-1.26235,-1.30339,-0.57837,2.41020,0.00068
-0.53264,0.73261,-1.26271,-1.30315,-0.57825,2.41074,0.00068
-0.53382,0.73238,-1.26287,-1.30304,-0.57819,2.41097,0.00068
-0.53501,0.73163,-1.26343,-1.30270,-0.57799,2.41172,0.00068
-0.53620,0.73089,-1.26397,-1.30235,-0.57779,2.41246,0.00068
-0.53739,0.73016,-1.26451,-1.30202,-0.57759,2.41319,0.00067
-0.53858,0.72944,-1.26503,-1.30168,-0.57739,2.41391,0.00067
-0.53977,0.72873,-1.26555,-1.30135,-0.57720,2.41462,0.00067
-0.54096,0.72803,-1.26607,-1.30103,-0.57702,2.41532,0.00067
-0.54215,0.72734,-1.26657,-1.30070,-0.57683,2.41601,0.00066
-0.54334,0.72666,-1.26707,-1.30039,-0.57665,2.41669,0.00066
-0.54453,0.72598,-1.26756,-1.30007,-0.57647,2.41736,0.00066
-0.54571,0.72532,-1.26804,-1.29976,-0.57630,2.41802,0.00066
-0.54690,0.72467,-1.26851,-1.29946,-0.57613,2.41868,0.00066
-0.54809,0.72402,-1.26898,-1.29916,-0.57596,2.41933,0.00065
-0.54928,0.72338,-1.26944,-1.29886,-0.57580,2.41996,0.00065
-0.55047,0.72275,-1.26990,-1.29857,-0.57564,2.42059,0.00065
-0.55166,0.72214,-1.27034,-1.29828,-0.57548,2.42121,0.00065
-0.55285,0.72152,-1.27078,-1.29799,-0.57533,2.42183,0.00065
-0.55404,0.72092,-1.27121,-1.29771,-0.57517,2.42243,0.00065
-0.55523,0.72033,-1.27164,-1.29743,-0.57503,2.42303,0.00064
-0.55641,0.71974,-1.27206,-1.29715,-0.57488,2.42362,0.00064
-0.55760,0.71916,-1.27247,-1.29688,-0.57474,2.42420,0.00064
-0.55879,0.71859,-1.27288,-1.29661,-0.57459,2.42477,0.00064
-0.55998,0.71802,-1.27328,-1.29635,-0.57446,2.42534,0.00064
-0.56117,0.71747,-1.27368,-1.29609,-0.57432,2.42590,0.00064
-0.56236,0.71692,-1.27407,-1.29583,-0.57419,2.42645,0.00064
-0.56355,0.71638,-1.27445,-1.29558,-0.57406,2.42699,0.00064
-0.56474,0.71584,-1.27483,-1.29533,-0.57393,2.42753,0.00064
-0.56593,0.71532,-1.27520,-1.29508,-0.57380,2.42806,0.00063
-0.56711,0.71480,-1.27556,-1.29483,-0.57368,2.42858,0.00063
-0.56830,0.71447,-1.27580,-1.29467,-0.57360,2.42891,0.00063
-0.56949,0.71374,-1.27637,-1.29429,-0.57341,2.42963,0.00063
-0.57068,0.71303,-1.27693,-1.29392,-0.57323,2.43034,0.00063
-0.57187,0.71233,-1.27748,-1.29355,-0.57304,2.43104,0.00063
-0.57306,0.71163,-1.27803,-1.29318,-0.57287,2.43174,0.00062
-0.57425,0.71095,-1.27856,-1.29282,-0.57269,2.43242,0.00062
-0.57544,0.71028,-1.27909,-1.29247,-0.57252,2.43309,0.00062
-0.57663,0.70961,-1.27960,-1.29212,-0.57235,2.43376,0.00062
-0.57781,0.70896,-1.28012,-1.29177,-0.57219,2.43441,0.00061
-0.57900,0.70831,-1.28062,-1.29143,-0.57203,2.43506,0.00061
-0.58019,0.70767,-1.28111,-1.29109,-0.57187,2.43570,0.00061
-0.58138,0.70704,-1.28160,-1.29076,-0.57171,2.43633,0.00061
-0.58257,0.70642,-1.28208,-1.29043,-0.57156,2.43695,0.00061
-0.58376,0.70581,-1.28255,-1.29010,-0.57141,2.43756,0.00061
-0.58495,0.70520,-1.28302,-1.28978,-0.57127,2.43817,0.00060
-0.58614,0.70461,-1.28347,-1.28947,-0.57112,2.43876,0.00060
-0.58733,0.70402,-1.28393,-1.28916,-0.57098,2.43935,0.00060
-0.58852,0.70344,-1.28437,-1.28885,-0.57084,2.43993,0.00060
-0.58970,0.70287,-1.28481,-1.28854,-0.57071,2.44050,0.00060
-0.59089,0.70231,-1.28524,-1.28824,-0.57058,2.44107,0.00060
-0.59208,0.70175,-1.28566,-1.28795,-0.57045,2.44162,0.00060
-0.59327,0.70120,-1.28608,-1.28766,-0.57032,2.44217,0.00059
-0.59446,0.70066,-1.28649,-1.28737,-0.57019,2.44272,0.00059
-0.59565,0.70013,-1.28689,-1.28709,-0.57007,2.44325,0.00059
-0.59684,0.69960,-1.28729,-1.28681,-0.56995,2.44378,0.00059
-0.59803,0.69909,-1.28768,-1.28653,-0.56984,2.44430,0.00059
-0.59922,0.69857,-1.28807,-1.28626,-0.56972,2.44481,0.00059
-0.60040,0.69807,-1.28845,-1.28599,-0.56961,2.44532,0.00059
-0.60159,0.69757,-1.28882,-1.28572,-0.56950,2.44582,0.00059
-0.60278,0.69738,-1.28897,-1.28562,-0.56944,2.44601,0.00059
-0.60397,0.69649,-1.28972,-1.28517,-0.56916,2.44689,0.00058
-0.60516,0.69562,-1.29046,-1.28471,-0.56887,2.44776,0.00058
-0.60635,0.69475,-1.29119,-1.28427,-0.56859,2.44862,0.00057
-0.60754,0.69390,-1.29191,-1.28383,-0.56832,2.44947,0.00057
-0.60873,0.69306,-1.29261,-1.28339,-0.56805,2.45030,0.00056
-0.60992,0.69224,-1.29330,-1.28296,-0.56779,2.45112,0.00056
-0.61110,0.69142,-1.29399,-1.28254,-0.56754,2.45194,0.00055
-0.61229,0.69062,-1.29466,-1.28212,-0.56729,2.45273,0.00055
-0.61348,0.68982,-1.29532,-1.28170,-0.56704,2.45352,0.00054
-0.61467,0.68904,-1.29597,-1.28129,-0.56680,2.45430,0.00054
-0.61586,0.68827,-1.29661,-1.28089,-0.56656,2.45507,0.00054
-0.61705,0.68752,-1.29724,-1.28049,-0.56633,2.45582,0.00053
-0.61824,0.68677,-1.29786,-1.28010,-0.56610,2.45657,0.00053
-0.61943,0.68603,-1.29847,-1.27971,-0.56588,2.45730,0.00053
-0.62062,0.68531,-1.29908,-1.27933,-0.56566,2.45803,0.00052
-0.62180,0.68459,-1.29967,-1.27895,-0.56545,2.45874,0.00052
-0.62299,0.68389,-1.30025,-1.27857,-0.56524,2.45944,0.00052
-0.62418,0.68319,-1.30083,-1.27821,-0.56503,2.46014,0.00051
-0.62537,0.68250,-1.30139,-1.27784,-0.56483,2.46082,0.00051
-0.62656,0.68183,-1.30195,-1.27748,-0.56464,2.46150,0.00051
-0.62775,0.68116,-1.30249,-1.27713,-0.56444,2.46216,0.00051
-0.62894,0.68051,-1.30303,-1.27678,-0.56425,2.46282,0.00050
-0.63013,0.67986,-1.30356,-1.27643,-0.56407,2.46346,0.00050
-0.63132,0.67922,-1.30409,-1.27609,-0.56389,2.46410,0.00050
-0.63251,0.67859,-1.30460,-1.27575,-0.56371,2.46473,0.00050
-0.63369,0.67797,-1.30510,-1.27542,-0.56353,2.46535,0.00050
-0.63488,0.67736,-1.30560,-1.27509,-0.56336,2.46596,0.00049
-0.63607,0.67676,-1.30609,-1.27477,-0.56320,2.46656,0.00049
-0.63726,0.67617,-1.30658,-1.27445,-0.56303,2.46716,0.00049
-0.63845,0.67558,-1.30705,-1.27414,-0.56287,2.46774,0.00049
-0.63964,0.67501,-1.30752,-1.27382,-0.56271,2.46832,0.00049
-0.64083,0.67444,-1.30798,-1.27352,-0.56256,2.46889,0.00049
-0.64202,0.67388,-1.30843,-1.27321,-0.56241,2.46945,0.00049
-0.64321,0.67332,-1.30888,-1.27292,-0.56226,2.47001,0.00049
-0.64439,0.67278,-1.30932,-1.27262,-0.56211,2.47055,0.00048
-0.64558,0.67224,-1.30975,-1.27233,-0.56197,2.47109,0.00048
-0.64677,0.67171,-1.31017,-1.27204,-0.56183,2.47162,0.00048
-0.64796,0.67119,-1.31059,-1.27176,-0.56169,2.47215,0.00048
-0.64915,0.67068,-1.31100,-1.27148,-0.56156,2.47266,0.00048
-0.65034,0.67017,-1.31141,-1.27120,-0.56143,2.47317,0.00048
-0.65153,0.66967,-1.31181,-1.27093,-0.56130,2.47367,0.00048
-0.65272,0.66918,-1.31220,-1.27066,-0.56117,2.47417,0.00048
-0.65391,0.66869,-1.31259,-1.27040,-0.56105,2.47466,0.00048
-0.65509,0.66821,-1.31297,-1.27014,-0.56093,2.47514,0.00048
-0.65628,0.66774,-1.31334,-1.26988,-0.56081,2.47561,0.00048
-0.65747,0.66768,-1.31339,-1.26985,-0.56079,2.47567,0.00048
-0.65866,0.66708,-1.31389,-1.26954,-0.56060,2.47627,0.00048
-0.65985,0.66650,-1.31438,-1.26923,-0.56042,2.47686,0.00047
-0.66104,0.66592,-1.31486,-1.26893,-0.56024,2.47744,0.00047
-0.66223,0.66535,-1.31534,-1.26863,-0.56006,2.47801,0.00047
-0.66342,0.66478,-1.31580,-1.26834,-0.55989,2.47857,0.00047
-0.66461,0.66423,-1.31626,-1.26805,-0.55972,2.47913,0.00047
-0.66579,0.66368,-1.31671,-1.26776,-0.55955,2.47968,0.00046
-0.66698,0.66314,-1.31716,-1.26748,-0.55938,2.48022,0.00046
-0.66817,0.66261,-1.31760,-1.26720,-0.55922,2.48075,0.00046
-0.66936,0.66209,-1.31803,-1.26693,-0.55907,2.48127,0.00046
-0.67055,0.66157,-1.31845,-1.26666,-0.55891,2.48179,0.00046
-0.67174,0.66106,-1.31887,-1.26639,-0.55876,2.48230,0.00046
-0.67293,0.66056,-1.31928,-1.26612,-0.55861,2.48280,0.00046
-0.67412,0.66007,-1.31969,-1.26586,-0.55847,2.48330,0.00046
-0.67531,0.65958,-1.32008,-1.26561,-0.55833,2.48379,0.00045
-0.67650,0.65910,-1.32048,-1.26535,-0.55819,2.48427,0.00045
-0.67768,0.65863,-1.32086,-1.26510,-0.55805,2.48474,0.00045
-0.67887,0.65816,-1.32124,-1.26485,-0.55792,2.48521,0.00045
-0.68006,0.65769,-1.32163,-1.26461,-0.55778,2.48569,0.00045
-0.68125,0.65712,-1.32210,-1.26435,-0.55757,2.48625,0.00045
-0.68244,0.65656,-1.32256,-1.26409,-0.55736,2.48681,0.00045
-0.68363,0.65601,-1.32302,-1.26384,-0.55715,2.48736,0.00044
-0.68482,0.65547,-1.32347,-1.26359,-0.55696,2.48790,0.00044
-0.68601,0.65493,-1.32391,-1.26334,-0.55676,2.48844,0.00044
-0.68720,0.65441,-1.32435,-1.26310,-0.55657,2.48897,0.00044
-0.68838,0.65389,-1.32477,-1.26286,-0.55638,2.48949,0.00044
-0.68957,0.65338,-1.32520,-1.26262,-0.55620,2.49000,0.00043
-0.69076,0.65287,-1.32561,-1.26239,-0.55601,2.49050,0.00043
-0.69195,0.65237,-1.32602,-1.26216,-0.55584,2.49100,0.00043
-0.69314,0.65188,-1.32642,-1.26193,-0.55566,2.49149,0.00043
-0.69433,0.65140,-1.32682,-1.26170,-0.55549,2.49198,0.00043
-0.69552,0.65092,-1.32721,-1.26148,-0.55533,2.49245,0.00043
-0.69671,0.65046,-1.32759,-1.26126,-0.55516,2.49292,0.00043
-0.69790,0.64999,-1.32797,-1.26104,-0.55500,2.49339,0.00042
-0.69908,0.64954,-1.32834,-1.26083,-0.55484,2.49384,0.00042
-0.70027,0.64912,-1.32868,-1.26063,-0.55469,2.49427,0.00042
-0.70146,0.64852,-1.32920,-1.26037,-0.55444,2.49487,0.00042
-0.70265,0.64792,-1.32970,-1.26011,-0.55419,2.49546,0.00041
-0.70384,0.64734,-1.33020,-1.25986,-0.55395,2.49604,0.00041
-0.70503,0.64676,-1.33070,-1.25961,-0.55371,2.49661,0.00041
-0.70622,0.64619,-1.33118,-1.25936,-0.55347,2.49718,0.00041
-0.70741,0.64564,-1.33166,-1.25911,-0.55325,2.49774,0.00040
-0.70860,0.64508,-1.33212,-1.25887,-0.55302,2.49829,0.00040
-0.70978,0.64454,-1.33259,-1.25863,-0.55280,2.49883,0.00040
-0.71097,0.64401,-1.33304,-1.25839,-0.55258,2.49936,0.00039
-0.71216,0.64348,-1.33349,-1.25816,-0.55237,2.49989,0.00039
-0.71335,0.64296,-1.33392,-1.25793,-0.55216,2.50041,0.00039
-0.71454,0.64245,-1.33436,-1.25770,-0.55196,2.50092,0.00039
-0.71573,0.64195,-1.33478,-1.25748,-0.55176,2.50142,0.00039
-0.71692,0.64145,-1.33520,-1.25726,-0.55156,2.50192,0.00038
-0.71811,0.64096,-1.33561,-1.25704,-0.55137,2.50241,0.00038
-0.71930,0.64048,-1.33602,-1.25682,-0.55118,2.50289,0.00038
-0.72049,0.64001,-1.33642,-1.25661,-0.55099,2.50337,0.00038
-0.72167,0.63954,-1.33681,-1.25640,-0.55081,2.50384,0.00038
-0.72286,0.63908,-1.33719,-1.25619,-0.55063,2.50430,0.00038
-0.72405,0.63862,-1.33757,-1.25598,-0.55046,2.50475,0.00038
-0.72524,0.63818,-1.33795,-1.25578,-0.55029,2.50520,0.00038
-0.72643,0.63774,-1.33831,-1.25558,-0.55012,2.50564,0.00038
-0.72762,0.63741,-1.33858,-1.25543,-0.54999,2.50597,0.00037
-0.72881,0.63681,-1.33912,-1.25517,-0.54972,2.50656,0.00037
-0.73000,0.63622,-1.33964,-1.25491,-0.54946,2.50715,0.00037
-0.73119,0.63564,-1.34016,-1.25466,-0.54920,2.50773,0.00036
-0.73237,0.63507,-1.34066,-1.25440,-0.54895,2.50830,0.00036
-0.73356,0.63450,-1.34116,-1.25416,-0.54870,2.50887,0.00036
-0.73475,0.63394,-1.34165,-1.25391,-0.54846,2.50942,0.00035
-0.73594,0.63340,-1.34213,-1.25367,-0.54822,2.50997,0.00035
-0.73713,0.63286,-1.34261,-1.25343,-0.54798,2.51051,0.00035
-0.73832,0.63232,-1.34308,-1.25319,-0.54775,2.51104,0.00035
-0.73951,0.63180,-1.34354,-1.25296,-0.54753,2.51156,0.00034
-0.74070,0.63128,-1.34399,-1.25272,-0.54731,2.51208,0.00034
-0.74189,0.63077,-1.34443,-1.25250,-0.54709,2.51259,0.00034
-0.74307,0.63027,-1.34487,-1.25227,-0.54688,2.51309,0.00034
-0.74426,0.62978,-1.34530,-1.25205,-0.54667,2.51358,0.00034
-0.74545,0.62929,-1.34573,-1.25183,-0.54647,2.51407,0.00034
-0.74664,0.62882,-1.34614,-1.25161,-0.54627,2.51455,0.00033
-0.74783,0.62834,-1.34655,-1.25140,-0.54607,2.51502,0.00033
-0.74902,0.62788,-1.34696,-1.25118,-0.54588,2.51548,0.00033
-0.75021,0.62742,-1.34735,-1.25098,-0.54569,2.51594,0.00033
-0.75140,0.62697,-1.34774,-1.25077,-0.54550,2.51639,0.00033
-0.75259,0.62653,-1.34813,-1.25056,-0.54532,2.51684,0.00033
-0.75377,0.62609,-1.34850,-1.25036,-0.54514,2.51727,0.00033
-0.75496,0.62566,-1.34888,-1.25017,-0.54497,2.51771,0.00033
-0.75615,0.62523,-1.34924,-1.24997,-0.54480,2.51813,0.00033
-0.75734,0.62505,-1.34940,-1.24988,-0.54472,2.51832,0.00033
-0.75853,0.62447,-1.34994,-1.24962,-0.54445,2.51890,0.00032
-0.75972,0.62390,-1.35046,-1.24937,-0.54419,2.51947,0.00032
-0.76091,0.62333,-1.35098,-1.24911,-0.54393,2.52003,0.00032
-0.76210,0.62278,-1.35149,-1.24886,-0.54367,2.52058,0.00031
-0.76329,0.62223,-1.35199,-1.24861,-0.54342,2.52113,0.00031
-0.76448,0.62169,-1.35248,-1.24837,-0.54318,2.52166,0.00031
-0.76566,0.62116,-1.35296,-1.24812,-0.54294,2.52219,0.00031
-0.76685,0.62064,-1.35344,-1.24788,-0.54270,2.52271,0.00030
-0.76804,0.62012,-1.35390,-1.24765,-0.54247,2.52323,0.00030
-0.76923,0.61962,-1.35436,-1.24741,-0.54224,2.52373,0.00030
-0.77042,0.61912,-1.35482,-1.24718,-0.54202,2.52423,0.00030
-0.77161,0.61863,-1.35526,-1.24696,-0.54180,2.52472,0.00030
-0.77280,0.61814,-1.35570,-1.24673,-0.54159,2.52521,0.00029
-0.77399,0.61767,-1.35613,-1.24651,-0.54138,2.52568,0.00029
-0.77518,0.61720,-1.35655,-1.24629,-0.54117,2.52615,0.00029
-0.77636,0.61673,-1.35697,-1.24607,-0.54097,2.52661,0.00029
-0.77755,0.61628,-1.35738,-1.24586,-0.54078,2.52707,0.00029
-0.77874,0.61583,-1.35778,-1.24565,-0.54058,2.52752,0.00029
-0.77993,0.61539,-1.35818,-1.24544,-0.54039,2.52796,0.00029
-0.78112,0.61495,-1.35857,-1.24523,-0.54021,2.52840,0.00029
-0.78231,0.61452,-1.35895,-1.24503,-0.54002,2.52883,0.00029
-0.78350,0.61410,-1.35933,-1.24483,-0.53985,2.52925,0.00029
-0.78469,0.61369,-1.35970,-1.24463,-0.53967,2.52966,0.00029
-0.78588,0.61328,-1.36007,-1.24444,-0.53950,2.53008,0.00029
-0.78706,0.61322,-1.36012,-1.24441,-0.53947,2.53013,0.00029
-0.78825,0.61267,-1.36064,-1.24416,-0.53921,2.53068,0.00028
-0.78944,0.61213,-1.36115,-1.24391,-0.53895,2.53122,0.00028
-0.79063,0.61160,-1.36165,-1.24366,-0.53869,2.53175,0.00028
-0.79182,0.61107,-1.36214,-1.24342,-0.53844,2.53227,0.00027
-0.79301,0.61056,-1.36263,-1.24318,-0.53820,2.53278,0.00027
-0.79420,0.61005,-1.36311,-1.24294,-0.53796,2.53329,0.00027
-0.79539,0.60955,-1.36357,-1.24271,-0.53773,2.53379,0.00027
-0.79658,0.60905,-1.36404,-1.24248,-0.53750,2.53428,0.00027
-0.79776,0.60857,-1.36449,-1.24225,-0.53727,2.53477,0.00026
-0.79895,0.60809,-1.36494,-1.24202,-0.53705,2.53525,0.00026
-0.80014,0.60762,-1.36538,-1.24180,-0.53683,2.53572,0.00026
-0.80133,0.60716,-1.36581,-1.24158,-0.53662,2.53618,0.00026
-0.80252,0.60670,-1.36623,-1.24136,-0.53641,2.53664,0.00026
-0.80371,0.60625,-1.36665,-1.24115,-0.53621,2.53708,0.00026
-0.80490,0.60581,-1.36706,-1.24094,-0.53601,2.53753,0.00026
-0.80609,0.60537,-1.36747,-1.24073,-0.53581,2.53796,0.00026
-0.80728,0.60494,-1.36786,-1.24052,-0.53562,2.53839,0.00026
-0.80847,0.60452,-1.36826,-1.24032,-0.53543,2.53882,0.00025
-0.80965,0.60410,-1.36864,-1.24012,-0.53524,2.53923,0.00025
-0.81084,0.60369,-1.36902,-1.23992,-0.53506,2.53964,0.00025
-0.81203,0.60329,-1.36939,-1.23972,-0.53488,2.54005,0.00025
-0.81322,0.60289,-1.36976,-1.23953,-0.53471,2.54045,0.00025
-0.81441,0.60284,-1.36981,-1.23950,-0.53469,2.54050,0.00025
-0.81560,0.60232,-1.37032,-1.23923,-0.53445,2.54102,0.00025
-0.81679,0.60181,-1.37082,-1.23897,-0.53421,2.54153,0.00025
-0.81798,0.60131,-1.37131,-1.23870,-0.53398,2.54203,0.00025
-0.81917,0.60081,-1.37180,-1.23845,-0.53375,2.54252,0.00024
-0.82035,0.60032,-1.37228,-1.23819,-0.53353,2.54301,0.00024
-0.82154,0.59984,-1.37275,-1.23794,-0.53331,2.54349,0.00024
-0.82273,0.59937,-1.37321,-1.23769,-0.53310,2.54396,0.00024
-0.82392,0.59890,-1.37366,-1.23744,-0.53289,2.54442,0.00024
-0.82511,0.59845,-1.37411,-1.23720,-0.53269,2.54488,0.00024
-0.82630,0.59799,-1.37455,-1.23696,-0.53248,2.54533,0.00024
-0.82749,0.59755,-1.37498,-1.23673,-0.53229,2.54577,0.00024
-0.82868,0.59711,-1.37541,-1.23649,-0.53209,2.54621,0.00023
-0.82987,0.59668,-1.37582,-1.23626,-0.53191,2.54664,0.00023
-0.83105,0.59626,-1.37623,-1.23603,-0.53172,2.54707,0.00023
-0.83224,0.59584,-1.37664,-1.23581,-0.53154,2.54748,0.00023
-0.83343,0.59543,-1.37704,-1.23559,-0.53136,2.54790,0.00023
-0.83462,0.59502,-1.37743,-1.23537,-0.53119,2.54830,0.00023
-0.83581,0.59463,-1.37781,-1.23515,-0.53102,2.54870,0.00023
-0.83700,0.59423,-1.37819,-1.23494,-0.53085,2.54909,0.00023
-0.83819,0.59385,-1.37856,-1.23473,-0.53068,2.54948,0.00023
-0.83938,0.59379,-1.37862,-1.23470,-0.53066,2.54953,0.00023
-0.84057,0.59326,-1.37916,-1.23442,-0.53040,2.55007,0.00023
-0.84175,0.59273,-1.37970,-1.23414,-0.53014,2.55059,0.00023
-0.84294,0.59222,-1.38022,-1.23386,-0.52990,2.55110,0.00022
-0.84413,0.59171,-1.38074,-1.23359,-0.52965,2.55161,0.00022
-0.84532,0.59121,-1.38125,-1.23332,-0.52941,2.55211,0.00022
-0.84651,0.59071,-1.38175,-1.23306,-0.52918,2.55260,0.00022
-0.84770,0.59023,-1.38224,-1.23279,-0.52895,2.55309,0.00021
-0.84889,0.58975,-1.38273,-1.23253,-0.52873,2.55356,0.00021
-0.85008,0.58928,-1.38320,-1.23228,-0.52851,2.55403,0.00021
-0.85127,0.58882,-1.38367,-1.23202,-0.52829,2.55449,0.00021
-0.85246,0.58836,-1.38413,-1.23178,-0.52808,2.55495,0.00021
-0.85364,0.58791,-1.38458,-1.23153,-0.52787,2.55540,0.00021
-0.85483,0.58747,-1.38503,-1.23129,-0.52767,2.55584,0.00021
-0.85602,0.58703,-1.38547,-1.23105,-0.52747,2.55627,0.00020
-0.85721,0.58661,-1.38590,-1.23081,-0.52727,2.55670,0.00020
-0.85840,0.58618,-1.38632,-1.23058,-0.52708,2.55712,0.00020
-0.85959,0.58577,-1.38674,-1.23035,-0.52690,2.55754,0.00020
-0.86078,0.58536,-1.38715,-1.23012,-0.52671,2.55795,0.00020
-0.86197,0.58496,-1.38755,-1.22989,-0.52653,2.55835,0.00020
-0.86316,0.58456,-1.38795,-1.22967,-0.52636,2.55874,0.00020
-0.86434,0.58417,-1.38833,-1.22945,-0.52618,2.55914,0.00020
-0.86553,0.58379,-1.38872,-1.22924,-0.52601,2.55952,0.00020
-0.86672,0.58341,-1.38910,-1.22902,-0.52585,2.55990,0.00020
-0.86791,0.58317,-1.38934,-1.22889,-0.52574,2.56014,0.00020
-0.86910,0.58264,-1.38990,-1.22859,-0.52548,2.56067,0.00020
-0.87029,0.58211,-1.39046,-1.22829,-0.52522,2.56119,0.00020
-0.87148,0.58160,-1.39100,-1.22800,-0.52497,2.56170,0.00019
-0.87267,0.58109,-1.39154,-1.22771,-0.52472,2.56220,0.00019
-0.87386,0.58059,-1.39207,-1.22743,-0.52448,2.56270,0.00019
-0.87504,0.58010,-1.39258,-1.22714,-0.52424,2.56319,0.00019
-0.87623,0.57962,-1.39309,-1.22687,-0.52401,2.56367,0.00018
-0.87742,0.57914,-1.39360,-1.22659,-0.52378,2.56414,0.00018
-0.87861,0.57868,-1.39409,-1.22632,-0.52356,2.56461,0.00018
-0.87980,0.57822,-1.39457,-1.22605,-0.52334,2.56507,0.00018
-0.88099,0.57776,-1.39505,-1.22579,-0.52313,2.56552,0.00018
-0.88218,0.57732,-1.39552,-1.22553,-0.52292,2.56597,0.00017
-0.88337,0.57688,-1.39598,-1.22527,-0.52272,2.56641,0.00017
-0.88456,0.57645,-1.39644,-1.22502,-0.52252,2.56684,0.00017
-0.88574,0.57602,-1.39688,-1.22477,-0.52232,2.56726,0.00017
-0.88693,0.57560,-1.39732,-1.22452,-0.52213,2.56768,0.00017
-0.88812,0.57519,-1.39775,-1.22428,-0.52194,2.56809,0.00017
-0.88931,0.57478,-1.39818,-1.22404,-0.52175,2.56850,0.00017
-0.89050,0.57438,-1.39859,-1.22380,-0.52157,2.56890,0.00017
-0.89169,0.57399,-1.39900,-1.22357,-0.52139,2.56929,0.00017
-0.89288,0.57360,-1.39941,-1.22333,-0.52122,2.56968,0.00017
-0.89407,0.57322,-1.39980,-1.22311,-0.52105,2.57006,0.00017
-0.89526,0.57285,-1.40019,-1.22288,-0.52088,2.57044,0.00017
-0.89645,0.57248,-1.40058,-1.22266,-0.52072,2.57081,0.00017
-0.89763,0.57211,-1.40096,-1.22244,-0.52056,2.57117,0.00017
-0.89882,0.57203,-1.40105,-1.22238,-0.52052,2.57126,0.00017
-0.90001,0.57151,-1.40163,-1.22205,-0.52028,2.57177,0.00017
-0.90120,0.57101,-1.40219,-1.22171,-0.52005,2.57227,0.00017
-0.90239,0.57051,-1.40275,-1.22138,-0.51982,2.57277,0.00016
-0.90358,0.57002,-1.40330,-1.22106,-0.51960,2.57326,0.00016
-0.90477,0.56954,-1.40383,-1.22074,-0.51938,2.57373,0.00016
-0.90596,0.56906,-1.40436,-1.22042,-0.51917,2.57421,0.00016
-0.90715,0.56860,-1.40488,-1.22011,-0.51896,2.57467,0.00015
-0.90833,0.56814,-1.40540,-1.21980,-0.51876,2.57513,0.00015
-0.90952,0.56769,-1.40590,-1.21950,-0.51856,2.57558,0.00015
-0.91071,0.56724,-1.40639,-1.21920,-0.51836,2.57602,0.00015
-0.91190,0.56680,-1.40688,-1.21890,-0.51817,2.57646,0.00015
-0.91309,0.56637,-1.40736,-1.21861,-0.51798,2.57689,0.00015
-0.91428,0.56595,-1.40783,-1.21832,-0.51780,2.57731,0.00015
-0.91547,0.56553,-1.40829,-1.21804,-0.51762,2.57773,0.00015
-0.91666,0.56512,-1.40875,-1.21776,-0.51744,2.57814,0.00015
-0.91785,0.56472,-1.40920,-1.21748,-0.51727,2.57854,0.00015
-0.91903,0.56432,-1.40964,-1.21721,-0.51710,2.57894,0.00015
-0.92022,0.56393,-1.41007,-1.21694,-0.51694,2.57933,0.00015
-0.92141,0.56354,-1.41049,-1.21667,-0.51677,2.57972,0.00015
-0.92260,0.56316,-1.41091,-1.21641,-0.51661,2.58010,0.00015
-0.92379,0.56279,-1.41132,-1.21615,-0.51646,2.58047,0.00015
-0.92498,0.56242,-1.41173,-1.21590,-0.51631,2.58084,0.00015
-0.92617,0.56206,-1.41213,-1.21564,-0.51616,2.58120,0.00015
-0.92736,0.56171,-1.41252,-1.21540,-0.51601,2.58156,0.00015
-0.92855,0.56135,-1.41292,-1.21514,-0.51587,2.58192,0.00015
-0.92973,0.56091,-1.41341,-1.21484,-0.51567,2.58235,0.00015
-0.93092,0.56048,-1.41390,-1.21454,-0.51548,2.58278,0.00015
-0.93211,0.56006,-1.41438,-1.21425,-0.51530,2.58320,0.00015
-0.93330,0.55965,-1.41485,-1.21395,-0.51512,2.58361,0.00014
-0.93449,0.55924,-1.41531,-1.21367,-0.51494,2.58402,0.00014
-0.93568,0.55884,-1.41577,-1.21338,-0.51477,2.58442,0.00014
-0.93687,0.55845,-1.41622,-1.21310,-0.51460,2.58481,0.00014
-0.93806,0.55806,-1.41666,-1.21283,-0.51443,2.58520,0.00014
-0.93925,0.55768,-1.41709,-1.21255,-0.51427,2.58558,0.00014
-0.94044,0.55730,-1.41752,-1.21229,-0.51411,2.58596,0.00014
-0.94162,0.55693,-1.41794,-1.21202,-0.51396,2.58633,0.00014
-0.94281,0.55657,-1.41835,-1.21176,-0.51380,2.58669,0.00014
-0.94400,0.55621,-1.41875,-1.21150,-0.51365,2.58705,0.00014
-0.94519,0.55586,-1.41915,-1.21125,-0.51351,2.58740,0.00014
-0.94638,0.55551,-1.41954,-1.21099,-0.51336,2.58775,0.00014
-0.94757,0.55518,-1.41992,-1.21075,-0.51323,2.58808,0.00014
-0.94876,0.55466,-1.42056,-1.21034,-0.51300,2.58860,0.00014
-0.94995,0.55414,-1.42119,-1.20994,-0.51278,2.58911,0.00014
-0.95114,0.55364,-1.42181,-1.20954,-0.51256,2.58962,0.00013
-0.95232,0.55314,-1.42241,-1.20915,-0.51235,2.59011,0.00013
-0.95351,0.55265,-1.42301,-1.20876,-0.51214,2.59060,0.00013
-0.95470,0.55217,-1.42360,-1.20837,-0.51194,2.59108,0.00012
-0.95589,0.55169,-1.42418,-1.20799,-0.51174,2.59155,0.00012
-0.95708,0.55122,-1.42475,-1.20762,-0.51154,2.59202,0.00012
-0.95827,0.55076,-1.42531,-1.20725,-0.51135,2.59247,0.00012
-0.95946,0.55031,-1.42586,-1.20689,-0.51117,2.59293,0.00012
-0.96065,0.54987,-1.42640,-1.20653,-0.51098,2.59337,0.00011
-0.96184,0.54943,-1.42693,-1.20617,-0.51081,2.59381,0.00011
-0.96302,0.54900,-1.42745,-1.20583,-0.51063,2.59423,0.00011
-0.96421,0.54857,-1.42797,-1.20548,-0.51046,2.59466,0.00011
-0.96540,0.54816,-1.42847,-1.20514,-0.51029,2.59507,0.00011
-0.96659,0.54775,-1.42897,-1.20481,-0.51013,2.59548,0.00011
-0.96778,0.54734,-1.42946,-1.20447,-0.50997,2.59589,0.00011
-0.96897,0.54695,-1.42994,-1.20415,-0.50982,2.59628,0.00011
-0.97016,0.54656,-1.43041,-1.20383,-0.50966,2.59667,0.00011
-0.97135,0.54617,-1.43088,-1.20351,-0.50951,2.59706,0.00011
-0.97254,0.54579,-1.43133,-1.20320,-0.50937,2.59744,0.00011
-0.97372,0.54542,-1.43178,-1.20289,-0.50923,2.59781,0.00011
-0.97491,0.54505,-1.43223,-1.20258,-0.50909,2.59818,0.00011
-0.97610,0.54469,-1.43266,-1.20228,-0.50895,2.59854,0.00011
-0.97729,0.54434,-1.43309,-1.20198,-0.50882,2.59889,0.00011
-0.97848,0.54399,-1.43351,-1.20169,-0.50869,2.59924,0.00011
-0.97967,0.54364,-1.43392,-1.20140,-0.50856,2.59959,0.00011
-0.98086,0.54331,-1.43433,-1.20112,-0.50843,2.59993,0.00011
-0.98205,0.54297,-1.43473,-1.20084,-0.50831,2.60026,0.00011
-0.98324,0.54273,-1.43503,-1.20062,-0.50822,2.60051,0.00011
-0.98443,0.54222,-1.43569,-1.20015,-0.50804,2.60101,0.00011
-0.98561,0.54173,-1.43634,-1.19969,-0.50786,2.60150,0.00011
-0.98680,0.54124,-1.43697,-1.19923,-0.50768,2.60198,0.00010
-0.98799,0.54076,-1.43760,-1.19877,-0.50751,2.60246,0.00010
-0.98918,0.54029,-1.43821,-1.19833,-0.50734,2.60293,0.00010
-0.99037,0.53983,-1.43882,-1.19789,-0.50718,2.60339,0.00010
-0.99156,0.53937,-1.43941,-1.19745,-0.50702,2.60385,0.00010
-0.99275,0.53892,-1.43999,-1.19702,-0.50686,2.60429,0.00009
-0.99394,0.53848,-1.44057,-1.19660,-0.50671,2.60473,0.00009
-0.99513,0.53805,-1.44113,-1.19618,-0.50656,2.60516,0.00009
-0.99631,0.53762,-1.44169,-1.19577,-0.50642,2.60559,0.00009
-0.99750,0.53720,-1.44224,-1.19536,-0.50628,2.60601,0.00009
-0.99869,0.53679,-1.44277,-1.19496,-0.50614,2.60642,0.00009
-0.99988,0.53638,-1.44330,-1.19457,-0.50600,2.60683,0.00009
-1.00107,0.53598,-1.44382,-1.19418,-0.50587,2.60723,0.00009
-1.00226,0.53559,-1.44433,-1.19380,-0.50574,2.60762,0.00009
-1.00345,0.53520,-1.44484,-1.19342,-0.50562,2.60801,0.00009
-1.00464,0.53482,-1.44533,-1.19304,-0.50549,2.60839,0.00009
-1.00583,0.53445,-1.44582,-1.19267,-0.50538,2.60876,0.00009
-1.00701,0.53408,-1.44629,-1.19231,-0.50526,2.60913,0.00009
-1.00820,0.53371,-1.44676,-1.19195,-0.50515,2.60950,0.00009
-1.00939,0.53336,-1.44723,-1.19160,-0.50503,2.60985,0.00009
-1.01058,0.53301,-1.44768,-1.19125,-0.50493,2.61020,0.00009
-1.01177,0.53266,-1.44813,-1.19091,-0.50482,2.61055,0.00009
-1.01296,0.53232,-1.44857,-1.19057,-0.50472,2.61089,0.00009
-1.01415,0.53199,-1.44900,-1.19023,-0.50462,2.61123,0.00009
-1.01534,0.53166,-1.44942,-1.18990,-0.50452,2.61156,0.00009
-1.01653,0.53133,-1.44984,-1.18958,-0.50442,2.61188,0.00009
-1.01771,0.53101,-1.45025,-1.18926,-0.50433,2.61220,0.00009
-1.01890,0.53075,-1.45060,-1.18899,-0.50425,2.61247,0.00009
-1.02009,0.53030,-1.45121,-1.18854,-0.50409,2.61291,0.00009
-1.02128,0.52986,-1.45180,-1.18810,-0.50393,2.61335,0.00009
-1.02247,0.52942,-1.45239,-1.18767,-0.50378,2.61379,0.00009
-1.02366,0.52900,-1.45297,-1.18724,-0.50364,2.61421,0.00008
-1.02485,0.52858,-1.45354,-1.18681,-0.50349,2.61463,0.00008
-1.02604,0.52816,-1.45409,-1.18639,-0.50335,2.61504,0.00008
-1.02723,0.52776,-1.45464,-1.18598,-0.50322,2.61545,0.00008
-1.02842,0.52736,-1.45518,-1.18558,-0.50308,2.61585,0.00008
-1.02960,0.52696,-1.45571,-1.18517,-0.50295,2.61624,0.00008
-1.03079,0.52658,-1.45624,-1.18478,-0.50282,2.61663,0.00008
-1.03198,0.52620,-1.45675,-1.18439,-0.50270,2.61701,0.00008
-1.03317,0.52582,-1.45725,-1.18400,-0.50258,2.61738,0.00007
-1.03436,0.52545,-1.45775,-1.18362,-0.50246,2.61775,0.00007
-1.03555,0.52509,-1.45824,-1.18325,-0.50235,2.61811,0.00007
-1.03674,0.52473,-1.45872,-1.18288,-0.50223,2.61847,0.00007
-1.03793,0.52438,-1.45919,-1.18252,-0.50212,2.61882,0.00007
-1.03912,0.52404,-1.45965,-1.18216,-0.50202,2.61917,0.00007
-1.04030,0.52370,-1.46011,-1.18180,-0.50191,2.61951,0.00007
-1.04149,0.52336,-1.46056,-1.18145,-0.50181,2.61984,0.00007
-1.04268,0.52304,-1.46100,-1.18111,-0.50171,2.62017,0.00007
-1.04387,0.52271,-1.46143,-1.18077,-0.50161,2.62050,0.00007
-1.04506,0.52239,-1.46186,-1.18044,-0.50152,2.62081,0.00008
-1.04625,0.52208,-1.46228,-1.18011,-0.50143,2.62113,0.00008
-1.04744,0.52177,-1.46269,-1.17978,-0.50134,2.62144,0.00008
-1.04863,0.52152,-1.46303,-1.17952,-0.50126,2.62169,0.00008
-1.04982,0.52113,-1.46357,-1.17911,-0.50113,2.62208,0.00008
-1.05100,0.52075,-1.46410,-1.17872,-0.50099,2.62246,0.00007
-1.05219,0.52037,-1.46462,-1.17833,-0.50086,2.62284,0.00007
-1.05338,0.52000,-1.46513,-1.17795,-0.50074,2.62321,0.00007
-1.05457,0.51963,-1.46563,-1.17757,-0.50061,2.62357,0.00007
-1.05576,0.51928,-1.46613,-1.17719,-0.50049,2.62393,0.00007
-1.05695,0.51892,-1.46661,-1.17682,-0.50037,2.62428,0.00007
-1.05814,0.51858,-1.46709,-1.17646,-0.50026,2.62463,0.00007
-1.05933,0.51823,-1.46756,-1.17610,-0.50015,2.62497,0.00007
-1.06052,0.51790,-1.46802,-1.17575,-0.50004,2.62531,0.00007
-1.06170,0.51757,-1.46847,-1.17540,-0.49993,2.62564,0.00007
-1.06289,0.51724,-1.46892,-1.17506,-0.49983,2.62597,0.00007
-1.06408,0.51692,-1.46936,-1.17472,-0.49972,2.62629,0.00007
-1.06527,0.51661,-1.46979,-1.17438,-0.49963,2.62660,0.00007
-1.06646,0.51630,-1.47022,-1.17405,-0.49953,2.62691,0.00007
-1.06765,0.51599,-1.47063,-1.17373,-0.49943,2.62722,0.00007
-1.06884,0.51569,-1.47104,-1.17341,-0.49934,2.62752,0.00007
-1.07003,0.51550,-1.47131,-1.17320,-0.49928,2.62771,0.00007
-1.07122,0.51509,-1.47191,-1.17273,-0.49915,2.62812,0.00006
-1.07241,0.51469,-1.47249,-1.17227,-0.49903,2.62852,0.00006
-1.07359,0.51429,-1.47307,-1.17182,-0.49890,2.62892,0.00006
-1.07478,0.51389,-1.47364,-1.17137,-0.49878,2.62931,0.00006
-1.07597,0.51351,-1.47420,-1.17093,-0.49867,2.62970,0.00006
-1.07716,0.51313,-1.47475,-1.17049,-0.49855,2.63008,0.00005
-1.07835,0.51275,-1.47529,-1.17006,-0.49844,2.63045,0.00005
-1.07954,0.51239,-1.47582,-1.16964,-0.49833,2.63082,0.00005
-1.08073,0.51203,-1.47635,-1.16922,-0.49823,2.63118,0.00005
-1.08192,0.51167,-1.47686,-1.16881,-0.49813,2.63153,0.00005
-1.08311,0.51132,-1.47737,-1.16840,-0.49803,2.63188,0.00005
-1.08429,0.51098,-1.47786,-1.16800,-0.49793,2.63223,0.00005
-1.08548,0.51064,-1.47835,-1.16760,-0.49783,2.63256,0.00005
-1.08667,0.51031,-1.47883,-1.16721,-0.49774,2.63290,0.00005
-1.08786,0.50998,-1.47931,-1.16683,-0.49765,2.63322,0.00005
-1.08905,0.50966,-1.47977,-1.16645,-0.49757,2.63355,0.00005
-1.09024,0.50934,-1.48023,-1.16607,-0.49748,2.63386,0.00005
-1.09143,0.50903,-1.48068,-1.16570,-0.49740,2.63418,0.00005
-1.09262,0.50872,-1.48112,-1.16534,-0.49732,2.63448,0.00005
-1.09381,0.50842,-1.48156,-1.16498,-0.49724,2.63479,0.00005
-1.09499,0.50812,-1.48198,-1.16463,-0.49716,2.63508,0.00005
-1.09618,0.50783,-1.48240,-1.16428,-0.49709,2.63538,0.00005
-1.09737,0.50754,-1.48282,-1.16394,-0.49702,2.63566,0.00005
-1.09856,0.50750,-1.48288,-1.16389,-0.49700,2.63571,0.00005
-1.09975,0.50709,-1.48349,-1.16344,-0.49685,2.63612,0.00004
-1.10094,0.50669,-1.48409,-1.16299,-0.49670,2.63652,0.00004
-1.10213,0.50629,-1.48467,-1.16254,-0.49656,2.63692,0.00004
-1.10332,0.50590,-1.48525,-1.16211,-0.49642,2.63731,0.00003
-1.10451,0.50551,-1.48582,-1.16168,-0.49628,2.63769,0.00003
-1.10569,0.50513,-1.48638,-1.16125,-0.49615,2.63807,0.00003
-1.10688,0.50476,-1.48693,-1.16083,-0.49602,2.63844,0.00003
-1.10807,0.50439,-1.48747,-1.16042,-0.49589,2.63880,0.00002
-1.10926,0.50403,-1.48800,-1.16001,-0.49577,2.63916,0.00002
-1.11045,0.50368,-1.48853,-1.15961,-0.49565,2.63952,0.00002
-1.11164,0.50333,-1.48904,-1.15921,-0.49553,2.63987,0.00002
-1.11283,0.50299,-1.48955,-1.15882,-0.49542,2.64021,0.00002
-1.11402,0.50265,-1.49004,-1.15844,-0.49530,2.64055,0.00001
-1.11521,0.50232,-1.49053,-1.15806,-0.49520,2.64088,0.00001
-1.11640,0.50199,-1.49101,-1.15768,-0.49509,2.64120,0.00001
-1.11758,0.50167,-1.49149,-1.15731,-0.49499,2.64152,0.00001
-1.11877,0.50135,-1.49195,-1.15695,-0.49489,2.64184,0.00001
-1.11996,0.50104,-1.49241,-1.15659,-0.49479,2.64215,0.00001
-1.12115,0.50074,-1.49286,-1.15623,-0.49469,2.64246,0.00001
-1.12234,0.50044,-1.49330,-1.15588,-0.49460,2.64276,0.00001
-1.12353,0.50014,-1.49373,-1.15554,-0.49451,2.64305,0.00001
-1.12472,0.49985,-1.49416,-1.15520,-0.49442,2.64335,0.00001
-1.12591,0.49957,-1.49458,-1.15486,-0.49433,2.64363,0.00001
-1.12710,0.49929,-1.49499,-1.15453,-0.49425,2.64391,0.00001
-1.12828,0.49910,-1.49526,-1.15432,-0.49419,2.64410,0.00001
-1.12947,0.49867,-1.49592,-1.15386,-0.49400,2.64453,0.00000
-1.13066,0.49825,-1.49656,-1.15341,-0.49382,2.64495,-0.00000
-1.13185,0.49783,-1.49719,-1.15296,-0.49364,2.64536,-0.00001
-1.13304,0.49742,-1.49781,-1.15252,-0.49346,2.64577,-0.00001
-1.13423,0.49702,-1.49842,-1.15208,-0.49329,2.64617,-0.00002
-1.13542,0.49662,-1.49902,-1.15165,-0.49312,2.64657,-0.00002
-1.13661,0.49623,-1.49961,-1.15123,-0.49296,2.64696,-0.00002
-1.13780,0.49584,-1.50019,-1.15081,-0.49280,2.64734,-0.00003
-1.13898,0.49547,-1.50076,-1.15040,-0.49264,2.64771,-0.00003
-1.14017,0.49510,-1.50132,-1.14999,-0.49249,2.64808,-0.00003
-1.14136,0.49473,-1.50187,-1.14959,-0.49235,2.64845,-0.00004
-1.14255,0.49437,-1.50241,-1.14919,-0.49220,2.64881,-0.00004
-1.14374,0.49402,-1.50295,-1.14880,-0.49206,2.64916,-0.00004
-1.14493,0.49367,-1.50347,-1.14842,-0.49192,2.64950,-0.00005
-1.14612,0.49333,-1.50399,-1.14804,-0.49179,2.64984,-0.00005
-1.14731,0.49300,-1.50449,-1.14766,-0.49166,2.65018,-0.00005
-1.14850,0.49267,-1.50499,-1.14729,-0.49153,2.65051,-0.00005
-1.14968,0.49234,-1.50548,-1.14693,-0.49140,2.65083,-0.00005
-1.15087,0.49202,-1.50596,-1.14657,-0.49128,2.65115,-0.00005
-1.15206,0.49171,-1.50643,-1.14621,-0.49116,2.65147,-0.00005
-1.15325,0.49140,-1.50690,-1.14586,-0.49105,2.65178,-0.00006
-1.15444,0.49110,-1.50736,-1.14552,-0.49094,2.65208,-0.00006
-1.15563,0.49080,-1.50781,-1.14518,-0.49083,2.65238,-0.00006
-1.15682,0.49051,-1.50825,-1.14484,-0.49072,2.65267,-0.00006
-1.15801,0.49022,-1.50869,-1.14451,-0.49061,2.65296,-0.00006
-1.15920,0.48993,-1.50911,-1.14418,-0.49051,2.65325,-0.00006
-1.16039,0.48966,-1.50953,-1.14386,-0.49041,2.65353,-0.00006
-1.16157,0.48938,-1.50995,-1.14354,-0.49031,2.65380,-0.00006
-1.16276,0.48911,-1.51035,-1.14323,-0.49022,2.65407,-0.00006
-1.16395,0.48902,-1.51049,-1.14313,-0.49018,2.65416,-0.00006
-1.16514,0.48866,-1.51104,-1.14274,-0.49003,2.65452,-0.00006
-1.16633,0.48831,-1.51158,-1.14236,-0.48987,2.65486,-0.00006
-1.16752,0.48797,-1.51210,-1.14198,-0.48972,2.65521,-0.00007
-1.16871,0.48763,-1.51262,-1.14161,-0.48957,2.65555,-0.00007
-1.16990,0.48730,-1.51314,-1.14124,-0.48943,2.65588,-0.00007
-1.17109,0.48697,-1.51364,-1.14088,-0.48929,2.65620,-0.00007
-1.17227,0.48665,-1.51413,-1.14052,-0.48915,2.65653,-0.00008
-1.17346,0.48633,-1.51462,-1.14017,-0.48902,2.65684,-0.00008
-1.17465,0.48602,-1.51510,-1.13983,-0.48889,2.65715,-0.00008
-1.17584,0.48572,-1.51557,-1.13948,-0.48876,2.65746,-0.00008
-1.17703,0.48542,-1.51603,-1.13915,-0.48864,2.65776,-0.00008
-1.17822,0.48512,-1.51648,-1.13881,-0.48851,2.65806,-0.00008
-1.17941,0.48483,-1.51693,-1.13848,-0.48840,2.65835,-0.00008
-1.18060,0.48454,-1.51737,-1.13816,-0.48828,2.65863,-0.00008
-1.18179,0.48426,-1.51780,-1.13784,-0.48817,2.65892,-0.00008
-1.18297,0.48398,-1.51823,-1.13753,-0.48806,2.65919,-0.00009
-1.18416,0.48371,-1.51864,-1.13721,-0.48795,2.65947,-0.00009
-1.18535,0.48344,-1.51905,-1.13691,-0.48784,2.65973,-0.00009
-1.18654,0.48318,-1.51946,-1.13660,-0.48774,2.66000,-0.00009
-1.18773,0.48309,-1.51960,-1.13650,-0.48770,2.66009,-0.00009
-1.18892,0.48268,-1.52026,-1.13603,-0.48752,2.66049,-0.00009
-1.19011,0.48228,-1.52090,-1.13557,-0.48734,2.66089,-0.00010
-1.19130,0.48189,-1.52153,-1.13511,-0.48717,2.66128,-0.00010
-1.19249,0.48150,-1.52215,-1.13466,-0.48700,2.66167,-0.00011
-1.19367,0.48113,-1.52277,-1.13422,-0.48684,2.66204,-0.00011
-1.19486,0.48075,-1.52337,-1.13378,-0.48668,2.66241,-0.00011
-1.19605,0.48039,-1.52396,-1.13335,-0.48652,2.66278,-0.00012
-1.19724,0.48003,-1.52454,-1.13292,-0.48637,2.66314,-0.00012
-1.19843,0.47967,-1.52511,-1.13250,-0.48622,2.66349,-0.00012
-1.19962,0.47932,-1.52567,-1.13209,-0.48607,2.66384,-0.00013
-1.20081,0.47898,-1.52622,-1.13168,-0.48593,2.66418,-0.00013
-1.20200,0.47864,-1.52677,-1.13128,-0.48579,2.66452,-0.00013
-1.20319,0.47831,-1.52730,-1.13088,-0.48566,2.66485,-0.00013
-1.20438,0.47799,-1.52782,-1.13048,-0.48553,2.66517,-0.00014
-1.20556,0.47767,-1.52834,-1.13010,-0.48540,2.66549,-0.00014
-1.20675,0.47735,-1.52885,-1.12972,-0.48527,2.66580,-0.00014
-1.20794,0.47704,-1.52935,-1.12934,-0.48515,2.66611,-0.00014
-1.20913,0.47674,-1.52984,-1.12897,-0.48503,2.66642,-0.00014
-1.21032,0.47644,-1.53032,-1.12860,-0.48492,2.66672,-0.00014
-1.21151,0.47615,-1.53079,-1.12824,-0.48480,2.66701,-0.00014
-1.21270,0.47586,-1.53126,-1.12788,-0.48469,2.66730,-0.00014
-1.21389,0.47557,-1.53172,-1.12753,-0.48459,2.66758,-0.00014
-1.21508,0.47529,-1.53217,-1.12718,-0.48448,2.66786,-0.00014
-1.21626,0.47502,-1.53261,-1.12684,-0.48438,2.66814,-0.00014
-1.21745,0.47475,-1.53305,-1.12650,-0.48428,2.66841,-0.00014
-1.21864,0.47448,-1.53348,-1.12617,-0.48418,2.66868,-0.00014
-1.21983,0.47422,-1.53390,-1.12584,-0.48409,2.66894,-0.00014
-1.22102,0.47396,-1.53431,-1.12552,-0.48400,2.66920,-0.00014
-1.22221,0.47371,-1.53472,-1.12520,-0.48391,2.66945,-0.00014
-1.22340,0.47367,-1.53478,-1.12515,-0.48389,2.66949,-0.00014
-1.22459,0.47331,-1.53538,-1.12471,-0.48373,2.66985,-0.00015
-1.22578,0.47295,-1.53598,-1.12427,-0.48358,2.67020,-0.00015
-1.22696,0.47260,-1.53656,-1.12383,-0.48343,2.67055,-0.00015
-1.22815,0.47226,-1.53714,-1.12341,-0.48328,2.67090,-0.00016
-1.22934,0.47192,-1.53771,-1.12299,-0.48314,2.67124,-0.00016
-1.23053,0.47158,-1.53826,-1.12257,-0.48300,2.67157,-0.00016
-1.23172,0.47126,-1.53881,-1.12216,-0.48287,2.67190,-0.00017
-1.23291,0.47093,-1.53935,-1.12176,-0.48273,2.67222,-0.00017
-1.23410,0.47062,-1.53987,-1.12136,-0.48260,2.67253,-0.00017
-1.23529,0.47031,-1.54039,-1.12096,-0.48248,2.67284,-0.00017
-1.23648,0.47000,-1.54091,-1.12058,-0.48236,2.67315,-0.00017
-1.23766,0.46970,-1.54141,-1.12019,-0.48224,2.67345,-0.00017
-1.23885,0.46940,-1.54190,-1.11981,-0.48212,2.67375,-0.00018
-1.24004,0.46911,-1.54239,-1.11944,-0.48201,2.67404,-0.00018
-1.24123,0.46882,-1.54286,-1.11907,-0.48190,2.67432,-0.00018
-1.24242,0.46854,-1.54333,-1.11871,-0.48179,2.67461,-0.00018
-1.24361,0.46827,-1.54380,-1.11835,-0.48168,2.67488,-0.00018
-1.24480,0.46799,-1.54425,-1.11800,-0.48158,2.67516,-0.00018
-1.24599,0.46773,-1.54470,-1.11765,-0.48148,2.67542,-0.00018
-1.24718,0.46746,-1.54514,-1.11731,-0.48139,2.67569,-0.00018
-1.24837,0.46720,-1.54557,-1.11697,-0.48129,2.67595,-0.00018
-1.24955,0.46695,-1.54599,-1.11664,-0.48120,2.67620,-0.00018
-1.25074,0.46670,-1.54641,-1.11631,-0.48111,2.67645,-0.00018
-1.25193,0.46645,-1.54682,-1.11598,-0.48102,2.67670,-0.00018
-1.25312,0.46635,-1.54700,-1.11584,-0.48099,2.67680,-0.00018
-1.25431,0.46604,-1.54754,-1.11540,-0.48088,2.67712,-0.00018
-1.25550,0.46573,-1.54808,-1.11496,-0.48078,2.67742,-0.00018
-1.25669,0.46542,-1.54861,-1.11453,-0.48068,2.67773,-0.00018
-1.25788,0.46513,-1.54913,-1.11410,-0.48059,2.67803,-0.00018
-1.25907,0.46483,-1.54964,-1.11368,-0.48050,2.67832,-0.00018
-1.26025,0.46454,-1.55014,-1.11327,-0.48041,2.67861,-0.00018
-1.26144,0.46426,-1.55064,-1.11286,-0.48032,2.67889,-0.00018
-1.26263,0.46398,-1.55112,-1.11246,-0.48024,2.67917,-0.00018
-1.26382,0.46371,-1.55160,-1.11206,-0.48015,2.67944,-0.00018
-1.26501,0.46344,-1.55207,-1.11167,-0.48007,2.67971,-0.00018
-1.26620,0.46317,-1.55254,-1.11128,-0.48000,2.67998,-0.00018
-1.26739,0.46291,-1.55299,-1.11090,-0.47992,2.68024,-0.00018
-1.26858,0.46266,-1.55344,-1.11053,-0.47985,2.68049,-0.00018
-1.26977,0.46241,-1.55388,-1.11016,-0.47978,2.68075,-0.00018
-1.27095,0.46216,-1.55431,-1.10979,-0.47971,2.68100,-0.00018
-1.27214,0.46191,-1.55473,-1.10943,-0.47964,2.68124,-0.00018
-1.27333,0.46167,-1.55515,-1.10907,-0.47958,2.68148,-0.00018
-1.27452,0.46158,-1.55533,-1.10893,-0.47955,2.68158,-0.00018
-1.27571,0.46130,-1.55582,-1.10853,-0.47945,2.68186,-0.00018
-1.27690,0.46102,-1.55630,-1.10813,-0.47936,2.68213,-0.00018
-1.27809,0.46075,-1.55678,-1.10774,-0.47928,2.68240,-0.00018
-1.27928,0.46048,-1.55725,-1.10736,-0.47919,2.68267,-0.00018
-1.28047,0.46022,-1.55771,-1.10698,-0.47911,2.68293,-0.00018
-1.28165,0.45997,-1.55816,-1.10661,-0.47903,2.68319,-0.00018
-1.28284,0.45971,-1.55861,-1.10624,-0.47895,2.68344,-0.00018
-1.28403,0.45946,-1.55905,-1.10587,-0.47887,2.68369,-0.00018
-1.28522,0.45922,-1.55948,-1.10552,-0.47880,2.68394,-0.00018
-1.28641,0.45898,-1.55990,-1.10516,-0.47873,2.68418,-0.00018
-1.28760,0.45874,-1.56032,-1.10481,-0.47866,2.68442,-0.00018
-1.28879,0.45862,-1.56053,-1.10464,-0.47862,2.68453,-0.00018
-1.28998,0.45838,-1.56097,-1.10426,-0.47855,2.68478,-0.00018
-1.29117,0.45813,-1.56141,-1.10390,-0.47848,2.68503,-0.00018
-1.29236,0.45789,-1.56184,-1.10353,-0.47841,2.68527,-0.00018
-1.29354,0.45766,-1.56226,-1.10317,-0.47835,2.68550,-0.00018
-1.29473,0.45747,-1.56259,-1.10289,-0.47830,2.68569,-0.00018
-1.29592,0.45722,-1.56304,-1.10251,-0.47823,2.68594,-0.00018
-1.29711,0.45698,-1.56348,-1.10213,-0.47817,2.68618,-0.00018
-1.29830,0.45674,-1.56391,-1.10176,-0.47811,2.68642,-0.00018
-1.29949,0.45650,-1.56433,-1.10139,-0.47805,2.68666,-0.00018
-1.30068,0.45630,-1.56471,-1.10107,-0.47800,2.68687,-0.00018
-1.30187,0.45606,-1.56514,-1.10070,-0.47794,2.68710,-0.00018
-1.30306,0.45583,-1.56556,-1.10033,-0.47788,2.68734,-0.00018
-1.30424,0.45571,-1.56575,-1.10022,-0.47780,2.68745,-0.00018
-1.30543,0.45547,-1.56597,-1.10055,-0.47726,2.68769,-0.00019
-1.30662,0.45524,-1.56619,-1.10088,-0.47673,2.68792,-0.00021
-1.30781,0.45501,-1.56641,-1.10120,-0.47621,2.68815,-0.00022
-1.30900,0.45478,-1.56662,-1.10152,-0.47569,2.68838,-0.00024
-1.31019,0.45456,-1.56683,-1.10183,-0.47519,2.68860,-0.00025
-1.31138,0.45434,-1.56703,-1.10214,-0.47469,2.68882,-0.00026
-1.31257,0.45412,-1.56723,-1.10244,-0.47420,2.68903,-0.00027
-1.31376,0.45391,-1.56742,-1.10274,-0.47372,2.68924,-0.00028
-1.31494,0.45370,-1.56762,-1.10303,-0.47325,2.68945,-0.00029
-1.31613,0.45350,-1.56780,-1.10332,-0.47278,2.68965,-0.00030
-1.31732,0.45330,-1.56799,-1.10360,-0.47233,2.68985,-0.00031
-1.31851,0.45310,-1.56817,-1.10388,-0.47188,2.69005,-0.00032
-1.31970,0.45291,-1.56834,-1.10415,-0.47143,2.69024,-0.00033
-1.32089,0.45272,-1.56852,-1.10442,-0.47100,2.69043,-0.00033
-1.32208,0.45253,-1.56869,-1.10469,-0.47057,2.69062,-0.00034
-1.32327,0.45235,-1.56885,-1.10495,-0.47015,2.69080,-0.00035
-1.32446,0.45217,-1.56902,-1.10520,-0.46974,2.69098,-0.00035
-1.32564,0.45199,-1.56918,-1.10546,-0.46933,2.69116,-0.00036
-1.32683,0.45182,-1.56933,-1.10570,-0.46894,2.69133,-0.00036
-1.32802,0.45165,-1.56949,-1.10595,-0.46854,2.69150,-0.00037
-1.32921,0.45148,-1.56963,-1.10620,-0.46815,2.69167,-0.00037
-1.33040,0.45132,-1.56976,-1.10654,-0.46769,2.69183,-0.00038
-1.33159,0.45115,-1.56987,-1.10688,-0.46724,2.69200,-0.00038
-1.33278,0.45099,-1.56999,-1.10721,-0.46680,2.69216,-0.00039
-1.33397,0.45083,-1.57010,-1.10754,-0.46636,2.69232,-0.00039
-1.33516,0.45067,-1.57021,-1.10786,-0.46593,2.69247,-0.00040
-1.33635,0.45052,-1.57032,-1.10818,-0.46551,2.69263,-0.00040
-1.33753,0.45037,-1.57043,-1.10849,-0.46510,2.69278,-0.00040
-1.33872,0.45029,-1.57046,-1.10874,-0.46483,2.69285,-0.00041
-1.33991,0.45011,-1.57036,-1.10994,-0.46376,2.69303,-0.00043
-1.34110,0.44993,-1.57026,-1.11112,-0.46270,2.69321,-0.00046
-1.34229,0.44975,-1.57016,-1.11228,-0.46166,2.69339,-0.00048
-1.34348,0.44958,-1.57006,-1.11343,-0.46064,2.69356,-0.00050
-1.34467,0.44941,-1.56997,-1.11456,-0.45964,2.69372,-0.00052
-1.34586,0.44924,-1.56987,-1.11566,-0.45865,2.69389,-0.00054
-1.34705,0.44908,-1.56977,-1.11676,-0.45768,2.69405,-0.00056
-1.34823,0.44892,-1.56968,-1.11783,-0.45672,2.69420,-0.00058
-1.34942,0.44876,-1.56958,-1.11889,-0.45578,2.69436,-0.00060
-1.35061,0.44861,-1.56949,-1.11993,-0.45485,2.69451,-0.00061
-1.35180,0.44845,-1.56939,-1.12095,-0.45394,2.69465,-0.00063
-1.35299,0.44831,-1.56930,-1.12196,-0.45304,2.69480,-0.00064
-1.35418,0.44816,-1.56921,-1.12295,-0.45216,2.69494,-0.00065
-1.35537,0.44802,-1.56912,-1.12392,-0.45129,2.69508,-0.00067
-1.35656,0.44788,-1.56903,-1.12488,-0.45043,2.69521,-0.00068
-1.35775,0.44775,-1.56893,-1.12583,-0.44959,2.69535,-0.00069
-1.35893,0.44761,-1.56885,-1.12676,-0.44876,2.69548,-0.00070
-1.36012,0.44748,-1.56876,-1.12767,-0.44794,2.69561,-0.00070
-1.36131,0.44735,-1.56867,-1.12857,-0.44714,2.69573,-0.00071
-1.36250,0.44723,-1.56858,-1.12946,-0.44635,2.69585,-0.00072
-1.36369,0.44710,-1.56849,-1.13033,-0.44557,2.69597,-0.00073
-1.36488,0.44698,-1.56841,-1.13119,-0.44481,2.69609,-0.00073
-1.36607,0.44687,-1.56832,-1.13204,-0.44406,2.69621,-0.00074
-1.36726,0.44675,-1.56823,-1.13287,-0.44332,2.69632,-0.00074
-1.36845,0.44664,-1.56815,-1.13369,-0.44259,2.69643,-0.00074
-1.36964,0.44652,-1.56807,-1.13449,-0.44187,2.69654,-0.00075
-1.37082,0.44642,-1.56798,-1.13529,-0.44116,2.69665,-0.00075
-1.37201,0.44631,-1.56790,-1.13607,-0.44047,2.69675,-0.00075
-1.37320,0.44620,-1.56782,-1.13684,-0.43978,2.69685,-0.00075
-1.37439,0.44610,-1.56773,-1.13759,-0.43911,2.69695,-0.00075
-1.37558,0.44600,-1.56765,-1.13834,-0.43845,2.69705,-0.00075
-1.37677,0.44590,-1.56757,-1.13907,-0.43779,2.69715,-0.00075
-1.37796,0.44581,-1.56749,-1.13979,-0.43715,2.69724,-0.00075
-1.37915,0.44571,-1.56741,-1.14050,-0.43652,2.69733,-0.00075
-1.38034,0.44562,-1.56734,-1.14120,-0.43590,2.69742,-0.00075
-1.38152,0.44553,-1.56726,-1.14189,-0.43529,2.69751,-0.00074
-1.38271,0.44544,-1.56718,-1.14256,-0.43468,2.69760,-0.00074
-1.38390,0.44535,-1.56710,-1.14323,-0.43409,2.69768,-0.00074
-1.38509,0.44527,-1.56703,-1.14389,-0.43351,2.69777,-0.00073
-1.38628,0.44518,-1.56695,-1.14453,-0.43293,2.69785,-0.00073
-1.38747,0.44510,-1.56688,-1.14517,-0.43237,2.69793,-0.00073
-1.38866,0.44502,-1.56680,-1.14579,-0.43181,2.69800,-0.00072
-1.38985,0.44494,-1.56673,-1.14641,-0.43127,2.69808,-0.00072
-1.39104,0.44486,-1.56666,-1.14701,-0.43073,2.69816,-0.00071
-1.39222,0.44479,-1.56658,-1.14761,-0.43020,2.69823,-0.00070
-1.39341,0.44471,-1.56651,-1.14820,-0.42968,2.69830,-0.00070
-1.39460,0.44464,-1.56644,-1.14878,-0.42916,2.69837,-0.00069
-1.39579,0.44457,-1.56637,-1.14935,-0.42866,2.69844,-0.00069
-1.39698,0.44450,-1.56630,-1.14991,-0.42816,2.69851,-0.00068
-1.39817,0.44443,-1.56623,-1.15046,-0.42767,2.69857,-0.00067
-1.39936,0.44437,-1.56616,-1.15100,-0.42719,2.69864,-0.00066
-1.40055,0.44430,-1.56609,-1.15154,-0.42672,2.69870,-0.00066
-1.40174,0.44425,-1.56603,-1.15195,-0.42636,2.69875,-0.00065
-1.40292,0.44417,-1.56588,-1.15290,-0.42556,2.69883,-0.00066
-1.40411,0.44408,-1.56574,-1.15383,-0.42478,2.69891,-0.00066
-1.40530,0.44400,-1.56559,-1.15475,-0.42401,2.69899,-0.00066
-1.40649,0.44392,-1.56545,-1.15565,-0.42326,2.69906,-0.00066
-1.40768,0.44384,-1.56530,-1.15654,-0.42251,2.69914,-0.00067
-1.40887,0.44377,-1.56516,-1.15742,-0.42178,2.69921,-0.00067
-1.41006,0.44369,-1.56502,-1.15828,-0.42106,2.69928,-0.00067
-1.41125,0.44362,-1.56488,-1.15913,-0.42035,2.69935,-0.00067
-1.41244,0.44355,-1.56475,-1.15997,-0.41965,2.69942,-0.00067
-1.41363,0.44348,-1.56461,-1.16079,-0.41896,2.69949,-0.00067
-1.41481,0.44341,-1.56448,-1.16160,-0.41829,2.69955,-0.00066
-1.41600,0.44334,-1.56434,-1.16239,-0.41762,2.69962,-0.00066
-1.41719,0.44327,-1.56421,-1.16318,-0.41697,2.69968,-0.00066
-1.41838,0.44321,-1.56409,-1.16395,-0.41632,2.69974,-0.00066
-1.41957,0.44315,-1.56396,-1.16471,-0.41569,2.69980,-0.00065
-1.42076,0.44309,-1.56383,-1.16545,-0.41506,2.69986,-0.00065
-1.42195,0.44303,-1.56371,-1.16619,-0.41445,2.69992,-0.00064
-1.42314,0.44297,-1.56358,-1.16691,-0.41384,2.69997,-0.00064
-1.42433,0.44291,-1.56346,-1.16763,-0.41325,2.70003,-0.00063
-1.42551,0.44285,-1.56334,-1.16833,-0.41266,2.70008,-0.00063
-1.42670,0.44280,-1.56322,-1.16902,-0.41208,2.70013,-0.00062
-1.42789,0.44274,-1.56310,-1.16970,-0.41152,2.70018,-0.00062
-1.42908,0.44269,-1.56299,-1.17037,-0.41096,2.70023,-0.00061
-1.43027,0.44264,-1.56287,-1.17102,-0.41041,2.70028,-0.00060
-1.43146,0.44259,-1.56276,-1.17167,-0.40986,2.70033,-0.00060
-1.43265,0.44254,-1.56265,-1.17231,-0.40933,2.70037,-0.00059
-1.43384,0.44249,-1.56253,-1.17294,-0.40881,2.70042,-0.00058
-1.43503,0.44244,-1.56242,-1.17356,-0.40829,2.70046,-0.00057
-1.43621,0.44240,-1.56232,-1.17416,-0.40778,2.70050,-0.00057
-1.43740,0.44235,-1.56221,-1.17476,-0.40728,2.70055,-0.00056
-1.43859,0.44231,-1.56210,-1.17535,-0.40679,2.70059,-0.00055
-1.43978,0.44227,-1.56200,-1.17593,-0.40631,2.70063,-0.00054
-1.44097,0.44222,-1.56189,-1.17650,-0.40583,2.70067,-0.00053
-1.44216,0.44218,-1.56179,-1.17707,-0.40536,2.70071,-0.00052
-1.44335,0.44218,-1.56178,-1.17714,-0.40530,2.70071,-0.00052
-1.44454,0.44213,-1.56164,-1.17784,-0.40473,2.70075,-0.00052
-1.44573,0.44209,-1.56151,-1.17854,-0.40416,2.70079,-0.00051
-1.44691,0.44205,-1.56138,-1.17923,-0.40360,2.70083,-0.00050
-1.44810,0.44201,-1.56125,-1.17990,-0.40305,2.70087,-0.00050
-1.44929,0.44197,-1.56112,-1.18056,-0.40251,2.70091,-0.00049
-1.45048,0.44193,-1.56099,-1.18122,-0.40197,2.70094,-0.00048
-1.45167,0.44189,-1.56087,-1.18186,-0.40145,2.70098,-0.00048
-1.45286,0.44185,-1.56074,-1.18249,-0.40093,2.70101,-0.00047
-1.45405,0.44181,-1.56062,-1.18311,-0.40042,2.70105,-0.00046
-1.45524,0.44178,-1.56050,-1.18373,-0.39992,2.70108,-0.00045
-1.45643,0.44174,-1.56038,-1.18433,-0.39943,2.70111,-0.00045
-1.45762,0.44171,-1.56026,-1.18493,-0.39895,2.70114,-0.00044
-1.45880,0.44167,-1.56015,-1.18551,-0.39847,2.70117,-0.00043
-1.45999,0.44164,-1.56003,-1.18609,-0.39800,2.70120,-0.00042
-1.46118,0.44162,-1.55997,-1.18639,-0.39776,2.70122,-0.00042
-1.46237,0.44159,-1.55982,-1.18713,-0.39716,2.70125,-0.00041
-1.46356,0.44155,-1.55967,-1.18786,-0.39658,2.70129,-0.00041
-1.46475,0.44151,-1.55952,-1.18858,-0.39600,2.70132,-0.00040
-1.46594,0.44148,-1.55938,-1.18928,-0.39544,2.70135,-0.00040
-1.46713,0.44145,-1.55923,-1.18998,-0.39488,2.70138,-0.00039
-1.46832,0.44141,-1.55909,-1.19066,-0.39433,2.70141,-0.00039
-1.46950,0.44138,-1.55895,-1.19134,-0.39379,2.70144,-0.00038
-1.47069,0.44135,-1.55881,-1.19200,-0.39326,2.70146,-0.00038
-1.47188,0.44132,-1.55867,-1.19265,-0.39274,2.70149,-0.00037
-1.47307,0.44129,-1.55854,-1.19330,-0.39222,2.70152,-0.00036
-1.47426,0.44126,-1.55840,-1.19393,-0.39172,2.70154,-0.00035
-1.47545,0.44124,-1.55827,-1.19455,-0.39122,2.70157,-0.00035
-1.47664,0.44121,-1.55814,-1.19517,-0.39073,2.70159,-0.00034
-1.47783,0.44118,-1.55801,-1.19577,-0.39025,2.70161,-0.00033
-1.47902,0.44116,-1.55789,-1.19636,-0.38977,2.70164,-0.00032
-1.48020,0.44113,-1.55776,-1.19695,-0.38930,2.70166,-0.00031
-1.48139,0.44112,-1.55769,-1.19731,-0.38901,2.70167,-0.00031
-1.48258,0.44109,-1.55753,-1.19803,-0.38844,2.70170,-0.00031
-1.48377,0.44106,-1.55738,-1.19874,-0.38788,2.70172,-0.00030
-1.48496,0.44103,-1.55723,-1.19944,-0.38733,2.70174,-0.00030
-1.48615,0.44101,-1.55708,-1.20013,-0.38678,2.70177,-0.00029
-1.48734,0.44098,-1.55693,-1.20081,-0.38625,2.70179,-0.00029
-1.48853,0.44096,-1.55679,-1.20147,-0.38572,2.70181,-0.00028
-1.48972,0.44093,-1.55664,-1.20213,-0.38520,2.70183,-0.00027
-1.49090,0.44091,-1.55650,-1.20278,-0.38469,2.70185,-0.00027
-1.49209,0.44088,-1.55636,-1.20341,-0.38418,2.70187,-0.00026
-1.49328,0.44086,-1.55622,-1.20404,-0.38369,2.70189,-0.00025
-1.49447,0.44084,-1.55609,-1.20466,-0.38320,2.70191,-0.00025
-1.49566,0.44082,-1.55595,-1.20526,-0.38272,2.70193,-0.00024
-1.49685,0.44080,-1.55582,-1.20586,-0.38225,2.70194,-0.00023
-1.49804,0.44078,-1.55569,-1.20645,-0.38178,2.70196,-0.00022
-1.49923,0.44077,-1.55562,-1.20675,-0.38154,2.70197,-0.00022
-1.50042,0.44075,-1.55547,-1.20745,-0.38099,2.70199,-0.00021
-1.50161,0.44072,-1.55532,-1.20814,-0.38045,2.70200,-0.00021
-1.50279,0.44070,-1.55517,-1.20882,-0.37992,2.70202,-0.00020
-1.50398,0.44068,-1.55502,-1.20949,-0.37939,2.70204,-0.00020
-1.50517,0.44066,-1.55487,-1.21014,-0.37888,2.70206,-0.00019
-1.50636,0.44064,-1.55473,-1.21079,-0.37837,2.70207,-0.00019
-1.50755,0.44062,-1.55458,-1.21143,-0.37787,2.70209,-0.00018
-1.50874,0.44061,-1.55444,-1.21205,-0.37738,2.70210,-0.00017
-1.50993,0.44059,-1.55430,-1.21267,-0.37689,2.70212,-0.00017
-1.51112,0.44057,-1.55417,-1.21328,-0.37642,2.70213,-0.00016
-1.51231,0.44055,-1.55403,-1.21387,-0.37595,2.70214,-0.00015
-1.51349,0.44054,-1.55390,-1.21446,-0.37548,2.70216,-0.00014
-1.51468,0.44053,-1.55386,-1.21465,-0.37534,2.70216,-0.00014
-1.51587,0.44051,-1.55370,-1.21532,-0.37481,2.70218,-0.00014
-1.51706,0.44050,-1.55355,-1.21599,-0.37429,2.70219,-0.00013
-1.51825,0.44048,-1.55341,-1.21664,-0.37378,2.70220,-0.00013
-1.51944,0.44046,-1.55326,-1.21729,-0.37327,2.70222,-0.00012
-1.52063,0.44045,-1.55312,-1.21792,-0.37277,2.70223,-0.00011
-1.52182,0.44043,-1.55297,-1.21855,-0.37229,2.70224,-0.00011
-1.52301,0.44041,-1.55283,-1.21916,-0.37180,2.70225,-0.00010
-1.52419,0.44040,-1.55270,-1.21977,-0.37133,2.70226,-0.00009
-1.52538,0.44039,-1.55256,-1.22036,-0.37086,2.70228,-0.00009
-1.52657,0.44037,-1.55242,-1.22095,-0.37041,2.70229,-0.00008
-1.52776,0.44037,-1.55241,-1.22102,-0.37035,2.70229,-0.00008
-1.52895,0.44035,-1.55225,-1.22172,-0.36980,2.70230,-0.00007
-1.53014,0.44034,-1.55209,-1.22241,-0.36927,2.70231,-0.00007
-1.53133,0.44032,-1.55194,-1.22309,-0.36874,2.70232,-0.00007
-1.53252,0.44031,-1.55179,-1.22376,-0.36821,2.70234,-0.00006
-1.53371,0.44029,-1.55164,-1.22442,-0.36770,2.70235,-0.00006
-1.53489,0.44028,-1.55149,-1.22507,-0.36720,2.70236,-0.00005
-1.53608,0.44026,-1.55134,-1.22570,-0.36670,2.70237,-0.00004
-1.53727,0.44025,-1.55120,-1.22633,-0.36621,2.70238,-0.00004
-1.53846,0.44024,-1.55106,-1.22695,-0.36573,2.70239,-0.00003
-1.53965,0.44022,-1.55092,-1.22755,-0.36526,2.70240,-0.00003
-1.54084,0.44021,-1.55078,-1.22815,-0.36479,2.70240,-0.00002
-1.54203,0.44020,-1.55064,-1.22874,-0.36433,2.70241,-0.00001
-1.54322,0.44020,-1.55060,-1.22892,-0.36419,2.70242,-0.00001
-1.54441,0.44017,-1.55047,-1.22958,-0.36366,2.70243,-0.00001
-1.54560,0.44015,-1.55033,-1.23023,-0.36314,2.70245,-0.00000
-1.54678,0.44013,-1.55020,-1.23087,-0.36263,2.70247,0.00000
-1.54797,0.44011,-1.55007,-1.23150,-0.36212,2.70248,0.00001
-1.54916,0.44009,-1.54994,-1.23212,-0.36163,2.70250,0.00001
-1.55035,0.44007,-1.54982,-1.23273,-0.36114,2.70251,0.00002
-1.55154,0.44006,-1.54969,-1.23333,-0.36066,2.70253,0.00002
-1.55273,0.44004,-1.54957,-1.23392,-0.36019,2.70254,0.00003
-1.55392,0.44002,-1.54944,-1.23450,-0.35972,2.70256,0.00004
-1.55511,0.44000,-1.54933,-1.23502,-0.35930,2.70257,0.00004
-1.55630,0.43999,-1.54920,-1.23566,-0.35880,2.70258,0.00005
-1.55748,0.43997,-1.54907,-1.23629,-0.35830,2.70260,0.00005
-1.55867,0.43995,-1.54894,-1.23691,-0.35780,2.70261,0.00006
-1.55986,0.43993,-1.54881,-1.23751,-0.35732,2.70263,0.00006
-1.56105,0.43992,-1.54868,-1.23811,-0.35684,2.70264,0.00007
-1.56224,0.43990,-1.54856,-1.23870,-0.35637,2.70265,0.00007
-1.56343,0.43989,-1.54843,-1.23928,-0.35591,2.70266,0.00008
-1.56462,0.43988,-1.54836,-1.23963,-0.35563,2.70267,0.00008
-1.56581,0.43986,-1.54823,-1.24024,-0.35514,2.70268,0.00009
-1.56700,0.43984,-1.54810,-1.24085,-0.35466,2.70269,0.00009
-1.56818,0.43983,-1.54797,-1.24144,-0.35419,2.70270,0.00010
-1.56937,0.43982,-1.54785,-1.24203,-0.35372,2.70271,0.00011
-1.57056,0.43980,-1.54772,-1.24260,-0.35327,2.70273,0.00011
-1.57175,0.43980,-1.54770,-1.24272,-0.35317,2.70273,0.00011
-1.57294,0.43978,-1.54757,-1.24331,-0.35271,2.70274,0.00012
-1.57413,0.43977,-1.54745,-1.24389,-0.35224,2.70275,0.00012
-1.57532,0.43976,-1.54737,-1.24424,-0.35197,2.70275,0.00013
-1.57651,0.43975,-1.54724,-1.24483,-0.35150,2.70276,0.00013
-1.57770,0.43974,-1.54712,-1.24541,-0.35104,2.70277,0.00014
-1.57888,0.43973,-1.54703,-1.24581,-0.35072,2.70278,0.00014
-1.58007,0.43971,-1.54690,-1.24641,-0.35025,2.70279,0.00015
-1.58126,0.43970,-1.54678,-1.24699,-0.34979,2.70280,0.00016
-1.58245,0.43969,-1.54670,-1.24733,-0.34951,2.70280,0.00016
-1.58364,0.43968,-1.54657,-1.24792,-0.34905,2.70281,0.00016
-1.58483,0.43967,-1.54645,-1.24851,-0.34859,2.70282,0.00017
-1.58602,0.43966,-1.54636,-1.24891,-0.34827,2.70283,0.00017
-1.58721,0.43967,-1.54631,-1.24904,-0.34818,2.70282,0.00018
-1.58840,0.43975,-1.54598,-1.24979,-0.34775,2.70274,0.00019
-1.58959,0.43983,-1.54566,-1.25052,-0.34733,2.70266,0.00020
-1.59077,0.43990,-1.54534,-1.25124,-0.34692,2.70258,0.00021
-1.59196,0.43998,-1.54503,-1.25195,-0.34652,2.70250,0.00022
-1.59315,0.44006,-1.54472,-1.25265,-0.34612,2.70242,0.00023
-1.59434,0.44013,-1.54441,-1.25333,-0.34572,2.70234,0.00024
-1.59553,0.44021,-1.54412,-1.25401,-0.34533,2.70227,0.00025
-1.59672,0.44030,-1.54377,-1.25472,-0.34496,2.70217,0.00026
-1.59791,0.44060,-1.54298,-1.25581,-0.34464,2.70188,0.00028
-1.59910,0.44089,-1.54220,-1.25689,-0.34432,2.70159,0.00030
-1.60029,0.44118,-1.54143,-1.25795,-0.34400,2.70130,0.00032
-1.60147,0.44147,-1.54068,-1.25899,-0.34370,2.70102,0.00034
-1.60266,0.44175,-1.53994,-1.26002,-0.34339,2.70074,0.00036
-1.60385,0.44203,-1.53921,-1.26103,-0.34309,2.70046,0.00038
-1.60504,0.44230,-1.53849,-1.26202,-0.34280,2.70019,0.00040
-1.60623,0.44257,-1.53778,-1.26300,-0.34251,2.69992,0.00042
-1.60742,0.44284,-1.53709,-1.26396,-0.34222,2.69966,0.00044
-1.60861,0.44310,-1.53641,-1.26491,-0.34194,2.69940,0.00046
-1.60980,0.44336,-1.53574,-1.26584,-0.34166,2.69914,0.00047
-1.61099,0.44361,-1.53508,-1.26675,-0.34139,2.69889,0.00049
-1.61217,0.44387,-1.53443,-1.26766,-0.34111,2.69864,0.00051
-1.61336,0.44411,-1.53379,-1.26854,-0.34085,2.69839,0.00053
-1.61455,0.44436,-1.53316,-1.26942,-0.34059,2.69815,0.00054
-1.61574,0.44460,-1.53254,-1.27028,-0.34033,2.69791,0.00056
-1.61693,0.44484,-1.53193,-1.27112,-0.34007,2.69767,0.00058
-1.61812,0.44507,-1.53134,-1.27196,-0.33982,2.69743,0.00059
-1.61931,0.44530,-1.53075,-1.27278,-0.33957,2.69720,0.00061
-1.62050,0.44553,-1.53017,-1.27358,-0.33933,2.69698,0.00062
-1.62169,0.44576,-1.52960,-1.27438,-0.33909,2.69675,0.00064
-1.62287,0.44598,-1.52904,-1.27516,-0.33885,2.69653,0.00065
-1.62406,0.44620,-1.52849,-1.27593,-0.33862,2.69631,0.00067
-1.62525,0.44641,-1.52795,-1.27668,-0.33839,2.69610,0.00068
-1.62644,0.44662,-1.52742,-1.27743,-0.33816,2.69588,0.00070
-1.62763,0.44683,-1.52690,-1.27816,-0.33794,2.69568,0.00071
-1.62882,0.44704,-1.52638,-1.27888,-0.33772,2.69547,0.00072
-1.63001,0.44724,-1.52588,-1.27959,-0.33750,2.69527,0.00074
-1.63120,0.44744,-1.52538,-1.28029,-0.33729,2.69506,0.00075
-1.63239,0.44764,-1.52489,-1.28097,-0.33708,2.69487,0.00076
-1.63358,0.44784,-1.52441,-1.28165,-0.33687,2.69467,0.00078
-1.63476,0.44803,-1.52394,-1.28231,-0.33667,2.69448,0.00079
-1.63595,0.44822,-1.52347,-1.28297,-0.33646,2.69429,0.00080
-1.63714,0.44840,-1.52301,-1.28361,-0.33627,2.69410,0.00081
-1.63833,0.44859,-1.52256,-1.28425,-0.33607,2.69392,0.00083
-1.63952,0.44877,-1.52212,-1.28487,-0.33588,2.69373,0.00084
-1.64071,0.44895,-1.52168,-1.28549,-0.33569,2.69355,0.00085
-1.64190,0.44912,-1.52126,-1.28609,-0.33550,2.69338,0.00086
-1.64309,0.44930,-1.52083,-1.28669,-0.33531,2.69320,0.00087
-1.64428,0.44945,-1.52048,-1.28711,-0.33523,2.69305,0.00088
-1.64546,0.45010,-1.51907,-1.28845,-0.33527,2.69241,0.00092
-1.64665,0.45074,-1.51768,-1.28975,-0.33532,2.69178,0.00095
-1.64784,0.45138,-1.51632,-1.29104,-0.33536,2.69115,0.00098
-1.64903,0.45200,-1.51498,-1.29231,-0.33541,2.69054,0.00102
-1.65022,0.45262,-1.51366,-1.29355,-0.33545,2.68993,0.00105
-1.65141,0.45323,-1.51236,-1.29477,-0.33549,2.68933,0.00108
-1.65260,0.45383,-1.51109,-1.29598,-0.33553,2.68873,0.00111
-1.65379,0.45442,-1.50984,-1.29716,-0.33557,2.68815,0.00113
-1.65498,0.45501,-1.50861,-1.29832,-0.33562,2.68757,0.00116
-1.65616,0.45559,-1.50740,-1.29947,-0.33566,2.68700,0.00119
-1.65735,0.45616,-1.50621,-1.30059,-0.33569,2.68643,0.00121
-1.65854,0.45672,-1.50504,-1.30170,-0.33573,2.68588,0.00124
-1.65973,0.45728,-1.50389,-1.30278,-0.33577,2.68533,0.00126
-1.66092,0.45782,-1.50276,-1.30385,-0.33581,2.68479,0.00128
-1.66211,0.45836,-1.50166,-1.30490,-0.33585,2.68425,0.00130
-1.66330,0.45890,-1.50056,-1.30594,-0.33588,2.68372,0.00133
-1.66449,0.45942,-1.49949,-1.30695,-0.33592,2.68320,0.00135
-1.66568,0.45994,-1.49844,-1.30796,-0.33595,2.68269,0.00137
-1.66686,0.46045,-1.49740,-1.30894,-0.33598,2.68218,0.00139
-1.66805,0.46096,-1.49638,-1.30991,-0.33602,2.68168,0.00140
-1.66924,0.46146,-1.49538,-1.31086,-0.33605,2.68119,0.00142
-1.67043,0.46195,-1.49440,-1.31179,-0.33608,2.68070,0.00144
-1.67162,0.46243,-1.49343,-1.31271,-0.33611,2.68022,0.00146
-1.67281,0.46291,-1.49248,-1.31362,-0.33614,2.67974,0.00147
-1.67400,0.46338,-1.49155,-1.31451,-0.33617,2.67927,0.00149
-1.67519,0.46385,-1.49063,-1.31539,-0.33620,2.67881,0.00150
-1.67638,0.46430,-1.48972,-1.31625,-0.33623,2.67836,0.00152
-1.67757,0.46476,-1.48884,-1.31709,-0.33625,2.67791,0.00153
-1.67875,0.46520,-1.48796,-1.31793,-0.33628,2.67746,0.00155
-1.67994,0.46564,-1.48711,-1.31875,-0.33631,2.67702,0.00156
-1.68113,0.46607,-1.48626,-1.31955,-0.33633,2.67659,0.00157
-1.68232,0.46650,-1.48544,-1.32035,-0.33636,2.67617,0.00158
-1.68351,0.46692,-1.48462,-1.32113,-0.33638,2.67575,0.00160
-1.68470,0.46734,-1.48382,-1.32189,-0.33640,2.67533,0.00161
-1.68589,0.46775,-1.48303,-1.32265,-0.33642,2.67492,0.00162
-1.68708,0.46815,-1.48226,-1.32339,-0.33645,2.67452,0.00163
-1.68827,0.46855,-1.48150,-1.32412,-0.33647,2.67412,0.00164
-1.68945,0.46895,-1.48075,-1.32484,-0.33649,2.67373,0.00165
-1.69064,0.46933,-1.48002,-1.32555,-0.33651,2.67334,0.00166
-1.69183,0.46972,-1.47929,-1.32624,-0.33653,2.67296,0.00167
-1.69302,0.47009,-1.47858,-1.32693,-0.33654,2.67258,0.00168
-1.69421,0.47046,-1.47788,-1.32760,-0.33656,2.67221,0.00168
-1.69540,0.47083,-1.47720,-1.32826,-0.33658,2.67185,0.00169
-1.69659,0.47119,-1.47652,-1.32892,-0.33660,2.67149,0.00170
-1.69778,0.47155,-1.47586,-1.32956,-0.33661,2.67113,0.00171
-1.69897,0.47190,-1.47521,-1.33019,-0.33663,2.67078,0.00171
-1.70015,0.47224,-1.47457,-1.33081,-0.33664,2.67043,0.00172
-1.70134,0.47258,-1.47394,-1.33142,-0.33666,2.67009,0.00173
-1.70253,0.47292,-1.47332,-1.33202,-0.33667,2.66975,0.00173
-1.70372,0.47325,-1.47271,-1.33261,-0.33668,2.66942,0.00174
-1.70491,0.47358,-1.47211,-1.33319,-0.33670,2.66909,0.00175
-1.70610,0.47390,-1.47152,-1.33376,-0.33671,2.66877,0.00175
-1.70729,0.47422,-1.47094,-1.33433,-0.33672,2.66845,0.00176
-1.70848,0.47453,-1.47037,-1.33488,-0.33673,2.66814,0.00176
-1.70967,0.47484,-1.46982,-1.33542,-0.33674,2.66783,0.00177
-1.71085,0.47514,-1.46927,-1.33596,-0.33675,2.66753,0.00177
-1.71204,0.47544,-1.46873,-1.33649,-0.33676,2.66722,0.00178
-1.71323,0.47574,-1.46820,-1.33701,-0.33677,2.66693,0.00178
-1.71442,0.47603,-1.46767,-1.33752,-0.33678,2.66664,0.00178
-1.71561,0.47631,-1.46716,-1.33802,-0.33679,2.66635,0.00179
-1.71680,0.47660,-1.46666,-1.33851,-0.33679,2.66606,0.00179
-1.71799,0.47687,-1.46616,-1.33900,-0.33680,2.66578,0.00180
-1.71918,0.47715,-1.46567,-1.33948,-0.33681,2.66551,0.00180
-1.72037,0.47742,-1.46519,-1.33995,-0.33681,2.66523,0.00180
-1.72156,0.47769,-1.46472,-1.34041,-0.33682,2.66497,0.00181
-1.72274,0.47795,-1.46426,-1.34087,-0.33682,2.66470,0.00181
-1.72393,0.47821,-1.46380,-1.34132,-0.33683,2.66444,0.00181
-1.72512,0.47846,-1.46336,-1.34176,-0.33683,2.66418,0.00181
-1.72631,0.47871,-1.46292,-1.34219,-0.33684,2.66393,0.00182
-1.72750,0.47896,-1.46247,-1.34261,-0.33686,2.66368,0.00182
-1.72869,0.47948,-1.46154,-1.34338,-0.33701,2.66316,0.00183
-1.72988,0.48000,-1.46063,-1.34413,-0.33717,2.66265,0.00185
-1.73107,0.48050,-1.45973,-1.34486,-0.33732,2.66215,0.00186
-1.73226,0.48100,-1.45884,-1.34559,-0.33747,2.66166,0.00187
-1.73344,0.48149,-1.45797,-1.34630,-0.33762,2.66117,0.00188
-1.73463,0.48198,-1.45712,-1.34700,-0.33776,2.66069,0.00189
-1.73582,0.48246,-1.45628,-1.34769,-0.33790,2.66021,0.00190
-1.73701,0.48293,-1.45545,-1.34837,-0.33804,2.65974,0.00191
-1.73820,0.48339,-1.45464,-1.34904,-0.33817,2.65928,0.00192
-1.73939,0.48385,-1.45384,-1.34970,-0.33831,2.65883,0.00193
-1.74058,0.48430,-1.45306,-1.35034,-0.33844,2.65837,0.00194
-1.74177,0.48475,-1.45229,-1.35098,-0.33857,2.65793,0.00195
-1.74296,0.48519,-1.45153,-1.35160,-0.33869,2.65749,0.00195
-1.74414,0.48562,-1.45079,-1.35221,-0.33882,2.65706,0.00196
-1.74533,0.48605,-1.45006,-1.35282,-0.33894,2.65663,0.00197
-1.74652,0.48647,-1.44934,-1.35341,-0.33906,2.65621,0.00198
-1.74771,0.48689,-1.44863,-1.35400,-0.33918,2.65580,0.00198
-1.74890,0.48730,-1.44794,-1.35457,-0.33929,2.65539,0.00199
-1.75009,0.48770,-1.44725,-1.35514,-0.33940,2.65499,0.00199
-1.75128,0.48810,-1.44658,-1.35569,-0.33951,2.65459,0.00200
-1.75247,0.48850,-1.44592,-1.35624,-0.33962,2.65420,0.00200
-1.75366,0.48888,-1.44527,-1.35678,-0.33973,2.65381,0.00201
-1.75484,0.48927,-1.44464,-1.35731,-0.33983,2.65343,0.00201
-1.75603,0.48964,-1.44401,-1.35783,-0.33994,2.65305,0.00202
-1.75722,0.49001,-1.44340,-1.35834,-0.34004,2.65268,0.00202
-1.75841,0.49038,-1.44279,-1.35885,-0.34014,2.65231,0.00202
-1.75960,0.49074,-1.44220,-1.35934,-0.34023,2.65195,0.00203
-1.76079,0.49110,-1.44161,-1.35983,-0.34033,2.65160,0.00203
-1.76198,0.49145,-1.44104,-1.36031,-0.34042,2.65125,0.00203
-1.76317,0.49179,-1.44047,-1.36078,-0.34051,2.65090,0.00204
-1.76436,0.49213,-1.43992,-1.36125,-0.34060,2.65056,0.00204
-1.76555,0.49247,-1.43937,-1.36170,-0.34069,2.65022,0.00204
-1.76673,0.49280,-1.43884,-1.36215,-0.34077,2.64989,0.00204
-1.76792,0.49313,-1.43831,-1.36260,-0.34086,2.64956,0.00204
-1.76911,0.49345,-1.43779,-1.36303,-0.34094,2.64924,0.00205
-1.77030,0.49377,-1.43728,-1.36346,-0.34102,2.64892,0.00205
-1.77149,0.49408,-1.43678,-1.36388,-0.34110,2.64861,0.00205
-1.77268,0.49439,-1.43629,-1.36430,-0.34118,2.64830,0.00205
-1.77387,0.49469,-1.43580,-1.36470,-0.34126,2.64799,0.00205
-1.77506,0.49499,-1.43533,-1.36511,-0.34133,2.64769,0.00205
-1.77625,0.49529,-1.43486,-1.36550,-0.34140,2.64740,0.00205
-1.77743,0.49558,-1.43440,-1.36589,-0.34147,2.64710,0.00205
-1.77862,0.49586,-1.43395,-1.36627,-0.34155,2.64682,0.00205
-1.77981,0.49615,-1.43351,-1.36665,-0.34161,2.64653,0.00205
-1.78100,0.49643,-1.43307,-1.36702,-0.34168,2.64625,0.00205
-1.78219,0.49670,-1.43264,-1.36738,-0.34175,2.64598,0.00205
-1.78338,0.49680,-1.43249,-1.36751,-0.34178,2.64588,0.00205
-1.78457,0.49724,-1.43178,-1.36804,-0.34194,2.64544,0.00206
-1.78576,0.49767,-1.43109,-1.36857,-0.34211,2.64501,0.00207
-1.78695,0.49809,-1.43040,-1.36909,-0.34227,2.64459,0.00207
-1.78813,0.49851,-1.42973,-1.36960,-0.34242,2.64417,0.00208
-1.78932,0.49892,-1.42907,-1.37010,-0.34258,2.64376,0.00208
-1.79051,0.49933,-1.42843,-1.37059,-0.34273,2.64336,0.00209
-1.79170,0.49973,-1.42779,-1.37108,-0.34288,2.64296,0.00209
-1.79289,0.50013,-1.42716,-1.37155,-0.34302,2.64256,0.00209
-1.79408,0.50052,-1.42655,-1.37202,-0.34317,2.64217,0.00210
-1.79527,0.50090,-1.42595,-1.37248,-0.34331,2.64179,0.00210
-1.79646,0.50128,-1.42535,-1.37294,-0.34345,2.64141,0.00210
-1.79765,0.50166,-1.42477,-1.37338,-0.34358,2.64104,0.00211
-1.79883,0.50203,-1.42419,-1.37382,-0.34372,2.64067,0.00211
-1.80002,0.50239,-1.42363,-1.37426,-0.34385,2.64031,0.00211
-1.80121,0.50275,-1.42308,-1.37468,-0.34398,2.63995,0.00211
-1.80240,0.50310,-1.42253,-1.37510,-0.34410,2.63959,0.00212
-1.80359,0.50345,-1.42200,-1.37551,-0.34422,2.63925,0.00212
-1.80478,0.50380,-1.42147,-1.37592,-0.34435,2.63890,0.00212
-1.80597,0.50413,-1.42095,-1.37631,-0.34447,2.63856,0.00212
-1.80716,0.50447,-1.42044,-1.37671,-0.34458,2.63823,0.00212
-1.80835,0.50480,-1.41994,-1.37709,-0.34470,2.63790,0.00212
-1.80954,0.50512,-1.41945,-1.37747,-0.34481,2.63757,0.00212
-1.81072,0.50544,-1.41897,-1.37784,-0.34492,2.63725,0.00212
-1.81191,0.50576,-1.41850,-1.37821,-0.34503,2.63694,0.00212
-1.81310,0.50607,-1.41803,-1.37857,-0.34513,2.63663,0.00213
-1.81429,0.50638,-1.41757,-1.37893,-0.34524,2.63632,0.00213
-1.81548,0.50668,-1.41712,-1.37928,-0.34534,2.63602,0.00213
-1.81667,0.50697,-1.41668,-1.37962,-0.34544,2.63572,0.00213
-1.81786,0.50727,-1.41624,-1.37996,-0.34554,2.63542,0.00212
-1.81905,0.50756,-1.41581,-1.38029,-0.34564,2.63513,0.00212
-1.82024,0.50783,-1.41541,-1.38061,-0.34573,2.63486,0.00212
-1.82142,0.50829,-1.41470,-1.38113,-0.34591,2.63441,0.00213
-1.82261,0.50873,-1.41401,-1.38164,-0.34609,2.63396,0.00213
-1.82380,0.50918,-1.41332,-1.38215,-0.34627,2.63352,0.00214
-1.82499,0.50961,-1.41265,-1.38264,-0.34644,2.63309,0.00214
-1.82618,0.51004,-1.41200,-1.38313,-0.34661,2.63266,0.00215
-1.82737,0.51047,-1.41135,-1.38361,-0.34677,2.63224,0.00215
-1.82856,0.51089,-1.41071,-1.38408,-0.34693,2.63182,0.00215
-1.82975,0.51130,-1.41009,-1.38454,-0.34709,2.63141,0.00216
-1.83094,0.51171,-1.40947,-1.38500,-0.34725,2.63101,0.00216
-1.83212,0.51211,-1.40887,-1.38545,-0.34740,2.63061,0.00216
-1.83331,0.51250,-1.40828,-1.38589,-0.34756,2.63021,0.00216
-1.83450,0.51289,-1.40769,-1.38633,-0.34770,2.62982,0.00216
-1.83569,0.51328,-1.40712,-1.38675,-0.34785,2.62944,0.00217
-1.83688,0.51366,-1.40656,-1.38717,-0.34799,2.62906,0.00217
-1.83807,0.51403,-1.40600,-1.38759,-0.34813,2.62869,0.00217
-1.83926,0.51440,-1.40546,-1.38799,-0.34827,2.62832,0.00217
-1.84045,0.51476,-1.40492,-1.38839,-0.34841,2.62796,0.00217
-1.84164,0.51512,-1.40440,-1.38879,-0.34854,2.62760,0.00217
-1.84282,0.51547,-1.40388,-1.38918,-0.34867,2.62725,0.00217
-1.84401,0.51582,-1.40337,-1.38956,-0.34880,2.62690,0.00217
-1.84520,0.51617,-1.40287,-1.38993,-0.34893,2.62656,0.00217
-1.84639,0.51650,-1.40238,-1.39030,-0.34905,2.62622,0.00217
-1.84758,0.51684,-1.40190,-1.39066,-0.34917,2.62588,0.00217
-1.84877,0.51717,-1.40143,-1.39102,-0.34929,2.62556,0.00217
-1.84996,0.51749,-1.40096,-1.39137,-0.34941,2.62523,0.00217
-1.85115,0.51781,-1.40050,-1.39172,-0.34952,2.62491,0.00217
-1.85234,0.51813,-1.40005,-1.39206,-0.34963,2.62459,0.00217
-1.85353,0.51844,-1.39961,-1.39239,-0.34975,2.62428,0.00217
-1.85471,0.51874,-1.39917,-1.39272,-0.34985,2.62398,0.00217
-1.85590,0.51905,-1.39875,-1.39304,-0.34996,2.62367,0.00217
-1.85709,0.51934,-1.39833,-1.39336,-0.35006,2.62338,0.00217
-1.85828,0.51940,-1.39824,-1.39342,-0.35009,2.62332,0.00217
-1.85947,0.51998,-1.39737,-1.39403,-0.35035,2.62275,0.00217
-1.86066,0.52054,-1.39652,-1.39462,-0.35060,2.62219,0.00218
-1.86185,0.52110,-1.39569,-1.39520,-0.35085,2.62163,0.00219
-1.86304,0.52166,-1.39487,-1.39578,-0.35109,2.62109,0.00219
-1.86423,0.52220,-1.39406,-1.39634,-0.35133,2.62055,0.00220
-1.86541,0.52274,-1.39327,-1.39689,-0.35156,2.62001,0.00220
-1.86660,0.52327,-1.39249,-1.39744,-0.35179,2.61949,0.00221
-1.86779,0.52379,-1.39172,-1.39798,-0.35202,2.61897,0.00221
-1.86898,0.52431,-1.39097,-1.39850,-0.35224,2.61846,0.00222
-1.87017,0.52482,-1.39023,-1.39902,-0.35246,2.61795,0.00222
-1.87136,0.52532,-1.38950,-1.39953,-0.35268,2.61745,0.00223
-1.87255,0.52581,-1.38879,-1.40003,-0.35289,2.61696,0.00223
-1.87374,0.52630,-1.38809,-1.40052,-0.35310,2.61647,0.00223
-1.87493,0.52679,-1.38740,-1.40101,-0.35330,2.61599,0.00223
-1.87611,0.52726,-1.38672,-1.40149,-0.35350,2.61552,0.00224
-1.87730,0.52773,-1.38605,-1.40196,-0.35370,2.61505,0.00224
-1.87849,0.52819,-1.38540,-1.40242,-0.35389,2.61459,0.00224
-1.87968,0.52865,-1.38475,-1.40287,-0.35409,2.61414,0.00224
-1.88087,0.52910,-1.38412,-1.40332,-0.35427,2.61369,0.00224
-1.88206,0.52954,-1.38350,-1.40376,-0.35446,2.61325,0.00225
-1.88325,0.52998,-1.38288,-1.40419,-0.35464,2.61281,0.00225
-1.88444,0.53041,-1.38228,-1.40461,-0.35482,2.61238,0.00225
-1.88563,0.53084,-1.38169,-1.40503,-0.35499,2.61196,0.00225
-1.88681,0.53126,-1.38111,-1.40544,-0.35516,2.61154,0.00225
-1.88800,0.53168,-1.38054,-1.40585,-0.35533,2.61112,0.00225
-1.88919,0.53208,-1.37998,-1.40624,-0.35550,2.61072,0.00225
-1.89038,0.53249,-1.37943,-1.40663,-0.35566,2.61031,0.00225
-1.89157,0.53289,-1.37888,-1.40702,-0.35582,2.60992,0.00225
-1.89276,0.53328,-1.37835,-1.40740,-0.35597,2.60952,0.00225
-1.89395,0.53366,-1.37783,-1.40777,-0.35613,2.60914,0.00225
-1.89514,0.53405,-1.37731,-1.40814,-0.35628,2.60876,0.00225
-1.89633,0.53442,-1.37681,-1.40850,-0.35643,2.60838,0.00225
-1.89752,0.53479,-1.37631,-1.40885,-0.35657,2.60801,0.00224
-1.89870,0.53516,-1.37582,-1.40920,-0.35672,2.60765,0.00224
-1.89989,0.53552,-1.37534,-1.40954,-0.35686,2.60728,0.00224
-1.90108,0.53587,-1.37487,-1.40988,-0.35700,2.60693,0.00224
-1.90227,0.53622,-1.37440,-1.41021,-0.35713,2.60658,0.00224
-1.90346,0.53657,-1.37395,-1.41054,-0.35726,2.60623,0.00224
-1.90465,0.53691,-1.37350,-1.41086,-0.35739,2.60589,0.00224
-1.90584,0.53725,-1.37306,-1.41118,-0.35752,2.60555,0.00223
-1.90703,0.53758,-1.37262,-1.41149,-0.35765,2.60522,0.00223
-1.90822,0.53791,-1.37220,-1.41180,-0.35777,2.60489,0.00223
-1.90940,0.53823,-1.37178,-1.41210,-0.35789,2.60457,0.00223
-1.91059,0.53837,-1.37159,-1.41223,-0.35795,2.60443,0.00223
-1.91178,0.53880,-1.37101,-1.41263,-0.35814,2.60400,0.00223
-1.91297,0.53923,-1.37043,-1.41302,-0.35832,2.60357,0.00223
-1.91416,0.53966,-1.36986,-1.41341,-0.35851,2.60315,0.00223
-1.91535,0.54008,-1.36930,-1.41379,-0.35868,2.60273,0.00223
-1.91654,0.54049,-1.36875,-1.41417,-0.35886,2.60232,0.00223
-1.91773,0.54089,-1.36821,-1.41453,-0.35903,2.60192,0.00223
-1.91892,0.54130,-1.36768,-1.41490,-0.35920,2.60152,0.00223
-1.92010,0.54169,-1.36716,-1.41525,-0.35937,2.60112,0.00223
-1.92129,0.54208,-1.36665,-1.41561,-0.35953,2.60073,0.00223
-1.92248,0.54247,-1.36614,-1.41595,-0.35969,2.60035,0.00223
-1.92367,0.54285,-1.36565,-1.41629,-0.35985,2.59997,0.00223
-1.92486,0.54322,-1.36516,-1.41663,-0.36000,2.59959,0.00223
-1.92605,0.54359,-1.36468,-1.41695,-0.36016,2.59923,0.00223
-1.92724,0.54395,-1.36421,-1.41728,-0.36031,2.59886,0.00223
-1.92843,0.54431,-1.36375,-1.41760,-0.36045,2.59850,0.00223
-1.92962,0.54467,-1.36330,-1.41791,-0.36060,2.59815,0.00222
-1.93080,0.54501,-1.36285,-1.41822,-0.36074,2.59780,0.00222
-1.93199,0.54536,-1.36241,-1.41852,-0.36088,2.59746,0.00222
-1.93318,0.54570,-1.36198,-1.41882,-0.36102,2.59712,0.00222
-1.93437,0.54603,-1.36155,-1.41911,-0.36115,2.59678,0.00222
-1.93556,0.54636,-1.36114,-1.41940,-0.36128,2.59645,0.00222
-1.93675,0.54654,-1.36091,-1.41956,-0.36135,2.59627,0.00222
-1.93794,0.54701,-1.36029,-1.41997,-0.36157,2.59581,0.00222
-1.93913,0.54748,-1.35968,-1.42037,-0.36177,2.59534,0.00222
-1.94032,0.54793,-1.35907,-1.42077,-0.36198,2.59489,0.00222
-1.94151,0.54838,-1.35848,-1.42116,-0.36218,2.59444,0.00222
-1.94269,0.54883,-1.35790,-1.42155,-0.36237,2.59400,0.00222
-1.94388,0.54927,-1.35733,-1.42193,-0.36257,2.59356,0.00223
-1.94507,0.54970,-1.35677,-1.42230,-0.36276,2.59313,0.00223
-1.94626,0.55013,-1.35622,-1.42267,-0.36294,2.59270,0.00223
-1.94745,0.55055,-1.35568,-1.42303,-0.36313,2.59228,0.00223
-1.94864,0.55097,-1.35514,-1.42338,-0.36331,2.59187,0.00223
-1.94983,0.55138,-1.35462,-1.42373,-0.36348,2.59146,0.00223
-1.95102,0.55178,-1.35410,-1.42407,-0.36366,2.59106,0.00223
-1.95221,0.55218,-1.35360,-1.42441,-0.36383,2.59066,0.00223
-1.95339,0.55258,-1.35310,-1.42474,-0.36400,2.59027,0.00223
-1.95458,0.55296,-1.35261,-1.42507,-0.36416,2.58988,0.00223
-1.95577,0.55335,-1.35213,-1.42539,-0.36432,2.58950,0.00223
-1.95696,0.55373,-1.35166,-1.42571,-0.36448,2.58912,0.00222
-1.95815,0.55410,-1.35119,-1.42602,-0.36464,2.58875,0.00222
-1.95934,0.55447,-1.35073,-1.42632,-0.36479,2.58838,0.00222
-1.96053,0.55483,-1.35029,-1.42662,-0.36494,2.58802,0.00222
-1.96172,0.55519,-1.34984,-1.42692,-0.36509,2.58766,0.00222
-1.96291,0.55554,-1.34941,-1.42721,-0.36524,2.58731,0.00222
-1.96409,0.55589,-1.34898,-1.42750,-0.36538,2.58696,0.00222
-1.96528,0.55623,-1.34856,-1.42778,-0.36552,2.58662,0.00222
-1.96647,0.55657,-1.34815,-1.42806,-0.36566,2.58628,0.00221
-1.96766,0.55663,-1.34808,-1.42811,-0.36569,2.58622,0.00221
-1.96885,0.55721,-1.34731,-1.42858,-0.36597,2.58564,0.00222
-1.97004,0.55779,-1.34657,-1.42905,-0.36625,2.58507,0.00222
-1.97123,0.55836,-1.34583,-1.42951,-0.36653,2.58450,0.00223
-1.97242,0.55892,-1.34511,-1.42996,-0.36680,2.58394,0.00223
-1.97361,0.55948,-1.34439,-1.43040,-0.36706,2.58339,0.00223
-1.97479,0.56003,-1.34370,-1.43084,-0.36732,2.58285,0.00224
-1.97598,0.56057,-1.34301,-1.43127,-0.36758,2.58231,0.00224
-1.97717,0.56110,-1.34233,-1.43169,-0.36783,2.58178,0.00224
-1.97836,0.56163,-1.34167,-1.43211,-0.36808,2.58126,0.00225
-1.97955,0.56215,-1.34102,-1.43252,-0.36832,2.58074,0.00225
-1.98074,0.56266,-1.34038,-1.43292,-0.36856,2.58023,0.00225
-1.98193,0.56317,-1.33975,-1.43331,-0.36880,2.57973,0.00225
-1.98312,0.56367,-1.33913,-1.43370,-0.36903,2.57923,0.00225
-1.98431,0.56416,-1.33852,-1.43408,-0.36926,2.57874,0.00225
-1.98550,0.56465,-1.33792,-1.43446,-0.36948,2.57825,0.00226
-1.98668,0.56513,-1.33733,-1.43483,-0.36970,2.57778,0.00226
-1.98787,0.56560,-1.33675,-1.43519,-0.36992,2.57731,0.00226
-1.98906,0.56607,-1.33618,-1.43555,-0.37013,2.57684,0.00226
-1.99025,0.56653,-1.33562,-1.43590,-0.37034,2.57638,0.00226
-1.99144,0.56699,-1.33508,-1.43625,-0.37054,2.57593,0.00226
-1.99263,0.56744,-1.33454,-1.43659,-0.37074,2.57548,0.00226
-1.99382,0.56788,-1.33400,-1.43692,-0.37094,2.57504,0.00226
-1.99501,0.56832,-1.33348,-1.43725,-0.37114,2.57460,0.00226
-1.99620,0.56875,-1.33297,-1.43758,-0.37133,2.57417,0.00226
-1.99738,0.56917,-1.33247,-1.43790,-0.37152,2.57375,0.00225
-1.99857,0.56959,-1.33197,-1.43821,-0.37170,2.57333,0.00225
-1.99976,0.57001,-1.33148,-1.43852,-0.37188,2.57292,0.00225
-2.00095,0.57042,-1.33100,-1.43882,-0.37206,2.57251,0.00225
-2.00214,0.57082,-1.33053,-1.43912,-0.37224,2.57211,0.00225
-2.00333,0.57122,-1.33007,-1.43942,-0.37241,2.57171,0.00225
-2.00452,0.57161,-1.32962,-1.43971,-0.37258,2.57132,0.00225
-2.00571,0.57200,-1.32917,-1.43999,-0.37274,2.57093,0.00225
-2.00690,0.57238,-1.32873,-1.44027,-0.37291,2.57055,0.00224
-2.00808,0.57275,-1.32830,-1.44055,-0.37307,2.57017,0.00224
-2.00927,0.57313,-1.32787,-1.44082,-0.37322,2.56980,0.00224
-2.01046,0.57349,-1.32745,-1.44109,-0.37338,2.56944,0.00224
-2.01165,0.57385,-1.32704,-1.44135,-0.37353,2.56907,0.00224
-2.01284,0.57405,-1.32682,-1.44149,-0.37362,2.56888,0.00224
-2.01403,0.57458,-1.32619,-1.44185,-0.37388,2.56835,0.00224
-2.01522,0.57510,-1.32557,-1.44221,-0.37414,2.56784,0.00224
-2.01641,0.57561,-1.32496,-1.44256,-0.37439,2.56733,0.00224
-2.01760,0.57612,-1.32437,-1.44291,-0.37464,2.56682,0.00224
-2.01878,0.57662,-1.32378,-1.44325,-0.37489,2.56633,0.00224
-2.01997,0.57711,-1.32321,-1.44359,-0.37513,2.56584,0.00225
-2.02116,0.57760,-1.32264,-1.44392,-0.37537,2.56535,0.00225
-2.02235,0.57808,-1.32208,-1.44424,-0.37560,2.56488,0.00225
-2.02354,0.57855,-1.32154,-1.44456,-0.37583,2.56440,0.00225
-2.02473,0.57902,-1.32100,-1.44488,-0.37606,2.56394,0.00225
-2.02592,0.57948,-1.32047,-1.44519,-0.37628,2.56348,0.00225
-2.02711,0.57994,-1.31995,-1.44549,-0.37649,2.56302,0.00225
-2.02830,0.58039,-1.31944,-1.44579,-0.37671,2.56258,0.00225
-2.02949,0.58083,-1.31893,-1.44609,-0.37692,2.56213,0.00225
-2.03067,0.58127,-1.31844,-1.44637,-0.37713,2.56170,0.00225
-2.03186,0.58170,-1.31796,-1.44666,-0.37733,2.56127,0.00225
-2.03305,0.58212,-1.31748,-1.44694,-0.37753,2.56084,0.00225
-2.03424,0.58255,-1.31701,-1.44722,-0.37772,2.56042,0.00225
-2.03543,0.58296,-1.31655,-1.44749,-0.37792,2.56001,0.00224
-2.03662,0.58337,-1.31609,-1.44775,-0.37811,2.55960,0.00224
-2.03781,0.58377,-1.31565,-1.44802,-0.37829,2.55920,0.00224
-2.03900,0.58417,-1.31521,-1.44828,-0.37848,2.55880,0.00224
-2.04019,0.58456,-1.31478,-1.44853,-0.37866,2.55841,0.00224
-2.04137,0.58495,-1.31436,-1.44878,-0.37883,2.55802,0.00224
-2.04256,0.58533,-1.31394,-1.44903,-0.37901,2.55764,0.00224
-2.04375,0.58571,-1.31353,-1.44927,-0.37918,2.55726,0.00223
-2.04494,0.58608,-1.31313,-1.44951,-0.37934,2.55689,0.00223
-2.04613,0.58618,-1.31302,-1.44957,-0.37939,2.55680,0.00223
-2.04732,0.58673,-1.31238,-1.44995,-0.37966,2.55624,0.00223
-2.04851,0.58729,-1.31174,-1.45031,-0.37992,2.55570,0.00224
-2.04970,0.58783,-1.31112,-1.45068,-0.38019,2.55516,0.00224
-2.05089,0.58837,-1.31051,-1.45103,-0.38044,2.55462,0.00224
-2.05207,0.58890,-1.30990,-1.45138,-0.38069,2.55410,0.00224
-2.05326,0.58942,-1.30931,-1.45173,-0.38094,2.55358,0.00224
-2.05445,0.58993,-1.30873,-1.45207,-0.38119,2.55307,0.00224
-2.05564,0.59044,-1.30816,-1.45240,-0.38143,2.55256,0.00224
-2.05683,0.59095,-1.30759,-1.45273,-0.38166,2.55206,0.00224
-2.05802,0.59144,-1.30704,-1.45306,-0.38189,2.55157,0.00224
-2.05921,0.59193,-1.30650,-1.45337,-0.38212,2.55108,0.00224
-2.06040,0.59241,-1.30596,-1.45369,-0.38235,2.55060,0.00224
-2.06159,0.59289,-1.30544,-1.45399,-0.38257,2.55012,0.00224
-2.06277,0.59336,-1.30492,-1.45430,-0.38278,2.54965,0.00224
-2.06396,0.59383,-1.30441,-1.45459,-0.38299,2.54919,0.00224
-2.06515,0.59429,-1.30391,-1.45489,-0.38320,2.54873,0.00224
-2.06634,0.59474,-1.30342,-1.45518,-0.38341,2.54828,0.00224
-2.06753,0.59518,-1.30294,-1.45546,-0.38361,2.54784,0.00224
-2.06872,0.59562,-1.30246,-1.45574,-0.38381,2.54740,0.00224
-2.06991,0.59606,-1.30200,-1.45601,-0.38401,2.54697,0.00224
-2.07110,0.59649,-1.30154,-1.45628,-0.38420,2.54654,0.00224
-2.07229,0.59691,-1.30109,-1.45655,-0.38439,2.54611,0.00224
-2.07348,0.59733,-1.30064,-1.45681,-0.38457,2.54570,0.00224
-2.07466,0.59774,-1.30021,-1.45707,-0.38475,2.54529,0.00223
-2.07585,0.59815,-1.29978,-1.45732,-0.38493,2.54488,0.00223
-2.07704,0.59855,-1.29936,-1.45757,-0.38511,2.54448,0.00223
-2.07823,0.59895,-1.29894,-1.45782,-0.38528,2.54408,0.00223
-2.07942,0.59934,-1.29854,-1.45806,-0.38545,2.54369,0.00223
-2.08061,0.59975,-1.29810,-1.45831,-0.38564,2.54328,0.00223
-2.08180,0.60040,-1.29738,-1.45869,-0.38598,2.54263,0.00223
-2.08299,0.60104,-1.29667,-1.45906,-0.38632,2.54200,0.00223
-2.08418,0.60168,-1.29597,-1.45943,-0.38665,2.54137,0.00224
-2.08536,0.60231,-1.29528,-1.45979,-0.38697,2.54075,0.00224
-2.08655,0.60293,-1.29460,-1.46014,-0.38730,2.54013,0.00224
-2.08774,0.60354,-1.29394,-1.46049,-0.38761,2.53953,0.00225
-2.08893,0.60414,-1.29329,-1.46083,-0.38792,2.53893,0.00225
-2.09012,0.60474,-1.29265,-1.46117,-0.38823,2.53834,0.00225
-2.09131,0.60532,-1.29201,-1.46150,-0.38853,2.53775,0.00225
-2.09250,0.60591,-1.29139,-1.46183,-0.38882,2.53718,0.00225
-2.09369,0.60648,-1.29078,-1.46215,-0.38911,2.53661,0.00226
-2.09488,0.60705,-1.29018,-1.46246,-0.38940,2.53604,0.00226
-2.09606,0.60760,-1.28960,-1.46277,-0.38968,2.53549,0.00226
-2.09725,0.60816,-1.28902,-1.46308,-0.38995,2.53494,0.00226
-2.09844,0.60870,-1.28845,-1.46338,-0.39022,2.53440,0.00226
-2.09963,0.60924,-1.28789,-1.46367,-0.39049,2.53386,0.00226
-2.10082,0.60977,-1.28734,-1.46396,-0.39075,2.53334,0.00226
-2.10201,0.61029,-1.28679,-1.46425,-0.39101,2.53281,0.00226
-2.10320,0.61081,-1.28626,-1.46453,-0.39127,2.53230,0.00226
-2.10439,0.61132,-1.28574,-1.46480,-0.39151,2.53179,0.00226
-2.10558,0.61183,-1.28522,-1.46508,-0.39176,2.53129,0.00226
-2.10676,0.61233,-1.28472,-1.46534,-0.39200,2.53079,0.00226
-2.10795,0.61282,-1.28422,-1.46561,-0.39224,2.53030,0.00226
-2.10914,0.61330,-1.28373,-1.46587,-0.39247,2.52982,0.00226
-2.11033,0.61378,-1.28325,-1.46612,-0.39270,2.52934,0.00226
-2.11152,0.61425,-1.28278,-1.46637,-0.39292,2.52887,0.00226
-2.11271,0.61472,-1.28231,-1.46662,-0.39315,2.52840,0.00225
-2.11390,0.61518,-1.28186,-1.46686,-0.39336,2.52794,0.00225
-2.11509,0.61564,-1.28141,-1.46710,-0.39358,2.52749,0.00225
-2.11628,0.61608,-1.28097,-1.46734,-0.39379,2.52704,0.00225
-2.11747,0.61653,-1.28053,-1.46757,-0.39399,2.52660,0.00225
-2.11865,0.61696,-1.28011,-1.46780,-0.39420,2.52616,0.00225
-2.11984,0.61740,-1.27969,-1.46802,-0.39440,2.52573,0.00225
-2.12103,0.61782,-1.27927,-1.46824,-0.39459,2.52531,0.00224
-2.12222,0.61824,-1.27887,-1.46846,-0.39479,2.52489,0.00224
-2.12341,0.61866,-1.27847,-1.46867,-0.39498,2.52447,0.00224
-2.12460,0.61907,-1.27808,-1.46888,-0.39516,2.52406,0.00224
-2.12579,0.61917,-1.27798,-1.46893,-0.39521,2.52397,0.00224
-2.12698,0.61975,-1.27738,-1.46925,-0.39549,2.52339,0.00224
-2.12817,0.62032,-1.27679,-1.46956,-0.39577,2.52282,0.00224
-2.12935,0.62089,-1.27621,-1.46986,-0.39605,2.52225,0.00224
-2.13054,0.62145,-1.27565,-1.47016,-0.39632,2.52170,0.00224
-2.13173,0.62200,-1.27509,-1.47046,-0.39658,2.52115,0.00224
-2.13292,0.62255,-1.27454,-1.47075,-0.39684,2.52060,0.00224
-2.13411,0.62309,-1.27400,-1.47103,-0.39710,2.52007,0.00224
-2.13530,0.62362,-1.27347,-1.47131,-0.39735,2.51954,0.00224
-2.13649,0.62414,-1.27295,-1.47159,-0.39760,2.51902,0.00224
-2.13768,0.62466,-1.27244,-1.47186,-0.39784,2.51850,0.00224
-2.13887,0.62518,-1.27193,-1.47213,-0.39808,2.51799,0.00224
-2.14005,0.62568,-1.27144,-1.47239,-0.39832,2.51749,0.00224
-2.14124,0.62618,-1.27095,-1.47265,-0.39855,2.51699,0.00224
-2.14243,0.62667,-1.27047,-1.47290,-0.39878,2.51650,0.00224
-2.14362,0.62716,-1.27000,-1.47315,-0.39900,2.51601,0.00224
-2.14481,0.62764,-1.26953,-1.47340,-0.39922,2.51553,0.00224
-2.14600,0.62812,-1.26908,-1.47364,-0.39944,2.51506,0.00224
-2.14719,0.62858,-1.26863,-1.47388,-0.39965,2.51459,0.00223
-2.14838,0.62905,-1.26819,-1.47412,-0.39986,2.51413,0.00223
-2.14957,0.62950,-1.26776,-1.47435,-0.40007,2.51368,0.00223
-2.15075,0.62995,-1.26733,-1.47458,-0.40027,2.51323,0.00223
-2.15194,0.63040,-1.26691,-1.47480,-0.40047,2.51278,0.00223
-2.15313,0.63084,-1.26650,-1.47502,-0.40067,2.51234,0.00223
-2.15432,0.63127,-1.26609,-1.47524,-0.40086,2.51191,0.00222
-2.15551,0.63170,-1.26569,-1.47545,-0.40105,2.51148,0.00222
-2.15670,0.63212,-1.26530,-1.47566,-0.40123,2.51106,0.00222
-2.15789,0.63222,-1.26521,-1.47571,-0.40128,2.51096,0.00222
-2.15908,0.63279,-1.26465,-1.47600,-0.40155,2.51039,0.00222
-2.16027,0.63335,-1.26410,-1.47629,-0.40182,2.50984,0.00222
-2.16146,0.63391,-1.26356,-1.47657,-0.40208,2.50928,0.00222
-2.16264,0.63446,-1.26302,-1.47684,-0.40234,2.50874,0.00222
-2.16383,0.63500,-1.26250,-1.47711,-0.40259,2.50820,0.00222
-2.16502,0.63553,-1.26199,-1.47738,-0.40284,2.50767,0.00222
-2.16621,0.63606,-1.26148,-1.47764,-0.40309,2.50714,0.00222
-2.16740,0.63658,-1.26098,-1.47790,-0.40333,2.50662,0.00222
-2.16859,0.63710,-1.26049,-1.47815,-0.40357,2.50611,0.00222
-2.16978,0.63761,-1.26001,-1.47840,-0.40380,2.50560,0.00222
-2.17097,0.63811,-1.25954,-1.47865,-0.40403,2.50510,0.00222
-2.17216,0.63860,-1.25908,-1.47889,-0.40426,2.50461,0.00222
-2.17334,0.63909,-1.25862,-1.47913,-0.40448,2.50412,0.00222
-2.17453,0.63958,-1.25817,-1.47937,-0.40470,2.50364,0.00222
-2.17572,0.64005,-1.25773,-1.47960,-0.40491,2.50316,0.00222
-2.17691,0.64052,-1.25729,-1.47983,-0.40513,2.50269,0.00222
-2.17810,0.64099,-1.25686,-1.48005,-0.40533,2.50223,0.00221
-2.17929,0.64145,-1.25644,-1.48027,-0.40554,2.50177,0.00221
-2.18048,0.64190,-1.25603,-1.48049,-0.40574,2.50132,0.00221
-2.18167,0.64235,-1.25562,-1.48070,-0.40594,2.50087,0.00221
-2.18286,0.64279,-1.25522,-1.48091,-0.40613,2.50043,0.00221
-2.18404,0.64323,-1.25483,-1.48112,-0.40632,2.49999,0.00221
-2.18523,0.64360,-1.25449,-1.48129,-0.40648,2.49963,0.00221
-2.18642,0.64423,-1.25388,-1.48160,-0.40678,2.49900,0.00221
-2.18761,0.64485,-1.25328,-1.48191,-0.40707,2.49838,0.00221
-2.18880,0.64547,-1.25269,-1.48222,-0.40736,2.49777,0.00221
-2.18999,0.64607,-1.25211,-1.48251,-0.40765,2.49717,0.00221
-2.19118,0.64668,-1.25154,-1.48281,-0.40793,2.49657,0.00221
-2.19237,0.64727,-1.25098,-1.48310,-0.40820,2.49598,0.00221
-2.19356,0.64786,-1.25042,-1.48338,-0.40847,2.49540,0.00221
-2.19474,0.64843,-1.24988,-1.48366,-0.40874,2.49482,0.00221
-2.19593,0.64901,-1.24935,-1.48394,-0.40900,2.49425,0.00221
-2.19712,0.64957,-1.24882,-1.48421,-0.40926,2.49369,0.00221
-2.19831,0.65013,-1.24830,-1.48447,-0.40951,2.49314,0.00221
-2.19950,0.65068,-1.24780,-1.48473,-0.40976,2.49259,0.00221
-2.20069,0.65123,-1.24730,-1.48499,-0.41000,2.49205,0.00221
-2.20188,0.65176,-1.24680,-1.48525,-0.41024,2.49151,0.00221
-2.20307,0.65229,-1.24632,-1.48550,-0.41048,2.49098,0.00221
-2.20426,0.65282,-1.24585,-1.48574,-0.41071,2.49046,0.00221
-2.20545,0.65334,-1.24538,-1.48598,-0.41094,2.48994,0.00221
-2.20663,0.65385,-1.24492,-1.48622,-0.41117,2.48943,0.00221
-2.20782,0.65435,-1.24447,-1.48646,-0.41139,2.48893,0.00221
-2.20901,0.65485,-1.24402,-1.48669,-0.41160,2.48843,0.00221
-2.21020,0.65535,-1.24358,-1.48691,-0.41182,2.48794,0.00221
-2.21139,0.65583,-1.24315,-1.48714,-0.41203,2.48746,0.00221
-2.21258,0.65631,-1.24273,-1.48736,-0.41224,2.48698,0.00220
-2.21377,0.65679,-1.24231,-1.48757,-0.41244,2.48650,0.00220
-2.21496,0.65726,-1.24191,-1.48779,-0.41264,2.48603,0.00220
-2.21615,0.65772,-1.24150,-1.48800,-0.41284,2.48557,0.00220
-2.21733,0.65818,-1.24111,-1.48820,-0.41303,2.48512,0.00220
-2.21852,0.65863,-1.24072,-1.48841,-0.41322,2.48466,0.00220
-2.21971,0.65892,-1.24046,-1.48854,-0.41335,2.48437,0.00220
-2.22090,0.65961,-1.23982,-1.48887,-0.41366,2.48369,0.00220
-2.22209,0.66028,-1.23918,-1.48919,-0.41398,2.48302,0.00220
-2.22328,0.66095,-1.23856,-1.48951,-0.41428,2.48235,0.00220
-2.22447,0.66162,-1.23795,-1.48982,-0.41458,2.48170,0.00220
-2.22566,0.66227,-1.23735,-1.49012,-0.41488,2.48105,0.00220
-2.22685,0.66292,-1.23675,-1.49042,-0.41517,2.48041,0.00221
-2.22803,0.66356,-1.23617,-1.49072,-0.41546,2.47977,0.00221
-2.22922,0.66419,-1.23560,-1.49101,-0.41574,2.47915,0.00221
-2.23041,0.66481,-1.23504,-1.49130,-0.41602,2.47853,0.00221
-2.23160,0.66543,-1.23448,-1.49158,-0.41630,2.47791,0.00221
-2.23279,0.66603,-1.23394,-1.49186,-0.41657,2.47731,0.00221
-2.23398,0.66664,-1.23340,-1.49213,-0.41683,2.47671,0.00221
-2.23517,0.66723,-1.23287,-1.49240,-0.41709,2.47612,0.00221
-2.23636,0.66782,-1.23236,-1.49267,-0.41735,2.47554,0.00221
-2.23755,0.66840,-1.23185,-1.49293,-0.41760,2.47496,0.00221
-2.23873,0.66897,-1.23134,-1.49319,-0.41785,2.47439,0.00221
-2.23992,0.66954,-1.23085,-1.49344,-0.41809,2.47383,0.00221
-2.24111,0.67009,-1.23037,-1.49369,-0.41833,2.47327,0.00221
-2.24230,0.67065,-1.22989,-1.49393,-0.41857,2.47272,0.00221
-2.24349,0.67119,-1.22942,-1.49417,-0.41880,2.47218,0.00221
-2.24468,0.67173,-1.22896,-1.49441,-0.41903,2.47164,0.00221
-2.24587,0.67226,-1.22850,-1.49464,-0.41925,2.47111,0.00220
-2.24706,0.67279,-1.22806,-1.49487,-0.41947,2.47058,0.00220
-2.24825,0.67331,-1.22762,-1.49510,-0.41969,2.47006,0.00220
-2.24944,0.67382,-1.22718,-1.49532,-0.41990,2.46955,0.00220
-2.25062,0.67433,-1.22676,-1.49554,-0.42011,2.46905,0.00220
-2.25181,0.67483,-1.22634,-1.49575,-0.42032,2.46855,0.00220
-2.25300,0.67532,-1.22593,-1.49597,-0.42052,2.46805,0.00220
-2.25419,0.67581,-1.22553,-1.49617,-0.42072,2.46756,0.00220
-2.25538,0.67630,-1.22513,-1.49638,-0.42092,2.46708,0.00219
-2.25657,0.67677,-1.22474,-1.49658,-0.42111,2.46661,0.00219
-2.25776,0.67724,-1.22435,-1.49678,-0.42130,2.46614,0.00219
-2.25895,0.67750,-1.22414,-1.49689,-0.42141,2.46588,0.00219
-2.26014,0.67814,-1.22357,-1.49719,-0.42168,2.46524,0.00219
-2.26132,0.67878,-1.22300,-1.49749,-0.42195,2.46460,0.00219
-2.26251,0.67942,-1.22245,-1.49779,-0.42221,2.46398,0.00219
-2.26370,0.68004,-1.22190,-1.49808,-0.42247,2.46335,0.00219
-2.26489,0.68066,-1.22136,-1.49836,-0.42272,2.46274,0.00219
-2.26608,0.68127,-1.22084,-1.49864,-0.42298,2.46213,0.00219
-2.26727,0.68187,-1.22032,-1.49892,-0.42322,2.46153,0.00219
-2.26846,0.68247,-1.21981,-1.49919,-0.42347,2.46094,0.00219
-2.26965,0.68306,-1.21930,-1.49945,-0.42370,2.46035,0.00219
-2.27084,0.68364,-1.21881,-1.49972,-0.42394,2.45978,0.00219
-2.27202,0.68421,-1.21832,-1.49998,-0.42417,2.45920,0.00219
-2.27321,0.68478,-1.21784,-1.50023,-0.42440,2.45864,0.00219
-2.27440,0.68534,-1.21737,-1.50048,-0.42462,2.45808,0.00219
-2.27559,0.68590,-1.21691,-1.50073,-0.42484,2.45753,0.00219
-2.27678,0.68645,-1.21645,-1.50097,-0.42506,2.45698,0.00219
-2.27797,0.68699,-1.21600,-1.50121,-0.42527,2.45644,0.00219
-2.27916,0.68752,-1.21556,-1.50144,-0.42548,2.45591,0.00219
-2.28035,0.68805,-1.21513,-1.50167,-0.42569,2.45538,0.00219
-2.28154,0.68857,-1.21470,-1.50190,-0.42589,2.45486,0.00218
-2.28273,0.68909,-1.21428,-1.50213,-0.42609,2.45434,0.00218
-2.28391,0.68960,-1.21387,-1.50235,-0.42629,2.45383,0.00218
-2.28510,0.69010,-1.21346,-1.50256,-0.42648,2.45333,0.00218
-2.28629,0.69060,-1.21306,-1.50278,-0.42667,2.45283,0.00218
-2.28748,0.69109,-1.21267,-1.50299,-0.42686,2.45234,0.00218
-2.28867,0.69158,-1.21228,-1.50320,-0.42704,2.45186,0.00218
-2.28986,0.69198,-1.21196,-1.50337,-0.42720,2.45145,0.00218
-2.29105,0.69265,-1.21138,-1.50368,-0.42746,2.45079,0.00218
-2.29224,0.69331,-1.21082,-1.50398,-0.42773,2.45014,0.00218
-2.29343,0.69396,-1.21027,-1.50428,-0.42799,2.44949,0.00218
-2.29461,0.69460,-1.20972,-1.50457,-0.42824,2.44885,0.00218
-2.29580,0.69524,-1.20919,-1.50486,-0.42849,2.44822,0.00218
-2.29699,0.69586,-1.20866,-1.50514,-0.42874,2.44759,0.00218
-2.29818,0.69648,-1.20814,-1.50542,-0.42898,2.44698,0.00218
-2.29937,0.69710,-1.20763,-1.50570,-0.42922,2.44637,0.00218
-2.30056,0.69771,-1.20712,-1.50597,-0.42945,2.44576,0.00218
-2.30175,0.69830,-1.20663,-1.50623,-0.42969,2.44517,0.00218
-2.30294,0.69890,-1.20614,-1.50649,-0.42991,2.44458,0.00218
-2.30413,0.69948,-1.20566,-1.50675,-0.43014,2.44399,0.00218
-2.30531,0.70006,-1.20519,-1.50701,-0.43036,2.44342,0.00218
-2.30650,0.70063,-1.20473,-1.50726,-0.43057,2.44285,0.00218
-2.30769,0.70120,-1.20427,-1.50750,-0.43079,2.44228,0.00218
-2.30888,0.70176,-1.20383,-1.50774,-0.43100,2.44173,0.00218
-2.31007,0.70231,-1.20339,-1.50798,-0.43121,2.44118,0.00218
-2.31126,0.70285,-1.20295,-1.50822,-0.43141,2.44063,0.00217
-2.31245,0.70339,-1.20252,-1.50845,-0.43161,2.44009,0.00217
-2.31364,0.70393,-1.20210,-1.50867,-0.43181,2.43956,0.00217
-2.31483,0.70445,-1.20169,-1.50890,-0.43200,2.43904,0.00217
-2.31601,0.70497,-1.20128,-1.50912,-0.43219,2.43852,0.00217
-2.31720,0.70549,-1.20088,-1.50934,-0.43238,2.43800,0.00217
-2.31839,0.70600,-1.20049,-1.50955,-0.43256,2.43750,0.00217
-2.31958,0.70650,-1.20010,-1.50976,-0.43274,2.43699,0.00217
-2.32077,0.70699,-1.19972,-1.50997,-0.43292,2.43650,0.00217
-2.32196,0.70711,-1.19962,-1.51002,-0.43297,2.43638,0.00217
-2.32315,0.70782,-1.19903,-1.51033,-0.43324,2.43568,0.00217
-2.32434,0.70851,-1.19845,-1.51064,-0.43351,2.43499,0.00217
-2.32553,0.70920,-1.19788,-1.51095,-0.43378,2.43431,0.00217
-2.32672,0.70988,-1.19732,-1.51125,-0.43404,2.43363,0.00217
-2.32790,0.71055,-1.19677,-1.51154,-0.43430,2.43297,0.00217
-2.32909,0.71121,-1.19623,-1.51184,-0.43455,2.43231,0.00217
-2.33028,0.71187,-1.19570,-1.51212,-0.43480,2.43165,0.00217
-2.33147,0.71252,-1.19517,-1.51240,-0.43505,2.43101,0.00217
-2.33266,0.71316,-1.19466,-1.51268,-0.43529,2.43037,0.00217
-2.33385,0.71380,-1.19415,-1.51295,-0.43553,2.42974,0.00217
-2.33504,0.71442,-1.19365,-1.51322,-0.43576,2.42911,0.00217
-2.33623,0.71504,-1.19316,-1.51349,-0.43599,2.42850,0.00217
-2.33742,0.71566,-1.19267,-1.51375,-0.43622,2.42789,0.00217
-2.33860,0.71626,-1.19220,-1.51400,-0.43644,2.42728,0.00217
-2.33979,0.71686,-1.19173,-1.51426,-0.43666,2.42669,0.00217
-2.34098,0.71745,-1.19127,-1.51450,-0.43688,2.42610,0.00217
-2.34217,0.71804,-1.19081,-1.51475,-0.43709,2.42551,0.00217
-2.34336,0.71862,-1.19037,-1.51499,-0.43730,2.42494,0.00217
-2.34455,0.71919,-1.18993,-1.51523,-0.43751,2.42437,0.00217
-2.34574,0.71975,-1.18949,-1.51546,-0.43771,2.42380,0.00217
-2.34693,0.72031,-1.18907,-1.51569,-0.43791,2.42325,0.00217
-2.34812,0.72086,-1.18865,-1.51591,-0.43811,2.42269,0.00217
-2.34930,0.72141,-1.18824,-1.51614,-0.43830,2.42215,0.00217
-2.35049,0.72195,-1.18783,-1.51636,-0.43849,2.42161,0.00217
-2.35168,0.72248,-1.18743,-1.51657,-0.43868,2.42108,0.00217
-2.35287,0.72301,-1.18704,-1.51678,-0.43886,2.42055,0.00217
-2.35406,0.72353,-1.18665,-1.51699,-0.43904,2.42003,0.00216
-2.35525,0.72405,-1.18627,-1.51720,-0.43922,2.41952,0.00216
-2.35644,0.72443,-1.18598,-1.51735,-0.43936,2.41914,0.00216
-2.35763,0.72517,-1.18538,-1.51767,-0.43964,2.41840,0.00216
-2.35882,0.72591,-1.18479,-1.51798,-0.43992,2.41767,0.00217
-2.36000,0.72663,-1.18421,-1.51829,-0.44020,2.41695,0.00217
-2.36119,0.72735,-1.18364,-1.51860,-0.44047,2.41623,0.00217
-2.36238,0.72806,-1.18307,-1.51889,-0.44074,2.41552,0.00217
-2.36357,0.72877,-1.18252,-1.51919,-0.44100,2.41483,0.00217
-2.36476,0.72946,-1.18197,-1.51948,-0.44126,2.41413,0.00217
-2.36595,0.73015,-1.18144,-1.51976,-0.44151,2.41345,0.00217
-2.36714,0.73083,-1.18091,-1.52004,-0.44176,2.41277,0.00217
-2.36833,0.73150,-1.18039,-1.52032,-0.44201,2.41210,0.00217
-2.36952,0.73217,-1.17988,-1.52059,-0.44225,2.41144,0.00217
-2.37071,0.73283,-1.17937,-1.52085,-0.44249,2.41079,0.00217
-2.37189,0.73348,-1.17888,-1.52112,-0.44273,2.41014,0.00217
-2.37308,0.73412,-1.17839,-1.52137,-0.44296,2.40950,0.00217
-2.37427,0.73476,-1.17791,-1.52163,-0.44319,2.40887,0.00217
-2.37546,0.73539,-1.17744,-1.52188,-0.44341,2.40824,0.00217
-2.37665,0.73601,-1.17697,-1.52213,-0.44363,2.40762,0.00217
-2.37784,0.73662,-1.17652,-1.52237,-0.44385,2.40701,0.00217
-2.37903,0.73723,-1.17607,-1.52261,-0.44407,2.40640,0.00217
-2.38022,0.73783,-1.17562,-1.52284,-0.44428,2.40580,0.00217
-2.38141,0.73843,-1.17519,-1.52307,-0.44449,2.40521,0.00217
-2.38259,0.73901,-1.17476,-1.52330,-0.44469,2.40462,0.00217
-2.38378,0.73960,-1.17434,-1.52353,-0.44489,2.40404,0.00217
-2.38497,0.74017,-1.17392,-1.52375,-0.44509,2.40347,0.00217
-2.38616,0.74074,-1.17351,-1.52397,-0.44529,2.40290,0.00217
-2.38735,0.74130,-1.17311,-1.52418,-0.44548,2.40234,0.00217
-2.38854,0.74186,-1.17271,-1.52439,-0.44567,2.40179,0.00217
-2.38973,0.74241,-1.17232,-1.52460,-0.44585,2.40124,0.00217
-2.39092,0.74295,-1.17194,-1.52480,-0.44604,2.40070,0.00217
-2.39211,0.74349,-1.17156,-1.52501,-0.44622,2.40016,0.00217
-2.39329,0.74402,-1.17118,-1.52520,-0.44640,2.39963,0.00217
-2.39448,0.74419,-1.17106,-1.52527,-0.44646,2.39945,0.00217
-2.39567,0.74491,-1.17052,-1.52555,-0.44672,2.39874,0.00217
-2.39686,0.74561,-1.16998,-1.52583,-0.44698,2.39804,0.00217
-2.39805,0.74631,-1.16946,-1.52610,-0.44723,2.39735,0.00217
-2.39924,0.74700,-1.16894,-1.52637,-0.44748,2.39666,0.00217
-2.40043,0.74768,-1.16844,-1.52664,-0.44772,2.39598,0.00217
-2.40162,0.74836,-1.16794,-1.52690,-0.44797,2.39531,0.00217
-2.40281,0.74902,-1.16744,-1.52715,-0.44821,2.39465,0.00217
-2.40399,0.74968,-1.16696,-1.52741,-0.44844,2.39399,0.00217
-2.40518,0.75034,-1.16648,-1.52765,-0.44867,2.39334,0.00217
-2.40637,0.75098,-1.16601,-1.52790,-0.44890,2.39270,0.00217
-2.40756,0.75162,-1.16555,-1.52814,-0.44912,2.39206,0.00217
-2.40875,0.75225,-1.16510,-1.52838,-0.44934,2.39143,0.00217
-2.40994,0.75288,-1.16465,-1.52861,-0.44956,2.39081,0.00217
-2.41113,0.75349,-1.16421,-1.52884,-0.44977,2.39020,0.00217
-2.41232,0.75411,-1.16378,-1.52906,-0.44998,2.38959,0.00217
-2.41351,0.75471,-1.16335,-1.52929,-0.45019,2.38898,0.00217
-2.41470,0.75531,-1.16293,-1.52951,-0.45040,2.38839,0.00217
-2.41588,0.75590,-1.16252,-1.52972,-0.45060,2.38780,0.00217
-2.41707,0.75648,-1.16211,-1.52993,-0.45079,2.38721,0.00217
-2.41826,0.75706,-1.16171,-1.53014,-0.45099,2.38664,0.00217
-2.41945,0.75763,-1.16131,-1.53035,-0.45118,2.38607,0.00217
-2.42064,0.75820,-1.16093,-1.53055,-0.45137,2.38550,0.00217
-2.42183,0.75876,-1.16054,-1.53075,-0.45156,2.38494,0.00217
-2.42302,0.75931,-1.16017,-1.53095,-0.45174,2.38439,0.00217
-2.42421,0.75986,-1.15980,-1.53114,-0.45192,2.38384,0.00217
-2.42540,0.76031,-1.15949,-1.53130,-0.45207,2.38340,0.00217
-2.42658,0.76100,-1.15900,-1.53153,-0.45234,2.38271,0.00217
-2.42777,0.76168,-1.15851,-1.53176,-0.45260,2.38203,0.00217
-2.42896,0.76236,-1.15803,-1.53198,-0.45285,2.38135,0.00217
-2.43015,0.76303,-1.15756,-1.53220,-0.45310,2.38069,0.00217
-2.43134,0.76369,-1.15710,-1.53242,-0.45335,2.38003,0.00217
-2.43253,0.76435,-1.15664,-1.53264,-0.45360,2.37937,0.00217
-2.43372,0.76500,-1.15619,-1.53285,-0.45384,2.37873,0.00217
-2.43491,0.76564,-1.15575,-1.53305,-0.45407,2.37809,0.00217
-2.43610,0.76628,-1.15532,-1.53326,-0.45431,2.37746,0.00217
-2.43728,0.76690,-1.15489,-1.53346,-0.45454,2.37683,0.00217
-2.43847,0.76752,-1.15447,-1.53366,-0.45476,2.37621,0.00217
-2.43966,0.76814,-1.15405,-1.53385,-0.45499,2.37560,0.00217
-2.44085,0.76875,-1.15364,-1.53404,-0.45521,2.37499,0.00217
-2.44204,0.76935,-1.15324,-1.53423,-0.45542,2.37439,0.00217
-2.44323,0.76994,-1.15284,-1.53442,-0.45564,2.37380,0.00217
-2.44442,0.77053,-1.15245,-1.53460,-0.45585,2.37321,0.00217
-2.44561,0.77111,-1.15207,-1.53478,-0.45605,2.37263,0.00217
-2.44680,0.77169,-1.15169,-1.53496,-0.45626,2.37206,0.00217
-2.44798,0.77226,-1.15132,-1.53514,-0.45646,2.37149,0.00217
-2.44917,0.77282,-1.15095,-1.53531,-0.45665,2.37093,0.00217
-2.45036,0.77338,-1.15059,-1.53548,-0.45685,2.37037,0.00217
-2.45155,0.77383,-1.15029,-1.53562,-0.45701,2.36991,0.00217
-2.45274,0.77454,-1.14982,-1.53580,-0.45731,2.36921,0.00217
-2.45393,0.77524,-1.14935,-1.53598,-0.45760,2.36852,0.00218
-2.45512,0.77593,-1.14889,-1.53615,-0.45789,2.36783,0.00218
-2.45631,0.77662,-1.14843,-1.53633,-0.45817,2.36715,0.00218
-2.45750,0.77729,-1.14799,-1.53650,-0.45845,2.36648,0.00218
-2.45869,0.77796,-1.14755,-1.53666,-0.45872,2.36581,0.00218
-2.45987,0.77862,-1.14711,-1.53683,-0.45899,2.36515,0.00218
-2.46106,0.77928,-1.14669,-1.53699,-0.45926,2.36450,0.00218
-2.46225,0.77993,-1.14627,-1.53715,-0.45952,2.36385,0.00218
-2.46344,0.78057,-1.14585,-1.53731,-0.45977,2.36321,0.00218
-2.46463,0.78120,-1.14544,-1.53747,-0.46003,2.36258,0.00218
-2.46582,0.78183,-1.14504,-1.53762,-0.46028,2.36195,0.00218
-2.46701,0.78245,-1.14465,-1.53777,-0.46052,2.36134,0.00218
-2.46820,0.78307,-1.14426,-1.53792,-0.46077,2.36072,0.00218
-2.46939,0.78368,-1.14388,-1.53807,-0.46100,2.36012,0.00218
-2.47057,0.78428,-1.14350,-1.53822,-0.46124,2.35952,0.00218
-2.47176,0.78487,-1.14313,-1.53836,-0.46147,2.35892,0.00218
-2.47295,0.78546,-1.14276,-1.53850,-0.46170,2.35834,0.00218
-2.47414,0.78604,-1.14240,-1.53864,-0.46192,2.35775,0.00218
-2.47533,0.78662,-1.14205,-1.53878,-0.46214,2.35718,0.00218
-2.47652,0.78719,-1.14170,-1.53891,-0.46236,2.35661,0.00218
-2.47771,0.78775,-1.14135,-1.53904,-0.46257,2.35605,0.00218
-2.47890,0.78792,-1.14125,-1.53908,-0.46264,2.35589,0.00218
-2.48009,0.78896,-1.14052,-1.53933,-0.46313,2.35485,0.00219
-2.48127,0.78999,-1.13980,-1.53957,-0.46360,2.35383,0.00219
-2.48246,0.79102,-1.13909,-1.53981,-0.46407,2.35282,0.00220
-2.48365,0.79203,-1.13839,-1.54004,-0.46453,2.35182,0.00220
-2.48484,0.79304,-1.13771,-1.54027,-0.46498,2.35082,0.00221
-2.48603,0.79403,-1.13703,-1.54050,-0.46543,2.34984,0.00221
-2.48722,0.79502,-1.13637,-1.54073,-0.46587,2.34887,0.00221
-2.48841,0.79599,-1.13571,-1.54095,-0.46631,2.34790,0.00222
-2.48960,0.79695,-1.13507,-1.54116,-0.46673,2.34695,0.00222
-2.49079,0.79791,-1.13444,-1.54138,-0.46715,2.34600,0.00222
-2.49197,0.79886,-1.13381,-1.54159,-0.46757,2.34507,0.00222
-2.49316,0.79979,-1.13320,-1.54179,-0.46797,2.34414,0.00223
-2.49435,0.80072,-1.13259,-1.54200,-0.46838,2.34322,0.00223
-2.49554,0.80164,-1.13200,-1.54220,-0.46877,2.34231,0.00223
-2.49673,0.80254,-1.13141,-1.54239,-0.46916,2.34141,0.00223
-2.49792,0.80344,-1.13084,-1.54259,-0.46955,2.34052,0.00223
-2.49911,0.80433,-1.13027,-1.54278,-0.46992,2.33963,0.00224
-2.50030,0.80521,-1.12971,-1.54297,-0.47030,2.33876,0.00224
-2.50149,0.80609,-1.12916,-1.54315,-0.47066,2.33789,0.00224
-2.50268,0.80695,-1.12862,-1.54334,-0.47102,2.33704,0.00224
-2.50386,0.80781,-1.12808,-1.54352,-0.47138,2.33619,0.00224
-2.50505,0.80865,-1.12756,-1.54369,-0.47173,2.33534,0.00224
-2.50624,0.80949,-1.12704,-1.54387,-0.47208,2.33451,0.00224
-2.50743,0.81032,-1.12653,-1.54404,-0.47242,2.33369,0.00224
-2.50862,0.81114,-1.12603,-1.54421,-0.47275,2.33287,0.00225
-2.50981,0.81195,-1.12554,-1.54438,-0.47308,2.33206,0.00225
-2.51100,0.81276,-1.12505,-1.54454,-0.47340,2.33126,0.00225
-2.51219,0.81355,-1.12457,-1.54470,-0.47372,2.33047,0.00225
-2.51338,0.81434,-1.12410,-1.54486,-0.47404,2.32968,0.00225
-2.51456,0.81512,-1.12363,-1.54502,-0.47435,2.32891,0.00225
-2.51575,0.81590,-1.12317,-1.54518,-0.47466,2.32814,0.00225
-2.51694,0.81666,-1.12272,-1.54533,-0.47496,2.32738,0.00225
-2.51813,0.81742,-1.12228,-1.54548,-0.47525,2.32662,0.00225
-2.51932,0.81817,-1.12184,-1.54563,-0.47555,2.32587,0.00225
-2.52051,0.81891,-1.12141,-1.54578,-0.47583,2.32513,0.00225
-2.52170,0.81965,-1.12099,-1.54592,-0.47612,2.32440,0.00225
-2.52289,0.82037,-1.12057,-1.54606,-0.47640,2.32368,0.00225
-2.52408,0.82109,-1.12016,-1.54620,-0.47667,2.32296,0.00225
-2.52526,0.82181,-1.11975,-1.54634,-0.47694,2.32225,0.00225
-2.52645,0.82251,-1.11935,-1.54648,-0.47721,2.32154,0.00225
-2.52764,0.82321,-1.11896,-1.54661,-0.47747,2.32085,0.00225
-2.52883,0.82390,-1.11857,-1.54675,-0.47773,2.32016,0.00225
-2.53002,0.82459,-1.11819,-1.54688,-0.47799,2.31947,0.00225
-2.53121,0.82526,-1.11781,-1.54701,-0.47824,2.31880,0.00224
-2.53240,0.82593,-1.11744,-1.54713,-0.47849,2.31813,0.00224
-2.53359,0.82660,-1.11707,-1.54726,-0.47873,2.31746,0.00224
-2.53478,0.82726,-1.11671,-1.54738,-0.47897,2.31681,0.00224
-2.53596,0.82791,-1.11636,-1.54751,-0.47921,2.31616,0.00224
-2.53715,0.82855,-1.11601,-1.54763,-0.47944,2.31551,0.00224
-2.53834,0.82919,-1.11566,-1.54775,-0.47968,2.31488,0.00224
-2.53953,0.82982,-1.11532,-1.54786,-0.47990,2.31425,0.00224
-2.54072,0.83044,-1.11499,-1.54798,-0.48013,2.31362,0.00224
-2.54191,0.83106,-1.11466,-1.54809,-0.48035,2.31300,0.00224
-2.54310,0.83167,-1.11433,-1.54821,-0.48056,2.31239,0.00224
-2.54429,0.83228,-1.11401,-1.54832,-0.48078,2.31178,0.00224
-2.54548,0.83272,-1.11378,-1.54840,-0.48093,2.31135,0.00224
-2.54667,0.83348,-1.11334,-1.54854,-0.48124,2.31058,0.00224
-2.54785,0.83424,-1.11290,-1.54868,-0.48153,2.30983,0.00224
-2.54904,0.83500,-1.11248,-1.54882,-0.48183,2.30908,0.00224
-2.55023,0.83574,-1.11206,-1.54895,-0.48211,2.30833,0.00224
-2.55142,0.83648,-1.11164,-1.54908,-0.48240,2.30760,0.00224
-2.55261,0.83721,-1.11123,-1.54922,-0.48268,2.30687,0.00224
-2.55380,0.83793,-1.11083,-1.54935,-0.48296,2.30615,0.00224
-2.55499,0.83865,-1.11043,-1.54947,-0.48323,2.30544,0.00224
-2.55618,0.83936,-1.11004,-1.54960,-0.48350,2.30473,0.00224
-2.55737,0.84006,-1.10966,-1.54973,-0.48376,2.30403,0.00224
-2.55855,0.84076,-1.10928,-1.54985,-0.48402,2.30334,0.00224
-2.55974,0.84145,-1.10890,-1.54997,-0.48428,2.30265,0.00224
-2.56093,0.84213,-1.10853,-1.55009,-0.48453,2.30197,0.00224
-2.56212,0.84280,-1.10817,-1.55021,-0.48478,2.30130,0.00224
-2.56331,0.84347,-1.10781,-1.55032,-0.48502,2.30063,0.00224
-2.56450,0.84413,-1.10746,-1.55044,-0.48526,2.29997,0.00224
-2.56569,0.84479,-1.10711,-1.55055,-0.48550,2.29932,0.00224
-2.56688,0.84544,-1.10677,-1.55066,-0.48574,2.29867,0.00224
-2.56807,0.84608,-1.10643,-1.55077,-0.48597,2.29803,0.00223
-2.56925,0.84671,-1.10610,-1.55088,-0.48620,2.29739,0.00223
-2.57044,0.84734,-1.10577,-1.55099,-0.48642,2.29676,0.00223
-2.57163,0.84797,-1.10545,-1.55110,-0.48664,2.29614,0.00223
-2.57282,0.84858,-1.10513,-1.55120,-0.48686,2.29552,0.00223
-2.57401,0.84919,-1.10481,-1.55131,-0.48708,2.29491,0.00223
-2.57520,0.84957,-1.10462,-1.55137,-0.48721,2.29453,0.00223
-2.57639,0.85033,-1.10420,-1.55149,-0.48751,2.29378,0.00223
-2.57758,0.85108,-1.10379,-1.55162,-0.48780,2.29304,0.00223
-2.57877,0.85182,-1.10338,-1.55174,-0.48808,2.29230,0.00223
-2.57995,0.85255,-1.10299,-1.55186,-0.48836,2.29157,0.00223
-2.58114,0.85328,-1.10259,-1.55198,-0.48864,2.29085,0.00223
-2.58233,0.85400,-1.10221,-1.55209,-0.48891,2.29013,0.00223
-2.58352,0.85471,-1.10182,-1.55221,-0.48918,2.28942,0.00223
-2.58471,0.85541,-1.10145,-1.55232,-0.48945,2.28872,0.00223
-2.58590,0.85611,-1.10108,-1.55244,-0.48971,2.28802,0.00223
-2.58709,0.85680,-1.10071,-1.55255,-0.48997,2.28733,0.00223
-2.58828,0.85749,-1.10035,-1.55265,-0.49022,2.28665,0.00223
-2.58947,0.85817,-1.10000,-1.55276,-0.49047,2.28597,0.00223
-2.59066,0.85884,-1.09965,-1.55287,-0.49072,2.28530,0.00223
-2.59184,0.85950,-1.09930,-1.55297,-0.49096,2.28464,0.00223
-2.59303,0.86016,-1.09896,-1.55308,-0.49120,2.28398,0.00223
-2.59422,0.86082,-1.09863,-1.55318,-0.49144,2.28333,0.00223
-2.59541,0.86146,-1.09830,-1.55328,-0.49167,2.28268,0.00223
-2.59660,0.86210,-1.09797,-1.55338,-0.49190,2.28204,0.00223
-2.59779,0.86274,-1.09765,-1.55348,-0.49213,2.28141,0.00223
-2.59898,0.86336,-1.09733,-1.55358,-0.49235,2.28078,0.00223
-2.60017,0.86399,-1.09702,-1.55367,-0.49257,2.28016,0.00223
-2.60136,0.86460,-1.09671,-1.55377,-0.49279,2.27954,0.00223
-2.60254,0.86492,-1.09655,-1.55382,-0.49290,2.27923,0.00223
-2.60373,0.86566,-1.09616,-1.55392,-0.49319,2.27849,0.00223
-2.60492,0.86640,-1.09577,-1.55403,-0.49347,2.27776,0.00223
-2.60611,0.86712,-1.09539,-1.55414,-0.49375,2.27704,0.00223
-2.60730,0.86784,-1.09501,-1.55424,-0.49403,2.27632,0.00223
-2.60849,0.86855,-1.09464,-1.55434,-0.49430,2.27561,0.00224
-2.60968,0.86926,-1.09428,-1.55444,-0.49457,2.27491,0.00224
-2.61087,0.86996,-1.09392,-1.55454,-0.49483,2.27421,0.00224
-2.61206,0.87065,-1.09356,-1.55464,-0.49509,2.27352,0.00224
-2.61324,0.87134,-1.09321,-1.55474,-0.49534,2.27283,0.00224
-2.61443,0.87202,-1.09287,-1.55484,-0.49560,2.27216,0.00224
-2.61562,0.87269,-1.09253,-1.55493,-0.49584,2.27149,0.00224
-2.61681,0.87336,-1.09219,-1.55503,-0.49609,2.27082,0.00224
-2.61800,0.87402,-1.09186,-1.55512,-0.49633,2.27016,0.00224
-2.61919,0.87467,-1.09153,-1.55521,-0.49657,2.26951,0.00224
-2.62038,0.87532,-1.09121,-1.55530,-0.49680,2.26886,0.00224
-2.62157,0.87596,-1.09089,-1.55539,-0.49703,2.26822,0.00224
-2.62276,0.87660,-1.09058,-1.55548,-0.49726,2.26759,0.00224
-2.62394,0.87723,-1.09027,-1.55557,-0.49749,2.26696,0.00224
-2.62513,0.87785,-1.08997,-1.55565,-0.49771,2.26633,0.00224
-2.62632,0.87847,-1.08967,-1.55574,-0.49793,2.26572,0.00224
-2.62751,0.87855,-1.08963,-1.55575,-0.49796,2.26564,0.00224
-2.62870,0.87934,-1.08922,-1.55583,-0.49829,2.26485,0.00224
-2.62989,0.88013,-1.08881,-1.55592,-0.49861,2.26407,0.00224
-2.63108,0.88091,-1.08841,-1.55600,-0.49893,2.26330,0.00224
-2.63227,0.88168,-1.08802,-1.55609,-0.49924,2.26253,0.00224
-2.63346,0.88244,-1.08763,-1.55617,-0.49955,2.26177,0.00224
-2.63465,0.88320,-1.08725,-1.55625,-0.49985,2.26102,0.00224
-2.63583,0.88395,-1.08687,-1.55633,-0.50015,2.26027,0.00224
-2.63702,0.88469,-1.08650,-1.55641,-0.50044,2.25953,0.00224
-2.63821,0.88543,-1.08613,-1.55649,-0.50073,2.25880,0.00224
-2.63940,0.88616,-1.08577,-1.55656,-0.50102,2.25808,0.00225
-2.64059,0.88688,-1.08542,-1.55664,-0.50130,2.25736,0.00225
-2.64178,0.88759,-1.08506,-1.55672,-0.50158,2.25664,0.00225
-2.64297,0.88830,-1.08472,-1.55679,-0.50186,2.25594,0.00225
-2.64416,0.88900,-1.08438,-1.55686,-0.50213,2.25524,0.00225
-2.64535,0.88970,-1.08404,-1.55694,-0.50239,2.25454,0.00225
-2.64653,0.89039,-1.08371,-1.55701,-0.50266,2.25386,0.00225
-2.64772,0.89107,-1.08338,-1.55708,-0.50292,2.25318,0.00225
-2.64891,0.89175,-1.08306,-1.55715,-0.50317,2.25250,0.00225
-2.65010,0.89242,-1.08274,-1.55722,-0.50342,2.25183,0.00225
-2.65129,0.89308,-1.08242,-1.55729,-0.50367,2.25117,0.00225
-2.65248,0.89374,-1.08211,-1.55736,-0.50391,2.25051,0.00225
-2.65367,0.89440,-1.08181,-1.55743,-0.50416,2.24986,0.00225
-2.65486,0.89504,-1.08151,-1.55749,-0.50439,2.24922,0.00225
-2.65605,0.89568,-1.08121,-1.55756,-0.50463,2.24858,0.00225
-2.65723,0.89632,-1.08092,-1.55763,-0.50486,2.24794,0.00225
-2.65842,0.89694,-1.08063,-1.55769,-0.50509,2.24732,0.00225
-2.65961,0.89747,-1.08038,-1.55775,-0.50528,2.24679,0.00225
-2.66080,0.89836,-1.07991,-1.55786,-0.50564,2.24591,0.00225
-2.66199,0.89925,-1.07945,-1.55797,-0.50599,2.24503,0.00225
-2.66318,0.90012,-1.07899,-1.55809,-0.50634,2.24416,0.00225
-2.66437,0.90099,-1.07854,-1.55820,-0.50668,2.24330,0.00225
-2.66556,0.90185,-1.07810,-1.55830,-0.50701,2.24244,0.00226
-2.66675,0.90271,-1.07766,-1.55841,-0.50735,2.24160,0.00226
-2.66793,0.90355,-1.07723,-1.55852,-0.50767,2.24076,0.00226
-2.66912,0.90439,-1.07681,-1.55862,-0.50800,2.23992,0.00226
-2.67031,0.90522,-1.07639,-1.55872,-0.50831,2.23910,0.00226
-2.67150,0.90605,-1.07598,-1.55882,-0.50863,2.23828,0.00226
-2.67269,0.90686,-1.07557,-1.55892,-0.50894,2.23747,0.00226
-2.67388,0.90767,-1.07517,-1.55902,-0.50924,2.23667,0.00226
-2.67507,0.90847,-1.07478,-1.55912,-0.50954,2.23587,0.00226
-2.67626,0.90927,-1.07439,-1.55922,-0.50984,2.23508,0.00227
-2.67745,0.91005,-1.07400,-1.55931,-0.51013,2.23429,0.00227
-2.67864,0.91084,-1.07362,-1.55941,-0.51042,2.23352,0.00227
-2.67982,0.91161,-1.07325,-1.55950,-0.51070,2.23275,0.00227
-2.68101,0.91238,-1.07288,-1.55959,-0.51098,2.23198,0.00227
-2.68220,0.91314,-1.07252,-1.55968,-0.51126,2.23123,0.00227
-2.68339,0.91389,-1.07216,-1.55977,-0.51153,2.23048,0.00227
-2.68458,0.91464,-1.07180,-1.55986,-0.51180,2.22973,0.00227
-2.68577,0.91538,-1.07145,-1.55995,-0.51206,2.22900,0.00227
-2.68696,0.91611,-1.07111,-1.56004,-0.51232,2.22827,0.00227
-2.68815,0.91684,-1.07077,-1.56012,-0.51258,2.22754,0.00227
-2.68934,0.91756,-1.07043,-1.56021,-0.51283,2.22682,0.00227
-2.69052,0.91827,-1.07010,-1.56029,-0.51308,2.22611,0.00227
-2.69171,0.91898,-1.06978,-1.56037,-0.51333,2.22540,0.00227
-2.69290,0.91968,-1.06946,-1.56045,-0.51358,2.22470,0.00227
-2.69409,0.92038,-1.06914,-1.56053,-0.51382,2.22401,0.00227
-2.69528,0.92107,-1.06883,-1.56061,-0.51405,2.22332,0.00227
-2.69647,0.92175,-1.06852,-1.56069,-0.51429,2.22264,0.00227
-2.69766,0.92243,-1.06821,-1.56077,-0.51452,2.22197,0.00227
-2.69885,0.92310,-1.06791,-1.56085,-0.51474,2.22129,0.00227
-2.70004,0.92376,-1.06761,-1.56092,-0.51497,2.22063,0.00227
-2.70122,0.92442,-1.06732,-1.56100,-0.51519,2.21997,0.00227
-2.70241,0.92508,-1.06703,-1.56107,-0.51541,2.21932,0.00227
-2.70360,0.92572,-1.06675,-1.56115,-0.51562,2.21867,0.00227
-2.70479,0.92637,-1.06647,-1.56122,-0.51584,2.21803,0.00227
-2.70598,0.92700,-1.06619,-1.56129,-0.51605,2.21739,0.00227
-2.70717,0.92716,-1.06611,-1.56132,-0.51610,2.21723,0.00227
-2.70836,0.92812,-1.06561,-1.56147,-0.51645,2.21629,0.00227
-2.70955,0.92907,-1.06512,-1.56162,-0.51678,2.21535,0.00227
-2.71074,0.93001,-1.06464,-1.56177,-0.51712,2.21442,0.00228
-2.71192,0.93094,-1.06417,-1.56192,-0.51745,2.21349,0.00228
-2.71311,0.93186,-1.06370,-1.56206,-0.51778,2.21258,0.00228
-2.71430,0.93278,-1.06323,-1.56221,-0.51810,2.21167,0.00228
-2.71549,0.93369,-1.06278,-1.56235,-0.51842,2.21076,0.00228
-2.71668,0.93459,-1.06233,-1.56249,-0.51873,2.20987,0.00228
-2.71787,0.93548,-1.06188,-1.56263,-0.51904,2.20898,0.00228
-2.71906,0.93637,-1.06145,-1.56276,-0.51934,2.20810,0.00228
-2.72025,0.93724,-1.06102,-1.56290,-0.51964,2.20723,0.00229
-2.72144,0.93812,-1.06059,-1.56303,-0.51994,2.20637,0.00229
-2.72263,0.93898,-1.06017,-1.56316,-0.52023,2.20551,0.00229
-2.72381,0.93984,-1.05976,-1.56329,-0.52052,2.20466,0.00229
-2.72500,0.94068,-1.05935,-1.56342,-0.52080,2.20381,0.00229
-2.72619,0.94153,-1.05895,-1.56354,-0.52108,2.20298,0.00229
-2.72738,0.94236,-1.05855,-1.56366,-0.52136,2.20215,0.00229
-2.72857,0.94319,-1.05816,-1.56379,-0.52163,2.20132,0.00229
-2.72976,0.94401,-1.05777,-1.56391,-0.52190,2.20051,0.00229
-2.73095,0.94482,-1.05739,-1.56403,-0.52217,2.19970,0.00229
-2.73214,0.94563,-1.05701,-1.56414,-0.52243,2.19889,0.00229
-2.73333,0.94643,-1.05664,-1.56426,-0.52269,2.19809,0.00229
-2.73451,0.94722,-1.05627,-1.56437,-0.52295,2.19730,0.00229
-2.73570,0.94801,-1.05591,-1.56449,-0.52320,2.19652,0.00230
-2.73689,0.94879,-1.05556,-1.56460,-0.52345,2.19574,0.00230
-2.73808,0.94957,-1.05520,-1.56471,-0.52369,2.19497,0.00230
-2.73927,0.95033,-1.05486,-1.56482,-0.52393,2.19421,0.00230
-2.74046,0.95109,-1.05451,-1.56492,-0.52417,2.19345,0.00230
-2.74165,0.95185,-1.05417,-1.56503,-0.52441,2.19270,0.00230
-2.74284,0.95260,-1.05384,-1.56513,-0.52464,2.19195,0.00230
-2.74403,0.95334,-1.05351,-1.56524,-0.52487,2.19121,0.00230
-2.74521,0.95407,-1.05319,-1.56534,-0.52510,2.19047,0.00230
-2.74640,0.95480,-1.05286,-1.56544,-0.52532,2.18975,0.00230
-2.74759,0.95553,-1.05255,-1.56554,-0.52555,2.18902,0.00230
-2.74878,0.95624,-1.05223,-1.56564,-0.52576,2.18831,0.00230
-2.74997,0.95696,-1.05193,-1.56574,-0.52598,2.18760,0.00230
-2.75116,0.95766,-1.05162,-1.56583,-0.52619,2.18689,0.00230
-2.75235,0.95836,-1.05132,-1.56593,-0.52640,2.18619,0.00230
-2.75354,0.95906,-1.05102,-1.56602,-0.52661,2.18550,0.00230
-2.75473,0.95974,-1.05073,-1.56611,-0.52681,2.18481,0.00230
-2.75591,0.96043,-1.05044,-1.56620,-0.52702,2.18413,0.00230
-2.75710,0.96110,-1.05015,-1.56630,-0.52722,2.18345,0.00230
-2.75829,0.96177,-1.04987,-1.56638,-0.52741,2.18278,0.00230
-2.75948,0.96244,-1.04959,-1.56647,-0.52761,2.18212,0.00230
-2.76067,0.96310,-1.04931,-1.56656,-0.52780,2.18146,0.00230
-2.76186,0.96376,-1.04904,-1.56665,-0.52799,2.18080,0.00230
-2.76305,0.96440,-1.04877,-1.56673,-0.52818,2.18015,0.00230
-2.76424,0.96500,-1.04853,-1.56681,-0.52835,2.17956,0.00230
-2.76543,0.96575,-1.04819,-1.56692,-0.52858,2.17880,0.00230
-2.76662,0.96651,-1.04785,-1.56703,-0.52881,2.17805,0.00230
-2.76780,0.96725,-1.04752,-1.56714,-0.52904,2.17731,0.00230
-2.76899,0.96799,-1.04719,-1.56724,-0.52926,2.17657,0.00230
-2.77018,0.96873,-1.04687,-1.56735,-0.52948,2.17584,0.00230
-2.77137,0.96945,-1.04655,-1.56745,-0.52970,2.17511,0.00230
-2.77256,0.97018,-1.04624,-1.56755,-0.52992,2.17439,0.00230
-2.77375,0.97089,-1.04593,-1.56766,-0.53013,2.17368,0.00230
-2.77494,0.97160,-1.04562,-1.56776,-0.53034,2.17297,0.00231
-2.77613,0.97231,-1.04532,-1.56785,-0.53055,2.17227,0.00231
-2.77732,0.97301,-1.04502,-1.56795,-0.53075,2.17157,0.00231
-2.77850,0.97370,-1.04472,-1.56805,-0.53095,2.17088,0.00231
-2.77969,0.97439,-1.04443,-1.56814,-0.53115,2.17019,0.00231
-2.78088,0.97507,-1.04414,-1.56824,-0.53135,2.16951,0.00231
-2.78207,0.97574,-1.04386,-1.56833,-0.53155,2.16883,0.00231
-2.78326,0.97641,-1.04358,-1.56842,-0.53174,2.16816,0.00231
-2.78445,0.97708,-1.04330,-1.56851,-0.53193,2.16750,0.00231
-2.78564,0.97774,-1.04303,-1.56860,-0.53212,2.16684,0.00231
-2.78683,0.97840,-1.04276,-1.56869,-0.53230,2.16618,0.00231
-2.78802,0.97904,-1.04249,-1.56878,-0.53249,2.16554,0.00231
-2.78920,0.97969,-1.04223,-1.56886,-0.53267,2.16489,0.00231
-2.79039,0.97976,-1.04220,-1.56887,-0.53269,2.16482,0.00231
-2.79158,0.98047,-1.04189,-1.56898,-0.53290,2.16411,0.00231
-2.79277,0.98118,-1.04159,-1.56907,-0.53310,2.16341,0.00231
-2.79396,0.98187,-1.04129,-1.56917,-0.53330,2.16271,0.00231
-2.79515,0.98257,-1.04099,-1.56927,-0.53351,2.16202,0.00231
-2.79634,0.98326,-1.04070,-1.56937,-0.53370,2.16133,0.00231
-2.79753,0.98394,-1.04042,-1.56946,-0.53390,2.16065,0.00231
-2.79872,0.98462,-1.04013,-1.56956,-0.53409,2.15997,0.00231
-2.79990,0.98529,-1.03985,-1.56965,-0.53428,2.15930,0.00231
-2.80109,0.98595,-1.03957,-1.56974,-0.53447,2.15864,0.00231
-2.80228,0.98662,-1.03930,-1.56983,-0.53466,2.15798,0.00231
-2.80347,0.98727,-1.03903,-1.56992,-0.53484,2.15732,0.00231
-2.80466,0.98792,-1.03876,-1.57001,-0.53503,2.15667,0.00232
-2.80585,0.98857,-1.03850,-1.57010,-0.53521,2.15602,0.00232
-2.80704,0.98890,-1.03836,-1.57014,-0.53530,2.15570,0.00232
-2.80823,0.98961,-1.03806,-1.57024,-0.53550,2.15499,0.00232
-2.80942,0.99031,-1.03776,-1.57034,-0.53571,2.15429,0.00232
-2.81061,0.99101,-1.03746,-1.57044,-0.53591,2.15359,0.00232
-2.81179,0.99170,-1.03717,-1.57054,-0.53611,2.15290,0.00232
-2.81298,0.99239,-1.03688,-1.57063,-0.53630,2.15221,0.00232
-2.81417,0.99307,-1.03659,-1.57073,-0.53650,2.15153,0.00232
-2.81536,0.99375,-1.03631,-1.57082,-0.53669,2.15085,0.00232
-2.81655,0.99442,-1.03603,-1.57092,-0.53688,2.15018,0.00232
-2.81774,0.99509,-1.03575,-1.57101,-0.53707,2.14952,0.00232
-2.81893,0.99575,-1.03548,-1.57110,-0.53725,2.14886,0.00232
-2.82012,0.99641,-1.03521,-1.57119,-0.53743,2.14820,0.00232
-2.82131,0.99706,-1.03495,-1.57128,-0.53761,2.14755,0.00232
-2.82249,0.99770,-1.03468,-1.57136,-0.53779,2.14690,0.00232
-2.82368,0.99822,-1.03447,-1.57143,-0.53794,2.14639,0.00232
-2.82487,0.99891,-1.03419,-1.57153,-0.53813,2.14570,0.00233
-2.82606,0.99959,-1.03390,-1.57162,-0.53832,2.14502,0.00233
-2.82725,1.00026,-1.03362,-1.57172,-0.53851,2.14435,0.00233
-2.82844,1.00093,-1.03335,-1.57181,-0.53870,2.14368,0.00233
-2.82963,1.00160,-1.03307,-1.57190,-0.53889,2.14302,0.00233
-2.83082,1.00226,-1.03280,-1.57199,-0.53907,2.14236,0.00233
-2.83201,1.00291,-1.03254,-1.57208,-0.53925,2.14171,0.00233
-2.83319,1.00356,-1.03227,-1.57217,-0.53943,2.14106,0.00233
-2.83438,1.00420,-1.03201,-1.57225,-0.53960,2.14042,0.00233
-2.83557,1.00453,-1.03188,-1.57230,-0.53969,2.14009,0.00233
-2.83676,1.00519,-1.03161,-1.57239,-0.53988,2.13943,0.00233
-2.83795,1.00584,-1.03134,-1.57248,-0.54006,2.13878,0.00233
-2.83914,1.00649,-1.03108,-1.57256,-0.54024,2.13813,0.00233
-2.84033,1.00714,-1.03082,-1.57265,-0.54041,2.13748,0.00233
-2.84152,1.00778,-1.03056,-1.57274,-0.54059,2.13684,0.00233
-2.84271,1.00847,-1.03027,-1.57283,-0.54078,2.13616,0.00234
-2.84389,1.00915,-1.02999,-1.57293,-0.54097,2.13548,0.00234
-2.84508,1.00982,-1.02971,-1.57302,-0.54116,2.13481,0.00234
-2.84627,1.01049,-1.02944,-1.57311,-0.54135,2.13414,0.00234
-2.84746,1.01115,-1.02917,-1.57320,-0.54153,2.13348,0.00234
-2.84865,1.01181,-1.02890,-1.57329,-0.54171,2.13282,0.00234
-2.84984,1.01247,-1.02863,-1.57338,-0.54189,2.13217,0.00234
-2.85103,1.01311,-1.02837,-1.57346,-0.54207,2.13152,0.00234
-2.85222,1.01376,-1.02811,-1.57355,-0.54225,2.13088,0.00234
-2.85341,1.01422,-1.02792,-1.57361,-0.54237,2.13042,0.00234
-2.85460,1.01500,-1.02758,-1.57373,-0.54261,2.12964,0.00234
-2.85578,1.01578,-1.02724,-1.57384,-0.54283,2.12887,0.00234
-2.85697,1.01655,-1.02691,-1.57395,-0.54306,2.12810,0.00235
-2.85816,1.01731,-1.02658,-1.57406,-0.54328,2.12734,0.00235
-2.85935,1.01807,-1.02625,-1.57417,-0.54350,2.12659,0.00235
-2.86054,1.01882,-1.02593,-1.57427,-0.54372,2.12584,0.00235
-2.86173,1.01957,-1.02562,-1.57438,-0.54394,2.12510,0.00235
-2.86292,1.02031,-1.02530,-1.57448,-0.54415,2.12436,0.00235
-2.86411,1.02105,-1.02499,-1.57458,-0.54436,2.12363,0.00235
-2.86530,1.02178,-1.02469,-1.57468,-0.54457,2.12290,0.00235
-2.86648,1.02250,-1.02438,-1.57478,-0.54477,2.12218,0.00236
-2.86767,1.02322,-1.02409,-1.57488,-0.54497,2.12146,0.00236
-2.86886,1.02393,-1.02379,-1.57498,-0.54517,2.12075,0.00236
-2.87005,1.02464,-1.02350,-1.57508,-0.54537,2.12004,0.00236
-2.87124,1.02535,-1.02321,-1.57517,-0.54557,2.11934,0.00236
-2.87243,1.02604,-1.02293,-1.57527,-0.54576,2.11865,0.00236
-2.87362,1.02674,-1.02264,-1.57536,-0.54595,2.11796,0.00236
-2.87481,1.02743,-1.02237,-1.57545,-0.54614,2.11727,0.00236
-2.87600,1.02811,-1.02209,-1.57554,-0.54633,2.11659,0.00236
-2.87718,1.02879,-1.02182,-1.57563,-0.54651,2.11591,0.00236
-2.87837,1.02946,-1.02155,-1.57572,-0.54670,2.11524,0.00236
-2.87956,1.03013,-1.02129,-1.57581,-0.54688,2.11457,0.00237
-2.88075,1.03079,-1.02102,-1.57589,-0.54705,2.11391,0.00237
-2.88194,1.03145,-1.02077,-1.57598,-0.54723,2.11326,0.00237
-2.88313,1.03210,-1.02051,-1.57606,-0.54740,2.11260,0.00237
-2.88432,1.03275,-1.02026,-1.57615,-0.54758,2.11196,0.00237
-2.88551,1.03339,-1.02001,-1.57623,-0.54775,2.11131,0.00237
-2.88670,1.03398,-1.01978,-1.57630,-0.54790,2.11073,0.00237
-2.88788,1.03468,-1.01950,-1.57637,-0.54812,2.11002,0.00237
-2.88907,1.03539,-1.01922,-1.57644,-0.54833,2.10932,0.00237
-2.89026,1.03609,-1.01895,-1.57650,-0.54854,2.10863,0.00237
-2.89145,1.03678,-1.01868,-1.57657,-0.54874,2.10794,0.00237
-2.89264,1.03747,-1.01841,-1.57664,-0.54894,2.10725,0.00238
-2.89383,1.03815,-1.01815,-1.57670,-0.54914,2.10657,0.00238
-2.89502,1.03883,-1.01789,-1.57677,-0.54934,2.10589,0.00238
-2.89621,1.03950,-1.01763,-1.57683,-0.54954,2.10522,0.00238
-2.89740,1.04017,-1.01738,-1.57690,-0.54973,2.10455,0.00238
-2.89859,1.04084,-1.01713,-1.57696,-0.54992,2.10389,0.00238
-2.89977,1.04149,-1.01688,-1.57702,-0.55011,2.10323,0.00238
-2.90096,1.04215,-1.01663,-1.57708,-0.55030,2.10258,0.00238
-2.90215,1.04280,-1.01639,-1.57714,-0.55048,2.10193,0.00238
-2.90334,1.04344,-1.01615,-1.57720,-0.55067,2.10129,0.00238
-2.90453,1.04408,-1.01591,-1.57726,-0.55085,2.10065,0.00239
-2.90572,1.04441,-1.01579,-1.57729,-0.55094,2.10032,0.00239
-2.90691,1.04514,-1.01550,-1.57734,-0.55118,2.09959,0.00239
-2.90810,1.04587,-1.01523,-1.57740,-0.55141,2.09887,0.00239
-2.90929,1.04659,-1.01495,-1.57745,-0.55163,2.09815,0.00239
-2.91047,1.04731,-1.01468,-1.57750,-0.55186,2.09744,0.00239
-2.91166,1.04802,-1.01441,-1.57755,-0.55208,2.09673,0.00239
-2.91285,1.04872,-1.01414,-1.57760,-0.55230,2.09603,0.00239
-2.91404,1.04942,-1.01388,-1.57764,-0.55252,2.09533,0.00239
-2.91523,1.05012,-1.01362,-1.57769,-0.55273,2.09464,0.00240
-2.91642,1.05081,-1.01336,-1.57774,-0.55294,2.09395,0.00240
-2.91761,1.05150,-1.01310,-1.57779,-0.55315,2.09326,0.00240
-2.91880,1.05218,-1.01285,-1.57784,-0.55336,2.09258,0.00240
-2.91999,1.05285,-1.01260,-1.57788,-0.55356,2.09191,0.00240
-2.92117,1.05353,-1.01236,-1.57793,-0.55376,2.09124,0.00240
-2.92236,1.05419,-1.01211,-1.57798,-0.55396,2.09058,0.00240
-2.92355,1.05485,-1.01187,-1.57802,-0.55416,2.08991,0.00240
-2.92474,1.05551,-1.01163,-1.57807,-0.55435,2.08926,0.00240
-2.92593,1.05616,-1.01140,-1.57811,-0.55455,2.08861,0.00240
-2.92712,1.05681,-1.01117,-1.57816,-0.55474,2.08796,0.00241
-2.92831,1.05746,-1.01093,-1.57820,-0.55493,2.08732,0.00241
-2.92950,1.05809,-1.01071,-1.57825,-0.55511,2.08668,0.00241
-2.93069,1.05861,-1.01052,-1.57828,-0.55526,2.08616,0.00241
-2.93187,1.05932,-1.01027,-1.57831,-0.55549,2.08546,0.00241
-2.93306,1.06002,-1.01001,-1.57834,-0.55572,2.08477,0.00241
-2.93425,1.06071,-1.00976,-1.57838,-0.55594,2.08407,0.00241
-2.93544,1.06140,-1.00951,-1.57841,-0.55616,2.08338,0.00241
-2.93663,1.06209,-1.00927,-1.57844,-0.55638,2.08270,0.00241
-2.93782,1.06277,-1.00902,-1.57847,-0.55659,2.08202,0.00242
-2.93901,1.06344,-1.00878,-1.57850,-0.55680,2.08135,0.00242
-2.94020,1.06412,-1.00854,-1.57853,-0.55701,2.08068,0.00242
-2.94139,1.06478,-1.00831,-1.57856,-0.55722,2.08001,0.00242
-2.94258,1.06544,-1.00808,-1.57859,-0.55742,2.07935,0.00242
-2.94376,1.06610,-1.00785,-1.57862,-0.55763,2.07870,0.00242
-2.94495,1.06676,-1.00762,-1.57865,-0.55783,2.07805,0.00242
-2.94614,1.06740,-1.00739,-1.57868,-0.55802,2.07740,0.00242
-2.94733,1.06805,-1.00717,-1.57871,-0.55822,2.07676,0.00242
-2.94852,1.06869,-1.00695,-1.57874,-0.55841,2.07612,0.00242
-2.94971,1.06932,-1.00673,-1.57877,-0.55860,2.07548,0.00242
-2.95090,1.06964,-1.00662,-1.57878,-0.55870,2.07516,0.00243
-2.95209,1.07032,-1.00639,-1.57880,-0.55892,2.07449,0.00243
-2.95328,1.07100,-1.00615,-1.57881,-0.55915,2.07382,0.00243
-2.95446,1.07166,-1.00593,-1.57882,-0.55936,2.07315,0.00243
-2.95565,1.07233,-1.00570,-1.57884,-0.55958,2.07249,0.00243
-2.95684,1.07299,-1.00547,-1.57885,-0.55979,2.07183,0.00243
-2.95803,1.07364,-1.00525,-1.57886,-0.56000,2.07117,0.00243
-2.95922,1.07429,-1.00503,-1.57888,-0.56021,2.07052,0.00243
-2.96041,1.07494,-1.00482,-1.57889,-0.56041,2.06988,0.00243
-2.96160,1.07558,-1.00460,-1.57891,-0.56062,2.06924,0.00243
-2.96279,1.07622,-1.00439,-1.57892,-0.56082,2.06860,0.00244
-2.96398,1.07685,-1.00418,-1.57894,-0.56102,2.06797,0.00244
-2.96516,1.07730,-1.00403,-1.57895,-0.56116,2.06753,0.00244
-2.96635,1.07797,-1.00379,-1.57897,-0.56137,2.06685,0.00244
-2.96754,1.07865,-1.00356,-1.57899,-0.56158,2.06618,0.00244
-2.96873,1.07931,-1.00333,-1.57902,-0.56179,2.06552,0.00244
-2.96992,1.07997,-1.00310,-1.57904,-0.56200,2.06486,0.00244
-2.97111,1.08063,-1.00288,-1.57906,-0.56220,2.06421,0.00244
-2.97230,1.08128,-1.00266,-1.57909,-0.56240,2.06355,0.00244
-2.97349,1.08193,-1.00244,-1.57911,-0.56260,2.06291,0.00244
-2.97468,1.08257,-1.00222,-1.57913,-0.56280,2.06227,0.00244
-2.97586,1.08321,-1.00200,-1.57916,-0.56299,2.06163,0.00245
-2.97705,1.08385,-1.00179,-1.57918,-0.56319,2.06099,0.00245
-2.97824,1.08448,-1.00158,-1.57920,-0.56338,2.06036,0.00245
-2.97943,1.08480,-1.00147,-1.57921,-0.56347,2.06005,0.00245
-2.98062,1.08545,-1.00125,-1.57924,-0.56367,2.05940,0.00245
-2.98181,1.08609,-1.00103,-1.57927,-0.56386,2.05876,0.00245
-2.98300,1.08673,-1.00081,-1.57930,-0.56405,2.05812,0.00245
-2.98419,1.08737,-1.00060,-1.57932,-0.56425,2.05748,0.00245
-2.98538,1.08800,-1.00038,-1.57935,-0.56443,2.05685,0.00245
-2.98657,1.08863,-1.00017,-1.57938,-0.56462,2.05622,0.00245
-2.98775,1.08928,-0.99995,-1.57941,-0.56481,2.05558,0.00245
-2.98894,1.08992,-0.99973,-1.57944,-0.56501,2.05493,0.00246
-2.99013,1.09056,-0.99951,-1.57947,-0.56519,2.05430,0.00246
-2.99132,1.09120,-0.99930,-1.57950,-0.56538,2.05366,0.00246
-2.99251,1.09183,-0.99908,-1.57953,-0.56557,2.05303,0.00246
-2.99370,1.09246,-0.99887,-1.57957,-0.56575,2.05240,0.00246
-2.99489,1.09311,-0.99865,-1.57960,-0.56594,2.05176,0.00246
-2.99608,1.09375,-0.99843,-1.57963,-0.56613,2.05112,0.00246
-2.99727,1.09439,-0.99821,-1.57967,-0.56632,2.05048,0.00246
-2.99845,1.09502,-0.99799,-1.57970,-0.56650,2.04984,0.00246
-2.99964,1.09565,-0.99778,-1.57974,-0.56668,2.04922,0.00246
-3.00083,1.09628,-0.99757,-1.57977,-0.56686,2.04859,0.00246
-3.00202,1.09634,-0.99755,-1.57977,-0.56688,2.04853,0.00246
-3.00321,1.09699,-0.99732,-1.57981,-0.56707,2.04788,0.00247
-3.00440,1.09763,-0.99710,-1.57985,-0.56726,2.04724,0.00247
-3.00559,1.09827,-0.99688,-1.57989,-0.56744,2.04660,0.00247
-3.00678,1.09891,-0.99667,-1.57992,-0.56762,2.04597,0.00247
-3.00797,1.09954,-0.99645,-1.57996,-0.56780,2.04534,0.00247
-3.00915,1.10016,-0.99624,-1.58000,-0.56798,2.04472,0.00247
-3.01034,1.10029,-0.99620,-1.58001,-0.56801,2.04459,0.00247
-3.01153,1.10093,-0.99597,-1.58007,-0.56818,2.04395,0.00247
-3.01272,1.10157,-0.99574,-1.58014,-0.56835,2.04331,0.00247
-3.01391,1.10221,-0.99551,-1.58020,-0.56852,2.04267,0.00247
-3.01510,1.10284,-0.99528,-1.58026,-0.56868,2.04204,0.00247
-3.01629,1.10347,-0.99506,-1.58033,-0.56884,2.04142,0.00247
-3.01748,1.10409,-0.99484,-1.58039,-0.56900,2.04079,0.00248
-3.01867,1.10422,-0.99480,-1.58040,-0.56903,2.04067,0.00248
-3.01985,1.10486,-0.99456,-1.58050,-0.56919,2.04002,0.00248
-3.02104,1.10550,-0.99432,-1.58059,-0.56934,2.03939,0.00248
-3.02223,1.10614,-0.99408,-1.58067,-0.56949,2.03875,0.00248
-3.02342,1.10677,-0.99385,-1.58076,-0.56963,2.03812,0.00248
-3.02461,1.10740,-0.99362,-1.58085,-0.56978,2.03750,0.00248
-3.02580,1.10802,-0.99339,-1.58093,-0.56993,2.03687,0.00248
-3.02699,1.10833,-0.99328,-1.58098,-0.57000,2.03657,0.00248
-3.02818,1.10858,-0.99318,-1.58102,-0.57005,2.03632,0.00248
-3.02937,1.10901,-0.99301,-1.58113,-0.57012,2.03589,0.00248
-3.03056,1.10964,-0.99273,-1.58134,-0.57019,2.03525,0.00248
-3.03174,1.11027,-0.99245,-1.58155,-0.57026,2.03462,0.00248
-3.03293,1.11090,-0.99218,-1.58176,-0.57033,2.03400,0.00248
-3.03412,1.11152,-0.99190,-1.58196,-0.57041,2.03338,0.00249
-3.03531,1.11214,-0.99164,-1.58216,-0.57048,2.03276,0.00249
-3.03650,1.11276,-0.99137,-1.58236,-0.57055,2.03214,0.00249
-3.03769,1.11337,-0.99111,-1.58256,-0.57062,2.03153,0.00249
-3.03888,1.11397,-0.99085,-1.58275,-0.57069,2.03093,0.00249
-3.04007,1.11458,-0.99059,-1.58294,-0.57076,2.03032,0.00249
-3.04126,1.11482,-0.99048,-1.58303,-0.57078,2.03008,0.00249
-3.04244,1.11544,-0.99017,-1.58335,-0.57078,2.02946,0.00249
-3.04363,1.11605,-0.98986,-1.58366,-0.57078,2.02885,0.00249
-3.04482,1.11667,-0.98956,-1.58397,-0.57079,2.02824,0.00249
-3.04601,1.11727,-0.98925,-1.58427,-0.57079,2.02763,0.00249
-3.04720,1.11788,-0.98896,-1.58457,-0.57080,2.02702,0.00249
-3.04839,1.11848,-0.98866,-1.58486,-0.57080,2.02642,0.00249
-3.04958,1.11908,-0.98837,-1.58515,-0.57081,2.02583,0.00249
-3.05077,1.11967,-0.98808,-1.58543,-0.57082,2.02523,0.00250
-3.05196,1.12026,-0.98780,-1.58571,-0.57082,2.02464,0.00250
-3.05314,1.12084,-0.98752,-1.58599,-0.57083,2.02405,0.00250
-3.05433,1.12143,-0.98724,-1.58626,-0.57084,2.02347,0.00250
-3.05552,1.12201,-0.98696,-1.58653,-0.57086,2.02289,0.00250
-3.05671,1.12258,-0.98669,-1.58679,-0.57087,2.02232,0.00250
-3.05790,1.12293,-0.98653,-1.58695,-0.57087,2.02197,0.00250
-3.05909,1.12349,-0.98624,-1.58726,-0.57086,2.02140,0.00250
-3.06028,1.12406,-0.98596,-1.58756,-0.57084,2.02084,0.00250
-3.06147,1.12462,-0.98568,-1.58786,-0.57082,2.02027,0.00250
-3.06266,1.12518,-0.98541,-1.58816,-0.57081,2.01971,0.00250
-3.06384,1.12540,-0.98530,-1.58827,-0.57080,2.01949,0.00250
-3.06503,1.12596,-0.98502,-1.58859,-0.57077,2.01893,0.00251
-3.06622,1.12651,-0.98474,-1.58890,-0.57075,2.01838,0.00251
-3.06741,1.12667,-0.98465,-1.58899,-0.57074,2.01822,0.00251
-3.06860,1.12721,-0.98437,-1.58932,-0.57070,2.01767,0.00251
-3.06979,1.12776,-0.98409,-1.58964,-0.57066,2.01713,0.00251
-3.07098,1.12797,-0.98398,-1.58977,-0.57064,2.01691,0.00251
-3.07217,1.12853,-0.98367,-1.59014,-0.57058,2.01635,0.00251
-3.07336,1.12909,-0.98337,-1.59051,-0.57052,2.01579,0.00251
-3.07455,1.12965,-0.98307,-1.59086,-0.57047,2.01523,0.00251
-3.07573,1.13020,-0.98278,-1.59122,-0.57042,2.01468,0.00251
-3.07692,1.13074,-0.98249,-1.59156,-0.57037,2.01413,0.00251
-3.07811,1.13129,-0.98220,-1.59190,-0.57032,2.01359,0.00252
-3.07930,1.13183,-0.98191,-1.59224,-0.57027,2.01305,0.00252
-3.08049,1.13237,-0.98163,-1.59257,-0.57022,2.01251,0.00252
-3.08168,1.13290,-0.98134,-1.59293,-0.57016,2.01197,0.00252
-3.08287,1.13348,-0.98094,-1.59353,-0.56997,2.01139,0.00252
-3.08406,1.13405,-0.98054,-1.59413,-0.56977,2.01082,0.00252
-3.08525,1.13462,-0.98015,-1.59472,-0.56958,2.01025,0.00252
-3.08643,1.13518,-0.97976,-1.59530,-0.56940,2.00968,0.00252
-3.08762,1.13574,-0.97938,-1.59587,-0.56922,2.00912,0.00252
-3.08881,1.13630,-0.97900,-1.59643,-0.56904,2.00856,0.00252
-3.09000,1.13685,-0.97862,-1.59698,-0.56887,2.00801,0.00253
-3.09119,1.13740,-0.97826,-1.59752,-0.56870,2.00745,0.00253
-3.09238,1.13795,-0.97789,-1.59805,-0.56854,2.00690,0.00253
-3.09357,1.13850,-0.97753,-1.59858,-0.56838,2.00636,0.00253
-3.09476,1.13904,-0.97718,-1.59909,-0.56822,2.00581,0.00253
-3.09595,1.13958,-0.97683,-1.59960,-0.56807,2.00527,0.00253
-3.09713,1.14011,-0.97648,-1.60010,-0.56792,2.00474,0.00253
-3.09832,1.14064,-0.97614,-1.60059,-0.56777,2.00420,0.00254
-3.09951,1.14117,-0.97581,-1.60107,-0.56763,2.00367,0.00254
-3.10070,1.14170,-0.97547,-1.60155,-0.56749,2.00314,0.00254
-3.10189,1.14222,-0.97515,-1.60202,-0.56735,2.00262,0.00254
-3.10308,1.14274,-0.97482,-1.60248,-0.56722,2.00209,0.00254
-3.10427,1.14326,-0.97450,-1.60293,-0.56709,2.00157,0.00254
-3.10546,1.14378,-0.97419,-1.60337,-0.56697,2.00106,0.00254
-3.10665,1.14429,-0.97387,-1.60381,-0.56685,2.00054,0.00255
-3.10783,1.14480,-0.97357,-1.60424,-0.56673,2.00003,0.00255
-3.10902,1.14530,-0.97326,-1.60467,-0.56661,1.99952,0.00255
-3.11021,1.14581,-0.97296,-1.60509,-0.56650,1.99902,0.00255
-3.11140,1.14631,-0.97266,-1.60550,-0.56639,1.99851,0.00255
-3.11259,1.14680,-0.97237,-1.60590,-0.56628,1.99801,0.00255
-3.11378,1.14730,-0.97208,-1.60630,-0.56617,1.99752,0.00256
-3.11497,1.14779,-0.97179,-1.60669,-0.56607,1.99702,0.00256
-3.11616,1.14828,-0.97151,-1.60707,-0.56597,1.99653,0.00256
-3.11735,1.14867,-0.97127,-1.60740,-0.56588,1.99613,0.00256
-3.11854,1.14920,-0.97089,-1.60801,-0.56566,1.99560,0.00256
-3.11972,1.14973,-0.97051,-1.60861,-0.56545,1.99508,0.00256
-3.12091,1.15025,-0.97013,-1.60920,-0.56524,1.99455,0.00257
-3.12210,1.15077,-0.96976,-1.60978,-0.56504,1.99403,0.00257
-3.12329,1.15128,-0.96939,-1.61035,-0.56484,1.99351,0.00257
-3.12448,1.15180,-0.96903,-1.61091,-0.56464,1.99300,0.00257
-3.12567,1.15231,-0.96868,-1.61146,-0.56445,1.99249,0.00257
-3.12686,1.15282,-0.96832,-1.61200,-0.56427,1.99198,0.00258
-3.12805,1.15332,-0.96797,-1.61254,-0.56408,1.99147,0.00258
-3.12924,1.15382,-0.96763,-1.61306,-0.56390,1.99096,0.00258
-3.13042,1.15432,-0.96729,-1.61358,-0.56373,1.99046,0.00258
-3.13161,1.15482,-0.96696,-1.61409,-0.56356,1.98996,0.00258
-3.13280,1.15531,-0.96663,-1.61459,-0.56339,1.98947,0.00259
-3.13399,1.15580,-0.96630,-1.61508,-0.56323,1.98897,0.00259
-3.13518,1.15629,-0.96598,-1.61556,-0.56307,1.98848,0.00259
-3.13637,1.15678,-0.96566,-1.61604,-0.56292,1.98799,0.00259
-3.13756,1.15726,-0.96535,-1.61651,-0.56277,1.98751,0.00259
-3.13875,1.15774,-0.96504,-1.61697,-0.56262,1.98702,0.00260
-3.13994,1.15822,-0.96473,-1.61742,-0.56247,1.98654,0.00260
-3.14112,1.15870,-0.96443,-1.61786,-0.56233,1.98607,0.00260
-3.14231,1.15917,-0.96413,-1.61830,-0.56220,1.98559,0.00260
-3.14350,1.15964,-0.96383,-1.61873,-0.56206,1.98512,0.00260
-3.14469,1.16011,-0.96354,-1.61916,-0.56193,1.98465,0.00261
-3.14588,1.16057,-0.96326,-1.61958,-0.56180,1.98418,0.00261
-3.14707,1.16104,-0.96297,-1.61999,-0.56168,1.98371,0.00261
-3.14826,1.16150,-0.96269,-1.62039,-0.56156,1.98325,0.00261
-3.14945,1.16160,-0.96262,-1.62050,-0.56152,1.98315,0.00261
-3.15064,1.16217,-0.96216,-1.62125,-0.56124,1.98258,0.00262
-3.15182,1.16274,-0.96170,-1.62197,-0.56097,1.98201,0.00262
-3.15301,1.16330,-0.96126,-1.62269,-0.56071,1.98144,0.00262
-3.15420,1.16386,-0.96081,-1.62340,-0.56045,1.98088,0.00262
-3.15539,1.16442,-0.96038,-1.62409,-0.56019,1.98032,0.00262
-3.15658,1.16498,-0.95995,-1.62477,-0.55995,1.97976,0.00263
-3.15777,1.16553,-0.95952,-1.62544,-0.55970,1.97921,0.00263
-3.15896,1.16608,-0.95911,-1.62610,-0.55947,1.97866,0.00263
-3.16015,1.16663,-0.95869,-1.62675,-0.55923,1.97811,0.00263
-3.16134,1.16717,-0.95829,-1.62739,-0.55901,1.97757,0.00264
-3.16253,1.16772,-0.95788,-1.62802,-0.55878,1.97703,0.00264
-3.16371,1.16825,-0.95749,-1.62863,-0.55857,1.97649,0.00264
-3.16490,1.16879,-0.95709,-1.62924,-0.55835,1.97595,0.00264
-3.16609,1.16932,-0.95671,-1.62984,-0.55815,1.97542,0.00265
-3.16728,1.16985,-0.95633,-1.63042,-0.55794,1.97488,0.00265
-3.16847,1.17038,-0.95595,-1.63100,-0.55775,1.97436,0.00265
-3.16966,1.17091,-0.95558,-1.63157,-0.55755,1.97383,0.00265
-3.17085,1.17143,-0.95521,-1.63213,-0.55736,1.97331,0.00266
-3.17204,1.17195,-0.95485,-1.63268,-0.55718,1.97279,0.00266
-3.17323,1.17246,-0.95449,-1.63322,-0.55700,1.97227,0.00266
-3.17441,1.17298,-0.95414,-1.63375,-0.55682,1.97175,0.00267
-3.17560,1.17349,-0.95379,-1.63427,-0.55665,1.97124,0.00267
-3.17679,1.17400,-0.95345,-1.63479,-0.55648,1.97073,0.00267
-3.17798,1.17450,-0.95311,-1.63529,-0.55632,1.97022,0.00267
-3.17917,1.17500,-0.95277,-1.63579,-0.55615,1.96972,0.00268
-3.18036,1.17550,-0.95244,-1.63628,-0.55600,1.96922,0.00268
-3.18155,1.17600,-0.95211,-1.63676,-0.55584,1.96872,0.00268
-3.18274,1.17650,-0.95179,-1.63723,-0.55570,1.96822,0.00268
-3.18393,1.17699,-0.95147,-1.63770,-0.55555,1.96773,0.00269
-3.18511,1.17748,-0.95116,-1.63816,-0.55541,1.96724,0.00269
-3.18630,1.17797,-0.95084,-1.63861,-0.55527,1.96675,0.00269
-3.18749,1.17845,-0.95054,-1.63905,-0.55513,1.96626,0.00269
-3.18868,1.17893,-0.95023,-1.63949,-0.55500,1.96578,0.00270
-3.18987,1.17941,-0.94993,-1.63992,-0.55487,1.96529,0.00270
-3.19106,1.17989,-0.94964,-1.64034,-0.55475,1.96481,0.00270
-3.19225,1.18037,-0.94935,-1.64076,-0.55463,1.96434,0.00270
-3.19344,1.18084,-0.94906,-1.64116,-0.55451,1.96386,0.00271
-3.19463,1.18131,-0.94877,-1.64157,-0.55439,1.96339,0.00271
-3.19582,1.18178,-0.94849,-1.64196,-0.55428,1.96292,0.00271
-3.19700,1.18224,-0.94821,-1.64235,-0.55417,1.96245,0.00272
-3.19819,1.18252,-0.94804,-1.64260,-0.55409,1.96217,0.00272
-3.19938,1.18303,-0.94767,-1.64316,-0.55390,1.96166,0.00272
-3.20057,1.18353,-0.94732,-1.64371,-0.55370,1.96116,0.00272
-3.20176,1.18403,-0.94696,-1.64426,-0.55352,1.96066,0.00272
-3.20295,1.18453,-0.94661,-1.64479,-0.55333,1.96016,0.00273
-3.20414,1.18503,-0.94627,-1.64532,-0.55315,1.95966,0.00273
-3.20533,1.18552,-0.94593,-1.64583,-0.55298,1.95917,0.00273
-3.20652,1.18601,-0.94560,-1.64634,-0.55281,1.95868,0.00274
-3.20770,1.18650,-0.94526,-1.64684,-0.55264,1.95819,0.00274
-3.20889,1.18698,-0.94494,-1.64733,-0.55248,1.95770,0.00274
-3.21008,1.18747,-0.94462,-1.64781,-0.55232,1.95722,0.00274
-3.21127,1.18795,-0.94430,-1.64829,-0.55216,1.95673,0.00275
-3.21246,1.18842,-0.94398,-1.64876,-0.55201,1.95625,0.00275
-3.21365,1.18890,-0.94367,-1.64922,-0.55186,1.95578,0.00275
-3.21484,1.18937,-0.94336,-1.64967,-0.55172,1.95530,0.00275
-3.21603,1.18984,-0.94306,-1.65012,-0.55158,1.95483,0.00276
-3.21722,1.19031,-0.94276,-1.65055,-0.55144,1.95436,0.00276
-3.21840,1.19078,-0.94247,-1.65098,-0.55131,1.95389,0.00276
-3.21959,1.19124,-0.94217,-1.65141,-0.55117,1.95343,0.00276
-3.22078,1.19170,-0.94188,-1.65182,-0.55105,1.95296,0.00277
-3.22197,1.19216,-0.94160,-1.65223,-0.55092,1.95250,0.00277
-3.22316,1.19262,-0.94132,-1.65264,-0.55080,1.95204,0.00277
-3.22435,1.19307,-0.94104,-1.65304,-0.55068,1.95159,0.00277
-3.22554,1.19348,-0.94079,-1.65340,-0.55058,1.95117,0.00278
-3.22673,1.19398,-0.94045,-1.65389,-0.55042,1.95068,0.00278
-3.22792,1.19447,-0.94012,-1.65437,-0.55027,1.95018,0.00278
-3.22910,1.19496,-0.93980,-1.65485,-0.55012,1.94969,0.00279
-3.23029,1.19545,-0.93948,-1.65531,-0.54997,1.94920,0.00279
-3.23148,1.19594,-0.93916,-1.65577,-0.54983,1.94872,0.00279
-3.23267,1.19642,-0.93885,-1.65622,-0.54969,1.94823,0.00279
-3.23386,1.19690,-0.93854,-1.65667,-0.54956,1.94775,0.00280
-3.23505,1.19738,-0.93824,-1.65711,-0.54942,1.94727,0.00280
-3.23624,1.19786,-0.93794,-1.65754,-0.54930,1.94679,0.00280
-3.23743,1.19833,-0.93764,-1.65796,-0.54917,1.94632,0.00280
-3.23862,1.19880,-0.93734,-1.65838,-0.54905,1.94584,0.00281
-3.23981,1.19927,-0.93705,-1.65879,-0.54893,1.94537,0.00281
-3.24099,1.19974,-0.93677,-1.65919,-0.54882,1.94491,0.00281
-3.24218,1.20020,-0.93648,-1.65958,-0.54870,1.94444,0.00281
-3.24337,1.20066,-0.93620,-1.65997,-0.54859,1.94398,0.00282
-3.24456,1.20112,-0.93593,-1.66036,-0.54849,1.94352,0.00282
-3.24575,1.20145,-0.93573,-1.66064,-0.54841,1.94319,0.00282
-3.24694,1.20192,-0.93539,-1.66116,-0.54822,1.94271,0.00282
-3.24813,1.20240,-0.93506,-1.66168,-0.54804,1.94224,0.00283
-3.24932,1.20287,-0.93473,-1.66219,-0.54786,1.94176,0.00283
-3.25051,1.20334,-0.93440,-1.66269,-0.54769,1.94129,0.00283
-3.25169,1.20381,-0.93408,-1.66318,-0.54752,1.94082,0.00283
-3.25288,1.20427,-0.93376,-1.66367,-0.54735,1.94036,0.00284
-3.25407,1.20473,-0.93345,-1.66414,-0.54719,1.93989,0.00284
-3.25526,1.20520,-0.93314,-1.66461,-0.54704,1.93943,0.00284
-3.25645,1.20565,-0.93284,-1.66507,-0.54688,1.93897,0.00284
-3.25764,1.20611,-0.93253,-1.66552,-0.54673,1.93851,0.00285
-3.25883,1.20656,-0.93224,-1.66597,-0.54658,1.93806,0.00285
-3.26002,1.20702,-0.93194,-1.66641,-0.54644,1.93760,0.00285
-3.26121,1.20747,-0.93165,-1.66684,-0.54630,1.93715,0.00286
-3.26239,1.20791,-0.93136,-1.66726,-0.54617,1.93670,0.00286
-3.26358,1.20836,-0.93108,-1.66768,-0.54603,1.93626,0.00286
-3.26477,1.20880,-0.93080,-1.66809,-0.54590,1.93581,0.00286
-3.26596,1.20924,-0.93052,-1.66849,-0.54578,1.93537,0.00287
-3.26715,1.20968,-0.93025,-1.66889,-0.54566,1.93493,0.00287
-3.26834,1.20977,-0.93019,-1.66898,-0.54562,1.93484,0.00287
-3.26953,1.21023,-0.92986,-1.66950,-0.54544,1.93438,0.00287
-3.27072,1.21068,-0.92954,-1.67001,-0.54525,1.93392,0.00287
-3.27191,1.21114,-0.92922,-1.67051,-0.54507,1.93347,0.00288
-3.27309,1.21159,-0.92891,-1.67100,-0.54490,1.93301,0.00288
-3.27428,1.21204,-0.92860,-1.67148,-0.54473,1.93256,0.00288
-3.27547,1.21248,-0.92829,-1.67196,-0.54456,1.93211,0.00288
-3.27666,1.21293,-0.92799,-1.67242,-0.54440,1.93167,0.00289
-3.27785,1.21337,-0.92769,-1.67288,-0.54424,1.93122,0.00289
-3.27904,1.21381,-0.92739,-1.67334,-0.54408,1.93078,0.00289
-3.28023,1.21425,-0.92710,-1.67378,-0.54393,1.93034,0.00289
-3.28142,1.21469,-0.92681,-1.67422,-0.54378,1.92990,0.00290
-3.28261,1.21512,-0.92652,-1.67465,-0.54364,1.92947,0.00290
-3.28380,1.21555,-0.92624,-1.67507,-0.54350,1.92903,0.00290
-3.28498,1.21598,-0.92597,-1.67549,-0.54336,1.92860,0.00290
-3.28617,1.21641,-0.92569,-1.67590,-0.54323,1.92817,0.00291
-3.28736,1.21680,-0.92544,-1.67628,-0.54310,1.92778,0.00291
-3.28855,1.21724,-0.92509,-1.67685,-0.54287,1.92734,0.00291
-3.28974,1.21768,-0.92476,-1.67742,-0.54265,1.92689,0.00291
-3.29093,1.21812,-0.92442,-1.67797,-0.54243,1.92645,0.00292
-3.29212,1.21856,-0.92409,-1.67852,-0.54222,1.92601,0.00292
-3.29331,1.21900,-0.92376,-1.67905,-0.54201,1.92557,0.00292
-3.29450,1.21943,-0.92344,-1.67958,-0.54181,1.92513,0.00292
-3.29568,1.21987,-0.92312,-1.68010,-0.54161,1.92470,0.00293
-3.29687,1.22030,-0.92281,-1.68061,-0.54141,1.92427,0.00293
-3.29806,1.22072,-0.92250,-1.68111,-0.54122,1.92384,0.00293
-3.29925,1.22115,-0.92219,-1.68161,-0.54104,1.92341,0.00293
-3.30044,1.22158,-0.92189,-1.68209,-0.54085,1.92298,0.00294
-3.30163,1.22200,-0.92159,-1.68257,-0.54068,1.92256,0.00294
-3.30282,1.22242,-0.92129,-1.68304,-0.54050,1.92213,0.00294
-3.30401,1.22284,-0.92100,-1.68350,-0.54033,1.92171,0.00294
-3.30520,1.22325,-0.92072,-1.68396,-0.54017,1.92129,0.00295
-3.30638,1.22367,-0.92043,-1.68440,-0.54001,1.92088,0.00295
-3.30757,1.22408,-0.92015,-1.68484,-0.53985,1.92046,0.00295
-3.30876,1.22449,-0.91987,-1.68527,-0.53969,1.92005,0.00295
-3.30995,1.22490,-0.91960,-1.68570,-0.53954,1.91964,0.00296
-3.31114,1.22531,-0.91933,-1.68612,-0.53940,1.91923,0.00296
-3.31233,1.22535,-0.91930,-1.68617,-0.53937,1.91919,0.00296
-3.31352,1.22575,-0.91898,-1.68673,-0.53914,1.91878,0.00296
-3.31471,1.22615,-0.91866,-1.68728,-0.53891,1.91838,0.00296
-3.31590,1.22655,-0.91835,-1.68782,-0.53868,1.91798,0.00297
-3.31708,1.22695,-0.91804,-1.68836,-0.53846,1.91758,0.00297
-3.31827,1.22734,-0.91773,-1.68888,-0.53824,1.91718,0.00297
-3.31946,1.22773,-0.91743,-1.68939,-0.53803,1.91678,0.00297
-3.32065,1.22813,-0.91713,-1.68990,-0.53782,1.91639,0.00298
-3.32184,1.22852,-0.91684,-1.69040,-0.53762,1.91599,0.00298
-3.32303,1.22890,-0.91655,-1.69089,-0.53742,1.91560,0.00298
-3.32422,1.22929,-0.91626,-1.69137,-0.53723,1.91521,0.00298
-3.32541,1.22968,-0.91598,-1.69184,-0.53704,1.91483,0.00299
-3.32660,1.23006,-0.91570,-1.69231,-0.53685,1.91444,0.00299
-3.32779,1.23044,-0.91543,-1.69276,-0.53667,1.91406,0.00299
-3.32897,1.23082,-0.91516,-1.69321,-0.53650,1.91367,0.00299
-3.33016,1.23120,-0.91489,-1.69366,-0.53632,1.91329,0.00300
-3.33135,1.23131,-0.91480,-1.69380,-0.53626,1.91318,0.00300
-3.33254,1.23168,-0.91448,-1.69438,-0.53600,1.91280,0.00300
-3.33373,1.23205,-0.91417,-1.69496,-0.53575,1.91243,0.00300
-3.33492,1.23242,-0.91386,-1.69552,-0.53550,1.91205,0.00300
-3.33611,1.23279,-0.91355,-1.69607,-0.53525,1.91168,0.00301
-3.33730,1.23316,-0.91325,-1.69661,-0.53501,1.91131,0.00301
-3.33849,1.23352,-0.91295,-1.69715,-0.53478,1.91094,0.00301
-3.33967,1.23389,-0.91266,-1.69767,-0.53455,1.91058,0.00301
-3.34086,1.23425,-0.91237,-1.69819,-0.53433,1.91021,0.00302
-3.34205,1.23461,-0.91208,-1.69870,-0.53411,1.90985,0.00302
-3.34324,1.23497,-0.91180,-1.69920,-0.53389,1.90949,0.00302
-3.34443,1.23532,-0.91152,-1.69969,-0.53368,1.90913,0.00302
-3.34562,1.23568,-0.91124,-1.70017,-0.53347,1.90877,0.00303
-3.34681,1.23603,-0.91097,-1.70065,-0.53327,1.90841,0.00303
-3.34800,1.23639,-0.91070,-1.70112,-0.53307,1.90805,0.00303
-3.34919,1.23674,-0.91043,-1.70157,-0.53288,1.90770,0.00303
-3.35037,1.23681,-0.91038,-1.70168,-0.53284,1.90763,0.00303
-3.35156,1.23715,-0.91007,-1.70225,-0.53257,1.90728,0.00304
-3.35275,1.23750,-0.90977,-1.70282,-0.53231,1.90693,0.00304
-3.35394,1.23784,-0.90947,-1.70337,-0.53206,1.90658,0.00304
-3.35513,1.23818,-0.90917,-1.70392,-0.53181,1.90624,0.00304
-3.35632,1.23853,-0.90888,-1.70445,-0.53156,1.90589,0.00304
-3.35751,1.23887,-0.90860,-1.70498,-0.53133,1.90555,0.00305
-3.35870,1.23920,-0.90831,-1.70550,-0.53109,1.90521,0.00305
-3.35989,1.23954,-0.90803,-1.70601,-0.53086,1.90486,0.00305
-3.36107,1.23988,-0.90776,-1.70651,-0.53064,1.90453,0.00305
-3.36226,1.24021,-0.90748,-1.70700,-0.53042,1.90419,0.00306
-3.36345,1.24054,-0.90722,-1.70749,-0.53020,1.90385,0.00306
-3.36464,1.24087,-0.90695,-1.70796,-0.52999,1.90352,0.00306
-3.36583,1.24114,-0.90674,-1.70835,-0.52982,1.90325,0.00306
-3.36702,1.24146,-0.90643,-1.70894,-0.52954,1.90292,0.00307
-3.36821,1.24179,-0.90613,-1.70951,-0.52927,1.90259,0.00307
-3.36940,1.24211,-0.90583,-1.71008,-0.52900,1.90226,0.00307
-3.37059,1.24243,-0.90554,-1.71064,-0.52874,1.90194,0.00307
-3.37178,1.24275,-0.90525,-1.71118,-0.52848,1.90161,0.00308
-3.37296,1.24307,-0.90497,-1.71172,-0.52823,1.90129,0.00308
-3.37415,1.24339,-0.90469,-1.71225,-0.52798,1.90097,0.00308
-3.37534,1.24371,-0.90441,-1.71277,-0.52774,1.90065,0.00308
-3.37653,1.24402,-0.90414,-1.71328,-0.52750,1.90033,0.00308
-3.37772,1.24434,-0.90387,-1.71378,-0.52727,1.90001,0.00309
-3.37891,1.24465,-0.90360,-1.71428,-0.52704,1.89969,0.00309
-3.38010,1.24496,-0.90334,-1.71476,-0.52682,1.89938,0.00309
-3.38129,1.24518,-0.90315,-1.71511,-0.52666,1.89916,0.00309
-3.38248,1.24549,-0.90286,-1.71568,-0.52638,1.89885,0.00310
-3.38366,1.24579,-0.90257,-1.71624,-0.52611,1.89853,0.00310
-3.38485,1.24610,-0.90229,-1.71679,-0.52585,1.89823,0.00310
-3.38604,1.24640,-0.90201,-1.71734,-0.52559,1.89792,0.00310
-3.38723,1.24671,-0.90173,-1.71787,-0.52533,1.89761,0.00311
-3.38842,1.24701,-0.90145,-1.71839,-0.52509,1.89730,0.00311
-3.38961,1.24731,-0.90118,-1.71891,-0.52484,1.89700,0.00311
-3.39080,1.24761,-0.90092,-1.71942,-0.52460,1.89670,0.00311
-3.39199,1.24790,-0.90066,-1.71991,-0.52437,1.89640,0.00311
-3.39318,1.24820,-0.90040,-1.72040,-0.52414,1.89610,0.00312
-3.39436,1.24829,-0.90032,-1.72055,-0.52407,1.89601,0.00312
-3.39555,1.24858,-0.90004,-1.72108,-0.52381,1.89571,0.00312
-3.39674,1.24888,-0.89977,-1.72160,-0.52356,1.89541,0.00312
-3.39793,1.24917,-0.89951,-1.72211,-0.52332,1.89512,0.00312
-3.39912,1.24946,-0.89925,-1.72262,-0.52308,1.89482,0.00313
-3.40031,1.24975,-0.89899,-1.72311,-0.52285,1.89453,0.00313
-3.40150,1.24983,-0.89891,-1.72326,-0.52277,1.89444,0.00313
-3.40269,1.25012,-0.89864,-1.72379,-0.52251,1.89415,0.00313
-3.40388,1.25041,-0.89837,-1.72432,-0.52226,1.89386,0.00313
-3.40506,1.25069,-0.89810,-1.72483,-0.52201,1.89357,0.00314
-3.40625,1.25097,-0.89784,-1.72534,-0.52177,1.89328,0.00314
-3.40744,1.25126,-0.89758,-1.72583,-0.52153,1.89300,0.00314
-3.40863,1.25137,-0.89748,-1.72603,-0.52144,1.89288,0.00314
-3.40982,1.25165,-0.89722,-1.72654,-0.52119,1.89260,0.00314
-3.41101,1.25193,-0.89696,-1.72704,-0.52095,1.89231,0.00315
-3.41220,1.25212,-0.89678,-1.72739,-0.52078,1.89212,0.00315
-3.41339,1.25240,-0.89652,-1.72790,-0.52053,1.89184,0.00315
-3.41458,1.25268,-0.89626,-1.72841,-0.52028,1.89156,0.00315
-3.41577,1.25287,-0.89608,-1.72876,-0.52012,1.89136,0.00315
-3.41695,1.25314,-0.89582,-1.72927,-0.51986,1.89108,0.00316
-3.41814,1.25341,-0.89556,-1.72977,-0.51962,1.89081,0.00316
-3.41933,1.25360,-0.89538,-1.73012,-0.51945,1.89061,0.00316
-3.42052,1.25387,-0.89512,-1.73064,-0.51919,1.89034,0.00316
-3.42171,1.25414,-0.89486,-1.73115,-0.51895,1.89007,0.00317
-3.42290,1.25433,-0.89469,-1.73150,-0.51877,1.88988,0.00317
-3.42409,1.25460,-0.89442,-1.73201,-0.51852,1.88961,0.00317
-3.42528,1.25486,-0.89417,-1.73252,-0.51827,1.88934,0.00317
-3.42647,1.25496,-0.89404,-1.73285,-0.51807,1.88923,0.00317
-3.42765,1.25433,-0.89428,-1.73310,-0.51759,1.88982,0.00317
-3.42884,1.25371,-0.89451,-1.73334,-0.51710,1.89041,0.00317
-3.43003,1.25308,-0.89475,-1.73359,-0.51663,1.89099,0.00317
-3.43122,1.25246,-0.89498,-1.73382,-0.51616,1.89158,0.00317
-3.43241,1.25184,-0.89521,-1.73405,-0.51570,1.89216,0.00317
-3.43360,1.25122,-0.89544,-1.73428,-0.51524,1.89275,0.00317
-3.43479,1.25061,-0.89567,-1.73450,-0.51479,1.89333,0.00317
-3.43598,1.24999,-0.89590,-1.73472,-0.51434,1.89391,0.00316
-3.43717,1.24938,-0.89613,-1.73493,-0.51390,1.89449,0.00316
-3.43835,1.24877,-0.89635,-1.73514,-0.51346,1.89507,0.00316
-3.43954,1.24816,-0.89658,-1.73535,-0.51304,1.89565,0.00316
-3.44073,1.24756,-0.89680,-1.73555,-0.51261,1.89622,0.00316
-3.44192,1.24695,-0.89702,-1.73574,-0.51219,1.89680,0.00316
-3.44311,1.24635,-0.89725,-1.73594,-0.51178,1.89737,0.00316
-3.44430,1.24575,-0.89746,-1.73613,-0.51137,1.89794,0.00316
-3.44549,1.24515,-0.89768,-1.73631,-0.51097,1.89851,0.00316
-3.44668,1.24455,-0.89790,-1.73649,-0.51057,1.89908,0.00316
-3.44787,1.24396,-0.89812,-1.73667,-0.51017,1.89965,0.00315
-3.44905,1.24337,-0.89833,-1.73684,-0.50979,1.90022,0.00315
-3.45024,1.24277,-0.89854,-1.73701,-0.50940,1.90078,0.00315
-3.45143,1.24219,-0.89876,-1.73717,-0.50902,1.90135,0.00315
-3.45262,1.24160,-0.89897,-1.73734,-0.50865,1.90191,0.00315
-3.45381,1.24101,-0.89918,-1.73749,-0.50828,1.90247,0.00315
-3.45500,1.24043,-0.89939,-1.73765,-0.50791,1.90303,0.00315
-3.45619,1.23985,-0.89959,-1.73780,-0.50755,1.90359,0.00315
-3.45738,1.23927,-0.89980,-1.73795,-0.50719,1.90414,0.00315
-3.45857,1.23870,-0.90001,-1.73810,-0.50684,1.90470,0.00315
-3.45976,1.23812,-0.90021,-1.73824,-0.50649,1.90525,0.00315
-3.46094,1.23755,-0.90041,-1.73838,-0.50615,1.90581,0.00315
-3.46213,1.23698,-0.90061,-1.73851,-0.50581,1.90636,0.00315
-3.46332,1.23641,-0.90082,-1.73865,-0.50547,1.90690,0.00315
-3.46451,1.23584,-0.90102,-1.73878,-0.50514,1.90745,0.00315
-3.46570,1.23528,-0.90121,-1.73890,-0.50481,1.90800,0.00314
-3.46689,1.23472,-0.90141,-1.73903,-0.50449,1.90854,0.00314
-3.46808,1.23416,-0.90161,-1.73915,-0.50417,1.90908,0.00314
-3.46927,1.23360,-0.90180,-1.73927,-0.50385,1.90962,0.00314
-3.47046,1.23305,-0.90200,-1.73939,-0.50354,1.91016,0.00314
-3.47164,1.23249,-0.90219,-1.73950,-0.50323,1.91070,0.00314
-3.47283,1.23194,-0.90238,-1.73961,-0.50292,1.91123,0.00314
-3.47402,1.23139,-0.90257,-1.73972,-0.50262,1.91177,0.00314
-3.47521,1.23084,-0.90276,-1.73983,-0.50232,1.91230,0.00314
-3.47640,1.23030,-0.90295,-1.73993,-0.50202,1.91283,0.00314
-3.47759,1.22976,-0.90314,-1.74003,-0.50173,1.91336,0.00314
-3.47878,1.22922,-0.90333,-1.74013,-0.50144,1.91388,0.00314
-3.47997,1.22868,-0.90351,-1.74023,-0.50116,1.91441,0.00314
-3.48116,1.22814,-0.90370,-1.74032,-0.50087,1.91493,0.00314
-3.48234,1.22757,-0.90390,-1.74041,-0.50058,1.91549,0.00314
-3.48353,1.22668,-0.90426,-1.74046,-0.50017,1.91635,0.00313
-3.48472,1.22580,-0.90462,-1.74051,-0.49976,1.91721,0.00313
-3.48591,1.22492,-0.90498,-1.74055,-0.49936,1.91806,0.00313
-3.48710,1.22404,-0.90533,-1.74059,-0.49896,1.91892,0.00313
-3.48829,1.22316,-0.90569,-1.74063,-0.49856,1.91977,0.00313
-3.48948,1.22229,-0.90604,-1.74067,-0.49817,1.92062,0.00313
-3.49067,1.22142,-0.90638,-1.74071,-0.49778,1.92147,0.00312
-3.49186,1.22056,-0.90673,-1.74075,-0.49740,1.92231,0.00312
-3.49304,1.21969,-0.90707,-1.74078,-0.49702,1.92315,0.00312
-3.49423,1.21884,-0.90741,-1.74081,-0.49664,1.92399,0.00312
-3.49542,1.21798,-0.90775,-1.74084,-0.49627,1.92482,0.00312
-3.49661,1.21713,-0.90809,-1.74087,-0.49590,1.92566,0.00311
-3.49780,1.21628,-0.90842,-1.74090,-0.49554,1.92648,0.00311
-3.49899,1.21543,-0.90876,-1.74093,-0.49518,1.92731,0.00311
-3.50018,1.21459,-0.90909,-1.74095,-0.49482,1.92814,0.00311
-3.50137,1.21375,-0.90942,-1.74097,-0.49446,1.92896,0.00311
-3.50256,1.21292,-0.90974,-1.74099,-0.49411,1.92977,0.00311
-3.50375,1.21209,-0.91007,-1.74101,-0.49376,1.93059,0.00311
-3.50493,1.21126,-0.91039,-1.74103,-0.49342,1.93140,0.00310
-3.50612,1.21043,-0.91071,-1.74105,-0.49308,1.93221,0.00310
-3.50731,1.20961,-0.91103,-1.74107,-0.49274,1.93302,0.00310
-3.50850,1.20879,-0.91134,-1.74108,-0.49241,1.93382,0.00310
-3.50969,1.20798,-0.91166,-1.74110,-0.49208,1.93462,0.00310
-3.51088,1.20717,-0.91197,-1.74111,-0.49175,1.93542,0.00310
-3.51207,1.20636,-0.91228,-1.74112,-0.49142,1.93621,0.00309
-3.51326,1.20555,-0.91259,-1.74113,-0.49110,1.93700,0.00309
-3.51445,1.20475,-0.91289,-1.74114,-0.49078,1.93779,0.00309
-3.51563,1.20395,-0.91320,-1.74115,-0.49047,1.93858,0.00309
-3.51682,1.20316,-0.91350,-1.74115,-0.49016,1.93936,0.00309
-3.51801,1.20237,-0.91380,-1.74116,-0.48985,1.94014,0.00309
-3.51920,1.20158,-0.91410,-1.74116,-0.48954,1.94091,0.00309
-3.52039,1.20080,-0.91440,-1.74117,-0.48924,1.94169,0.00308
-3.52158,1.20002,-0.91469,-1.74117,-0.48893,1.94246,0.00308
-3.52277,1.19924,-0.91498,-1.74117,-0.48864,1.94322,0.00308
-3.52396,1.19847,-0.91528,-1.74117,-0.48834,1.94399,0.00308
-3.52515,1.19770,-0.91557,-1.74117,-0.48805,1.94475,0.00308
-3.52633,1.19693,-0.91585,-1.74117,-0.48776,1.94550,0.00308
-3.52752,1.19617,-0.91614,-1.74117,-0.48747,1.94626,0.00308
-3.52871,1.19541,-0.91642,-1.74116,-0.48719,1.94701,0.00308
-3.52990,1.19465,-0.91670,-1.74116,-0.48691,1.94776,0.00307
-3.53109,1.19390,-0.91698,-1.74116,-0.48663,1.94850,0.00307
-3.53228,1.19315,-0.91726,-1.74115,-0.48635,1.94924,0.00307
-3.53347,1.19241,-0.91754,-1.74114,-0.48608,1.94998,0.00307
-3.53466,1.19167,-0.91781,-1.74114,-0.48580,1.95071,0.00307
-3.53585,1.19093,-0.91809,-1.74113,-0.48553,1.95145,0.00307
-3.53703,1.19019,-0.91836,-1.74112,-0.48527,1.95217,0.00307
-3.53822,1.18946,-0.91863,-1.74111,-0.48500,1.95290,0.00307
-3.53941,1.18873,-0.91890,-1.74110,-0.48474,1.95362,0.00307
-3.54060,1.18801,-0.91916,-1.74109,-0.48448,1.95434,0.00306
-3.54179,1.18729,-0.91943,-1.74108,-0.48422,1.95505,0.00306
-3.54298,1.18657,-0.91969,-1.74107,-0.48397,1.95577,0.00306
-3.54417,1.18585,-0.91995,-1.74105,-0.48372,1.95648,0.00306
-3.54536,1.18514,-0.92021,-1.74104,-0.48347,1.95718,0.00306
-3.54655,1.18444,-0.92047,-1.74103,-0.48322,1.95788,0.00306
-3.54774,1.18373,-0.92073,-1.74101,-0.48297,1.95858,0.00306
-3.54892,1.18303,-0.92098,-1.74100,-0.48273,1.95928,0.00306
-3.55011,1.18233,-0.92123,-1.74098,-0.48249,1.95997,0.00306
-3.55130,1.18164,-0.92149,-1.74097,-0.48225,1.96066,0.00305
-3.55249,1.18095,-0.92174,-1.74095,-0.48201,1.96135,0.00305
-3.55368,1.18026,-0.92199,-1.74093,-0.48178,1.96203,0.00305
-3.55487,1.17958,-0.92223,-1.74092,-0.48154,1.96271,0.00305
-3.55606,1.17890,-0.92248,-1.74090,-0.48131,1.96339,0.00305
-3.55725,1.17822,-0.92272,-1.74088,-0.48108,1.96406,0.00305
-3.55844,1.17755,-0.92296,-1.74086,-0.48086,1.96473,0.00305
-3.55962,1.17688,-0.92320,-1.74084,-0.48063,1.96540,0.00305
-3.56081,1.17622,-0.92344,-1.74082,-0.48041,1.96606,0.00305
-3.56200,1.17555,-0.92368,-1.74080,-0.48019,1.96672,0.00305
-3.56319,1.17489,-0.92392,-1.74078,-0.47997,1.96738,0.00305
-3.56438,1.17424,-0.92415,-1.74076,-0.47975,1.96803,0.00304
-3.56557,1.17358,-0.92438,-1.74074,-0.47954,1.96868,0.00304
-3.56676,1.17294,-0.92462,-1.74071,-0.47932,1.96933,0.00304
-3.56795,1.17229,-0.92485,-1.74069,-0.47911,1.96997,0.00304
-3.56914,1.17165,-0.92507,-1.74067,-0.47890,1.97061,0.00304
-3.57032,1.17101,-0.92530,-1.74065,-0.47869,1.97125,0.00304
-3.57151,1.17037,-0.92553,-1.74062,-0.47849,1.97189,0.00304
-3.57270,1.16974,-0.92575,-1.74060,-0.47828,1.97252,0.00304
-3.57389,1.16911,-0.92598,-1.74058,-0.47808,1.97315,0.00304
-3.57508,1.16848,-0.92620,-1.74055,-0.47788,1.97377,0.00304
-3.57627,1.16786,-0.92642,-1.74053,-0.47768,1.97439,0.00304
-3.57746,1.16724,-0.92664,-1.74050,-0.47748,1.97501,0.00303
-3.57865,1.16662,-0.92685,-1.74048,-0.47728,1.97563,0.00303
-3.57984,1.16601,-0.92707,-1.74045,-0.47709,1.97624,0.00303
-3.58102,1.16540,-0.92728,-1.74043,-0.47690,1.97685,0.00303
-3.58221,1.16479,-0.92750,-1.74040,-0.47671,1.97746,0.00303
-3.58340,1.16468,-0.92755,-1.74039,-0.47667,1.97757,0.00303
-3.58459,1.16351,-0.92807,-1.74028,-0.47625,1.97872,0.00303
-3.58578,1.16235,-0.92858,-1.74018,-0.47584,1.97987,0.00302
-3.58697,1.16119,-0.92909,-1.74007,-0.47544,1.98100,0.00302
-3.58816,1.16004,-0.92959,-1.73997,-0.47504,1.98214,0.00302
-3.58935,1.15889,-0.93009,-1.73986,-0.47464,1.98327,0.00302
-3.59054,1.15775,-0.93059,-1.73975,-0.47424,1.98439,0.00301
-3.59173,1.15662,-0.93109,-1.73965,-0.47385,1.98551,0.00301
-3.59291,1.15549,-0.93158,-1.73954,-0.47347,1.98662,0.00301
-3.59410,1.15437,-0.93206,-1.73944,-0.47308,1.98773,0.00300
-3.59529,1.15325,-0.93255,-1.73933,-0.47270,1.98883,0.00300
-3.59648,1.15214,-0.93302,-1.73923,-0.47232,1.98992,0.00300
-3.59767,1.15104,-0.93350,-1.73913,-0.47195,1.99102,0.00299
-3.59886,1.14994,-0.93397,-1.73902,-0.47158,1.99210,0.00299
-3.60005,1.14884,-0.93444,-1.73892,-0.47121,1.99318,0.00299
-3.60124,1.14776,-0.93490,-1.73881,-0.47085,1.99426,0.00299
-3.60243,1.14668,-0.93536,-1.73871,-0.47049,1.99533,0.00298
-3.60361,1.14560,-0.93582,-1.73861,-0.47013,1.99639,0.00298
-3.60480,1.14453,-0.93627,-1.73851,-0.46978,1.99745,0.00298
-3.60599,1.14347,-0.93672,-1.73840,-0.46943,1.99850,0.00297
-3.60718,1.14241,-0.93717,-1.73830,-0.46908,1.99955,0.00297
-3.60837,1.14135,-0.93761,-1.73820,-0.46873,2.00060,0.00297
-3.60956,1.14031,-0.93805,-1.73810,-0.46839,2.00163,0.00297
-3.61075,1.13927,-0.93849,-1.73800,-0.46805,2.00266,0.00296
-3.61194,1.13823,-0.93892,-1.73790,-0.46772,2.00369,0.00296
-3.61313,1.13720,-0.93935,-1.73780,-0.46739,2.00471,0.00296
-3.61431,1.13618,-0.93978,-1.73770,-0.46706,2.00573,0.00296
-3.61550,1.13516,-0.94020,-1.73760,-0.46673,2.00674,0.00296
-3.61669,1.13415,-0.94062,-1.73750,-0.46641,2.00774,0.00295
-3.61788,1.13314,-0.94104,-1.73740,-0.46608,2.00874,0.00295
-3.61907,1.13214,-0.94145,-1.73730,-0.46577,2.00974,0.00295
-3.62026,1.13115,-0.94186,-1.73720,-0.46545,2.01072,0.00295
-3.62145,1.13016,-0.94227,-1.73710,-0.46514,2.01171,0.00294
-3.62264,1.12918,-0.94267,-1.73701,-0.46483,2.01268,0.00294
-3.62383,1.12820,-0.94307,-1.73691,-0.46452,2.01366,0.00294
-3.62501,1.12723,-0.94347,-1.73681,-0.46422,2.01462,0.00294
-3.62620,1.12626,-0.94387,-1.73671,-0.46392,2.01558,0.00294
-3.62739,1.12530,-0.94426,-1.73662,-0.46362,2.01654,0.00293
-3.62858,1.12435,-0.94465,-1.73652,-0.46332,2.01749,0.00293
-3.62977,1.12340,-0.94503,-1.73643,-0.46303,2.01843,0.00293
-3.63096,1.12246,-0.94541,-1.73633,-0.46273,2.01937,0.00293
-3.63215,1.12152,-0.94579,-1.73624,-0.46245,2.02031,0.00293
-3.63334,1.12059,-0.94617,-1.73614,-0.46216,2.02124,0.00292
-3.63453,1.11966,-0.94654,-1.73605,-0.46188,2.02216,0.00292
-3.63572,1.11874,-0.94691,-1.73596,-0.46160,2.02308,0.00292
-3.63690,1.11783,-0.94728,-1.73586,-0.46132,2.02399,0.00292
-3.63809,1.11692,-0.94765,-1.73577,-0.46104,2.02490,0.00292
-3.63928,1.11602,-0.94801,-1.73568,-0.46077,2.02580,0.00291
-3.64047,1.11512,-0.94837,-1.73559,-0.46050,2.02669,0.00291
-3.64166,1.11423,-0.94872,-1.73550,-0.46023,2.02758,0.00291
-3.64285,1.11334,-0.94908,-1.73541,-0.45996,2.02847,0.00291
-3.64404,1.11246,-0.94943,-1.73531,-0.45970,2.02935,0.00291
-3.64523,1.11158,-0.94978,-1.73522,-0.45943,2.03023,0.00291
-3.64642,1.11071,-0.95012,-1.73513,-0.45918,2.03109,0.00290
-3.64760,1.10985,-0.95046,-1.73505,-0.45892,2.03196,0.00290
-3.64879,1.10899,-0.95080,-1.73496,-0.45866,2.03282,0.00290
-3.64998,1.10813,-0.95114,-1.73487,-0.45841,2.03367,0.00290
-3.65117,1.10728,-0.95148,-1.73478,-0.45816,2.03452,0.00290
-3.65236,1.10644,-0.95181,-1.73469,-0.45791,2.03536,0.00290
-3.65355,1.10560,-0.95214,-1.73461,-0.45767,2.03620,0.00290
-3.65474,1.10477,-0.95246,-1.73452,-0.45742,2.03703,0.00289
-3.65593,1.10394,-0.95279,-1.73443,-0.45718,2.03786,0.00289
-3.65712,1.10312,-0.95311,-1.73435,-0.45694,2.03868,0.00289
-3.65830,1.10231,-0.95343,-1.73426,-0.45670,2.03950,0.00289
-3.65949,1.10149,-0.95374,-1.73418,-0.45647,2.04031,0.00289
-3.66068,1.10069,-0.95406,-1.73409,-0.45623,2.04112,0.00289
-3.66187,1.09989,-0.95437,-1.73401,-0.45600,2.04192,0.00289
-3.66306,1.09909,-0.95468,-1.73393,-0.45577,2.04272,0.00288
-3.66425,1.09830,-0.95499,-1.73384,-0.45554,2.04351,0.00288
-3.66544,1.09752,-0.95529,-1.73376,-0.45532,2.04430,0.00288
-3.66663,1.09674,-0.95559,-1.73368,-0.45510,2.04508,0.00288
-3.66782,1.09596,-0.95589,-1.73360,-0.45487,2.04586,0.00288
-3.66900,1.09519,-0.95619,-1.73351,-0.45466,2.04663,0.00288
-3.67019,1.09443,-0.95648,-1.73343,-0.45444,2.04740,0.00288
-3.67138,1.09367,-0.95677,-1.73335,-0.45422,2.04816,0.00288
-3.67257,1.09291,-0.95706,-1.73327,-0.45401,2.04891,0.00287
-3.67376,1.09216,-0.95735,-1.73319,-0.45380,2.04967,0.00287
-3.67495,1.09142,-0.95764,-1.73311,-0.45359,2.05041,0.00287
-3.67614,1.09068,-0.95792,-1.73304,-0.45338,2.05115,0.00287
-3.67733,1.08995,-0.95820,-1.73296,-0.45317,2.05189,0.00287
-3.67852,1.08922,-0.95848,-1.73288,-0.45297,2.05262,0.00287
-3.67971,1.08849,-0.95876,-1.73280,-0.45276,2.05335,0.00287
-3.68089,1.08777,-0.95903,-1.73273,-0.45256,2.05407,0.00287
-3.68208,1.08706,-0.95930,-1.73265,-0.45236,2.05479,0.00287
-3.68327,1.08635,-0.95957,-1.73257,-0.45217,2.05551,0.00286
-3.68446,1.08564,-0.95984,-1.73250,-0.45197,2.05621,0.00286
-3.68565,1.08494,-0.96011,-1.73242,-0.45178,2.05692,0.00286
-3.68684,1.08425,-0.96037,-1.73235,-0.45158,2.05762,0.00286
-3.68803,1.08355,-0.96063,-1.73227,-0.45139,2.05831,0.00286
-3.68922,1.08287,-0.96089,-1.73220,-0.45120,2.05900,0.00286
-3.69041,1.08219,-0.96115,-1.73213,-0.45102,2.05969,0.00286
-3.69159,1.08151,-0.96140,-1.73205,-0.45083,2.06037,0.00286
-3.69278,1.08084,-0.96165,-1.73198,-0.45065,2.06104,0.00286
-3.69397,1.08017,-0.96190,-1.73191,-0.45046,2.06171,0.00286
-3.69516,1.07951,-0.96215,-1.73184,-0.45028,2.06238,0.00286
-3.69635,1.07885,-0.96240,-1.73177,-0.45010,2.06304,0.00285
-3.69754,1.07820,-0.96265,-1.73170,-0.44993,2.06370,0.00285
-3.69873,1.07755,-0.96289,-1.73163,-0.44975,2.06435,0.00285
-3.69992,1.07690,-0.96313,-1.73156,-0.44958,2.06500,0.00285
-3.70111,1.07634,-0.96335,-1.73149,-0.44942,2.06556,0.00285
-3.70229,1.07523,-0.96386,-1.73136,-0.44903,2.06666,0.00285
-3.70348,1.07413,-0.96437,-1.73123,-0.44865,2.06775,0.00284
-3.70467,1.07304,-0.96487,-1.73110,-0.44828,2.06883,0.00284
-3.70586,1.07195,-0.96537,-1.73097,-0.44791,2.06991,0.00284
-3.70705,1.07088,-0.96586,-1.73085,-0.44754,2.07098,0.00283
-3.70824,1.06981,-0.96635,-1.73072,-0.44718,2.07204,0.00283
-3.70943,1.06874,-0.96683,-1.73059,-0.44682,2.07310,0.00283
-3.71062,1.06769,-0.96731,-1.73046,-0.44646,2.07414,0.00283
-3.71181,1.06664,-0.96779,-1.73034,-0.44611,2.07518,0.00282
-3.71299,1.06560,-0.96826,-1.73021,-0.44576,2.07622,0.00282
-3.71418,1.06456,-0.96873,-1.73009,-0.44542,2.07724,0.00282
-3.71537,1.06354,-0.96919,-1.72997,-0.44508,2.07826,0.00281
-3.71656,1.06252,-0.96965,-1.72984,-0.44474,2.07928,0.00281
-3.71775,1.06151,-0.97010,-1.72972,-0.44441,2.08028,0.00281
-3.71894,1.06050,-0.97055,-1.72960,-0.44408,2.08128,0.00281
-3.72013,1.05951,-0.97100,-1.72948,-0.44375,2.08227,0.00280
-3.72132,1.05852,-0.97144,-1.72936,-0.44343,2.08326,0.00280
-3.72251,1.05753,-0.97187,-1.72924,-0.44311,2.08424,0.00280
-3.72370,1.05656,-0.97231,-1.72912,-0.44279,2.08521,0.00280
-3.72488,1.05559,-0.97274,-1.72900,-0.44248,2.08617,0.00280
-3.72607,1.05463,-0.97316,-1.72888,-0.44217,2.08713,0.00279
-3.72726,1.05367,-0.97358,-1.72877,-0.44186,2.08808,0.00279
-3.72845,1.05273,-0.97400,-1.72865,-0.44156,2.08903,0.00279
-3.72964,1.05178,-0.97441,-1.72854,-0.44126,2.08997,0.00279
-3.73083,1.05085,-0.97482,-1.72842,-0.44096,2.09090,0.00278
-3.73202,1.04992,-0.97522,-1.72831,-0.44066,2.09182,0.00278
-3.73321,1.04900,-0.97563,-1.72819,-0.44037,2.09274,0.00278
-3.73440,1.04809,-0.97602,-1.72808,-0.44008,2.09365,0.00278
-3.73558,1.04719,-0.97642,-1.72797,-0.43980,2.09455,0.00278
-3.73677,1.04629,-0.97681,-1.72786,-0.43952,2.09545,0.00277
-3.73796,1.04539,-0.97719,-1.72775,-0.43924,2.09634,0.00277
-3.73915,1.04451,-0.97758,-1.72764,-0.43896,2.09723,0.00277
-3.74034,1.04363,-0.97796,-1.72753,-0.43869,2.09811,0.00277
-3.74153,1.04276,-0.97833,-1.72742,-0.43842,2.09898,0.00277
-3.74272,1.04189,-0.97870,-1.72731,-0.43815,2.09985,0.00277
-3.74391,1.04103,-0.97907,-1.72720,-0.43789,2.10070,0.00276
-3.74510,1.04018,-0.97944,-1.72710,-0.43762,2.10156,0.00276
-3.74628,1.03933,-0.97980,-1.72699,-0.43736,2.10240,0.00276
-3.74747,1.03849,-0.98016,-1.72689,-0.43711,2.10324,0.00276
-3.74866,1.03766,-0.98051,-1.72678,-0.43685,2.10408,0.00276
-3.74985,1.03683,-0.98087,-1.72668,-0.43660,2.10491,0.00276
-3.75104,1.03601,-0.98121,-1.72658,-0.43635,2.10573,0.00275
-3.75223,1.03519,-0.98156,-1.72647,-0.43611,2.10654,0.00275
-3.75342,1.03439,-0.98190,-1.72637,-0.43586,2.10735,0.00275
-3.75461,1.03358,-0.98224,-1.72627,-0.43562,2.10816,0.00275
-3.75580,1.03279,-0.98257,-1.72617,-0.43538,2.10895,0.00275
-3.75698,1.03200,-0.98291,-1.72607,-0.43515,2.10975,0.00275
-3.75817,1.03121,-0.98324,-1.72597,-0.43491,2.11053,0.00275
-3.75936,1.03044,-0.98356,-1.72588,-0.43468,2.11131,0.00275
-3.76055,1.02967,-0.98388,-1.72578,-0.43445,2.11208,0.00274
-3.76174,1.02890,-0.98420,-1.72568,-0.43423,2.11285,0.00274
-3.76293,1.02814,-0.98452,-1.72558,-0.43400,2.11361,0.00274
-3.76412,1.02739,-0.98483,-1.72549,-0.43378,2.11437,0.00274
-3.76531,1.02664,-0.98515,-1.72539,-0.43356,2.11512,0.00274
-3.76650,1.02590,-0.98545,-1.72530,-0.43334,2.11586,0.00274
-3.76769,1.02516,-0.98576,-1.72521,-0.43313,2.11660,0.00274
-3.76887,1.02443,-0.98606,-1.72511,-0.43291,2.11733,0.00274
-3.77006,1.02371,-0.98636,-1.72502,-0.43270,2.11806,0.00274
-3.77125,1.02299,-0.98666,-1.72493,-0.43249,2.11878,0.00273
-3.77244,1.02228,-0.98695,-1.72484,-0.43229,2.11950,0.00273
-3.77363,1.02157,-0.98724,-1.72475,-0.43208,2.12021,0.00273
-3.77482,1.02087,-0.98753,-1.72466,-0.43188,2.12091,0.00273
-3.77601,1.02017,-0.98781,-1.72457,-0.43168,2.12161,0.00273
-3.77720,1.01948,-0.98810,-1.72448,-0.43148,2.12230,0.00273
-3.77839,1.01880,-0.98838,-1.72440,-0.43129,2.12299,0.00273
-3.77957,1.01812,-0.98865,-1.72431,-0.43109,2.12367,0.00273
-3.78076,1.01745,-0.98893,-1.72422,-0.43090,2.12435,0.00273
-3.78195,1.01678,-0.98920,-1.72414,-0.43071,2.12502,0.00273
-3.78314,1.01611,-0.98947,-1.72405,-0.43052,2.12569,0.00273
-3.78433,1.01546,-0.98974,-1.72397,-0.43034,2.12635,0.00273
-3.78552,1.01480,-0.99000,-1.72389,-0.43015,2.12701,0.00272
-3.78671,1.01431,-0.99021,-1.72382,-0.43001,2.12750,0.00272
-3.78790,1.01325,-0.99074,-1.72365,-0.42965,2.12855,0.00272
-3.78909,1.01220,-0.99126,-1.72348,-0.42930,2.12960,0.00272
-3.79027,1.01116,-0.99178,-1.72331,-0.42895,2.13063,0.00271
-3.79146,1.01013,-0.99229,-1.72314,-0.42860,2.13165,0.00271
-3.79265,1.00910,-0.99280,-1.72297,-0.42826,2.13267,0.00271
-3.79384,1.00809,-0.99330,-1.72281,-0.42792,2.13368,0.00271
-3.79503,1.00708,-0.99379,-1.72264,-0.42759,2.13468,0.00270
-3.79622,1.00608,-0.99429,-1.72248,-0.42726,2.13568,0.00270
-3.79741,1.00509,-0.99477,-1.72232,-0.42693,2.13666,0.00270
-3.79860,1.00411,-0.99525,-1.72216,-0.42661,2.13764,0.00270
-3.79979,1.00313,-0.99573,-1.72200,-0.42629,2.13861,0.00269
-3.80097,1.00217,-0.99620,-1.72184,-0.42597,2.13957,0.00269
-3.80216,1.00121,-0.99666,-1.72169,-0.42566,2.14053,0.00269
-3.80335,1.00026,-0.99712,-1.72153,-0.42536,2.14147,0.00269
-3.80454,0.99932,-0.99758,-1.72138,-0.42505,2.14241,0.00268
-3.80573,0.99838,-0.99803,-1.72122,-0.42475,2.14334,0.00268
-3.80692,0.99745,-0.99847,-1.72107,-0.42445,2.14427,0.00268
-3.80811,0.99654,-0.99891,-1.72092,-0.42416,2.14518,0.00268
-3.80930,0.99562,-0.99935,-1.72078,-0.42387,2.14609,0.00268
-3.81049,0.99472,-0.99978,-1.72063,-0.42358,2.14699,0.00267
-3.81168,0.99383,-1.00020,-1.72048,-0.42330,2.14789,0.00267
-3.81286,0.99294,-1.00063,-1.72034,-0.42302,2.14877,0.00267
-3.81405,0.99206,-1.00104,-1.72020,-0.42274,2.14965,0.00267
-3.81524,0.99118,-1.00146,-1.72005,-0.42247,2.15053,0.00267
-3.81643,0.99032,-1.00187,-1.71991,-0.42220,2.15139,0.00266
-3.81762,0.98946,-1.00227,-1.71977,-0.42193,2.15225,0.00266
-3.81881,0.98861,-1.00267,-1.71963,-0.42166,2.15310,0.00266
-3.82000,0.98776,-1.00307,-1.71950,-0.42140,2.15394,0.00266
-3.82119,0.98693,-1.00346,-1.71936,-0.42114,2.15478,0.00266
-3.82238,0.98610,-1.00384,-1.71923,-0.42089,2.15561,0.00266
-3.82356,0.98528,-1.00423,-1.71909,-0.42063,2.15643,0.00265
-3.82475,0.98446,-1.00461,-1.71896,-0.42038,2.15725,0.00265
-3.82594,0.98365,-1.00498,-1.71883,-0.42014,2.15805,0.00265
-3.82713,0.98285,-1.00535,-1.71870,-0.41989,2.15886,0.00265
-3.82832,0.98206,-1.00572,-1.71857,-0.41965,2.15965,0.00265
-3.82951,0.98127,-1.00608,-1.71844,-0.41941,2.16044,0.00265
-3.83070,0.98049,-1.00644,-1.71832,-0.41918,2.16122,0.00265
-3.83189,0.97972,-1.00680,-1.71819,-0.41894,2.16200,0.00265
-3.83308,0.97895,-1.00715,-1.71807,-0.41871,2.16276,0.00264
-3.83426,0.97819,-1.00750,-1.71794,-0.41849,2.16353,0.00264
-3.83545,0.97744,-1.00784,-1.71782,-0.41826,2.16428,0.00264
-3.83664,0.97669,-1.00818,-1.71770,-0.41804,2.16503,0.00264
-3.83783,0.97595,-1.00852,-1.71758,-0.41782,2.16577,0.00264
-3.83902,0.97521,-1.00885,-1.71746,-0.41760,2.16651,0.00264
-3.84021,0.97449,-1.00918,-1.71734,-0.41739,2.16724,0.00264
-3.84140,0.97377,-1.00950,-1.71723,-0.41717,2.16796,0.00264
-3.84259,0.97305,-1.00983,-1.71711,-0.41696,2.16868,0.00264
-3.84378,0.97234,-1.01015,-1.71700,-0.41675,2.16939,0.00264
-3.84496,0.97164,-1.01046,-1.71688,-0.41655,2.17009,0.00263
-3.84615,0.97095,-1.01077,-1.71677,-0.41635,2.17079,0.00263
-3.84734,0.97026,-1.01108,-1.71666,-0.41615,2.17148,0.00263
-3.84853,0.96957,-1.01139,-1.71655,-0.41595,2.17217,0.00263
-3.84972,0.96890,-1.01169,-1.71644,-0.41575,2.17285,0.00263
-3.85091,0.96822,-1.01199,-1.71633,-0.41556,2.17353,0.00263
-3.85210,0.96756,-1.01228,-1.71622,-0.41536,2.17419,0.00263
-3.85329,0.96690,-1.01258,-1.71612,-0.41517,2.17486,0.00263
-3.85448,0.96625,-1.01286,-1.71601,-0.41499,2.17551,0.00263
-3.85567,0.96560,-1.01315,-1.71591,-0.41480,2.17617,0.00263
-3.85685,0.96531,-1.01328,-1.71586,-0.41472,2.17645,0.00263
-3.85804,0.96439,-1.01376,-1.71569,-0.41441,2.17737,0.00263
-3.85923,0.96347,-1.01424,-1.71551,-0.41410,2.17829,0.00262
-3.86042,0.96256,-1.01471,-1.71534,-0.41380,2.17919,0.00262
-3.86161,0.96166,-1.01517,-1.71517,-0.41351,2.18009,0.00262
-3.86280,0.96077,-1.01563,-1.71501,-0.41322,2.18098,0.00262
-3.86399,0.95988,-1.01608,-1.71484,-0.41293,2.18186,0.00261
-3.86518,0.95901,-1.01653,-1.71468,-0.41264,2.18273,0.00261
-3.86637,0.95814,-1.01697,-1.71451,-0.41236,2.18360,0.00261
-3.86755,0.95728,-1.01740,-1.71435,-0.41208,2.18445,0.00261
-3.86874,0.95643,-1.01784,-1.71419,-0.41181,2.18530,0.00261
-3.86993,0.95558,-1.01826,-1.71404,-0.41154,2.18615,0.00260
-3.87112,0.95475,-1.01869,-1.71388,-0.41127,2.18698,0.00260
-3.87231,0.95392,-1.01910,-1.71372,-0.41100,2.18781,0.00260
-3.87350,0.95310,-1.01951,-1.71357,-0.41074,2.18863,0.00260
-3.87469,0.95228,-1.01992,-1.71342,-0.41048,2.18944,0.00260
-3.87588,0.95148,-1.02032,-1.71327,-0.41023,2.19025,0.00260
-3.87707,0.95068,-1.02072,-1.71312,-0.40998,2.19105,0.00259
-3.87825,0.94989,-1.02112,-1.71297,-0.40973,2.19184,0.00259
-3.87944,0.94910,-1.02151,-1.71283,-0.40948,2.19262,0.00259
-3.88063,0.94833,-1.02189,-1.71268,-0.40924,2.19340,0.00259
-3.88182,0.94756,-1.02227,-1.71254,-0.40900,2.19417,0.00259
-3.88301,0.94679,-1.02265,-1.71240,-0.40876,2.19493,0.00259
-3.88420,0.94604,-1.02302,-1.71226,-0.40853,2.19569,0.00259
-3.88539,0.94529,-1.02338,-1.71212,-0.40830,2.19643,0.00259
-3.88658,0.94455,-1.02375,-1.71198,-0.40807,2.19718,0.00258
-3.88777,0.94381,-1.02410,-1.71184,-0.40784,2.19791,0.00258
-3.88895,0.94309,-1.02446,-1.71171,-0.40762,2.19864,0.00258
-3.89014,0.94237,-1.02481,-1.71158,-0.40740,2.19936,0.00258
-3.89133,0.94165,-1.02516,-1.71144,-0.40718,2.20008,0.00258
-3.89252,0.94095,-1.02550,-1.71131,-0.40697,2.20079,0.00258
-3.89371,0.94025,-1.02584,-1.71118,-0.40675,2.20149,0.00258
-3.89490,0.93955,-1.02617,-1.71106,-0.40655,2.20218,0.00258
-3.89609,0.93886,-1.02650,-1.71093,-0.40634,2.20287,0.00258
-3.89728,0.93818,-1.02683,-1.71080,-0.40613,2.20356,0.00258
-3.89847,0.93751,-1.02715,-1.71068,-0.40593,2.20423,0.00257
-3.89966,0.93684,-1.02747,-1.71056,-0.40573,2.20490,0.00257
-3.90084,0.93618,-1.02779,-1.71043,-0.40554,2.20557,0.00257
-3.90203,0.93552,-1.02810,-1.71031,-0.40534,2.20623,0.00257
-3.90322,0.93487,-1.02841,-1.71019,-0.40515,2.20688,0.00257
-3.90441,0.93423,-1.02871,-1.71007,-0.40496,2.20752,0.00257
-3.90560,0.93362,-1.02901,-1.70996,-0.40477,2.20814,0.00257
-3.90679,0.93262,-1.02957,-1.70977,-0.40440,2.20913,0.00257
-3.90798,0.93162,-1.03012,-1.70958,-0.40404,2.21012,0.00256
-3.90917,0.93063,-1.03067,-1.70939,-0.40368,2.21110,0.00256
-3.91036,0.92966,-1.03121,-1.70920,-0.40333,2.21207,0.00256
-3.91154,0.92869,-1.03174,-1.70901,-0.40298,2.21303,0.00255
-3.91273,0.92774,-1.03227,-1.70883,-0.40264,2.21398,0.00255
-3.91392,0.92679,-1.03279,-1.70865,-0.40230,2.21492,0.00255
-3.91511,0.92585,-1.03330,-1.70847,-0.40196,2.21586,0.00255
-3.91630,0.92492,-1.03381,-1.70829,-0.40163,2.21678,0.00254
-3.91749,0.92400,-1.03431,-1.70811,-0.40131,2.21770,0.00254
-3.91868,0.92309,-1.03481,-1.70793,-0.40098,2.21860,0.00254
-3.91987,0.92219,-1.03530,-1.70776,-0.40067,2.21950,0.00254
-3.92106,0.92129,-1.03578,-1.70759,-0.40035,2.22039,0.00253
-3.92224,0.92041,-1.03626,-1.70742,-0.40004,2.22127,0.00253
-3.92343,0.91953,-1.03673,-1.70725,-0.39974,2.22215,0.00253
-3.92462,0.91867,-1.03720,-1.70708,-0.39944,2.22301,0.00253
-3.92581,0.91781,-1.03766,-1.70691,-0.39914,2.22387,0.00253
-3.92700,0.91696,-1.03811,-1.70675,-0.39885,2.22472,0.00252
-3.92819,0.91612,-1.03856,-1.70659,-0.39856,2.22556,0.00252
-3.92938,0.91528,-1.03901,-1.70642,-0.39828,2.22639,0.00252
-3.93057,0.91446,-1.03944,-1.70626,-0.39800,2.22721,0.00252
-3.93176,0.91364,-1.03988,-1.70611,-0.39772,2.22803,0.00252
-3.93294,0.91283,-1.04030,-1.70595,-0.39744,2.22883,0.00251
-3.93413,0.91203,-1.04073,-1.70580,-0.39717,2.22963,0.00251
-3.93532,0.91124,-1.04114,-1.70564,-0.39691,2.23043,0.00251
-3.93651,0.91046,-1.04155,-1.70549,-0.39665,2.23121,0.00251
-3.93770,0.90968,-1.04196,-1.70534,-0.39639,2.23199,0.00251
-3.93889,0.90891,-1.04236,-1.70519,-0.39613,2.23275,0.00251
-3.94008,0.90815,-1.04276,-1.70504,-0.39588,2.23352,0.00251
-3.94127,0.90739,-1.04315,-1.70490,-0.39563,2.23427,0.00251
-3.94246,0.90665,-1.04354,-1.70475,-0.39538,2.23502,0.00250
-3.94365,0.90591,-1.04392,-1.70461,-0.39514,2.23576,0.00250
-3.94483,0.90518,-1.04430,-1.70447,-0.39490,2.23649,0.00250
-3.94602,0.90446,-1.04467,-1.70433,-0.39466,2.23721,0.00250
-3.94721,0.90374,-1.04504,-1.70419,-0.39443,2.23793,0.00250
-3.94840,0.90303,-1.04541,-1.70405,-0.39420,2.23864,0.00250
-3.94959,0.90233,-1.04577,-1.70392,-0.39397,2.23934,0.00250
-3.95078,0.90163,-1.04612,-1.70378,-0.39375,2.24004,0.00250
-3.95197,0.90095,-1.04647,-1.70365,-0.39353,2.24073,0.00250
-3.95316,0.90027,-1.04682,-1.70352,-0.39331,2.24141,0.00250
-3.95435,0.89959,-1.04716,-1.70339,-0.39309,2.24209,0.00250
-3.95553,0.89892,-1.04750,-1.70326,-0.39288,2.24276,0.00250
-3.95672,0.89826,-1.04783,-1.70313,-0.39267,2.24342,0.00249
-3.95791,0.89761,-1.04816,-1.70300,-0.39247,2.24408,0.00249
-3.95910,0.89696,-1.04849,-1.70288,-0.39226,2.24472,0.00249
-3.96029,0.89632,-1.04881,-1.70276,-0.39206,2.24537,0.00249
-3.96148,0.89569,-1.04913,-1.70263,-0.39186,2.24600,0.00249
-3.96267,0.89503,-1.04947,-1.70250,-0.39165,2.24667,0.00249
-3.96386,0.89404,-1.05005,-1.70227,-0.39129,2.24764,0.00249
-3.96505,0.89307,-1.05063,-1.70204,-0.39094,2.24861,0.00249
-3.96623,0.89211,-1.05120,-1.70182,-0.39059,2.24957,0.00248
-3.96742,0.89116,-1.05177,-1.70160,-0.39025,2.25051,0.00248
-3.96861,0.89022,-1.05232,-1.70138,-0.38991,2.25145,0.00248
-3.96980,0.88929,-1.05287,-1.70116,-0.38958,2.25237,0.00247
-3.97099,0.88836,-1.05341,-1.70094,-0.38925,2.25329,0.00247
-3.97218,0.88745,-1.05395,-1.70073,-0.38893,2.25420,0.00247
-3.97337,0.88655,-1.05448,-1.70052,-0.38861,2.25510,0.00247
-3.97456,0.88565,-1.05500,-1.70031,-0.38829,2.25599,0.00246
-3.97575,0.88477,-1.05551,-1.70010,-0.38798,2.25687,0.00246
-3.97693,0.88390,-1.05602,-1.69990,-0.38768,2.25774,0.00246
-3.97812,0.88303,-1.05652,-1.69970,-0.38738,2.25860,0.00246
-3.97931,0.88218,-1.05701,-1.69950,-0.38708,2.25946,0.00246
-3.98050,0.88133,-1.05750,-1.69930,-0.38679,2.26030,0.00245
-3.98169,0.88049,-1.05798,-1.69911,-0.38650,2.26114,0.00245
-3.98288,0.87966,-1.05846,-1.69891,-0.38621,2.26196,0.00245
-3.98407,0.87884,-1.05893,-1.69872,-0.38593,2.26278,0.00245
-3.98526,0.87803,-1.05939,-1.69853,-0.38566,2.26359,0.00245
-3.98645,0.87723,-1.05985,-1.69834,-0.38538,2.26439,0.00245
-3.98764,0.87643,-1.06030,-1.69816,-0.38511,2.26519,0.00244
-3.98882,0.87565,-1.06075,-1.69798,-0.38485,2.26597,0.00244
-3.99001,0.87487,-1.06119,-1.69780,-0.38459,2.26675,0.00244
-3.99120,0.87410,-1.06162,-1.69762,-0.38433,2.26752,0.00244
-3.99239,0.87334,-1.06205,-1.69744,-0.38408,2.26828,0.00244
-3.99358,0.87258,-1.06247,-1.69726,-0.38382,2.26903,0.00244
-3.99477,0.87184,-1.06289,-1.69709,-0.38358,2.26978,0.00244
-3.99596,0.87110,-1.06330,-1.69692,-0.38333,2.27052,0.00244
-3.99715,0.87037,-1.06371,-1.69675,-0.38309,2.27125,0.00244
-3.99834,0.86965,-1.06411,-1.69658,-0.38286,2.27197,0.00243
-3.99952,0.86894,-1.06450,-1.69642,-0.38262,2.27268,0.00243
-4.00071,0.86823,-1.06489,-1.69625,-0.38239,2.27339,0.00243
-4.00190,0.86753,-1.06528,-1.69609,-0.38216,2.27409,0.00243
-4.00309,0.86684,-1.06566,-1.69593,-0.38194,2.27478,0.00243
-4.00428,0.86616,-1.06604,-1.69577,-0.38172,2.27546,0.00243
-4.00547,0.86548,-1.06641,-1.69562,-0.38150,2.27614,0.00243
-4.00666,0.86482,-1.06677,-1.69546,-0.38129,2.27681,0.00243
-4.00785,0.86415,-1.06714,-1.69531,-0.38107,2.27748,0.00243
-4.00904,0.86350,-1.06749,-1.69516,-0.38086,2.27813,0.00243
-4.01022,0.86285,-1.06784,-1.69501,-0.38066,2.27878,0.00243
-4.01141,0.86221,-1.06819,-1.69486,-0.38046,2.27942,0.00243
-4.01260,0.86158,-1.06853,-1.69472,-0.38025,2.28006,0.00243
-4.01379,0.86095,-1.06887,-1.69457,-0.38006,2.28069,0.00243
-4.01498,0.86033,-1.06921,-1.69443,-0.37986,2.28131,0.00243
-4.01617,0.85975,-1.06953,-1.69429,-0.37968,2.28189,0.00243
-4.01736,0.85886,-1.07008,-1.69406,-0.37936,2.28278,0.00242
-4.01855,0.85798,-1.07063,-1.69383,-0.37904,2.28366,0.00242
-4.01974,0.85711,-1.07117,-1.69360,-0.37873,2.28452,0.00242
-4.02092,0.85625,-1.07170,-1.69337,-0.37842,2.28538,0.00242
-4.02211,0.85540,-1.07222,-1.69314,-0.37812,2.28623,0.00241
-4.02330,0.85456,-1.07274,-1.69292,-0.37782,2.28707,0.00241
-4.02449,0.85372,-1.07325,-1.69270,-0.37753,2.28790,0.00241
-4.02568,0.85290,-1.07376,-1.69248,-0.37724,2.28872,0.00241
-4.02687,0.85209,-1.07425,-1.69227,-0.37695,2.28953,0.00241
-4.02806,0.85128,-1.07475,-1.69206,-0.37667,2.29033,0.00240
-4.02925,0.85048,-1.07523,-1.69185,-0.37640,2.29113,0.00240
-4.03044,0.84970,-1.07571,-1.69164,-0.37613,2.29191,0.00240
-4.03163,0.84892,-1.07618,-1.69144,-0.37586,2.29269,0.00240
-4.03281,0.84815,-1.07664,-1.69123,-0.37559,2.29346,0.00240
-4.03400,0.84739,-1.07710,-1.69103,-0.37533,2.29422,0.00240
-4.03519,0.84663,-1.07755,-1.69083,-0.37507,2.29497,0.00240
-4.03638,0.84589,-1.07800,-1.69064,-0.37482,2.29572,0.00239
-4.03757,0.84515,-1.07844,-1.69045,-0.37457,2.29645,0.00239
-4.03876,0.84442,-1.07887,-1.69026,-0.37433,2.29718,0.00239
-4.03995,0.84370,-1.07930,-1.69007,-0.37408,2.29790,0.00239
-4.04114,0.84299,-1.07972,-1.68988,-0.37384,2.29861,0.00239
-4.04233,0.84229,-1.08014,-1.68970,-0.37361,2.29932,0.00239
-4.04351,0.84159,-1.08055,-1.68951,-0.37338,2.30001,0.00239
-4.04470,0.84090,-1.08095,-1.68933,-0.37315,2.30070,0.00239
-4.04589,0.84022,-1.08135,-1.68916,-0.37292,2.30138,0.00239
-4.04708,0.83955,-1.08175,-1.68898,-0.37270,2.30206,0.00239
-4.04827,0.83888,-1.08214,-1.68881,-0.37248,2.30272,0.00239
-4.04946,0.83823,-1.08252,-1.68864,-0.37227,2.30338,0.00239
-4.05065,0.83758,-1.08290,-1.68847,-0.37205,2.30404,0.00238
-4.05184,0.83693,-1.08327,-1.68830,-0.37185,2.30468,0.00238
-4.05303,0.83630,-1.08364,-1.68813,-0.37164,2.30532,0.00238
-4.05421,0.83567,-1.08401,-1.68797,-0.37144,2.30595,0.00238
-4.05540,0.83505,-1.08436,-1.68781,-0.37123,2.30657,0.00238
-4.05659,0.83443,-1.08472,-1.68765,-0.37104,2.30719,0.00238
-4.05778,0.83383,-1.08507,-1.68749,-0.37084,2.30780,0.00238
-4.05897,0.83322,-1.08541,-1.68733,-0.37065,2.30840,0.00238
-4.06016,0.83286,-1.08565,-1.68722,-0.37052,2.30876,0.00238
-4.06135,0.83102,-1.08705,-1.68659,-0.36977,2.31057,0.00237
-4.06254,0.82921,-1.08842,-1.68596,-0.36903,2.31236,0.00236
-4.06373,0.82742,-1.08978,-1.68534,-0.36830,2.31412,0.00235
-4.06491,0.82565,-1.09111,-1.68472,-0.36758,2.31587,0.00234
-4.06610,0.82390,-1.09243,-1.68411,-0.36688,2.31759,0.00233
-4.06729,0.82218,-1.09373,-1.68351,-0.36619,2.31929,0.00232
-4.06848,0.82047,-1.09501,-1.68291,-0.36551,2.32097,0.00231
-4.06967,0.81879,-1.09627,-1.68232,-0.36484,2.32263,0.00230
-4.07086,0.81713,-1.09751,-1.68174,-0.36419,2.32427,0.00229
-4.07205,0.81549,-1.09874,-1.68116,-0.36354,2.32589,0.00228
-4.07324,0.81388,-1.09995,-1.68059,-0.36291,2.32748,0.00227
-4.07443,0.81228,-1.10114,-1.68003,-0.36228,2.32906,0.00226
-4.07562,0.81070,-1.10232,-1.67947,-0.36167,2.33062,0.00225
-4.07680,0.80915,-1.10347,-1.67891,-0.36106,2.33216,0.00225
-4.07799,0.80761,-1.10462,-1.67837,-0.36047,2.33368,0.00224
-4.07918,0.80610,-1.10574,-1.67783,-0.35989,2.33518,0.00223
-4.08037,0.80460,-1.10685,-1.67729,-0.35931,2.33666,0.00222
-4.08156,0.80312,-1.10794,-1.67676,-0.35875,2.33813,0.00222
-4.08275,0.80166,-1.10902,-1.67624,-0.35820,2.33957,0.00221
-4.08394,0.80022,-1.11008,-1.67572,-0.35765,2.34100,0.00221
-4.08513,0.79880,-1.11113,-1.67521,-0.35711,2.34241,0.00220
-4.08632,0.79740,-1.11216,-1.67471,-0.35659,2.34380,0.00219
-4.08750,0.79602,-1.11318,-1.67421,-0.35607,2.34518,0.00219
-4.08869,0.79465,-1.11418,-1.67372,-0.35556,2.34654,0.00218
-4.08988,0.79330,-1.11517,-1.67323,-0.35506,2.34788,0.00218
-4.09107,0.79197,-1.11614,-1.67275,-0.35456,2.34920,0.00217
-4.09226,0.79065,-1.11710,-1.67227,-0.35408,2.35050,0.00217
-4.09345,0.78936,-1.11805,-1.67180,-0.35360,2.35179,0.00216
-4.09464,0.78808,-1.11898,-1.67134,-0.35313,2.35307,0.00216
-4.09583,0.78681,-1.11990,-1.67088,-0.35267,2.35433,0.00216
-4.09702,0.78556,-1.12080,-1.67042,-0.35222,2.35557,0.00215
-4.09820,0.78433,-1.12169,-1.66997,-0.35177,2.35679,0.00215
-4.09939,0.78312,-1.12257,-1.66953,-0.35134,2.35800,0.00214
-4.10058,0.78192,-1.12344,-1.66909,-0.35090,2.35920,0.00214
-4.10177,0.78073,-1.12429,-1.66866,-0.35048,2.36038,0.00214
-4.10296,0.77957,-1.12513,-1.66823,-0.35006,2.36154,0.00214
-4.10415,0.77841,-1.12596,-1.66781,-0.34965,2.36269,0.00213
-4.10534,0.77727,-1.12678,-1.66739,-0.34925,2.36383,0.00213
-4.10653,0.77615,-1.12758,-1.66698,-0.34885,2.36495,0.00213
-4.10772,0.77504,-1.12838,-1.66657,-0.34846,2.36606,0.00213
-4.10891,0.77395,-1.12916,-1.66617,-0.34808,2.36715,0.00212
-4.11009,0.77287,-1.12993,-1.66578,-0.34770,2.36823,0.00212
-4.11128,0.77180,-1.13069,-1.66538,-0.34733,2.36930,0.00212
-4.11247,0.77075,-1.13144,-1.66500,-0.34697,2.37035,0.00212
-4.11366,0.76971,-1.13217,-1.66461,-0.34661,2.37139,0.00212
-4.11485,0.76868,-1.13290,-1.66424,-0.34625,2.37241,0.00211
-4.11604,0.76767,-1.13362,-1.66386,-0.34591,2.37342,0.00211
-4.11723,0.76667,-1.13432,-1.66350,-0.34556,2.37442,0.00211
-4.11842,0.76569,-1.13502,-1.66313,-0.34523,2.37541,0.00211
-4.11961,0.76471,-1.13570,-1.66277,-0.34490,2.37638,0.00211
-4.12079,0.76375,-1.13638,-1.66242,-0.34457,2.37734,0.00211
-4.12198,0.76281,-1.13704,-1.66207,-0.34425,2.37829,0.00211
-4.12317,0.76187,-1.13770,-1.66172,-0.34394,2.37923,0.00211
-4.12436,0.76095,-1.13834,-1.66138,-0.34363,2.38015,0.00211
-4.12555,0.76004,-1.13898,-1.66105,-0.34332,2.38107,0.00211
-4.12674,0.75914,-1.13960,-1.66071,-0.34303,2.38197,0.00211
-4.12793,0.75825,-1.14022,-1.66039,-0.34273,2.38286,0.00211
-4.12912,0.75737,-1.14083,-1.66006,-0.34244,2.38374,0.00211
-4.13031,0.75651,-1.14143,-1.65974,-0.34216,2.38460,0.00211
-4.13149,0.75566,-1.14202,-1.65943,-0.34188,2.38546,0.00211
-4.13268,0.75482,-1.14260,-1.65911,-0.34160,2.38631,0.00211
-4.13387,0.75398,-1.14318,-1.65881,-0.34133,2.38714,0.00211
-4.13506,0.75316,-1.14374,-1.65850,-0.34106,2.38796,0.00211
-4.13625,0.75235,-1.14430,-1.65820,-0.34080,2.38878,0.00211
-4.13744,0.75156,-1.14485,-1.65791,-0.34054,2.38958,0.00211
-4.13863,0.75077,-1.14539,-1.65761,-0.34029,2.39037,0.00211
-4.13982,0.74999,-1.14592,-1.65733,-0.34004,2.39115,0.00211
-4.14101,0.74922,-1.14644,-1.65704,-0.33979,2.39193,0.00211
-4.14219,0.74846,-1.14696,-1.65676,-0.33955,2.39269,0.00211
-4.14338,0.74771,-1.14747,-1.65648,-0.33931,2.39344,0.00211
-4.14457,0.74698,-1.14797,-1.65621,-0.33908,2.39418,0.00211
-4.14576,0.74625,-1.14847,-1.65594,-0.33885,2.39492,0.00211
-4.14695,0.74553,-1.14895,-1.65567,-0.33862,2.39564,0.00211
-4.14814,0.74482,-1.14943,-1.65541,-0.33840,2.39636,0.00211
-4.14933,0.74412,-1.14991,-1.65515,-0.33818,2.39706,0.00212
-4.15052,0.74343,-1.15037,-1.65490,-0.33796,2.39776,0.00212
-4.15171,0.74274,-1.15083,-1.65464,-0.33775,2.39845,0.00212
-4.15290,0.74207,-1.15128,-1.65440,-0.33754,2.39913,0.00212
-4.15408,0.74140,-1.15173,-1.65415,-0.33733,2.39980,0.00212
-4.15527,0.74075,-1.15217,-1.65391,-0.33713,2.40046,0.00212
-4.15646,0.74010,-1.15260,-1.65367,-0.33693,2.40111,0.00212
-4.15765,0.73946,-1.15303,-1.65343,-0.33674,2.40175,0.00212
-4.15884,0.73883,-1.15345,-1.65320,-0.33654,2.40239,0.00213
-4.16003,0.73821,-1.15386,-1.65297,-0.33636,2.40302,0.00213
-4.16122,0.73759,-1.15427,-1.65274,-0.33617,2.40364,0.00213
-4.16241,0.73699,-1.15467,-1.65252,-0.33599,2.40425,0.00213
-4.16360,0.73639,-1.15507,-1.65230,-0.33580,2.40486,0.00213
-4.16478,0.73580,-1.15546,-1.65208,-0.33563,2.40545,0.00213
-4.16597,0.73522,-1.15584,-1.65186,-0.33545,2.40604,0.00214
-4.16716,0.73464,-1.15622,-1.65165,-0.33528,2.40662,0.00214
-4.16835,0.73407,-1.15659,-1.65144,-0.33511,2.40720,0.00214
-4.16954,0.73351,-1.15696,-1.65124,-0.33494,2.40776,0.00214
-4.17073,0.73298,-1.15732,-1.65104,-0.33478,2.40830,0.00214
-4.17192,0.73210,-1.15801,-1.65067,-0.33446,2.40917,0.00214
-4.17311,0.73124,-1.15868,-1.65030,-0.33415,2.41003,0.00214
-4.17430,0.73039,-1.15935,-1.64994,-0.33384,2.41089,0.00214
-4.17548,0.72954,-1.16001,-1.64958,-0.33353,2.41173,0.00213
-4.17667,0.72871,-1.16066,-1.64923,-0.33323,2.41256,0.00213
-4.17786,0.72790,-1.16129,-1.64889,-0.33294,2.41337,0.00213
-4.17905,0.72709,-1.16192,-1.64855,-0.33265,2.41418,0.00213
-4.18024,0.72629,-1.16254,-1.64821,-0.33237,2.41498,0.00213
-4.18143,0.72550,-1.16315,-1.64788,-0.33209,2.41576,0.00213
-4.18262,0.72473,-1.16375,-1.64755,-0.33181,2.41654,0.00212
-4.18381,0.72396,-1.16434,-1.64722,-0.33154,2.41730,0.00212
-4.18500,0.72321,-1.16492,-1.64690,-0.33128,2.41806,0.00212
-4.18618,0.72247,-1.16549,-1.64659,-0.33102,2.41881,0.00212
-4.18737,0.72173,-1.16605,-1.64628,-0.33076,2.41954,0.00212
-4.18856,0.72101,-1.16661,-1.64597,-0.33051,2.42027,0.00212
-4.18975,0.72029,-1.16716,-1.64567,-0.33026,2.42098,0.00212
-4.19094,0.71959,-1.16769,-1.64537,-0.33002,2.42169,0.00212
-4.19213,0.71889,-1.16822,-1.64507,-0.32978,2.42239,0.00212
-4.19332,0.71820,-1.16875,-1.64478,-0.32955,2.42308,0.00212
-4.19451,0.71753,-1.16926,-1.64450,-0.32932,2.42375,0.00212
-4.19570,0.71686,-1.16977,-1.64421,-0.32909,2.42442,0.00212
-4.19689,0.71620,-1.17027,-1.64393,-0.32887,2.42509,0.00212
-4.19807,0.71555,-1.17076,-1.64366,-0.32865,2.42574,0.00212
-4.19926,0.71491,-1.17124,-1.64339,-0.32843,2.42638,0.00212
-4.20045,0.71428,-1.17172,-1.64312,-0.32822,2.42702,0.00212
-4.20164,0.71365,-1.17218,-1.64286,-0.32801,2.42764,0.00212
-4.20283,0.71304,-1.17264,-1.64259,-0.32781,2.42826,0.00212
-4.20402,0.71243,-1.17310,-1.64234,-0.32760,2.42887,0.00212
-4.20521,0.71183,-1.17355,-1.64208,-0.32741,2.42947,0.00212
-4.20640,0.71124,-1.17399,-1.64183,-0.32721,2.43007,0.00212
-4.20759,0.71066,-1.17442,-1.64159,-0.32702,2.43066,0.00212
-4.20877,0.71008,-1.17485,-1.64134,-0.32683,2.43123,0.00212
-4.20996,0.70951,-1.17527,-1.64110,-0.32665,2.43180,0.00212
-4.21115,0.70895,-1.17568,-1.64087,-0.32646,2.43237,0.00213
-4.21234,0.70840,-1.17609,-1.64063,-0.32628,2.43292,0.00213
-4.21353,0.70786,-1.17649,-1.64040,-0.32611,2.43347,0.00213
-4.21472,0.70732,-1.17689,-1.64018,-0.32593,2.43401,0.00213
-4.21591,0.70679,-1.17728,-1.63995,-0.32576,2.43455,0.00213
-4.21710,0.70627,-1.17766,-1.63973,-0.32560,2.43508,0.00213
-4.21829,0.70587,-1.17796,-1.63956,-0.32546,2.43547,0.00213
-4.21947,0.70501,-1.17871,-1.63915,-0.32513,2.43633,0.00213
-4.22066,0.70416,-1.17944,-1.63874,-0.32481,2.43718,0.00212
-4.22185,0.70332,-1.18016,-1.63834,-0.32449,2.43801,0.00212
-4.22304,0.70250,-1.18087,-1.63794,-0.32417,2.43883,0.00212
-4.22423,0.70168,-1.18157,-1.63755,-0.32386,2.43964,0.00211
-4.22542,0.70088,-1.18226,-1.63717,-0.32356,2.44044,0.00211
-4.22661,0.70009,-1.18293,-1.63679,-0.32326,2.44123,0.00211
-4.22780,0.69931,-1.18360,-1.63641,-0.32297,2.44201,0.00211
-4.22899,0.69854,-1.18426,-1.63604,-0.32268,2.44278,0.00210
-4.23017,0.69778,-1.18490,-1.63568,-0.32240,2.44353,0.00210
-4.23136,0.69703,-1.18554,-1.63532,-0.32212,2.44428,0.00210
-4.23255,0.69630,-1.18616,-1.63496,-0.32185,2.44501,0.00210
-4.23374,0.69557,-1.18678,-1.63461,-0.32158,2.44574,0.00210
-4.23493,0.69485,-1.18738,-1.63427,-0.32132,2.44646,0.00209
-4.23612,0.69415,-1.18798,-1.63393,-0.32106,2.44716,0.00209
-4.23731,0.69345,-1.18857,-1.63359,-0.32081,2.44786,0.00209
-4.23850,0.69276,-1.18915,-1.63326,-0.32056,2.44855,0.00209
-4.23969,0.69208,-1.18972,-1.63294,-0.32031,2.44923,0.00209
-4.24088,0.69141,-1.19028,-1.63261,-0.32007,2.44989,0.00209
-4.24206,0.69076,-1.19083,-1.63230,-0.31984,2.45055,0.00209
-4.24325,0.69011,-1.19137,-1.63198,-0.31960,2.45120,0.00209
-4.24444,0.68947,-1.19190,-1.63167,-0.31938,2.45184,0.00209
-4.24563,0.68883,-1.19243,-1.63137,-0.31915,2.45248,0.00209
-4.24682,0.68821,-1.19295,-1.63107,-0.31893,2.45310,0.00209
-4.24801,0.68760,-1.19346,-1.63077,-0.31871,2.45372,0.00209
-4.24920,0.68699,-1.19396,-1.63048,-0.31850,2.45432,0.00209
-4.25039,0.68639,-1.19445,-1.63019,-0.31829,2.45492,0.00209
-4.25158,0.68580,-1.19494,-1.62991,-0.31809,2.45551,0.00209
-4.25276,0.68522,-1.19541,-1.62963,-0.31789,2.45610,0.00209
-4.25395,0.68465,-1.19588,-1.62935,-0.31769,2.45667,0.00209
-4.25514,0.68409,-1.19635,-1.62908,-0.31749,2.45724,0.00209
-4.25633,0.68353,-1.19680,-1.62881,-0.31730,2.45780,0.00209
-4.25752,0.68298,-1.19725,-1.62855,-0.31711,2.45835,0.00209
-4.25871,0.68244,-1.19769,-1.62828,-0.31693,2.45889,0.00209
-4.25990,0.68190,-1.19813,-1.62803,-0.31675,2.45943,0.00209
-4.26109,0.68138,-1.19856,-1.62777,-0.31657,2.45996,0.00209
-4.26228,0.68086,-1.19898,-1.62752,-0.31640,2.46048,0.00209
-4.26346,0.68035,-1.19939,-1.62728,-0.31622,2.46100,0.00209
-4.26465,0.67984,-1.19980,-1.62703,-0.31605,2.46150,0.00209
-4.26584,0.67934,-1.20020,-1.62679,-0.31589,2.46200,0.00209
-4.26703,0.67885,-1.20060,-1.62656,-0.31572,2.46250,0.00210
-4.26822,0.67853,-1.20087,-1.62640,-0.31561,2.46282,0.00210
-4.26941,0.67773,-1.20160,-1.62600,-0.31528,2.46361,0.00209
-4.27060,0.67695,-1.20232,-1.62560,-0.31496,2.46440,0.00209
-4.27179,0.67617,-1.20304,-1.62521,-0.31464,2.46517,0.00208
-4.27298,0.67541,-1.20374,-1.62482,-0.31433,2.46592,0.00208
-4.27416,0.67466,-1.20442,-1.62444,-0.31402,2.46667,0.00208
-4.27535,0.67392,-1.20510,-1.62406,-0.31372,2.46741,0.00207
-4.27654,0.67319,-1.20577,-1.62369,-0.31342,2.46814,0.00207
-4.27773,0.67247,-1.20642,-1.62332,-0.31313,2.46885,0.00207
-4.27892,0.67176,-1.20707,-1.62296,-0.31285,2.46956,0.00207
-4.28011,0.67106,-1.20771,-1.62260,-0.31257,2.47026,0.00206
-4.28130,0.67037,-1.20833,-1.62225,-0.31229,2.47094,0.00206
-4.28249,0.66969,-1.20895,-1.62191,-0.31202,2.47162,0.00206
-4.28368,0.66902,-1.20955,-1.62156,-0.31176,2.47229,0.00206
-4.28487,0.66837,-1.21015,-1.62123,-0.31150,2.47295,0.00206
-4.28605,0.66772,-1.21073,-1.62089,-0.31124,2.47360,0.00205
-4.28724,0.66707,-1.21131,-1.62057,-0.31099,2.47424,0.00205
-4.28843,0.66644,-1.21188,-1.62024,-0.31075,2.47487,0.00205
-4.28962,0.66582,-1.21244,-1.61992,-0.31050,2.47549,0.00205
-4.29081,0.66521,-1.21299,-1.61961,-0.31027,2.47610,0.00205
-4.29200,0.66460,-1.21353,-1.61930,-0.31003,2.47671,0.00205
-4.29319,0.66401,-1.21406,-1.61899,-0.30980,2.47731,0.00205
-4.29438,0.66342,-1.21458,-1.61869,-0.30958,2.47789,0.00205
-4.29557,0.66284,-1.21510,-1.61839,-0.30936,2.47847,0.00205
-4.29675,0.66227,-1.21561,-1.61810,-0.30914,2.47905,0.00205
-4.29794,0.66170,-1.21610,-1.61781,-0.30893,2.47961,0.00205
-4.29913,0.66115,-1.21660,-1.61753,-0.30872,2.48017,0.00205
-4.30032,0.66060,-1.21708,-1.61725,-0.30851,2.48071,0.00205
-4.30151,0.66006,-1.21755,-1.61697,-0.30831,2.48125,0.00205
-4.30270,0.65953,-1.21802,-1.61670,-0.30811,2.48179,0.00205
-4.30389,0.65901,-1.21848,-1.61643,-0.30792,2.48231,0.00205
-4.30508,0.65849,-1.21893,-1.61616,-0.30773,2.48283,0.00205
-4.30627,0.65798,-1.21938,-1.61590,-0.30754,2.48334,0.00205
-4.30745,0.65748,-1.21982,-1.61564,-0.30736,2.48384,0.00205
-4.30864,0.65699,-1.22025,-1.61539,-0.30718,2.48434,0.00205
-4.30983,0.65650,-1.22068,-1.61514,-0.30700,2.48483,0.00205
-4.31102,0.65602,-1.22109,-1.61489,-0.30682,2.48531,0.00205
-4.31221,0.65555,-1.22150,-1.61465,-0.30665,2.48579,0.00205
-4.31340,0.65508,-1.22191,-1.61441,-0.30648,2.48626,0.00205
-4.31459,0.65462,-1.22231,-1.61417,-0.30632,2.48672,0.00205
-4.31578,0.65456,-1.22237,-1.61414,-0.30629,2.48678,0.00205
-4.31697,0.65393,-1.22296,-1.61381,-0.30603,2.48741,0.00205
-4.31815,0.65331,-1.22354,-1.61349,-0.30577,2.48803,0.00205
-4.31934,0.65270,-1.22411,-1.61317,-0.30551,2.48863,0.00205
-4.32053,0.65210,-1.22468,-1.61285,-0.30526,2.48923,0.00205
-4.32172,0.65151,-1.22523,-1.61254,-0.30501,2.48982,0.00204
-4.32291,0.65092,-1.22578,-1.61224,-0.30477,2.49041,0.00204
-4.32410,0.65035,-1.22632,-1.61194,-0.30453,2.49098,0.00204
-4.32529,0.64978,-1.22684,-1.61164,-0.30430,2.49155,0.00204
-4.32648,0.64922,-1.22736,-1.61135,-0.30407,2.49211,0.00204
-4.32767,0.64867,-1.22788,-1.61106,-0.30385,2.49266,0.00204
-4.32886,0.64813,-1.22838,-1.61077,-0.30363,2.49320,0.00204
-4.33004,0.64760,-1.22887,-1.61049,-0.30341,2.49373,0.00204
-4.33123,0.64707,-1.22936,-1.61021,-0.30320,2.49426,0.00204
-4.33242,0.64655,-1.22984,-1.60994,-0.30299,2.49478,0.00204
-4.33361,0.64604,-1.23031,-1.60967,-0.30278,2.49529,0.00204
-4.33480,0.64554,-1.23077,-1.60941,-0.30258,2.49580,0.00204
-4.33599,0.64504,-1.23123,-1.60915,-0.30239,2.49629,0.00204
-4.33718,0.64455,-1.23168,-1.60889,-0.30219,2.49678,0.00204
-4.33837,0.64407,-1.23212,-1.60863,-0.30200,2.49727,0.00204
-4.33956,0.64359,-1.23256,-1.60838,-0.30181,2.49775,0.00204
-4.34074,0.64312,-1.23298,-1.60814,-0.30163,2.49822,0.00204
-4.34193,0.64266,-1.23340,-1.60789,-0.30145,2.49868,0.00204
-4.34312,0.64221,-1.23382,-1.60765,-0.30127,2.49914,0.00204
-4.34431,0.64176,-1.23422,-1.60742,-0.30110,2.49959,0.00204
-4.34550,0.64129,-1.23465,-1.60717,-0.30091,2.50005,0.00204
-4.34669,0.64062,-1.23532,-1.60680,-0.30062,2.50072,0.00204
-4.34788,0.63997,-1.23598,-1.60643,-0.30032,2.50137,0.00203
-4.34907,0.63932,-1.23663,-1.60607,-0.30004,2.50201,0.00203
-4.35026,0.63868,-1.23727,-1.60571,-0.29976,2.50265,0.00203
-4.35144,0.63806,-1.23790,-1.60536,-0.29948,2.50327,0.00202
-4.35263,0.63744,-1.23851,-1.60502,-0.29921,2.50389,0.00202
-4.35382,0.63683,-1.23912,-1.60468,-0.29894,2.50450,0.00202
-4.35501,0.63623,-1.23972,-1.60434,-0.29868,2.50510,0.00202
-4.35620,0.63564,-1.24031,-1.60401,-0.29842,2.50569,0.00202
-4.35739,0.63505,-1.24089,-1.60368,-0.29817,2.50627,0.00201
-4.35858,0.63448,-1.24145,-1.60336,-0.29793,2.50684,0.00201
-4.35977,0.63391,-1.24201,-1.60304,-0.29768,2.50740,0.00201
-4.36096,0.63335,-1.24256,-1.60272,-0.29745,2.50796,0.00201
-4.36214,0.63281,-1.24310,-1.60241,-0.29721,2.50851,0.00201
-4.36333,0.63226,-1.24364,-1.60211,-0.29698,2.50905,0.00201
-4.36452,0.63173,-1.24416,-1.60181,-0.29676,2.50958,0.00201
-4.36571,0.63121,-1.24468,-1.60151,-0.29654,2.51011,0.00201
-4.36690,0.63069,-1.24518,-1.60122,-0.29632,2.51062,0.00201
-4.36809,0.63018,-1.24568,-1.60093,-0.29611,2.51113,0.00200
-4.36928,0.62968,-1.24617,-1.60065,-0.29590,2.51164,0.00200
-4.37047,0.62918,-1.24665,-1.60037,-0.29569,2.51213,0.00200
-4.37166,0.62869,-1.24713,-1.60009,-0.29549,2.51262,0.00200
-4.37285,0.62821,-1.24760,-1.59982,-0.29530,2.51310,0.00200
-4.37403,0.62774,-1.24805,-1.59955,-0.29510,2.51357,0.00200
-4.37522,0.62727,-1.24851,-1.59929,-0.29491,2.51404,0.00201
-4.37641,0.62681,-1.24895,-1.59903,-0.29472,2.51450,0.00201
-4.37760,0.62636,-1.24939,-1.59877,-0.29454,2.51496,0.00201
-4.37879,0.62592,-1.24982,-1.59852,-0.29436,2.51540,0.00201
-4.37998,0.62548,-1.25024,-1.59827,-0.29418,2.51584,0.00201
-4.38117,0.62504,-1.25066,-1.59802,-0.29401,2.51628,0.00201
-4.38236,0.62462,-1.25106,-1.59778,-0.29384,2.51671,0.00201
-4.38355,0.62433,-1.25134,-1.59762,-0.29372,2.51699,0.00201
-4.38473,0.62364,-1.25210,-1.59716,-0.29342,2.51768,0.00200
-4.38592,0.62295,-1.25284,-1.59672,-0.29313,2.51836,0.00200
-4.38711,0.62227,-1.25357,-1.59628,-0.29284,2.51904,0.00200
-4.38830,0.62161,-1.25429,-1.59584,-0.29255,2.51970,0.00199
-4.38949,0.62095,-1.25500,-1.59542,-0.29228,2.52035,0.00199
-4.39068,0.62031,-1.25569,-1.59500,-0.29200,2.52099,0.00199
-4.39187,0.61967,-1.25638,-1.59458,-0.29173,2.52163,0.00198
-4.39306,0.61904,-1.25705,-1.59417,-0.29147,2.52225,0.00198
-4.39425,0.61843,-1.25771,-1.59377,-0.29121,2.52286,0.00198
-4.39543,0.61782,-1.25836,-1.59337,-0.29096,2.52347,0.00198
-4.39662,0.61722,-1.25900,-1.59298,-0.29071,2.52407,0.00197
-4.39781,0.61663,-1.25963,-1.59259,-0.29047,2.52465,0.00197
-4.39900,0.61605,-1.26025,-1.59221,-0.29023,2.52523,0.00197
-4.40019,0.61548,-1.26085,-1.59183,-0.29000,2.52580,0.00197
-4.40138,0.61491,-1.26145,-1.59146,-0.28977,2.52636,0.00197
-4.40257,0.61436,-1.26204,-1.59110,-0.28954,2.52692,0.00197
-4.40376,0.61381,-1.26262,-1.59074,-0.28932,2.52746,0.00197
-4.40495,0.61328,-1.26319,-1.59039,-0.28910,2.52800,0.00196
-4.40613,0.61275,-1.26375,-1.59004,-0.28889,2.52853,0.00196
-4.40732,0.61222,-1.26430,-1.58969,-0.28868,2.52905,0.00196
-4.40851,0.61171,-1.26484,-1.58935,-0.28848,2.52956,0.00196
-4.40970,0.61120,-1.26537,-1.58902,-0.28828,2.53007,0.00196
-4.41089,0.61070,-1.26590,-1.58869,-0.28808,2.53057,0.00196
-4.41208,0.61021,-1.26641,-1.58836,-0.28789,2.53106,0.00196
-4.41327,0.60973,-1.26692,-1.58805,-0.28770,2.53154,0.00196
-4.41446,0.60925,-1.26742,-1.58773,-0.28751,2.53202,0.00196
-4.41565,0.60878,-1.26791,-1.58742,-0.28733,2.53249,0.00196
-4.41684,0.60832,-1.26839,-1.58711,-0.28715,2.53295,0.00196
-4.41802,0.60787,-1.26886,-1.58681,-0.28697,2.53341,0.00196
-4.41921,0.60742,-1.26933,-1.58651,-0.28680,2.53386,0.00197
-4.42040,0.60697,-1.26979,-1.58622,-0.28663,2.53430,0.00197
-4.42159,0.60654,-1.27024,-1.58593,-0.28647,2.53474,0.00197
-4.42278,0.60611,-1.27068,-1.58565,-0.28630,2.53517,0.00197
-4.42397,0.60569,-1.27112,-1.58537,-0.28614,2.53559,0.00197
-4.42516,0.60527,-1.27155,-1.58509,-0.28599,2.53601,0.00197
-4.42635,0.60486,-1.27197,-1.58482,-0.28583,2.53642,0.00197
-4.42754,0.60446,-1.27238,-1.58455,-0.28568,2.53683,0.00197
-4.42872,0.60428,-1.27257,-1.58444,-0.28561,2.53700,0.00197
-4.42991,0.60375,-1.27316,-1.58406,-0.28540,2.53754,0.00197
-4.43110,0.60322,-1.27374,-1.58368,-0.28519,2.53806,0.00197
-4.43229,0.60270,-1.27432,-1.58331,-0.28498,2.53858,0.00197
-4.43348,0.60219,-1.27488,-1.58295,-0.28478,2.53909,0.00197
-4.43467,0.60168,-1.27544,-1.58259,-0.28458,2.53960,0.00197
-4.43586,0.60119,-1.27598,-1.58224,-0.28439,2.54009,0.00197
-4.43705,0.60070,-1.27652,-1.58189,-0.28420,2.54058,0.00197
-4.43824,0.60022,-1.27705,-1.58155,-0.28401,2.54106,0.00197
-4.43942,0.59974,-1.27757,-1.58121,-0.28383,2.54154,0.00197
-4.44061,0.59927,-1.27808,-1.58087,-0.28365,2.54200,0.00197
-4.44180,0.59881,-1.27858,-1.58055,-0.28347,2.54246,0.00197
-4.44299,0.59836,-1.27907,-1.58022,-0.28330,2.54292,0.00197
-4.44418,0.59791,-1.27956,-1.57990,-0.28313,2.54336,0.00197
-4.44537,0.59748,-1.28004,-1.57959,-0.28296,2.54380,0.00197
-4.44656,0.59704,-1.28050,-1.57928,-0.28280,2.54424,0.00197
-4.44775,0.59662,-1.28097,-1.57898,-0.28264,2.54466,0.00197
-4.44894,0.59620,-1.28142,-1.57868,-0.28248,2.54508,0.00197
-4.45012,0.59578,-1.28187,-1.57838,-0.28232,2.54550,0.00197
-4.45131,0.59537,-1.28231,-1.57809,-0.28217,2.54591,0.00197
-4.45250,0.59497,-1.28274,-1.57780,-0.28202,2.54631,0.00197
-4.45369,0.59458,-1.28316,-1.57752,-0.28188,2.54671,0.00197
-4.45488,0.59419,-1.28358,-1.57724,-0.28174,2.54710,0.00197
-4.45607,0.59405,-1.28373,-1.57714,-0.28168,2.54723,0.00197
-4.45726,0.59345,-1.28444,-1.57668,-0.28144,2.54783,0.00197
-4.45845,0.59286,-1.28514,-1.57622,-0.28120,2.54842,0.00197
-4.45964,0.59228,-1.28583,-1.57577,-0.28097,2.54900,0.00196
-4.46083,0.59170,-1.28650,-1.57532,-0.28074,2.54957,0.00196
-4.46201,0.59114,-1.28717,-1.57488,-0.28051,2.55013,0.00196
-4.46320,0.59058,-1.28782,-1.57445,-0.28029,2.55069,0.00196
-4.46439,0.59003,-1.28846,-1.57402,-0.28007,2.55123,0.00195
-4.46558,0.58950,-1.28909,-1.57360,-0.27986,2.55177,0.00195
-4.46677,0.58896,-1.28971,-1.57319,-0.27966,2.55230,0.00195
-4.46796,0.58844,-1.29032,-1.57278,-0.27945,2.55282,0.00195
-4.46915,0.58793,-1.29092,-1.57238,-0.27925,2.55333,0.00195
-4.47034,0.58742,-1.29151,-1.57199,-0.27906,2.55384,0.00195
-4.47153,0.58692,-1.29209,-1.57160,-0.27886,2.55433,0.00195
-4.47271,0.58643,-1.29266,-1.57121,-0.27868,2.55482,0.00194
-4.47390,0.58595,-1.29322,-1.57083,-0.27849,2.55531,0.00194
-4.47509,0.58547,-1.29377,-1.57046,-0.27831,2.55578,0.00194
-4.47628,0.58500,-1.29432,-1.57009,-0.27813,2.55625,0.00194
-4.47747,0.58454,-1.29485,-1.56973,-0.27796,2.55671,0.00194
-4.47866,0.58409,-1.29537,-1.56938,-0.27779,2.55716,0.00194
-4.47985,0.58364,-1.29589,-1.56903,-0.27762,2.55761,0.00194
-4.48104,0.58320,-1.29640,-1.56868,-0.27746,2.55805,0.00194
-4.48223,0.58277,-1.29689,-1.56834,-0.27730,2.55849,0.00194
-4.48341,0.58234,-1.29738,-1.56800,-0.27714,2.55891,0.00194
-4.48460,0.58192,-1.29787,-1.56767,-0.27699,2.55933,0.00194
-4.48579,0.58151,-1.29834,-1.56735,-0.27684,2.55975,0.00194
-4.48698,0.58110,-1.29880,-1.56703,-0.27669,2.56016,0.00195
-4.48817,0.58070,-1.29926,-1.56671,-0.27654,2.56056,0.00195
-4.48936,0.58030,-1.29971,-1.56640,-0.27640,2.56096,0.00195
-4.49055,0.57991,-1.30016,-1.56609,-0.27626,2.56135,0.00195
-4.49174,0.57953,-1.30059,-1.56579,-0.27613,2.56173,0.00195
-4.49293,0.57915,-1.30102,-1.56549,-0.27599,2.56211,0.00195
-4.49411,0.57878,-1.30144,-1.56520,-0.27586,2.56248,0.00195
-4.49530,0.57864,-1.30160,-1.56509,-0.27581,2.56262,0.00195
-4.49649,0.57803,-1.30238,-1.56454,-0.27558,2.56323,0.00195
-4.49768,0.57743,-1.30314,-1.56400,-0.27536,2.56383,0.00194
-4.49887,0.57683,-1.30389,-1.56347,-0.27514,2.56442,0.00194
-4.50006,0.57625,-1.30462,-1.56295,-0.27493,2.56500,0.00194
-4.50125,0.57567,-1.30534,-1.56244,-0.27472,2.56557,0.00193
-4.50244,0.57510,-1.30606,-1.56193,-0.27451,2.56614,0.00193
-4.50363,0.57454,-1.30675,-1.56143,-0.27431,2.56669,0.00193
-4.50482,0.57399,-1.30744,-1.56094,-0.27412,2.56724,0.00193
-4.50600,0.57345,-1.30812,-1.56046,-0.27393,2.56778,0.00192
-4.50719,0.57292,-1.30878,-1.55998,-0.27374,2.56831,0.00192
-4.50838,0.57240,-1.30944,-1.55951,-0.27355,2.56883,0.00192
-4.50957,0.57188,-1.31008,-1.55905,-0.27337,2.56935,0.00192
-4.51076,0.57137,-1.31071,-1.55859,-0.27320,2.56985,0.00192
-4.51195,0.57087,-1.31133,-1.55814,-0.27302,2.57035,0.00192
-4.51314,0.57038,-1.31194,-1.55770,-0.27285,2.57084,0.00192
-4.51433,0.56990,-1.31254,-1.55726,-0.27269,2.57132,0.00192
-4.51552,0.56942,-1.31313,-1.55684,-0.27252,2.57180,0.00192
-4.51670,0.56895,-1.31371,-1.55641,-0.27237,2.57227,0.00191
-4.51789,0.56849,-1.31428,-1.55600,-0.27221,2.57273,0.00191
-4.51908,0.56804,-1.31484,-1.55559,-0.27206,2.57318,0.00191
-4.52027,0.56759,-1.31539,-1.55518,-0.27191,2.57363,0.00191
-4.52146,0.56715,-1.31594,-1.55478,-0.27176,2.57407,0.00191
-4.52265,0.56672,-1.31647,-1.55439,-0.27162,2.57451,0.00191
-4.52384,0.56629,-1.31699,-1.55400,-0.27148,2.57493,0.00192
-4.52503,0.56587,-1.31751,-1.55362,-0.27134,2.57535,0.00192
-4.52622,0.56545,-1.31802,-1.55325,-0.27120,2.57577,0.00192
-4.52740,0.56505,-1.31851,-1.55288,-0.27107,2.57618,0.00192
-4.52859,0.56465,-1.31900,-1.55252,-0.27094,2.57658,0.00192
-4.52978,0.56425,-1.31948,-1.55216,-0.27081,2.57697,0.00192
-4.53097,0.56386,-1.31996,-1.55181,-0.27069,2.57736,0.00192
-4.53216,0.56348,-1.32042,-1.55146,-0.27057,2.57775,0.00192
-4.53335,0.56310,-1.32088,-1.55112,-0.27045,2.57812,0.00192
-4.53454,0.56273,-1.32133,-1.55078,-0.27033,2.57850,0.00192
-4.53573,0.56237,-1.32177,-1.55045,-0.27022,2.57886,0.00193
-4.53692,0.56201,-1.32221,-1.55012,-0.27011,2.57922,0.00193
-4.53810,0.56165,-1.32264,-1.54980,-0.27000,2.57958,0.00193
-4.53929,0.56143,-1.32291,-1.54959,-0.26993,2.57980,0.00193
-4.54048,0.56093,-1.32355,-1.54913,-0.26975,2.58030,0.00193
-4.54167,0.56045,-1.32419,-1.54867,-0.26958,2.58079,0.00193
-4.54286,0.55996,-1.32481,-1.54821,-0.26941,2.58126,0.00192
-4.54405,0.55949,-1.32542,-1.54777,-0.26924,2.58174,0.00192
-4.54524,0.55903,-1.32602,-1.54733,-0.26908,2.58220,0.00192
-4.54643,0.55857,-1.32661,-1.54689,-0.26892,2.58266,0.00192
-4.54762,0.55812,-1.32719,-1.54647,-0.26877,2.58311,0.00192
-4.54881,0.55767,-1.32776,-1.54605,-0.26862,2.58355,0.00192
-4.54999,0.55724,-1.32832,-1.54563,-0.26847,2.58399,0.00192
-4.55118,0.55681,-1.32887,-1.54522,-0.26832,2.58442,0.00192
-4.55237,0.55638,-1.32941,-1.54482,-0.26818,2.58484,0.00192
-4.55356,0.55597,-1.32994,-1.54443,-0.26804,2.58526,0.00192
-4.55475,0.55556,-1.33047,-1.54404,-0.26791,2.58567,0.00192
-4.55594,0.55515,-1.33098,-1.54365,-0.26777,2.58607,0.00192
-4.55713,0.55476,-1.33149,-1.54328,-0.26764,2.58647,0.00192
-4.55832,0.55437,-1.33199,-1.54290,-0.26751,2.58686,0.00192
-4.55951,0.55398,-1.33248,-1.54254,-0.26739,2.58724,0.00192
-4.56069,0.55360,-1.33296,-1.54218,-0.26727,2.58762,0.00192
-4.56188,0.55323,-1.33343,-1.54182,-0.26715,2.58800,0.00192
-4.56307,0.55286,-1.33389,-1.54147,-0.26703,2.58837,0.00192
-4.56426,0.55250,-1.33435,-1.54113,-0.26691,2.58873,0.00192
-4.56545,0.55214,-1.33480,-1.54079,-0.26680,2.58908,0.00192
-4.56664,0.55179,-1.33524,-1.54045,-0.26669,2.58944,0.00192
-4.56783,0.55145,-1.33568,-1.54012,-0.26658,2.58978,0.00192
-4.56902,0.55111,-1.33610,-1.53980,-0.26647,2.59012,0.00193
-4.57021,0.55099,-1.33627,-1.53968,-0.26643,2.59025,0.00193
-4.57139,0.55042,-1.33704,-1.53911,-0.26622,2.59081,0.00192
-4.57258,0.54987,-1.33781,-1.53855,-0.26602,2.59136,0.00192
-4.57377,0.54932,-1.33856,-1.53801,-0.26582,2.59190,0.00191
-4.57496,0.54878,-1.33929,-1.53747,-0.26563,2.59244,0.00191
-4.57615,0.54825,-1.34002,-1.53693,-0.26543,2.59296,0.00190
-4.57734,0.54773,-1.34073,-1.53641,-0.26525,2.59348,0.00190
-4.57853,0.54722,-1.34143,-1.53589,-0.26506,2.59399,0.00190
-4.57972,0.54672,-1.34212,-1.53538,-0.26489,2.59449,0.00190
-4.58091,0.54622,-1.34279,-1.53488,-0.26471,2.59498,0.00189
-4.58209,0.54574,-1.34346,-1.53439,-0.26454,2.59547,0.00189
-4.58328,0.54526,-1.34411,-1.53390,-0.26437,2.59595,0.00189
-4.58447,0.54478,-1.34476,-1.53342,-0.26421,2.59642,0.00189
-4.58566,0.54432,-1.34539,-1.53295,-0.26405,2.59688,0.00189
-4.58685,0.54386,-1.34601,-1.53249,-0.26389,2.59734,0.00188
-4.58804,0.54341,-1.34662,-1.53203,-0.26374,2.59779,0.00188
-4.58923,0.54297,-1.34722,-1.53158,-0.26359,2.59823,0.00188
-4.59042,0.54253,-1.34781,-1.53113,-0.26344,2.59866,0.00188
-4.59161,0.54211,-1.34839,-1.53069,-0.26330,2.59909,0.00188
-4.59280,0.54168,-1.34896,-1.53026,-0.26315,2.59951,0.00188
-4.59398,0.54127,-1.34952,-1.52984,-0.26302,2.59993,0.00188
-4.59517,0.54086,-1.35007,-1.52942,-0.26288,2.60034,0.00188
-4.59636,0.54046,-1.35061,-1.52901,-0.26275,2.60074,0.00188
-4.59755,0.54006,-1.35115,-1.52860,-0.26262,2.60113,0.00188
-4.59874,0.53967,-1.35167,-1.52820,-0.26249,2.60152,0.00188
-4.59993,0.53929,-1.35218,-1.52781,-0.26237,2.60191,0.00188
-4.60112,0.53891,-1.35269,-1.52742,-0.26225,2.60228,0.00188
-4.60231,0.53854,-1.35319,-1.52704,-0.26213,2.60265,0.00188
-4.60350,0.53818,-1.35368,-1.52667,-0.26202,2.60302,0.00188
-4.60468,0.53782,-1.35416,-1.52630,-0.26190,2.60338,0.00188
-4.60587,0.53747,-1.35463,-1.52593,-0.26179,2.60374,0.00188
-4.60706,0.53712,-1.35509,-1.52557,-0.26168,2.60408,0.00188
-4.60825,0.53677,-1.35555,-1.52522,-0.26158,2.60443,0.00188
-4.60944,0.53644,-1.35600,-1.52487,-0.26147,2.60477,0.00189
-4.61063,0.53611,-1.35644,-1.52453,-0.26137,2.60510,0.00189
-4.61182,0.53578,-1.35687,-1.52419,-0.26127,2.60543,0.00189
-4.61301,0.53546,-1.35730,-1.52386,-0.26117,2.60575,0.00189
-4.61420,0.53541,-1.35736,-1.52381,-0.26116,2.60579,0.00189
-4.61538,0.53497,-1.35799,-1.52334,-0.26100,2.60624,0.00189
-4.61657,0.53453,-1.35860,-1.52287,-0.26086,2.60667,0.00189
-4.61776,0.53410,-1.35921,-1.52241,-0.26071,2.60710,0.00188
-4.61895,0.53368,-1.35980,-1.52196,-0.26057,2.60752,0.00188
-4.62014,0.53326,-1.36039,-1.52151,-0.26043,2.60794,0.00188
-4.62133,0.53285,-1.36096,-1.52107,-0.26029,2.60835,0.00188
-4.62252,0.53245,-1.36153,-1.52064,-0.26016,2.60875,0.00188
-4.62371,0.53205,-1.36208,-1.52021,-0.26003,2.60915,0.00188
-4.62490,0.53166,-1.36263,-1.51979,-0.25990,2.60954,0.00188
-4.62608,0.53128,-1.36316,-1.51938,-0.25978,2.60992,0.00188
-4.62727,0.53090,-1.36369,-1.51897,-0.25966,2.61030,0.00188
-4.62846,0.53053,-1.36421,-1.51857,-0.25954,2.61067,0.00188
-4.62965,0.53016,-1.36472,-1.51818,-0.25942,2.61104,0.00188
-4.63084,0.52980,-1.36522,-1.51779,-0.25931,2.61140,0.00188
-4.63203,0.52945,-1.36571,-1.51740,-0.25919,2.61175,0.00188
-4.63322,0.52910,-1.36620,-1.51703,-0.25909,2.61210,0.00188
-4.63441,0.52876,-1.36667,-1.51665,-0.25898,2.61244,0.00188
-4.63560,0.52842,-1.36714,-1.51629,-0.25887,2.61278,0.00188
-4.63679,0.52809,-1.36760,-1.51593,-0.25877,2.61312,0.00188
-4.63797,0.52776,-1.36805,-1.51557,-0.25867,2.61344,0.00188
-4.63916,0.52744,-1.36849,-1.51522,-0.25857,2.61377,0.00188
-4.64035,0.52712,-1.36893,-1.51488,-0.25848,2.61408,0.00188
-4.64154,0.52681,-1.36936,-1.51454,-0.25838,2.61440,0.00189
-4.64273,0.52671,-1.36950,-1.51443,-0.25835,2.61450,0.00189
-4.64392,0.52631,-1.37007,-1.51399,-0.25822,2.61489,0.00188
-4.64511,0.52593,-1.37063,-1.51355,-0.25809,2.61528,0.00188
-4.64630,0.52554,-1.37119,-1.51313,-0.25797,2.61567,0.00188
-4.64749,0.52516,-1.37173,-1.51271,-0.25785,2.61604,0.00188
-4.64867,0.52479,-1.37226,-1.51229,-0.25773,2.61641,0.00188
-4.64986,0.52443,-1.37278,-1.51188,-0.25761,2.61678,0.00188
-4.65105,0.52407,-1.37330,-1.51148,-0.25750,2.61714,0.00188
-4.65224,0.52372,-1.37381,-1.51108,-0.25739,2.61749,0.00188
-4.65343,0.52337,-1.37430,-1.51069,-0.25728,2.61784,0.00188
-4.65462,0.52303,-1.37479,-1.51031,-0.25717,2.61818,0.00188
-4.65581,0.52269,-1.37527,-1.50993,-0.25707,2.61852,0.00188
-4.65700,0.52236,-1.37574,-1.50956,-0.25696,2.61885,0.00188
-4.65819,0.52203,-1.37621,-1.50919,-0.25686,2.61918,0.00188
-4.65937,0.52171,-1.37667,-1.50883,-0.25677,2.61950,0.00188
-4.66056,0.52139,-1.37711,-1.50847,-0.25667,2.61982,0.00188
-4.66175,0.52108,-1.37756,-1.50812,-0.25658,2.62013,0.00188
-4.66294,0.52078,-1.37799,-1.50778,-0.25649,2.62043,0.00189
-4.66413,0.52053,-1.37835,-1.50749,-0.25641,2.62069,0.00189
-4.66532,0.52013,-1.37894,-1.50703,-0.25628,2.62108,0.00188
-4.66651,0.51974,-1.37952,-1.50658,-0.25615,2.62147,0.00188
-4.66770,0.51935,-1.38009,-1.50614,-0.25603,2.62186,0.00188
-4.66889,0.51898,-1.38065,-1.50570,-0.25590,2.62223,0.00188
-4.67007,0.51860,-1.38120,-1.50526,-0.25579,2.62261,0.00188
-4.67126,0.51824,-1.38174,-1.50484,-0.25567,2.62297,0.00188
-4.67245,0.51788,-1.38227,-1.50442,-0.25555,2.62333,0.00188
-4.67364,0.51752,-1.38280,-1.50401,-0.25544,2.62369,0.00188
-4.67483,0.51717,-1.38331,-1.50360,-0.25533,2.62403,0.00188
-4.67602,0.51683,-1.38381,-1.50320,-0.25523,2.62438,0.00188
-4.67721,0.51649,-1.38431,-1.50281,-0.25512,2.62472,0.00188
-4.67840,0.51616,-1.38480,-1.50242,-0.25502,2.62505,0.00188
-4.67959,0.51583,-1.38528,-1.50203,-0.25492,2.62537,0.00188
-4.68078,0.51551,-1.38575,-1.50166,-0.25483,2.62570,0.00188
-4.68196,0.51520,-1.38622,-1.50129,-0.25473,2.62601,0.00188
-4.68315,0.51488,-1.38667,-1.50092,-0.25464,2.62633,0.00188
-4.68434,0.51458,-1.38712,-1.50056,-0.25455,2.62663,0.00188
-4.68553,0.51428,-1.38756,-1.50021,-0.25446,2.62694,0.00188
-4.68672,0.51398,-1.38799,-1.49986,-0.25437,2.62723,0.00188
-4.68791,0.51380,-1.38826,-1.49964,-0.25432,2.62742,0.00188
-4.68910,0.51343,-1.38882,-1.49920,-0.25420,2.62778,0.00188
-4.69029,0.51307,-1.38936,-1.49877,-0.25409,2.62814,0.00188
-4.69148,0.51272,-1.38989,-1.49835,-0.25398,2.62849,0.00188
-4.69266,0.51237,-1.39042,-1.49793,-0.25387,2.62884,0.00188
-4.69385,0.51203,-1.39094,-1.49752,-0.25376,2.62918,0.00188
-4.69504,0.51169,-1.39144,-1.49711,-0.25366,2.62952,0.00187
-4.69623,0.51136,-1.39194,-1.49671,-0.25356,2.62985,0.00187
-4.69742,0.51103,-1.39243,-1.49632,-0.25346,2.63018,0.00187
-4.69861,0.51071,-1.39291,-1.49593,-0.25336,2.63050,0.00187
-4.69980,0.51040,-1.39339,-1.49555,-0.25327,2.63081,0.00187
-4.70099,0.51009,-1.39385,-1.49518,-0.25318,2.63112,0.00187
-4.70218,0.50978,-1.39431,-1.49481,-0.25309,2.63143,0.00188
-4.70336,0.50948,-1.39476,-1.49444,-0.25300,2.63173,0.00188
-4.70455,0.50918,-1.39520,-1.49408,-0.25291,2.63203,0.00188
-4.70574,0.50889,-1.39564,-1.49373,-0.25283,2.63232,0.00188
-4.70693,0.50866,-1.39600,-1.49344,-0.25276,2.63256,0.00188
-4.70812,0.50829,-1.39657,-1.49298,-0.25264,2.63293,0.00188
-4.70931,0.50793,-1.39713,-1.49254,-0.25253,2.63329,0.00187
-4.71050,0.50757,-1.39768,-1.49209,-0.25242,2.63364,0.00187
-4.71169,0.50722,-1.39823,-1.49166,-0.25231,2.63399,0.00187
-4.71288,0.50687,-1.39876,-1.49123,-0.25221,2.63434,0.00187
-4.71406,0.50653,-1.39929,-1.49081,-0.25210,2.63468,0.00187
-4.71525,0.50620,-1.39980,-1.49039,-0.25200,2.63501,0.00187
-4.71644,0.50587,-1.40031,-1.48998,-0.25190,2.63534,0.00187
-4.71763,0.50555,-1.40081,-1.48958,-0.25181,2.63566,0.00187
-4.71882,0.50523,-1.40130,-1.48918,-0.25171,2.63598,0.00187
-4.72001,0.50492,-1.40178,-1.48879,-0.25162,2.63629,0.00187
-4.72120,0.50461,-1.40225,-1.48840,-0.25153,2.63660,0.00187
-4.72239,0.50431,-1.40272,-1.48802,-0.25144,2.63690,0.00187
-4.72358,0.50401,-1.40317,-1.48765,-0.25136,2.63720,0.00187
-4.72477,0.50372,-1.40362,-1.48728,-0.25127,2.63750,0.00187
-4.72595,0.50343,-1.40407,-1.48692,-0.25119,2.63778,0.00187
-4.72714,0.50314,-1.40450,-1.48656,-0.25111,2.63807,0.00187
-4.72833,0.50297,-1.40477,-1.48634,-0.25106,2.63825,0.00187
-4.72952,0.50261,-1.40534,-1.48590,-0.25093,2.63861,0.00187
-4.73071,0.50225,-1.40590,-1.48547,-0.25080,2.63896,0.00187
-4.73190,0.50190,-1.40645,-1.48504,-0.25068,2.63931,0.00186
-4.73309,0.50156,-1.40699,-1.48462,-0.25056,2.63965,0.00186
-4.73428,0.50122,-1.40752,-1.48421,-0.25044,2.63999,0.00186
-4.73547,0.50089,-1.40805,-1.48380,-0.25032,2.64032,0.00186
-4.73665,0.50056,-1.40856,-1.48340,-0.25021,2.64065,0.00186
-4.73784,0.50024,-1.40907,-1.48301,-0.25010,2.64097,0.00186
-4.73903,0.49992,-1.40956,-1.48262,-0.24999,2.64128,0.00185
-4.74022,0.49961,-1.41005,-1.48224,-0.24989,2.64160,0.00185
-4.74141,0.49930,-1.41053,-1.48186,-0.24978,2.64190,0.00185
-4.74260,0.49900,-1.41100,-1.48149,-0.24968,2.64220,0.00185
-4.74379,0.49871,-1.41146,-1.48112,-0.24958,2.64250,0.00185
-4.74498,0.49842,-1.41192,-1.48076,-0.24949,2.64279,0.00185
-4.74617,0.49813,-1.41237,-1.48041,-0.24939,2.64308,0.00185
-4.74735,0.49785,-1.41280,-1.48006,-0.24930,2.64336,0.00185
-4.74854,0.49757,-1.41324,-1.47972,-0.24921,2.64364,0.00185
-4.74973,0.49742,-1.41347,-1.47954,-0.24916,2.64379,0.00185
-4.75092,0.49707,-1.41403,-1.47911,-0.24902,2.64414,0.00185
-4.75211,0.49672,-1.41459,-1.47869,-0.24888,2.64449,0.00185
-4.75330,0.49638,-1.41514,-1.47827,-0.24875,2.64483,0.00185
-4.75449,0.49604,-1.41568,-1.47786,-0.24862,2.64516,0.00184
-4.75568,0.49571,-1.41621,-1.47746,-0.24849,2.64549,0.00184
-4.75687,0.49538,-1.41673,-1.47706,-0.24837,2.64582,0.00184
-4.75805,0.49506,-1.41724,-1.47667,-0.24825,2.64614,0.00184
-4.75924,0.49475,-1.41775,-1.47629,-0.24813,2.64646,0.00184
-4.76043,0.49444,-1.41824,-1.47591,-0.24801,2.64677,0.00183
-4.76162,0.49413,-1.41873,-1.47554,-0.24790,2.64707,0.00183
-4.76281,0.49383,-1.41921,-1.47517,-0.24779,2.64737,0.00183
-4.76400,0.49354,-1.41968,-1.47481,-0.24768,2.64767,0.00183
-4.76519,0.49325,-1.42014,-1.47445,-0.24757,2.64796,0.00183
-4.76638,0.49296,-1.42059,-1.47410,-0.24747,2.64824,0.00183
-4.76757,0.49268,-1.42104,-1.47375,-0.24737,2.64852,0.00183
-4.76876,0.49240,-1.42148,-1.47341,-0.24727,2.64880,0.00183
-4.76994,0.49213,-1.42191,-1.47308,-0.24717,2.64907,0.00183
-4.77113,0.49199,-1.42213,-1.47291,-0.24712,2.64921,0.00183
-4.77232,0.49168,-1.42262,-1.47257,-0.24697,2.64952,0.00183
-4.77351,0.49138,-1.42310,-1.47223,-0.24683,2.64982,0.00183
-4.77470,0.49109,-1.42357,-1.47190,-0.24669,2.65012,0.00183
-4.77589,0.49079,-1.42403,-1.47158,-0.24655,2.65041,0.00182
-4.77708,0.49051,-1.42449,-1.47126,-0.24641,2.65070,0.00182
-4.77827,0.49022,-1.42493,-1.47094,-0.24628,2.65098,0.00182
-4.77946,0.48994,-1.42537,-1.47063,-0.24615,2.65126,0.00182
-4.78064,0.48967,-1.42581,-1.47033,-0.24602,2.65153,0.00182
-4.78183,0.48940,-1.42623,-1.47003,-0.24590,2.65180,0.00182
-4.78302,0.48927,-1.42644,-1.46988,-0.24584,2.65193,0.00182
-4.78421,0.48899,-1.42687,-1.46959,-0.24569,2.65221,0.00182
-4.78540,0.48873,-1.42729,-1.46931,-0.24555,2.65248,0.00182
-4.78659,0.48854,-1.42759,-1.46912,-0.24545,2.65266,0.00181
-4.78778,0.48827,-1.42801,-1.46885,-0.24530,2.65294,0.00181
-4.78897,0.48800,-1.42843,-1.46859,-0.24514,2.65320,0.00181
-4.79016,0.48781,-1.42872,-1.46840,-0.24503,2.65339,0.00181
-4.79134,0.48754,-1.42914,-1.46813,-0.24488,2.65366,0.00181
-4.79253,0.48728,-1.42956,-1.46787,-0.24473,2.65392,0.00181
-4.79372,0.48717,-1.42973,-1.46776,-0.24467,2.65403,0.00181
-4.79491,0.48690,-1.43015,-1.46748,-0.24452,2.65430,0.00181
-4.79610,0.48664,-1.43057,-1.46721,-0.24437,2.65456,0.00180
-4.79729,0.48651,-1.43078,-1.46710,-0.24429,2.65470,0.00180
-4.79848,0.48624,-1.43116,-1.46702,-0.24399,2.65496,0.00180
-4.79967,0.48598,-1.43153,-1.46693,-0.24371,2.65522,0.00179
-4.80086,0.48573,-1.43190,-1.46685,-0.24342,2.65547,0.00179
-4.80204,0.48548,-1.43226,-1.46678,-0.24315,2.65572,0.00178
-4.80323,0.48523,-1.43262,-1.46670,-0.24287,2.65597,0.00178
-4.80442,0.48516,-1.43272,-1.46668,-0.24278,2.65604,0.00177
-4.80561,0.48490,-1.43307,-1.46671,-0.24242,2.65629,0.00177
-4.80680,0.48465,-1.43341,-1.46673,-0.24206,2.65654,0.00176
-4.80799,0.48441,-1.43375,-1.46675,-0.24171,2.65679,0.00175
-4.80918,0.48417,-1.43408,-1.46677,-0.24137,2.65703,0.00174
-4.81037,0.48393,-1.43440,-1.46679,-0.24103,2.65726,0.00174
-4.81156,0.48370,-1.43472,-1.46681,-0.24070,2.65750,0.00173
-4.81275,0.48347,-1.43504,-1.46683,-0.24037,2.65772,0.00173
-4.81393,0.48331,-1.43525,-1.46685,-0.24014,2.65788,0.00172
-4.81512,0.48307,-1.43556,-1.46696,-0.23972,2.65812,0.00171
-4.81631,0.48284,-1.43586,-1.46708,-0.23932,2.65835,0.00171
-4.81750,0.48261,-1.43616,-1.46719,-0.23892,2.65857,0.00170
-4.81869,0.48239,-1.43645,-1.46730,-0.23852,2.65880,0.00169
-4.81988,0.48217,-1.43673,-1.46741,-0.23814,2.65902,0.00169
-4.82107,0.48195,-1.43701,-1.46751,-0.23776,2.65923,0.00168
-4.82226,0.48174,-1.43729,-1.46762,-0.23738,2.65944,0.00167
-4.82345,0.48153,-1.43756,-1.46772,-0.23702,2.65965,0.00167
-4.82463,0.48136,-1.43777,-1.46781,-0.23672,2.65982,0.00166
-4.82582,0.48114,-1.43803,-1.46805,-0.23623,2.66003,0.00165
-4.82701,0.48093,-1.43828,-1.46829,-0.23574,2.66024,0.00165
-4.82820,0.48072,-1.43853,-1.46852,-0.23527,2.66045,0.00164
-4.82939,0.48051,-1.43878,-1.46875,-0.23481,2.66066,0.00163
-4.83058,0.48031,-1.43902,-1.46898,-0.23435,2.66086,0.00162
-4.83177,0.48011,-1.43925,-1.46920,-0.23390,2.66106,0.00161
-4.83296,0.47992,-1.43948,-1.46942,-0.23346,2.66125,0.00161
-4.83415,0.47972,-1.43971,-1.46963,-0.23302,2.66144,0.00160
-4.83533,0.47954,-1.43993,-1.46984,-0.23260,2.66163,0.00160
-4.83652,0.47935,-1.44015,-1.47004,-0.23218,2.66181,0.00159
-4.83771,0.47917,-1.44037,-1.47024,-0.23177,2.66200,0.00159
-4.83890,0.47899,-1.44058,-1.47044,-0.23136,2.66217,0.00158
-4.84009,0.47886,-1.44072,-1.47059,-0.23107,2.66230,0.00158
-4.84128,0.47867,-1.44093,-1.47093,-0.23054,2.66249,0.00157
-4.84247,0.47849,-1.44112,-1.47126,-0.23002,2.66267,0.00156
-4.84366,0.47831,-1.44132,-1.47158,-0.22951,2.66285,0.00156
-4.84485,0.47813,-1.44151,-1.47190,-0.22901,2.66303,0.00155
-4.84603,0.47795,-1.44170,-1.47221,-0.22851,2.66320,0.00154
-4.84722,0.47778,-1.44188,-1.47252,-0.22803,2.66337,0.00154
-4.84841,0.47761,-1.44206,-1.47282,-0.22755,2.66354,0.00153
-4.84960,0.47744,-1.44224,-1.47312,-0.22708,2.66370,0.00153
-4.85079,0.47728,-1.44241,-1.47341,-0.22662,2.66387,0.00152
-4.85198,0.47712,-1.44258,-1.47370,-0.22617,2.66403,0.00152
-4.85317,0.47696,-1.44275,-1.47398,-0.22573,2.66418,0.00151
-4.85436,0.47680,-1.44292,-1.47425,-0.22529,2.66434,0.00151
-4.85555,0.47665,-1.44308,-1.47452,-0.22486,2.66449,0.00151
-4.85674,0.47654,-1.44319,-1.47473,-0.22455,2.66459,0.00151
-4.85792,0.47638,-1.44334,-1.47516,-0.22397,2.66475,0.00150
-4.85911,0.47622,-1.44349,-1.47558,-0.22341,2.66491,0.00149
-4.86030,0.47606,-1.44364,-1.47599,-0.22286,2.66507,0.00148
-4.86149,0.47591,-1.44378,-1.47640,-0.22232,2.66522,0.00148
-4.86268,0.47576,-1.44392,-1.47680,-0.22178,2.66537,0.00147
-4.86387,0.47561,-1.44406,-1.47719,-0.22126,2.66552,0.00147
-4.86506,0.47546,-1.44419,-1.47758,-0.22074,2.66566,0.00146
-4.86625,0.47532,-1.44432,-1.47796,-0.22023,2.66580,0.00146
-4.86744,0.47518,-1.44445,-1.47833,-0.21973,2.66594,0.00145
-4.86862,0.47504,-1.44458,-1.47870,-0.21924,2.66608,0.00145
-4.86981,0.47490,-1.44471,-1.47906,-0.21876,2.66621,0.00145
-4.87100,0.47477,-1.44483,-1.47941,-0.21829,2.66634,0.00144
-4.87219,0.47463,-1.44495,-1.47976,-0.21782,2.66647,0.00144
-4.87338,0.47450,-1.44507,-1.48010,-0.21736,2.66660,0.00144
-4.87457,0.47438,-1.44519,-1.48044,-0.21691,2.66673,0.00144
-4.87576,0.47425,-1.44530,-1.48077,-0.21647,2.66685,0.00144
-4.87695,0.47423,-1.44532,-1.48086,-0.21635,2.66688,0.00144
-4.87814,0.47408,-1.44543,-1.48144,-0.21567,2.66702,0.00143
-4.87932,0.47393,-1.44554,-1.48202,-0.21500,2.66717,0.00142
-4.88051,0.47379,-1.44565,-1.48258,-0.21433,2.66731,0.00141
-4.88170,0.47364,-1.44576,-1.48314,-0.21368,2.66744,0.00140
-4.88289,0.47351,-1.44586,-1.48369,-0.21304,2.66758,0.00139
-4.88408,0.47337,-1.44596,-1.48422,-0.21241,2.66771,0.00139
-4.88527,0.47324,-1.44606,-1.48475,-0.21179,2.66784,0.00138
-4.88646,0.47311,-1.44616,-1.48527,-0.21118,2.66797,0.00137
-4.88765,0.47298,-1.44625,-1.48578,-0.21058,2.66810,0.00137
-4.88884,0.47285,-1.44635,-1.48628,-0.20999,2.66822,0.00136
-4.89002,0.47273,-1.44644,-1.48677,-0.20942,2.66834,0.00136
-4.89121,0.47260,-1.44653,-1.48725,-0.20885,2.66846,0.00136
-4.89240,0.47248,-1.44662,-1.48773,-0.20829,2.66858,0.00135
-4.89359,0.47237,-1.44670,-1.48819,-0.20774,2.66869,0.00135
-4.89478,0.47225,-1.44679,-1.48865,-0.20719,2.66881,0.00135
-4.89597,0.47214,-1.44687,-1.48910,-0.20666,2.66892,0.00135
-4.89716,0.47202,-1.44695,-1.48954,-0.20614,2.66903,0.00135
-4.89835,0.47192,-1.44703,-1.48998,-0.20563,2.66913,0.00135
-4.89954,0.47181,-1.44711,-1.49041,-0.20512,2.66924,0.00134
-4.90073,0.47170,-1.44719,-1.49083,-0.20462,2.66934,0.00134
-4.90191,0.47160,-1.44726,-1.49124,-0.20413,2.66944,0.00135
-4.90310,0.47150,-1.44734,-1.49165,-0.20365,2.66954,0.00135
-4.90429,0.47140,-1.44741,-1.49205,-0.20318,2.66964,0.00135
-4.90548,0.47130,-1.44748,-1.49244,-0.20271,2.66974,0.00135
-4.90667,0.47120,-1.44755,-1.49282,-0.20226,2.66983,0.00135
-4.90786,0.47115,-1.44758,-1.49303,-0.20202,2.66988,0.00135
-4.90905,0.47105,-1.44763,-1.49361,-0.20140,2.66997,0.00135
-4.91024,0.47096,-1.44767,-1.49418,-0.20080,2.67007,0.00134
-4.91143,0.47086,-1.44771,-1.49473,-0.20020,2.67016,0.00134
-4.91261,0.47077,-1.44775,-1.49528,-0.19962,2.67025,0.00134
-4.91380,0.47068,-1.44779,-1.49582,-0.19904,2.67034,0.00133
-4.91499,0.47059,-1.44783,-1.49635,-0.19848,2.67043,0.00133
-4.91618,0.47050,-1.44787,-1.49687,-0.19792,2.67051,0.00133
-4.91737,0.47041,-1.44790,-1.49738,-0.19737,2.67060,0.00133
-4.91856,0.47032,-1.44794,-1.49788,-0.19683,2.67068,0.00133
-4.91975,0.47024,-1.44798,-1.49837,-0.19631,2.67076,0.00133
-4.92094,0.47016,-1.44801,-1.49886,-0.19579,2.67084,0.00133
-4.92213,0.47008,-1.44804,-1.49933,-0.19527,2.67092,0.00133
-4.92331,0.47000,-1.44808,-1.49980,-0.19477,2.67100,0.00133
-4.92450,0.46992,-1.44811,-1.50026,-0.19428,2.67107,0.00134
-4.92569,0.46984,-1.44814,-1.50071,-0.19379,2.67114,0.00134
-4.92688,0.46977,-1.44817,-1.50116,-0.19331,2.67122,0.00134
-4.92807,0.46970,-1.44820,-1.50160,-0.19284,2.67129,0.00134
-4.92926,0.46962,-1.44823,-1.50203,-0.19238,2.67136,0.00134
-4.93045,0.46957,-1.44825,-1.50233,-0.19206,2.67141,0.00135
-4.93164,0.46950,-1.44827,-1.50281,-0.19155,2.67147,0.00135
-4.93283,0.46943,-1.44829,-1.50329,-0.19105,2.67154,0.00135
-4.93401,0.46936,-1.44831,-1.50375,-0.19056,2.67161,0.00135
-4.93520,0.46930,-1.44833,-1.50421,-0.19008,2.67167,0.00135
-4.93639,0.46923,-1.44835,-1.50467,-0.18961,2.67174,0.00136
-4.93758,0.46916,-1.44837,-1.50511,-0.18915,2.67180,0.00136
-4.93877,0.46910,-1.44838,-1.50555,-0.18869,2.67186,0.00136
-4.93996,0.46904,-1.44840,-1.50602,-0.18820,2.67192,0.00136
-4.94115,0.46897,-1.44841,-1.50649,-0.18772,2.67198,0.00137
-4.94234,0.46891,-1.44842,-1.50695,-0.18725,2.67204,0.00137
-4.94353,0.46885,-1.44843,-1.50740,-0.18678,2.67210,0.00137
-4.94472,0.46881,-1.44844,-1.50775,-0.18642,2.67214,0.00137
-4.94590,0.46875,-1.44844,-1.50821,-0.18595,2.67220,0.00138
-4.94709,0.46869,-1.44845,-1.50866,-0.18549,2.67226,0.00138
-4.94828,0.46866,-1.44846,-1.50888,-0.18526,2.67228,0.00138
-4.94947,0.46860,-1.44846,-1.50934,-0.18479,2.67234,0.00138
-4.95066,0.46855,-1.44846,-1.50980,-0.18433,2.67239,0.00139
-4.95185,0.46852,-1.44847,-1.51003,-0.18410,2.67242,0.00139
-4.95304,0.46846,-1.44848,-1.51052,-0.18359,2.67248,0.00139
-4.95423,0.46839,-1.44850,-1.51100,-0.18309,2.67254,0.00139
-4.95542,0.46833,-1.44851,-1.51148,-0.18260,2.67260,0.00139
-4.95660,0.46827,-1.44853,-1.51194,-0.18211,2.67266,0.00139
-4.95779,0.46821,-1.44854,-1.51240,-0.18164,2.67271,0.00140
-4.95898,0.46815,-1.44855,-1.51285,-0.18117,2.67277,0.00140
-4.96017,0.46809,-1.44857,-1.51330,-0.18071,2.67283,0.00140
-4.96136,0.46807,-1.44857,-1.51349,-0.18051,2.67285,0.00140
-4.96255,0.46800,-1.44858,-1.51413,-0.17987,2.67292,0.00140
-4.96374,0.46793,-1.44859,-1.51476,-0.17924,2.67298,0.00139
-4.96493,0.46786,-1.44859,-1.51538,-0.17862,2.67304,0.00139
-4.96612,0.46779,-1.44860,-1.51598,-0.17801,2.67311,0.00139
-4.96730,0.46773,-1.44861,-1.51658,-0.17741,2.67317,0.00139
-4.96849,0.46766,-1.44862,-1.51716,-0.17682,2.67323,0.00138
-4.96968,0.46760,-1.44862,-1.51774,-0.17624,2.67329,0.00138
-4.97087,0.46754,-1.44863,-1.51830,-0.17567,2.67335,0.00138
-4.97206,0.46748,-1.44863,-1.51886,-0.17511,2.67340,0.00138
-4.97325,0.46742,-1.44864,-1.51940,-0.17456,2.67346,0.00138
-4.97444,0.46736,-1.44864,-1.51994,-0.17402,2.67351,0.00138
-4.97563,0.46730,-1.44865,-1.52047,-0.17348,2.67357,0.00138
-4.97682,0.46724,-1.44865,-1.52099,-0.17296,2.67362,0.00138
-4.97800,0.46719,-1.44866,-1.52150,-0.17244,2.67367,0.00139
-4.97919,0.46714,-1.44866,-1.52200,-0.17194,2.67372,0.00139
-4.98038,0.46708,-1.44866,-1.52249,-0.17144,2.67377,0.00139
-4.98157,0.46703,-1.44867,-1.52297,-0.17095,2.67382,0.00139
-4.98276,0.46698,-1.44867,-1.52345,-0.17047,2.67387,0.00140
-4.98395,0.46693,-1.44867,-1.52392,-0.16999,2.67392,0.00140
-4.98514,0.46688,-1.44868,-1.52437,-0.16953,2.67396,0.00140
-4.98633,0.46683,-1.44868,-1.52483,-0.16907,2.67401,0.00141
-4.98752,0.46683,-1.44868,-1.52489,-0.16901,2.67401,0.00141
-4.98871,0.46677,-1.44868,-1.52549,-0.16840,2.67407,0.00140
-4.98989,0.46671,-1.44869,-1.52608,-0.16781,2.67412,0.00140
-4.99108,0.46665,-1.44869,-1.52666,-0.16723,2.67418,0.00140
-4.99227,0.46659,-1.44869,-1.52724,-0.16665,2.67423,0.00140
-4.99346,0.46654,-1.44870,-1.52780,-0.16609,2.67428,0.00140
-4.99465,0.46648,-1.44870,-1.52835,-0.16553,2.67433,0.00140
-4.99584,0.46643,-1.44870,-1.52889,-0.16499,2.67438,0.00140
-4.99703,0.46638,-1.44871,-1.52943,-0.16445,2.67443,0.00140
-4.99822,0.46633,-1.44871,-1.52995,-0.16392,2.67448,0.00140
-4.99941,0.46628,-1.44871,-1.53047,-0.16340,2.67452,0.00140
-5.00059,0.46623,-1.44871,-1.53097,-0.16289,2.67457,0.00141
-5.00178,0.46618,-1.44871,-1.53147,-0.16239,2.67461,0.00141
-5.00297,0.46613,-1.44871,-1.53196,-0.16190,2.67466,0.00141
-5.00416,0.46608,-1.44871,-1.53244,-0.16141,2.67470,0.00141
-5.00535,0.46604,-1.44872,-1.53292,-0.16093,2.67474,0.00142
-5.00654,0.46599,-1.44872,-1.53338,-0.16046,2.67479,0.00142
-5.00773,0.46595,-1.44872,-1.53384,-0.16000,2.67483,0.00142
-5.00892,0.46592,-1.44872,-1.53412,-0.15972,2.67485,0.00143
-5.01011,0.46588,-1.44871,-1.53463,-0.15922,2.67489,0.00143
-5.01129,0.46584,-1.44870,-1.53513,-0.15872,2.67493,0.00143
-5.01248,0.46579,-1.44870,-1.53562,-0.15823,2.67497,0.00143
-5.01367,0.46575,-1.44869,-1.53610,-0.15775,2.67501,0.00144
-5.01486,0.46571,-1.44869,-1.53658,-0.15727,2.67504,0.00144
-5.01605,0.46567,-1.44868,-1.53705,-0.15681,2.67508,0.00144
-5.01724,0.46563,-1.44867,-1.53751,-0.15635,2.67512,0.00145
-5.01843,0.46563,-1.44867,-1.53756,-0.15630,2.67512,0.00145
-5.01962,0.46559,-1.44866,-1.53805,-0.15581,2.67515,0.00145
-5.02081,0.46555,-1.44865,-1.53854,-0.15534,2.67519,0.00145
-5.02200,0.46552,-1.44864,-1.53902,-0.15486,2.67522,0.00146
-5.02318,0.46548,-1.44863,-1.53949,-0.15440,2.67526,0.00146
-5.02437,0.46545,-1.44862,-1.53991,-0.15399,2.67529,0.00146
-5.02556,0.46541,-1.44861,-1.54040,-0.15350,2.67532,0.00147
-5.02675,0.46537,-1.44859,-1.54089,-0.15302,2.67535,0.00147
-5.02794,0.46534,-1.44858,-1.54137,-0.15255,2.67538,0.00147
-5.02913,0.46531,-1.44857,-1.54185,-0.15209,2.67541,0.00148
-5.03032,0.46528,-1.44855,-1.54227,-0.15168,2.67544,0.00148
-5.03151,0.46524,-1.44854,-1.54275,-0.15121,2.67547,0.00148
-5.03270,0.46521,-1.44852,-1.54322,-0.15075,2.67550,0.00149
-5.03388,0.46519,-1.44851,-1.54345,-0.15052,2.67551,0.00149
-5.03507,0.46516,-1.44849,-1.54396,-0.15004,2.67554,0.00149
-5.03626,0.46513,-1.44847,-1.54445,-0.14956,2.67557,0.00149
-5.03745,0.46510,-1.44846,-1.54493,-0.14909,2.67560,0.00150
-5.03864,0.46507,-1.44844,-1.54541,-0.14863,2.67563,0.00150
-5.03983,0.46504,-1.44842,-1.54584,-0.14822,2.67565,0.00150
-5.04102,0.46501,-1.44840,-1.54632,-0.14775,2.67568,0.00151
-5.04221,0.46498,-1.44838,-1.54679,-0.14729,2.67570,0.00151
-5.04340,0.46497,-1.44837,-1.54703,-0.14706,2.67571,0.00151
-5.04458,0.46494,-1.44835,-1.54751,-0.14660,2.67574,0.00151
-5.04577,0.46491,-1.44833,-1.54799,-0.14614,2.67576,0.00152
-5.04696,0.46494,-1.44822,-1.54829,-0.14594,2.67573,0.00152
-5.04815,0.46539,-1.44723,-1.54939,-0.14579,2.67529,0.00155
-5.04934,0.46583,-1.44627,-1.55048,-0.14564,2.67486,0.00158
-5.05053,0.46627,-1.44531,-1.55155,-0.14550,2.67443,0.00161
-5.05172,0.46669,-1.44438,-1.55260,-0.14536,2.67401,0.00164
-5.05291,0.46712,-1.44346,-1.55363,-0.14522,2.67360,0.00167
-5.05410,0.46753,-1.44256,-1.55464,-0.14508,2.67319,0.00169
-5.05528,0.46795,-1.44167,-1.55564,-0.14494,2.67278,0.00172
-5.05647,0.46835,-1.44079,-1.55662,-0.14481,2.67238,0.00174
-5.05766,0.46875,-1.43994,-1.55758,-0.14468,2.67199,0.00177
-5.05885,0.46915,-1.43909,-1.55853,-0.14455,2.67160,0.00179
-5.06004,0.46954,-1.43826,-1.55946,-0.14443,2.67122,0.00182
-5.06123,0.46992,-1.43745,-1.56038,-0.14430,2.67084,0.00184
-5.06242,0.47030,-1.43665,-1.56128,-0.14418,2.67046,0.00186
-5.06361,0.47067,-1.43586,-1.56216,-0.14406,2.67010,0.00188
-5.06480,0.47104,-1.43508,-1.56303,-0.14395,2.66973,0.00190
-5.06599,0.47140,-1.43432,-1.56389,-0.14383,2.66937,0.00192
-5.06717,0.47176,-1.43357,-1.56473,-0.14372,2.66902,0.00195
-5.06836,0.47212,-1.43284,-1.56555,-0.14361,2.66867,0.00197
-5.06955,0.47247,-1.43211,-1.56636,-0.14350,2.66832,0.00198
-5.07074,0.47281,-1.43140,-1.56716,-0.14339,2.66798,0.00200
-5.07193,0.47315,-1.43070,-1.56795,-0.14329,2.66765,0.00202
-5.07312,0.47348,-1.43002,-1.56872,-0.14318,2.66732,0.00204
-5.07431,0.47381,-1.42934,-1.56948,-0.14308,2.66699,0.00206
-5.07550,0.47414,-1.42868,-1.57023,-0.14298,2.66667,0.00208
-5.07669,0.47446,-1.42803,-1.57096,-0.14288,2.66635,0.00209
-5.07787,0.47477,-1.42739,-1.57168,-0.14279,2.66604,0.00211
-5.07906,0.47509,-1.42676,-1.57239,-0.14269,2.66573,0.00212
-5.08025,0.47539,-1.42614,-1.57309,-0.14260,2.66542,0.00214
-5.08144,0.47570,-1.42553,-1.57377,-0.14251,2.66512,0.00216
-5.08263,0.47599,-1.42493,-1.57445,-0.14242,2.66483,0.00217
-5.08382,0.47629,-1.42434,-1.57511,-0.14233,2.66453,0.00219
-5.08501,0.47658,-1.42376,-1.57576,-0.14224,2.66424,0.00220
-5.08620,0.47687,-1.42319,-1.57640,-0.14215,2.66396,0.00221
-5.08739,0.47715,-1.42263,-1.57703,-0.14207,2.66368,0.00223
-5.08857,0.47743,-1.42208,-1.57765,-0.14199,2.66340,0.00224
-5.08976,0.47770,-1.42154,-1.57826,-0.14191,2.66313,0.00225
-5.09095,0.47797,-1.42101,-1.57886,-0.14182,2.66286,0.00227
-5.09214,0.47824,-1.42049,-1.57945,-0.14175,2.66259,0.00228
-5.09333,0.47850,-1.41998,-1.58003,-0.14167,2.66233,0.00229
-5.09452,0.47876,-1.41947,-1.58060,-0.14159,2.66207,0.00230
-5.09571,0.47901,-1.41898,-1.58116,-0.14152,2.66182,0.00231
-5.09690,0.47927,-1.41849,-1.58171,-0.14144,2.66157,0.00233
-5.09809,0.47951,-1.41801,-1.58225,-0.14137,2.66132,0.00234
-5.09927,0.47976,-1.41754,-1.58278,-0.14130,2.66108,0.00235
-5.10046,0.48000,-1.41708,-1.58330,-0.14123,2.66084,0.00236
-5.10165,0.48024,-1.41662,-1.58382,-0.14116,2.66060,0.00237
-5.10284,0.48047,-1.41617,-1.58432,-0.14109,2.66036,0.00238
-5.10403,0.48070,-1.41573,-1.58482,-0.14102,2.66013,0.00239
-5.10522,0.48093,-1.41530,-1.58531,-0.14095,2.65991,0.00240
-5.10641,0.48119,-1.41482,-1.58584,-0.14090,2.65965,0.00241
-5.10760,0.48171,-1.41380,-1.58675,-0.14098,2.65913,0.00243
-5.10879,0.48223,-1.41281,-1.58765,-0.14105,2.65862,0.00245
-5.10998,0.48274,-1.41183,-1.58854,-0.14112,2.65812,0.00247
-5.11116,0.48325,-1.41087,-1.58941,-0.14119,2.65762,0.00249
-5.11235,0.48374,-1.40993,-1.59026,-0.14126,2.65713,0.00251
-5.11354,0.48423,-1.40900,-1.59111,-0.14133,2.65664,0.00253
-5.11473,0.48472,-1.40809,-1.59193,-0.14140,2.65616,0.00255
-5.11592,0.48520,-1.40719,-1.59274,-0.14147,2.65569,0.00256
-5.11711,0.48567,-1.40631,-1.59354,-0.14154,2.65522,0.00258
-5.11830,0.48613,-1.40544,-1.59433,-0.14160,2.65476,0.00260
-5.11949,0.48659,-1.40459,-1.59510,-0.14167,2.65431,0.00261
-5.12068,0.48705,-1.40375,-1.59585,-0.14173,2.65386,0.00263
-5.12186,0.48749,-1.40293,-1.59660,-0.14180,2.65342,0.00264
-5.12305,0.48793,-1.40212,-1.59733,-0.14186,2.65298,0.00266
-5.12424,0.48837,-1.40133,-1.59805,-0.14192,2.65255,0.00267
-5.12543,0.48879,-1.40054,-1.59876,-0.14198,2.65212,0.00268
-5.12662,0.48922,-1.39978,-1.59945,-0.14205,2.65170,0.00269
-5.12781,0.48963,-1.39902,-1.60014,-0.14210,2.65129,0.00271
-5.12900,0.49004,-1.39828,-1.60081,-0.14216,2.65088,0.00272
-5.13019,0.49045,-1.39755,-1.60147,-0.14222,2.65048,0.00273
-5.13138,0.49085,-1.39683,-1.60212,-0.14228,2.65008,0.00274
-5.13256,0.49124,-1.39613,-1.60276,-0.14233,2.64969,0.00275
-5.13375,0.49163,-1.39544,-1.60339,-0.14239,2.64930,0.00276
-5.13494,0.49202,-1.39476,-1.60400,-0.14244,2.64892,0.00277
-5.13613,0.49239,-1.39409,-1.60461,-0.14250,2.64855,0.00278
-5.13732,0.49277,-1.39343,-1.60521,-0.14255,2.64817,0.00279
-5.13851,0.49313,-1.39278,-1.60579,-0.14260,2.64781,0.00280
-5.13970,0.49350,-1.39215,-1.60637,-0.14265,2.64745,0.00281
-5.14089,0.49385,-1.39152,-1.60694,-0.14271,2.64709,0.00282
-5.14208,0.49421,-1.39091,-1.60749,-0.14276,2.64674,0.00282
-5.14326,0.49455,-1.39031,-1.60804,-0.14280,2.64639,0.00283
-5.14445,0.49490,-1.38971,-1.60858,-0.14285,2.64605,0.00284
-5.14564,0.49523,-1.38913,-1.60911,-0.14290,2.64572,0.00285
-5.14683,0.49557,-1.38856,-1.60963,-0.14295,2.64538,0.00285
-5.14802,0.49590,-1.38799,-1.61014,-0.14299,2.64506,0.00286
-5.14921,0.49622,-1.38744,-1.61065,-0.14304,2.64473,0.00286
-5.15040,0.49654,-1.38690,-1.61114,-0.14308,2.64441,0.00287
-5.15159,0.49685,-1.38636,-1.61163,-0.14313,2.64410,0.00288
-5.15278,0.49716,-1.38584,-1.61211,-0.14317,2.64379,0.00288
-5.15397,0.49747,-1.38532,-1.61258,-0.14321,2.64348,0.00289
-5.15515,0.49777,-1.38481,-1.61304,-0.14325,2.64318,0.00289
-5.15634,0.49807,-1.38431,-1.61349,-0.14329,2.64288,0.00290
-5.15753,0.49836,-1.38382,-1.61394,-0.14333,2.64259,0.00290
-5.15872,0.49865,-1.38334,-1.61438,-0.14337,2.64230,0.00290
-5.15991,0.49893,-1.38286,-1.61481,-0.14341,2.64202,0.00291
-5.16110,0.49921,-1.38240,-1.61524,-0.14345,2.64173,0.00291
-5.16229,0.49949,-1.38194,-1.61566,-0.14349,2.64146,0.00292
-5.16348,0.49976,-1.38149,-1.61607,-0.14352,2.64118,0.00292
-5.16467,0.50003,-1.38105,-1.61647,-0.14356,2.64091,0.00292
-5.16585,0.50023,-1.38072,-1.61676,-0.14360,2.64072,0.00293
-5.16704,0.50086,-1.37961,-1.61764,-0.14381,2.64010,0.00294
-5.16823,0.50148,-1.37853,-1.61850,-0.14402,2.63948,0.00296
-5.16942,0.50210,-1.37746,-1.61934,-0.14423,2.63887,0.00297
-5.17061,0.50270,-1.37641,-1.62018,-0.14443,2.63828,0.00299
-5.17180,0.50330,-1.37538,-1.62099,-0.14463,2.63768,0.00300
-5.17299,0.50389,-1.37437,-1.62180,-0.14483,2.63710,0.00302
-5.17418,0.50447,-1.37337,-1.62259,-0.14502,2.63652,0.00303
-5.17537,0.50505,-1.37239,-1.62336,-0.14521,2.63596,0.00304
-5.17655,0.50561,-1.37143,-1.62412,-0.14540,2.63539,0.00305
-5.17774,0.50617,-1.37049,-1.62487,-0.14559,2.63484,0.00307
-5.17893,0.50672,-1.36956,-1.62561,-0.14577,2.63429,0.00308
-5.18012,0.50727,-1.36864,-1.62633,-0.14595,2.63375,0.00309
-5.18131,0.50781,-1.36775,-1.62704,-0.14613,2.63322,0.00310
-5.18250,0.50834,-1.36686,-1.62774,-0.14631,2.63269,0.00310
-5.18369,0.50886,-1.36600,-1.62843,-0.14648,2.63217,0.00311
-5.18488,0.50938,-1.36514,-1.62910,-0.14665,2.63166,0.00312
-5.18607,0.50989,-1.36430,-1.62977,-0.14682,2.63116,0.00313
-5.18725,0.51039,-1.36348,-1.63042,-0.14699,2.63066,0.00314
-5.18844,0.51089,-1.36267,-1.63106,-0.14715,2.63016,0.00314
-5.18963,0.51137,-1.36188,-1.63169,-0.14731,2.62968,0.00315
-5.19082,0.51186,-1.36109,-1.63231,-0.14747,2.62920,0.00316
-5.19201,0.51233,-1.36032,-1.63292,-0.14763,2.62872,0.00316
-5.19320,0.51280,-1.35957,-1.63352,-0.14778,2.62826,0.00317
-5.19439,0.51327,-1.35883,-1.63411,-0.14793,2.62780,0.00317
-5.19558,0.51372,-1.35810,-1.63468,-0.14808,2.62734,0.00318
-5.19677,0.51417,-1.35738,-1.63525,-0.14823,2.62689,0.00318
-5.19796,0.51462,-1.35667,-1.63581,-0.14837,2.62645,0.00319
-5.19914,0.51506,-1.35598,-1.63636,-0.14851,2.62601,0.00319
-5.20033,0.51549,-1.35530,-1.63690,-0.14865,2.62558,0.00320
-5.20152,0.51592,-1.35463,-1.63743,-0.14879,2.62516,0.00320
-5.20271,0.51634,-1.35397,-1.63795,-0.14892,2.62474,0.00320
-5.20390,0.51675,-1.35332,-1.63846,-0.14906,2.62432,0.00321
-5.20509,0.51716,-1.35269,-1.63897,-0.14919,2.62391,0.00321
-5.20628,0.51756,-1.35206,-1.63946,-0.14932,2.62351,0.00321
-5.20747,0.51796,-1.35145,-1.63995,-0.14944,2.62311,0.00321
-5.20866,0.51836,-1.35084,-1.64043,-0.14957,2.62272,0.00322
-5.20984,0.51874,-1.35025,-1.64090,-0.14969,2.62233,0.00322
-5.21103,0.51913,-1.34966,-1.64136,-0.14981,2.62195,0.00322
-5.21222,0.51950,-1.34909,-1.64182,-0.14993,2.62158,0.00322
-5.21341,0.51987,-1.34853,-1.64227,-0.15005,2.62120,0.00322
-5.21460,0.52024,-1.34797,-1.64271,-0.15016,2.62084,0.00322
-5.21579,0.52060,-1.34743,-1.64314,-0.15028,2.62048,0.00322
-5.21698,0.52096,-1.34689,-1.64357,-0.15039,2.62012,0.00322
-5.21817,0.52131,-1.34636,-1.64398,-0.15050,2.61977,0.00322
-5.21936,0.52166,-1.34585,-1.64439,-0.15061,2.61942,0.00323
-5.22054,0.52200,-1.34534,-1.64480,-0.15071,2.61908,0.00323
-5.22173,0.52233,-1.34484,-1.64520,-0.15082,2.61874,0.00323
-5.22292,0.52267,-1.34435,-1.64559,-0.15092,2.61841,0.00323
-5.22411,0.52299,-1.34386,-1.64597,-0.15102,2.61808,0.00323
-5.22530,0.52332,-1.34339,-1.64635,-0.15112,2.61776,0.00322
-5.22649,0.52363,-1.34292,-1.64672,-0.15122,2.61744,0.00322
-5.22768,0.52395,-1.34246,-1.64709,-0.15131,2.61712,0.00322
-5.22887,0.52426,-1.34201,-1.64745,-0.15141,2.61681,0.00322
-5.23006,0.52456,-1.34157,-1.64780,-0.15150,2.61651,0.00322
-5.23124,0.52479,-1.34124,-1.64806,-0.15157,2.61628,0.00322
-5.23243,0.52522,-1.34057,-1.64857,-0.15173,2.61585,0.00322
-5.23362,0.52565,-1.33992,-1.64907,-0.15188,2.61542,0.00323
-5.23481,0.52607,-1.33928,-1.64956,-0.15203,2.61500,0.00323
-5.23600,0.52649,-1.33865,-1.65004,-0.15217,2.61459,0.00323
-5.23719,0.52690,-1.33803,-1.65052,-0.15232,2.61418,0.00324
-5.23838,0.52731,-1.33742,-1.65098,-0.15246,2.61377,0.00324
-5.23957,0.52771,-1.33682,-1.65144,-0.15260,2.61337,0.00324
-5.24076,0.52810,-1.33623,-1.65189,-0.15274,2.61298,0.00324
-5.24195,0.52849,-1.33566,-1.65234,-0.15287,2.61259,0.00324
-5.24313,0.52887,-1.33509,-1.65277,-0.15300,2.61221,0.00324
-5.24432,0.52925,-1.33453,-1.65320,-0.15313,2.61183,0.00324
-5.24551,0.52963,-1.33398,-1.65362,-0.15326,2.61146,0.00324
-5.24670,0.52999,-1.33344,-1.65404,-0.15339,2.61109,0.00325
-5.24789,0.53036,-1.33291,-1.65445,-0.15351,2.61073,0.00325
-5.24908,0.53071,-1.33239,-1.65485,-0.15364,2.61037,0.00325
-5.25027,0.53107,-1.33187,-1.65524,-0.15376,2.61002,0.00325
-5.25146,0.53142,-1.33137,-1.65563,-0.15388,2.60967,0.00325
-5.25265,0.53176,-1.33088,-1.65601,-0.15399,2.60932,0.00325
-5.25383,0.53210,-1.33039,-1.65638,-0.15411,2.60899,0.00325
-5.25502,0.53243,-1.32991,-1.65675,-0.15422,2.60865,0.00325
-5.25621,0.53276,-1.32944,-1.65711,-0.15433,2.60832,0.00324
-5.25740,0.53309,-1.32898,-1.65747,-0.15444,2.60800,0.00324
-5.25859,0.53341,-1.32852,-1.65782,-0.15455,2.60768,0.00324
-5.25978,0.53372,-1.32807,-1.65817,-0.15465,2.60736,0.00324
-5.26097,0.53403,-1.32763,-1.65850,-0.15476,2.60705,0.00324
-5.26216,0.53409,-1.32755,-1.65856,-0.15478,2.60699,0.00324
-5.26335,0.53462,-1.32675,-1.65915,-0.15499,2.60647,0.00325
-5.26453,0.53514,-1.32597,-1.65973,-0.15519,2.60595,0.00325
-5.26572,0.53565,-1.32519,-1.66030,-0.15539,2.60544,0.00326
-5.26691,0.53616,-1.32443,-1.66086,-0.15559,2.60494,0.00326
-5.26810,0.53666,-1.32369,-1.66141,-0.15578,2.60444,0.00327
-5.26929,0.53716,-1.32295,-1.66195,-0.15598,2.60395,0.00327
-5.27048,0.53764,-1.32223,-1.66248,-0.15617,2.60346,0.00327
-5.27167,0.53813,-1.32152,-1.66300,-0.15635,2.60299,0.00328
-5.27286,0.53860,-1.32082,-1.66352,-0.15654,2.60251,0.00328
-5.27405,0.53907,-1.32014,-1.66402,-0.15672,2.60205,0.00328
-5.27523,0.53953,-1.31946,-1.66452,-0.15689,2.60159,0.00328
-5.27642,0.53999,-1.31880,-1.66500,-0.15707,2.60113,0.00329
-5.27761,0.54044,-1.31815,-1.66548,-0.15724,2.60068,0.00329
-5.27880,0.54088,-1.31751,-1.66596,-0.15741,2.60024,0.00329
-5.27999,0.54132,-1.31688,-1.66642,-0.15758,2.59981,0.00329
-5.28118,0.54175,-1.31626,-1.66687,-0.15774,2.59938,0.00329
-5.28237,0.54218,-1.31565,-1.66732,-0.15790,2.59895,0.00329
-5.28356,0.54260,-1.31506,-1.66776,-0.15806,2.59853,0.00329
-5.28475,0.54302,-1.31447,-1.66819,-0.15822,2.59812,0.00330
-5.28594,0.54343,-1.31389,-1.66862,-0.15837,2.59771,0.00330
-5.28712,0.54383,-1.31332,-1.66904,-0.15852,2.59731,0.00330
-5.28831,0.54423,-1.31276,-1.66945,-0.15867,2.59691,0.00330
-5.28950,0.54462,-1.31221,-1.66985,-0.15882,2.59652,0.00330
-5.29069,0.54501,-1.31167,-1.67025,-0.15896,2.59613,0.00330
-5.29188,0.54539,-1.31114,-1.67064,-0.15910,2.59575,0.00330
-5.29307,0.54577,-1.31062,-1.67103,-0.15924,2.59537,0.00330
-5.29426,0.54614,-1.31011,-1.67140,-0.15938,2.59500,0.00329
-5.29545,0.54651,-1.30961,-1.67178,-0.15952,2.59463,0.00329
-5.29664,0.54687,-1.30911,-1.67214,-0.15965,2.59427,0.00329
-5.29782,0.54723,-1.30862,-1.67250,-0.15978,2.59391,0.00329
-5.29901,0.54758,-1.30815,-1.67285,-0.15991,2.59356,0.00329
-5.30020,0.54793,-1.30767,-1.67320,-0.16003,2.59321,0.00329
-5.30139,0.54827,-1.30721,-1.67354,-0.16016,2.59287,0.00329
-5.30258,0.54861,-1.30676,-1.67388,-0.16028,2.59253,0.00329
-5.30377,0.54894,-1.30631,-1.67421,-0.16040,2.59220,0.00329
-5.30496,0.54927,-1.30587,-1.67453,-0.16052,2.59187,0.00328
-5.30615,0.54935,-1.30575,-1.67462,-0.16055,2.59178,0.00328
-5.30734,0.54987,-1.30501,-1.67517,-0.16075,2.59127,0.00329
-5.30852,0.55038,-1.30428,-1.67571,-0.16094,2.59076,0.00329
-5.30971,0.55089,-1.30356,-1.67624,-0.16112,2.59026,0.00329
-5.31090,0.55139,-1.30285,-1.67677,-0.16131,2.58976,0.00329
-5.31209,0.55188,-1.30215,-1.67728,-0.16149,2.58927,0.00330
-5.31328,0.55237,-1.30147,-1.67779,-0.16167,2.58879,0.00330
-5.31447,0.55284,-1.30080,-1.67828,-0.16184,2.58832,0.00330
-5.31566,0.55332,-1.30014,-1.67877,-0.16202,2.58785,0.00330
-5.31685,0.55378,-1.29949,-1.67925,-0.16219,2.58738,0.00330
-5.31804,0.55424,-1.29885,-1.67972,-0.16236,2.58692,0.00330
-5.31922,0.55470,-1.29822,-1.68018,-0.16252,2.58647,0.00330
-5.32041,0.55515,-1.29761,-1.68064,-0.16268,2.58603,0.00330
-5.32160,0.55559,-1.29700,-1.68109,-0.16284,2.58558,0.00331
-5.32279,0.55602,-1.29640,-1.68153,-0.16300,2.58515,0.00331
-5.32398,0.55645,-1.29582,-1.68196,-0.16316,2.58472,0.00331
-5.32517,0.55688,-1.29524,-1.68239,-0.16331,2.58430,0.00331
-5.32636,0.55730,-1.29468,-1.68281,-0.16346,2.58388,0.00331
-5.32755,0.55771,-1.29412,-1.68322,-0.16361,2.58347,0.00330
-5.32874,0.55812,-1.29357,-1.68362,-0.16375,2.58306,0.00330
-5.32993,0.55852,-1.29303,-1.68402,-0.16390,2.58266,0.00330
-5.33111,0.55892,-1.29250,-1.68441,-0.16404,2.58226,0.00330
-5.33230,0.55931,-1.29198,-1.68480,-0.16418,2.58187,0.00330
-5.33349,0.55970,-1.29147,-1.68517,-0.16431,2.58149,0.00330
-5.33468,0.56008,-1.29097,-1.68555,-0.16445,2.58110,0.00330
-5.33587,0.56045,-1.29047,-1.68591,-0.16458,2.58073,0.00330
-5.33706,0.56082,-1.28999,-1.68627,-0.16471,2.58036,0.00330
-5.33825,0.56119,-1.28951,-1.68663,-0.16484,2.57999,0.00330
-5.33944,0.56155,-1.28904,-1.68697,-0.16496,2.57963,0.00329
-5.34063,0.56191,-1.28858,-1.68731,-0.16509,2.57927,0.00329
-5.34181,0.56226,-1.28812,-1.68765,-0.16521,2.57892,0.00329
-5.34300,0.56261,-1.28768,-1.68798,-0.16533,2.57858,0.00329
-5.34419,0.56295,-1.28724,-1.68831,-0.16545,2.57823,0.00329
-5.34538,0.56300,-1.28717,-1.68835,-0.16547,2.57819,0.00329
-5.34657,0.56347,-1.28653,-1.68881,-0.16565,2.57771,0.00329
-5.34776,0.56394,-1.28589,-1.68927,-0.16583,2.57724,0.00329
-5.34895,0.56441,-1.28527,-1.68971,-0.16601,2.57678,0.00329
-5.35014,0.56487,-1.28466,-1.69015,-0.16619,2.57633,0.00329
-5.35133,0.56532,-1.28405,-1.69058,-0.16637,2.57588,0.00329
-5.35251,0.56576,-1.28346,-1.69100,-0.16654,2.57543,0.00329
-5.35370,0.56620,-1.28288,-1.69141,-0.16671,2.57499,0.00329
-5.35489,0.56664,-1.28231,-1.69182,-0.16687,2.57456,0.00329
-5.35608,0.56707,-1.28174,-1.69222,-0.16704,2.57413,0.00329
-5.35727,0.56749,-1.28119,-1.69262,-0.16720,2.57371,0.00329
-5.35846,0.56791,-1.28065,-1.69301,-0.16736,2.57330,0.00329
-5.35965,0.56832,-1.28011,-1.69339,-0.16751,2.57288,0.00329
-5.36084,0.56873,-1.27958,-1.69376,-0.16767,2.57248,0.00329
-5.36203,0.56913,-1.27907,-1.69413,-0.16782,2.57208,0.00329
-5.36321,0.56952,-1.27856,-1.69450,-0.16797,2.57168,0.00329
-5.36440,0.56991,-1.27806,-1.69485,-0.16811,2.57129,0.00329
-5.36559,0.57030,-1.27757,-1.69520,-0.16826,2.57091,0.00329
-5.36678,0.57068,-1.27708,-1.69555,-0.16840,2.57053,0.00329
-5.36797,0.57105,-1.27661,-1.69589,-0.16854,2.57016,0.00329
-5.36916,0.57142,-1.27614,-1.69622,-0.16867,2.56979,0.00329
-5.37035,0.57179,-1.27568,-1.69655,-0.16881,2.56942,0.00329
-5.37154,0.57215,-1.27523,-1.69687,-0.16894,2.56906,0.00328
-5.37273,0.57250,-1.27479,-1.69719,-0.16907,2.56871,0.00328
-5.37392,0.57284,-1.27435,-1.69749,-0.16920,2.56837,0.00328
-5.37510,0.57344,-1.27355,-1.69804,-0.16945,2.56778,0.00329
-5.37629,0.57402,-1.27277,-1.69858,-0.16970,2.56720,0.00329
-5.37748,0.57460,-1.27199,-1.69910,-0.16995,2.56662,0.00329
-5.37867,0.57518,-1.27123,-1.69962,-0.17019,2.56605,0.00330
-5.37986,0.57574,-1.27048,-1.70013,-0.17042,2.56549,0.00330
-5.38105,0.57630,-1.26975,-1.70063,-0.17066,2.56494,0.00330
-5.38224,0.57685,-1.26903,-1.70113,-0.17089,2.56439,0.00331
-5.38343,0.57739,-1.26832,-1.70161,-0.17111,2.56386,0.00331
-5.38462,0.57793,-1.26762,-1.70209,-0.17134,2.56332,0.00331
-5.38580,0.57846,-1.26693,-1.70255,-0.17156,2.56280,0.00331
-5.38699,0.57898,-1.26625,-1.70301,-0.17177,2.56228,0.00332
-5.38818,0.57950,-1.26559,-1.70347,-0.17198,2.56176,0.00332
-5.38937,0.58001,-1.26494,-1.70391,-0.17219,2.56126,0.00332
-5.39056,0.58051,-1.26429,-1.70435,-0.17240,2.56076,0.00332
-5.39175,0.58100,-1.26366,-1.70478,-0.17260,2.56026,0.00332
-5.39294,0.58149,-1.26304,-1.70520,-0.17280,2.55978,0.00332
-5.39413,0.58198,-1.26243,-1.70562,-0.17300,2.55930,0.00332
-5.39532,0.58246,-1.26183,-1.70602,-0.17319,2.55882,0.00332
-5.39650,0.58293,-1.26124,-1.70642,-0.17339,2.55835,0.00332
-5.39769,0.58339,-1.26066,-1.70682,-0.17357,2.55789,0.00332
-5.39888,0.58385,-1.26009,-1.70721,-0.17376,2.55743,0.00332
-5.40007,0.58430,-1.25953,-1.70759,-0.17394,2.55698,0.00332
-5.40126,0.58475,-1.25898,-1.70796,-0.17412,2.55653,0.00332
-5.40245,0.58519,-1.25844,-1.70833,-0.17429,2.55609,0.00332
-5.40364,0.58563,-1.25790,-1.70870,-0.17447,2.55566,0.00332
-5.40483,0.58606,-1.25738,-1.70905,-0.17464,2.55523,0.00332
-5.40602,0.58648,-1.25687,-1.70940,-0.17481,2.55481,0.00332
-5.40720,0.58690,-1.25636,-1.70975,-0.17497,2.55439,0.00332
-5.40839,0.58731,-1.25586,-1.71009,-0.17514,2.55398,0.00332
-5.40958,0.58772,-1.25537,-1.71042,-0.17530,2.55357,0.00332
-5.41077,0.58812,-1.25489,-1.71075,-0.17545,2.55317,0.00331
-5.41196,0.58852,-1.25441,-1.71107,-0.17561,2.55277,0.00331
-5.41315,0.58891,-1.25395,-1.71139,-0.17576,2.55238,0.00331
-5.41434,0.58930,-1.25349,-1.71170,-0.17591,2.55199,0.00331
-5.41553,0.58968,-1.25304,-1.71201,-0.17606,2.55161,0.00331
-5.41672,0.59006,-1.25260,-1.71231,-0.17620,2.55124,0.00331
-5.41791,0.59045,-1.25213,-1.71262,-0.17636,2.55084,0.00330
-5.41909,0.59102,-1.25141,-1.71310,-0.17660,2.55028,0.00331
-5.42028,0.59158,-1.25070,-1.71356,-0.17685,2.54972,0.00331
-5.42147,0.59214,-1.25001,-1.71402,-0.17709,2.54916,0.00331
-5.42266,0.59269,-1.24932,-1.71447,-0.17732,2.54862,0.00331
-5.42385,0.59324,-1.24865,-1.71491,-0.17755,2.54808,0.00332
-5.42504,0.59377,-1.24798,-1.71535,-0.17778,2.54754,0.00332
-5.42623,0.59430,-1.24733,-1.71578,-0.17801,2.54702,0.00332
-5.42742,0.59483,-1.24669,-1.71620,-0.17823,2.54650,0.00332
-5.42861,0.59534,-1.24606,-1.71661,-0.17844,2.54598,0.00332
-5.42979,0.59585,-1.24544,-1.71702,-0.17866,2.54548,0.00332
-5.43098,0.59636,-1.24483,-1.71742,-0.17887,2.54497,0.00332
-5.43217,0.59685,-1.24423,-1.71781,-0.17908,2.54448,0.00332
-5.43336,0.59734,-1.24364,-1.71820,-0.17928,2.54399,0.00332
-5.43455,0.59783,-1.24307,-1.71858,-0.17948,2.54351,0.00332
-5.43574,0.59830,-1.24250,-1.71895,-0.17968,2.54303,0.00332
-5.43693,0.59878,-1.24194,-1.71932,-0.17988,2.54256,0.00332
-5.43812,0.59924,-1.24139,-1.71968,-0.18007,2.54210,0.00332
-5.43931,0.59970,-1.24084,-1.72004,-0.18026,2.54164,0.00332
-5.44049,0.60016,-1.24031,-1.72039,-0.18044,2.54119,0.00332
-5.44168,0.60060,-1.23979,-1.72073,-0.18063,2.54074,0.00332
-5.44287,0.60105,-1.23927,-1.72107,-0.18081,2.54030,0.00332
-5.44406,0.60148,-1.23877,-1.72140,-0.18098,2.53986,0.00332
-5.44525,0.60191,-1.23827,-1.72173,-0.18116,2.53943,0.00332
-5.44644,0.60234,-1.23778,-1.72205,-0.18133,2.53901,0.00332
-5.44763,0.60276,-1.23730,-1.72236,-0.18150,2.53859,0.00331
-5.44882,0.60317,-1.23682,-1.72268,-0.18167,2.53818,0.00331
-5.45001,0.60358,-1.23636,-1.72298,-0.18183,2.53777,0.00331
-5.45119,0.60399,-1.23590,-1.72328,-0.18199,2.53736,0.00331
-5.45238,0.60439,-1.23545,-1.72358,-0.18215,2.53697,0.00331
-5.45357,0.60478,-1.23501,-1.72387,-0.18231,2.53657,0.00331
-5.45476,0.60517,-1.23457,-1.72415,-0.18246,2.53618,0.00330
-5.45595,0.60526,-1.23447,-1.72422,-0.18250,2.53609,0.00330
-5.45714,0.60578,-1.23384,-1.72462,-0.18272,2.53557,0.00331
-5.45833,0.60630,-1.23323,-1.72501,-0.18294,2.53506,0.00331
-5.45952,0.60681,-1.23263,-1.72540,-0.18316,2.53455,0.00331
-5.46071,0.60732,-1.23204,-1.72578,-0.18338,2.53405,0.00331
-5.46190,0.60781,-1.23146,-1.72615,-0.18359,2.53355,0.00331
-5.46308,0.60831,-1.23089,-1.72652,-0.18380,2.53306,0.00331
-5.46427,0.60879,-1.23032,-1.72688,-0.18400,2.53258,0.00331
-5.46546,0.60927,-1.22977,-1.72723,-0.18420,2.53210,0.00331
-5.46665,0.60974,-1.22923,-1.72758,-0.18440,2.53163,0.00331
-5.46784,0.61021,-1.22869,-1.72792,-0.18460,2.53116,0.00331
-5.46903,0.61067,-1.22817,-1.72826,-0.18479,2.53070,0.00331
-5.47022,0.61113,-1.22765,-1.72859,-0.18498,2.53025,0.00331
-5.47141,0.61158,-1.22714,-1.72891,-0.18516,2.52980,0.00331
-5.47260,0.61202,-1.22664,-1.72924,-0.18535,2.52936,0.00331
-5.47378,0.61246,-1.22615,-1.72955,-0.18553,2.52892,0.00331
-5.47497,0.61289,-1.22566,-1.72986,-0.18570,2.52849,0.00330
-5.47616,0.61332,-1.22519,-1.73016,-0.18588,2.52806,0.00330
-5.47735,0.61374,-1.22472,-1.73046,-0.18605,2.52764,0.00330
-5.47854,0.61416,-1.22426,-1.73076,-0.18622,2.52723,0.00330
-5.47973,0.61457,-1.22381,-1.73105,-0.18639,2.52682,0.00330
-5.48092,0.61498,-1.22336,-1.73133,-0.18655,2.52641,0.00330
-5.48211,0.61538,-1.22292,-1.73161,-0.18671,2.52601,0.00330
-5.48330,0.61568,-1.22259,-1.73183,-0.18684,2.52571,0.00330
-5.48448,0.61633,-1.22181,-1.73231,-0.18713,2.52506,0.00330
-5.48567,0.61698,-1.22104,-1.73278,-0.18742,2.52442,0.00330
-5.48686,0.61762,-1.22029,-1.73325,-0.18771,2.52379,0.00331
-5.48805,0.61825,-1.21955,-1.73371,-0.18799,2.52316,0.00331
-5.48924,0.61887,-1.21883,-1.73416,-0.18826,2.52255,0.00331
-5.49043,0.61949,-1.21811,-1.73460,-0.18854,2.52194,0.00331
-5.49162,0.62009,-1.21741,-1.73503,-0.18881,2.52133,0.00332
-5.49281,0.62069,-1.21672,-1.73546,-0.18907,2.52074,0.00332
-5.49400,0.62129,-1.21604,-1.73588,-0.18933,2.52015,0.00332
-5.49518,0.62187,-1.21537,-1.73629,-0.18959,2.51957,0.00332
-5.49637,0.62245,-1.21471,-1.73670,-0.18984,2.51899,0.00332
-5.49756,0.62302,-1.21407,-1.73710,-0.19009,2.51843,0.00332
-5.49875,0.62358,-1.21343,-1.73749,-0.19033,2.51787,0.00333
-5.49994,0.62414,-1.21280,-1.73788,-0.19058,2.51731,0.00333
-5.50113,0.62469,-1.21219,-1.73826,-0.19081,2.51677,0.00333
-5.50232,0.62523,-1.21158,-1.73863,-0.19105,2.51623,0.00333
-5.50351,0.62577,-1.21099,-1.73900,-0.19128,2.51569,0.00333
-5.50470,0.62630,-1.21041,-1.73936,-0.19150,2.51516,0.00333
-5.50589,0.62682,-1.20983,-1.73971,-0.19173,2.51464,0.00333
-5.50707,0.62734,-1.20926,-1.74006,-0.19195,2.51413,0.00333
-5.50826,0.62785,-1.20871,-1.74041,-0.19216,2.51362,0.00333
-5.50945,0.62835,-1.20816,-1.74074,-0.19238,2.51312,0.00333
-5.51064,0.62885,-1.20762,-1.74107,-0.19259,2.51262,0.00333
-5.51183,0.62934,-1.20709,-1.74140,-0.19279,2.51213,0.00333
-5.51302,0.62983,-1.20657,-1.74172,-0.19300,2.51165,0.00332
-5.51421,0.63031,-1.20606,-1.74204,-0.19320,2.51117,0.00332
-5.51540,0.63078,-1.20556,-1.74235,-0.19339,2.51070,0.00332
-5.51659,0.63125,-1.20506,-1.74265,-0.19359,2.51023,0.00332
-5.51777,0.63171,-1.20457,-1.74295,-0.19378,2.50977,0.00332
-5.51896,0.63217,-1.20409,-1.74325,-0.19397,2.50932,0.00332
-5.52015,0.63262,-1.20362,-1.74354,-0.19415,2.50887,0.00332
-5.52134,0.63306,-1.20316,-1.74382,-0.19433,2.50842,0.00332
-5.52253,0.63350,-1.20270,-1.74410,-0.19451,2.50798,0.00331
-5.52372,0.63393,-1.20225,-1.74438,-0.19469,2.50755,0.00331
-5.52491,0.63436,-1.20181,-1.74465,-0.19486,2.50712,0.00331
-5.52610,0.63478,-1.20138,-1.74492,-0.19504,2.50670,0.00331
-5.52729,0.63507,-1.20108,-1.74510,-0.19515,2.50642,0.00331
-5.52847,0.63580,-1.20025,-1.74560,-0.19549,2.50569,0.00331
-5.52966,0.63653,-1.19943,-1.74609,-0.19582,2.50497,0.00332
-5.53085,0.63724,-1.19862,-1.74656,-0.19615,2.50427,0.00332
-5.53204,0.63795,-1.19783,-1.74704,-0.19647,2.50356,0.00332
-5.53323,0.63865,-1.19705,-1.74750,-0.19678,2.50287,0.00333
-5.53442,0.63934,-1.19628,-1.74795,-0.19709,2.50219,0.00333
-5.53561,0.64003,-1.19553,-1.74840,-0.19740,2.50151,0.00333
-5.53680,0.64070,-1.19479,-1.74884,-0.19770,2.50084,0.00333
-5.53799,0.64137,-1.19406,-1.74927,-0.19800,2.50018,0.00334
-5.53917,0.64203,-1.19334,-1.74970,-0.19829,2.49952,0.00334
-5.54036,0.64268,-1.19264,-1.75012,-0.19858,2.49888,0.00334
-5.54155,0.64332,-1.19194,-1.75053,-0.19887,2.49824,0.00334
-5.54274,0.64396,-1.19126,-1.75093,-0.19915,2.49761,0.00334
-5.54393,0.64459,-1.19059,-1.75133,-0.19942,2.49698,0.00334
-5.54512,0.64521,-1.18993,-1.75172,-0.19970,2.49637,0.00334
-5.54631,0.64582,-1.18928,-1.75210,-0.19996,2.49576,0.00335
-5.54750,0.64643,-1.18864,-1.75248,-0.20023,2.49515,0.00335
-5.54869,0.64702,-1.18801,-1.75285,-0.20049,2.49456,0.00335
-5.54988,0.64762,-1.18739,-1.75321,-0.20074,2.49397,0.00335
-5.55106,0.64820,-1.18679,-1.75357,-0.20099,2.49339,0.00335
-5.55225,0.64878,-1.18619,-1.75393,-0.20124,2.49281,0.00335
-5.55344,0.64935,-1.18560,-1.75427,-0.20149,2.49225,0.00335
-5.55463,0.64991,-1.18502,-1.75461,-0.20173,2.49169,0.00335
-5.55582,0.65047,-1.18445,-1.75495,-0.20196,2.49113,0.00335
-5.55701,0.65102,-1.18389,-1.75528,-0.20220,2.49058,0.00334
-5.55820,0.65156,-1.18334,-1.75561,-0.20243,2.49004,0.00334
-5.55939,0.65210,-1.18280,-1.75592,-0.20265,2.48951,0.00334
-5.56058,0.65263,-1.18227,-1.75624,-0.20288,2.48898,0.00334
-5.56176,0.65315,-1.18174,-1.75655,-0.20310,2.48846,0.00334
-5.56295,0.65367,-1.18123,-1.75685,-0.20331,2.48794,0.00334
-5.56414,0.65418,-1.18072,-1.75715,-0.20352,2.48743,0.00334
-5.56533,0.65468,-1.18022,-1.75744,-0.20373,2.48693,0.00334
-5.56652,0.65518,-1.17973,-1.75773,-0.20394,2.48643,0.00334
-5.56771,0.65567,-1.17925,-1.75802,-0.20414,2.48594,0.00333
-5.56890,0.65616,-1.17877,-1.75830,-0.20434,2.48545,0.00333
-5.57009,0.65664,-1.17831,-1.75857,-0.20454,2.48497,0.00333
-5.57128,0.65711,-1.17785,-1.75884,-0.20473,2.48450,0.00333
-5.57246,0.65758,-1.17739,-1.75911,-0.20493,2.48403,0.00333
-5.57365,0.65805,-1.17695,-1.75937,-0.20511,2.48357,0.00333
-5.57484,0.65850,-1.17651,-1.75963,-0.20530,2.48311,0.00332
-5.57603,0.65896,-1.17608,-1.75988,-0.20548,2.48266,0.00332
-5.57722,0.65937,-1.17568,-1.76011,-0.20565,2.48224,0.00332
-5.57841,0.65998,-1.17507,-1.76044,-0.20593,2.48164,0.00332
-5.57960,0.66057,-1.17447,-1.76077,-0.20621,2.48105,0.00332
-5.58079,0.66116,-1.17388,-1.76109,-0.20648,2.48047,0.00332
-5.58198,0.66174,-1.17330,-1.76140,-0.20675,2.47989,0.00332
-5.58316,0.66231,-1.17273,-1.76171,-0.20701,2.47932,0.00332
-5.58435,0.66288,-1.17217,-1.76202,-0.20727,2.47875,0.00332
-5.58554,0.66344,-1.17162,-1.76232,-0.20753,2.47819,0.00332
-5.58673,0.66399,-1.17107,-1.76261,-0.20778,2.47764,0.00332
-5.58792,0.66454,-1.17054,-1.76290,-0.20803,2.47710,0.00332
-5.58911,0.66508,-1.17001,-1.76319,-0.20827,2.47656,0.00332
-5.59030,0.66562,-1.16950,-1.76347,-0.20851,2.47603,0.00332
-5.59149,0.66614,-1.16899,-1.76374,-0.20875,2.47550,0.00332
-5.59268,0.66667,-1.16849,-1.76401,-0.20898,2.47498,0.00332
-5.59387,0.66718,-1.16799,-1.76428,-0.20921,2.47447,0.00332
-5.59505,0.66769,-1.16751,-1.76454,-0.20944,2.47396,0.00332
-5.59624,0.66819,-1.16703,-1.76480,-0.20966,2.47346,0.00332
-5.59743,0.66869,-1.16656,-1.76505,-0.20988,2.47297,0.00332
-5.59862,0.66918,-1.16610,-1.76530,-0.21010,2.47248,0.00332
-5.59981,0.66966,-1.16565,-1.76555,-0.21031,2.47199,0.00332
-5.60100,0.67014,-1.16520,-1.76579,-0.21052,2.47151,0.00331
-5.60219,0.67062,-1.16476,-1.76603,-0.21072,2.47104,0.00331
-5.60338,0.67108,-1.16433,-1.76626,-0.21093,2.47057,0.00331
-5.60457,0.67154,-1.16390,-1.76649,-0.21113,2.47011,0.00331
-5.60575,0.67193,-1.16355,-1.76668,-0.21130,2.46973,0.00331
-5.60694,0.67258,-1.16290,-1.76701,-0.21161,2.46908,0.00331
-5.60813,0.67322,-1.16227,-1.76733,-0.21192,2.46845,0.00331
-5.60932,0.67386,-1.16165,-1.76765,-0.21223,2.46782,0.00331
-5.61051,0.67448,-1.16103,-1.76796,-0.21254,2.46719,0.00332
-5.61170,0.67510,-1.16043,-1.76826,-0.21283,2.46658,0.00332
-5.61289,0.67572,-1.15984,-1.76856,-0.21313,2.46597,0.00332
-5.61408,0.67632,-1.15926,-1.76886,-0.21342,2.46537,0.00332
-5.61527,0.67692,-1.15868,-1.76915,-0.21370,2.46477,0.00332
-5.61645,0.67751,-1.15812,-1.76944,-0.21398,2.46419,0.00332
-5.61764,0.67809,-1.15756,-1.76972,-0.21426,2.46360,0.00332
-5.61883,0.67867,-1.15701,-1.77000,-0.21453,2.46303,0.00332
-5.62002,0.67924,-1.15648,-1.77027,-0.21480,2.46246,0.00332
-5.62121,0.67981,-1.15595,-1.77054,-0.21506,2.46190,0.00332
-5.62240,0.68036,-1.15543,-1.77080,-0.21532,2.46135,0.00332
-5.62359,0.68091,-1.15492,-1.77106,-0.21558,2.46080,0.00332
-5.62478,0.68146,-1.15441,-1.77131,-0.21583,2.46026,0.00332
-5.62597,0.68200,-1.15392,-1.77157,-0.21608,2.45972,0.00332
-5.62715,0.68253,-1.15343,-1.77181,-0.21632,2.45919,0.00332
-5.62834,0.68305,-1.15295,-1.77206,-0.21656,2.45867,0.00332
-5.62953,0.68357,-1.15248,-1.77229,-0.21680,2.45815,0.00332
-5.63072,0.68409,-1.15201,-1.77253,-0.21704,2.45764,0.00332
-5.63191,0.68459,-1.15155,-1.77276,-0.21726,2.45713,0.00332
-5.63310,0.68509,-1.15110,-1.77299,-0.21749,2.45663,0.00331
-5.63429,0.68559,-1.15066,-1.77321,-0.21771,2.45614,0.00331
-5.63548,0.68608,-1.15023,-1.77343,-0.21793,2.45565,0.00331
-5.63667,0.68656,-1.14980,-1.77365,-0.21815,2.45517,0.00331
-5.63786,0.68704,-1.14937,-1.77386,-0.21836,2.45469,0.00331
-5.63904,0.68754,-1.14893,-1.77408,-0.21860,2.45419,0.00331
-5.64023,0.68831,-1.14818,-1.77438,-0.21904,2.45342,0.00331
-5.64142,0.68908,-1.14745,-1.77468,-0.21947,2.45267,0.00332
-5.64261,0.68983,-1.14673,-1.77497,-0.21990,2.45192,0.00332
-5.64380,0.69058,-1.14602,-1.77526,-0.22032,2.45118,0.00332
-5.64499,0.69132,-1.14533,-1.77554,-0.22073,2.45045,0.00333
-5.64618,0.69205,-1.14464,-1.77581,-0.22114,2.44972,0.00333
-5.64737,0.69277,-1.14397,-1.77608,-0.22154,2.44901,0.00333
-5.64856,0.69349,-1.14330,-1.77635,-0.22194,2.44830,0.00334
-5.64974,0.69420,-1.14265,-1.77662,-0.22233,2.44760,0.00334
-5.65093,0.69489,-1.14201,-1.77687,-0.22271,2.44691,0.00334
-5.65212,0.69558,-1.14138,-1.77713,-0.22309,2.44622,0.00334
-5.65331,0.69627,-1.14075,-1.77738,-0.22346,2.44554,0.00335
-5.65450,0.69694,-1.14014,-1.77762,-0.22383,2.44487,0.00335
-5.65569,0.69761,-1.13954,-1.77787,-0.22419,2.44421,0.00335
-5.65688,0.69827,-1.13895,-1.77810,-0.22455,2.44356,0.00335
-5.65807,0.69892,-1.13837,-1.77834,-0.22490,2.44291,0.00335
-5.65926,0.69957,-1.13779,-1.77857,-0.22524,2.44227,0.00335
-5.66044,0.70020,-1.13723,-1.77880,-0.22558,2.44164,0.00335
-5.66163,0.70083,-1.13668,-1.77902,-0.22592,2.44101,0.00335
-5.66282,0.70146,-1.13613,-1.77924,-0.22624,2.44039,0.00335
-5.66401,0.70207,-1.13559,-1.77945,-0.22657,2.43978,0.00335
-5.66520,0.70268,-1.13506,-1.77967,-0.22689,2.43917,0.00335
-5.66639,0.70328,-1.13454,-1.77988,-0.22720,2.43857,0.00335
-5.66758,0.70388,-1.13403,-1.78008,-0.22751,2.43798,0.00335
-5.66877,0.70446,-1.13353,-1.78028,-0.22782,2.43740,0.00335
-5.66996,0.70505,-1.13303,-1.78048,-0.22812,2.43682,0.00335
-5.67114,0.70562,-1.13254,-1.78068,-0.22841,2.43624,0.00335
-5.67233,0.70619,-1.13206,-1.78087,-0.22870,2.43568,0.00335
-5.67352,0.70675,-1.13159,-1.78106,-0.22899,2.43512,0.00335
-5.67471,0.70730,-1.13113,-1.78125,-0.22927,2.43457,0.00335
-5.67590,0.70785,-1.13067,-1.78143,-0.22955,2.43402,0.00335
-5.67709,0.70839,-1.13022,-1.78161,-0.22982,2.43348,0.00335
-5.67828,0.70893,-1.12977,-1.78179,-0.23009,2.43294,0.00335
-5.67947,0.70946,-1.12934,-1.78197,-0.23036,2.43242,0.00334
-5.68066,0.70998,-1.12891,-1.78214,-0.23062,2.43189,0.00334
-5.68185,0.71050,-1.12849,-1.78231,-0.23088,2.43138,0.00334
-5.68303,0.71101,-1.12807,-1.78248,-0.23113,2.43087,0.00334
-5.68422,0.71152,-1.12766,-1.78264,-0.23138,2.43036,0.00334
-5.68541,0.71202,-1.12726,-1.78281,-0.23162,2.42986,0.00334
-5.68660,0.71228,-1.12704,-1.78289,-0.23176,2.42960,0.00334
-5.68779,0.71295,-1.12646,-1.78310,-0.23213,2.42893,0.00334
-5.68898,0.71362,-1.12589,-1.78331,-0.23249,2.42828,0.00334
-5.69017,0.71427,-1.12533,-1.78351,-0.23285,2.42763,0.00334
-5.69136,0.71492,-1.12478,-1.78371,-0.23320,2.42698,0.00334
-5.69255,0.71556,-1.12424,-1.78391,-0.23355,2.42635,0.00334
-5.69373,0.71619,-1.12370,-1.78411,-0.23389,2.42572,0.00334
-5.69492,0.71682,-1.12318,-1.78430,-0.23423,2.42510,0.00334
-5.69611,0.71743,-1.12266,-1.78449,-0.23456,2.42448,0.00334
-5.69730,0.71805,-1.12215,-1.78467,-0.23489,2.42387,0.00334
-5.69849,0.71865,-1.12165,-1.78485,-0.23521,2.42327,0.00334
-5.69968,0.71925,-1.12115,-1.78503,-0.23553,2.42268,0.00334
-5.70087,0.71984,-1.12067,-1.78521,-0.23584,2.42209,0.00334
-5.70206,0.72042,-1.12019,-1.78538,-0.23615,2.42151,0.00334
-5.70325,0.72100,-1.11972,-1.78556,-0.23645,2.42093,0.00334
-5.70443,0.72157,-1.11926,-1.78572,-0.23675,2.42036,0.00334
-5.70562,0.72214,-1.11880,-1.78589,-0.23704,2.41980,0.00334
-5.70681,0.72270,-1.11835,-1.78605,-0.23733,2.41924,0.00334
-5.70800,0.72325,-1.11791,-1.78622,-0.23761,2.41869,0.00334
-5.70919,0.72380,-1.11748,-1.78637,-0.23789,2.41815,0.00334
-5.71038,0.72433,-1.11705,-1.78653,-0.23817,2.41761,0.00333
-5.71157,0.72487,-1.11663,-1.78668,-0.23844,2.41708,0.00333
-5.71276,0.72540,-1.11621,-1.78683,-0.23871,2.41655,0.00333
-5.71395,0.72592,-1.11581,-1.78698,-0.23897,2.41603,0.00333
-5.71513,0.72643,-1.11540,-1.78713,-0.23923,2.41551,0.00333
-5.71632,0.72694,-1.11501,-1.78728,-0.23949,2.41501,0.00333
-5.71751,0.72717,-1.11483,-1.78734,-0.23960,2.41478,0.00333
-5.71870,0.72787,-1.11424,-1.78754,-0.23999,2.41409,0.00333
-5.71989,0.72856,-1.11366,-1.78774,-0.24038,2.41340,0.00333
-5.72108,0.72925,-1.11309,-1.78793,-0.24076,2.41272,0.00333
-5.72227,0.72993,-1.11253,-1.78812,-0.24113,2.41204,0.00333
-5.72346,0.73060,-1.11197,-1.78831,-0.24150,2.41137,0.00333
-5.72465,0.73127,-1.11143,-1.78849,-0.24186,2.41071,0.00333
-5.72584,0.73193,-1.11089,-1.78868,-0.24222,2.41006,0.00333
-5.72702,0.73258,-1.11036,-1.78886,-0.24257,2.40941,0.00334
-5.72821,0.73322,-1.10984,-1.78903,-0.24292,2.40877,0.00334
-5.72940,0.73386,-1.10933,-1.78921,-0.24326,2.40814,0.00334
-5.73059,0.73449,-1.10882,-1.78938,-0.24360,2.40752,0.00334
-5.73178,0.73511,-1.10833,-1.78954,-0.24393,2.40690,0.00334
-5.73297,0.73572,-1.10784,-1.78971,-0.24425,2.40629,0.00334
-5.73416,0.73633,-1.10736,-1.78987,-0.24457,2.40568,0.00333
-5.73535,0.73693,-1.10689,-1.79003,-0.24489,2.40508,0.00333
-5.73654,0.73753,-1.10642,-1.79019,-0.24520,2.40449,0.00333
-5.73772,0.73812,-1.10596,-1.79035,-0.24551,2.40390,0.00333
-5.73891,0.73870,-1.10551,-1.79050,-0.24581,2.40332,0.00333
-5.74010,0.73928,-1.10507,-1.79065,-0.24611,2.40275,0.00333
-5.74129,0.73984,-1.10463,-1.79080,-0.24640,2.40218,0.00333
-5.74248,0.74041,-1.10420,-1.79095,-0.24669,2.40162,0.00333
-5.74367,0.74096,-1.10378,-1.79109,-0.24697,2.40107,0.00333
-5.74486,0.74151,-1.10336,-1.79123,-0.24725,2.40052,0.00333
-5.74605,0.74206,-1.10295,-1.79137,-0.24752,2.39997,0.00333
-5.74724,0.74260,-1.10254,-1.79151,-0.24780,2.39944,0.00332
-5.74842,0.74313,-1.10215,-1.79165,-0.24806,2.39891,0.00332
-5.74961,0.74366,-1.10175,-1.79178,-0.24833,2.39838,0.00332
-5.75080,0.74415,-1.10138,-1.79191,-0.24857,2.39789,0.00332
-5.75199,0.74489,-1.10077,-1.79215,-0.24894,2.39716,0.00332
-5.75318,0.74562,-1.10017,-1.79239,-0.24931,2.39643,0.00332
-5.75437,0.74634,-1.09958,-1.79262,-0.24967,2.39571,0.00332
-5.75556,0.74706,-1.09900,-1.79285,-0.25003,2.39500,0.00332
-5.75675,0.74777,-1.09842,-1.79307,-0.25038,2.39430,0.00332
-5.75794,0.74847,-1.09786,-1.79329,-0.25073,2.39360,0.00333
-5.75912,0.74916,-1.09730,-1.79351,-0.25107,2.39292,0.00333
-5.76031,0.74985,-1.09676,-1.79373,-0.25141,2.39223,0.00333
-5.76150,0.75053,-1.09622,-1.79394,-0.25174,2.39156,0.00333
-5.76269,0.75120,-1.09569,-1.79414,-0.25206,2.39089,0.00333
-5.76388,0.75186,-1.09516,-1.79435,-0.25239,2.39023,0.00333
-5.76507,0.75252,-1.09465,-1.79455,-0.25270,2.38958,0.00333
-5.76626,0.75317,-1.09414,-1.79475,-0.25301,2.38893,0.00332
-5.76745,0.75381,-1.09365,-1.79494,-0.25332,2.38829,0.00332
-5.76864,0.75445,-1.09316,-1.79513,-0.25362,2.38766,0.00332
-5.76983,0.75508,-1.09267,-1.79532,-0.25392,2.38703,0.00332
-5.77101,0.75570,-1.09220,-1.79551,-0.25422,2.38641,0.00332
-5.77220,0.75632,-1.09173,-1.79569,-0.25451,2.38580,0.00332
-5.77339,0.75693,-1.09127,-1.79587,-0.25479,2.38520,0.00332
-5.77458,0.75753,-1.09081,-1.79605,-0.25507,2.38459,0.00332
-5.77577,0.75812,-1.09037,-1.79622,-0.25535,2.38400,0.00332
-5.77696,0.75871,-1.08993,-1.79639,-0.25562,2.38341,0.00332
-5.77815,0.75930,-1.08949,-1.79656,-0.25589,2.38283,0.00332
-5.77934,0.75987,-1.08907,-1.79673,-0.25615,2.38226,0.00331
-5.78053,0.76044,-1.08865,-1.79690,-0.25642,2.38169,0.00331
-5.78171,0.76101,-1.08823,-1.79706,-0.25667,2.38113,0.00331
-5.78290,0.76157,-1.08783,-1.79722,-0.25693,2.38057,0.00331
-5.78409,0.76212,-1.08743,-1.79737,-0.25717,2.38002,0.00331
-5.78528,0.76266,-1.08703,-1.79753,-0.25742,2.37947,0.00331
-5.78647,0.76320,-1.08664,-1.79768,-0.25766,2.37893,0.00330
-5.78766,0.76339,-1.08650,-1.79773,-0.25775,2.37874,0.00330
-5.78885,0.76422,-1.08584,-1.79797,-0.25818,2.37793,0.00331
-5.79004,0.76503,-1.08519,-1.79820,-0.25859,2.37712,0.00331
-5.79123,0.76584,-1.08455,-1.79843,-0.25901,2.37632,0.00331
-5.79241,0.76663,-1.08392,-1.79866,-0.25941,2.37553,0.00331
-5.79360,0.76742,-1.08330,-1.79888,-0.25981,2.37475,0.00331
-5.79479,0.76821,-1.08270,-1.79909,-0.26020,2.37398,0.00332
-5.79598,0.76898,-1.08210,-1.79931,-0.26059,2.37321,0.00332
-5.79717,0.76974,-1.08150,-1.79952,-0.26097,2.37245,0.00332
-5.79836,0.77050,-1.08092,-1.79973,-0.26135,2.37170,0.00332
-5.79955,0.77125,-1.08035,-1.79993,-0.26172,2.37096,0.00332
-5.80074,0.77199,-1.07979,-1.80013,-0.26209,2.37022,0.00332
-5.80193,0.77272,-1.07923,-1.80033,-0.26245,2.36950,0.00332
-5.80311,0.77345,-1.07869,-1.80053,-0.26280,2.36877,0.00332
-5.80430,0.77417,-1.07815,-1.80072,-0.26315,2.36806,0.00332
-5.80549,0.77488,-1.07762,-1.80091,-0.26349,2.36735,0.00332
-5.80668,0.77558,-1.07710,-1.80109,-0.26383,2.36665,0.00332
-5.80787,0.77628,-1.07658,-1.80128,-0.26417,2.36596,0.00332
-5.80906,0.77697,-1.07608,-1.80146,-0.26450,2.36528,0.00332
-5.81025,0.77765,-1.07558,-1.80163,-0.26482,2.36460,0.00332
-5.81144,0.77832,-1.07509,-1.80181,-0.26514,2.36393,0.00332
-5.81263,0.77899,-1.07460,-1.80198,-0.26546,2.36326,0.00332
-5.81382,0.77965,-1.07413,-1.80215,-0.26577,2.36261,0.00332
-5.81500,0.78031,-1.07366,-1.80232,-0.26607,2.36196,0.00332
-5.81619,0.78095,-1.07320,-1.80248,-0.26637,2.36131,0.00332
-5.81738,0.78159,-1.07274,-1.80264,-0.26667,2.36067,0.00332
-5.81857,0.78223,-1.07230,-1.80280,-0.26696,2.36004,0.00332
-5.81976,0.78285,-1.07186,-1.80296,-0.26725,2.35942,0.00331
-5.82095,0.78347,-1.07142,-1.80312,-0.26754,2.35880,0.00331
-5.82214,0.78409,-1.07099,-1.80327,-0.26782,2.35819,0.00331
-5.82333,0.78469,-1.07057,-1.80342,-0.26809,2.35758,0.00331
-5.82452,0.78530,-1.07016,-1.80357,-0.26836,2.35698,0.00331
-5.82570,0.78589,-1.06975,-1.80371,-0.26863,2.35639,0.00331
-5.82689,0.78648,-1.06935,-1.80386,-0.26890,2.35580,0.00331
-5.82808,0.78706,-1.06895,-1.80400,-0.26916,2.35522,0.00331
-5.82927,0.78764,-1.06856,-1.80414,-0.26941,2.35465,0.00330
-5.83046,0.78821,-1.06817,-1.80427,-0.26967,2.35408,0.00330
-5.83165,0.78877,-1.06779,-1.80441,-0.26991,2.35351,0.00330
-5.83284,0.78924,-1.06748,-1.80452,-0.27012,2.35305,0.00330
-5.83403,0.78999,-1.06692,-1.80472,-0.27049,2.35230,0.00330
-5.83522,0.79074,-1.06638,-1.80491,-0.27084,2.35156,0.00330
-5.83640,0.79148,-1.06584,-1.80509,-0.27120,2.35083,0.00330
-5.83759,0.79221,-1.06531,-1.80528,-0.27155,2.35010,0.00330
-5.83878,0.79293,-1.06479,-1.80546,-0.27189,2.34938,0.00330
-5.83997,0.79365,-1.06428,-1.80564,-0.27223,2.34867,0.00330
-5.84116,0.79436,-1.06377,-1.80581,-0.27256,2.34797,0.00330
-5.84235,0.79506,-1.06327,-1.80599,-0.27289,2.34727,0.00330
-5.84354,0.79575,-1.06278,-1.80616,-0.27321,2.34658,0.00330
-5.84473,0.79644,-1.06230,-1.80632,-0.27353,2.34589,0.00330
-5.84592,0.79712,-1.06183,-1.80649,-0.27384,2.34522,0.00330
-5.84710,0.79779,-1.06136,-1.80665,-0.27415,2.34455,0.00330
-5.84829,0.79846,-1.06090,-1.80681,-0.27446,2.34388,0.00330
-5.84948,0.79912,-1.06044,-1.80697,-0.27476,2.34323,0.00330
-5.85067,0.79977,-1.05999,-1.80713,-0.27505,2.34258,0.00330
-5.85186,0.80042,-1.05955,-1.80728,-0.27535,2.34193,0.00330
-5.85305,0.80106,-1.05912,-1.80743,-0.27563,2.34129,0.00330
-5.85424,0.80169,-1.05869,-1.80758,-0.27592,2.34066,0.00330
-5.85543,0.80232,-1.05827,-1.80773,-0.27620,2.34004,0.00330
-5.85662,0.80294,-1.05785,-1.80787,-0.27647,2.33942,0.00330
-5.85781,0.80355,-1.05744,-1.80802,-0.27674,2.33881,0.00330
-5.85899,0.80416,-1.05704,-1.80816,-0.27701,2.33820,0.00329
-5.86018,0.80476,-1.05664,-1.80829,-0.27728,2.33760,0.00329
-5.86137,0.80536,-1.05625,-1.80843,-0.27754,2.33701,0.00329
-5.86256,0.80595,-1.05586,-1.80856,-0.27779,2.33642,0.00329
-5.86375,0.80653,-1.05548,-1.80870,-0.27804,2.33584,0.00329
-5.86494,0.80711,-1.05511,-1.80883,-0.27829,2.33526,0.00329
-5.86613,0.80768,-1.05474,-1.80896,-0.27854,2.33469,0.00329
-5.86732,0.80775,-1.05469,-1.80898,-0.27857,2.33462,0.00329
-5.86851,0.80848,-1.05418,-1.80917,-0.27890,2.33389,0.00329
-5.86969,0.80920,-1.05367,-1.80936,-0.27922,2.33318,0.00329
-5.87088,0.80992,-1.05317,-1.80954,-0.27954,2.33247,0.00329
-5.87207,0.81062,-1.05268,-1.80972,-0.27985,2.33177,0.00329
-5.87326,0.81132,-1.05220,-1.80990,-0.28015,2.33107,0.00329
-5.87445,0.81201,-1.05172,-1.81008,-0.28046,2.33038,0.00329
-5.87564,0.81270,-1.05125,-1.81025,-0.28076,2.32970,0.00329
-5.87683,0.81338,-1.05079,-1.81043,-0.28105,2.32902,0.00329
-5.87802,0.81405,-1.05033,-1.81060,-0.28134,2.32835,0.00329
-5.87921,0.81472,-1.04988,-1.81076,-0.28163,2.32769,0.00329
-5.88039,0.81538,-1.04944,-1.81093,-0.28191,2.32703,0.00329
-5.88158,0.81603,-1.04901,-1.81109,-0.28219,2.32638,0.00329
-5.88277,0.81668,-1.04858,-1.81125,-0.28246,2.32574,0.00328
-5.88396,0.81731,-1.04815,-1.81140,-0.28273,2.32510,0.00328
-5.88515,0.81795,-1.04774,-1.81156,-0.28300,2.32447,0.00328
-5.88634,0.81857,-1.04733,-1.81171,-0.28326,2.32385,0.00328
-5.88753,0.81919,-1.04692,-1.81186,-0.28352,2.32323,0.00328
-5.88872,0.81981,-1.04652,-1.81201,-0.28378,2.32262,0.00328
-5.88991,0.82042,-1.04613,-1.81216,-0.28403,2.32201,0.00328
-5.89109,0.82102,-1.04574,-1.81230,-0.28428,2.32141,0.00328
-5.89228,0.82162,-1.04536,-1.81244,-0.28452,2.32082,0.00328
-5.89347,0.82221,-1.04498,-1.81258,-0.28476,2.32023,0.00328
-5.89466,0.82279,-1.04461,-1.81272,-0.28500,2.31964,0.00328
-5.89585,0.82327,-1.04431,-1.81283,-0.28520,2.31917,0.00328
-5.89704,0.82399,-1.04381,-1.81305,-0.28548,2.31845,0.00328
-5.89823,0.82470,-1.04332,-1.81325,-0.28577,2.31774,0.00328
-5.89942,0.82540,-1.04284,-1.81346,-0.28605,2.31704,0.00328
-5.90061,0.82610,-1.04236,-1.81366,-0.28633,2.31635,0.00327
-5.90180,0.82679,-1.04189,-1.81386,-0.28660,2.31566,0.00327
-5.90298,0.82748,-1.04143,-1.81406,-0.28687,2.31498,0.00327
-5.90417,0.82815,-1.04098,-1.81425,-0.28714,2.31431,0.00327
-5.90536,0.82883,-1.04053,-1.81444,-0.28740,2.31364,0.00327
-5.90655,0.82949,-1.04009,-1.81463,-0.28766,2.31298,0.00327
-5.90774,0.83015,-1.03965,-1.81481,-0.28792,2.31232,0.00327
-5.90893,0.83080,-1.03922,-1.81499,-0.28817,2.31167,0.00327
-5.91012,0.83144,-1.03880,-1.81517,-0.28842,2.31103,0.00327
-5.91131,0.83208,-1.03838,-1.81535,-0.28866,2.31039,0.00327
-5.91250,0.83272,-1.03797,-1.81552,-0.28890,2.30976,0.00327
-5.91368,0.83334,-1.03757,-1.81569,-0.28914,2.30914,0.00327
-5.91487,0.83396,-1.03717,-1.81586,-0.28938,2.30852,0.00327
-5.91606,0.83458,-1.03678,-1.81603,-0.28961,2.30790,0.00327
-5.91725,0.83519,-1.03639,-1.81619,-0.28984,2.30730,0.00327
-5.91844,0.83579,-1.03601,-1.81635,-0.29006,2.30670,0.00327
-5.91963,0.83638,-1.03563,-1.81651,-0.29028,2.30610,0.00326
-5.92082,0.83697,-1.03526,-1.81666,-0.29050,2.30551,0.00326
-5.92201,0.83740,-1.03499,-1.81678,-0.29066,2.30508,0.00326
-5.92320,0.83817,-1.03445,-1.81703,-0.29096,2.30432,0.00326
-5.92438,0.83894,-1.03393,-1.81727,-0.29125,2.30356,0.00326
-5.92557,0.83969,-1.03341,-1.81750,-0.29153,2.30281,0.00326
-5.92676,0.84044,-1.03290,-1.81773,-0.29182,2.30207,0.00327
-5.92795,0.84118,-1.03239,-1.81796,-0.29210,2.30133,0.00327
-5.92914,0.84192,-1.03190,-1.81819,-0.29237,2.30060,0.00327
-5.93033,0.84265,-1.03141,-1.81841,-0.29264,2.29988,0.00327
-5.93152,0.84337,-1.03092,-1.81863,-0.29291,2.29916,0.00327
-5.93271,0.84408,-1.03045,-1.81884,-0.29317,2.29845,0.00327
-5.93390,0.84479,-1.02998,-1.81906,-0.29343,2.29775,0.00327
-5.93509,0.84549,-1.02952,-1.81926,-0.29369,2.29705,0.00327
-5.93627,0.84618,-1.02906,-1.81947,-0.29394,2.29636,0.00327
-5.93746,0.84687,-1.02862,-1.81967,-0.29419,2.29567,0.00327
-5.93865,0.84755,-1.02817,-1.81987,-0.29444,2.29500,0.00327
-5.93984,0.84822,-1.02774,-1.82007,-0.29469,2.29432,0.00326
-5.94103,0.84889,-1.02731,-1.82026,-0.29493,2.29366,0.00326
-5.94222,0.84955,-1.02689,-1.82045,-0.29516,2.29300,0.00326
-5.94341,0.85021,-1.02647,-1.82064,-0.29540,2.29235,0.00326
-5.94460,0.85086,-1.02606,-1.82082,-0.29563,2.29170,0.00326
-5.94579,0.85150,-1.02565,-1.82101,-0.29586,2.29106,0.00326
-5.94697,0.85213,-1.02525,-1.82118,-0.29608,2.29043,0.00326
-5.94816,0.85277,-1.02486,-1.82136,-0.29630,2.28980,0.00326
-5.94935,0.85339,-1.02447,-1.82153,-0.29652,2.28917,0.00326
-5.95054,0.85401,-1.02409,-1.82171,-0.29674,2.28856,0.00326
-5.95173,0.85462,-1.02371,-1.82187,-0.29695,2.28795,0.00326
-5.95292,0.85523,-1.02334,-1.82204,-0.29716,2.28734,0.00326
-5.95411,0.85583,-1.02297,-1.82221,-0.29737,2.28674,0.00326
-5.95530,0.85638,-1.02263,-1.82236,-0.29756,2.28619,0.00326
-5.95649,0.85714,-1.02212,-1.82260,-0.29783,2.28543,0.00326
-5.95767,0.85790,-1.02162,-1.82284,-0.29810,2.28468,0.00326
-5.95886,0.85865,-1.02112,-1.82307,-0.29837,2.28394,0.00326
-5.96005,0.85939,-1.02063,-1.82330,-0.29863,2.28320,0.00326
-5.96124,0.86012,-1.02015,-1.82353,-0.29889,2.28247,0.00326
-5.96243,0.86085,-1.01968,-1.82375,-0.29915,2.28175,0.00326
-5.96362,0.86157,-1.01921,-1.82397,-0.29940,2.28103,0.00326
-5.96481,0.86228,-1.01875,-1.82418,-0.29965,2.28032,0.00326
-5.96600,0.86299,-1.01829,-1.82440,-0.29989,2.27962,0.00326
-5.96719,0.86369,-1.01785,-1.82461,-0.30013,2.27892,0.00326
-5.96837,0.86438,-1.01741,-1.82481,-0.30037,2.27823,0.00326
-5.96956,0.86507,-1.01697,-1.82501,-0.30061,2.27754,0.00326
-5.97075,0.86575,-1.01654,-1.82521,-0.30084,2.27686,0.00326
-5.97194,0.86643,-1.01612,-1.82541,-0.30107,2.27619,0.00326
-5.97313,0.86710,-1.01570,-1.82561,-0.30130,2.27553,0.00326
-5.97432,0.86776,-1.01529,-1.82580,-0.30152,2.27486,0.00326
-5.97551,0.86842,-1.01488,-1.82599,-0.30175,2.27421,0.00326
-5.97670,0.86907,-1.01448,-1.82617,-0.30196,2.27356,0.00326
-5.97789,0.86971,-1.01409,-1.82635,-0.30218,2.27292,0.00326
-5.97908,0.87035,-1.01370,-1.82653,-0.30239,2.27228,0.00326
-5.98026,0.87098,-1.01332,-1.82671,-0.30260,2.27165,0.00326
-5.98145,0.87161,-1.01294,-1.82689,-0.30281,2.27103,0.00326
-5.98264,0.87223,-1.01257,-1.82706,-0.30302,2.27041,0.00326
-5.98383,0.87284,-1.01220,-1.82723,-0.30322,2.26979,0.00326
-5.98502,0.87345,-1.01184,-1.82739,-0.30342,2.26918,0.00326
-5.98621,0.87406,-1.01148,-1.82756,-0.30362,2.26858,0.00326
-5.98740,0.87413,-1.01143,-1.82758,-0.30364,2.26851,0.00326
-5.98859,0.87486,-1.01097,-1.82778,-0.30390,2.26778,0.00326
-5.98978,0.87558,-1.01052,-1.82798,-0.30416,2.26707,0.00326
-5.99096,0.87630,-1.01007,-1.82818,-0.30441,2.26635,0.00326
-5.99215,0.87700,-1.00962,-1.82838,-0.30467,2.26565,0.00326
-5.99334,0.87771,-1.00919,-1.82857,-0.30491,2.26495,0.00326
-5.99453,0.87840,-1.00876,-1.82876,-0.30516,2.26426,0.00326
-5.99572,0.87909,-1.00833,-1.82895,-0.30540,2.26357,0.00326
-5.99691,0.87978,-1.00792,-1.82913,-0.30564,2.26289,0.00326
-5.99810,0.88045,-1.00750,-1.82931,-0.30587,2.26221,0.00326
-5.99929,0.88113,-1.00710,-1.82949,-0.30610,2.26154,0.00326
-6.00048,0.88179,-1.00669,-1.82967,-0.30633,2.26088,0.00326
-6.00166,0.88245,-1.00630,-1.82984,-0.30656,2.26022,0.00326
-6.00285,0.88310,-1.00591,-1.83001,-0.30678,2.25957,0.00326
-6.00404,0.88375,-1.00552,-1.83018,-0.30700,2.25893,0.00326
-6.00523,0.88439,-1.00515,-1.83034,-0.30722,2.25829,0.00326
-6.00642,0.88503,-1.00477,-1.83051,-0.30744,2.25765,0.00326
-6.00761,0.88566,-1.00440,-1.83067,-0.30765,2.25703,0.00326
-6.00880,0.88628,-1.00404,-1.83082,-0.30786,2.25640,0.00326
-6.00999,0.88690,-1.00368,-1.83098,-0.30806,2.25579,0.00326
-6.01118,0.88751,-1.00332,-1.83114,-0.30827,2.25517,0.00326
-6.01236,0.88801,-1.00303,-1.83126,-0.30844,2.25468,0.00326
-6.01355,0.88875,-1.00257,-1.83148,-0.30868,2.25395,0.00326
-6.01474,0.88947,-1.00212,-1.83169,-0.30893,2.25322,0.00326
-6.01593,0.89020,-1.00167,-1.83190,-0.30917,2.25250,0.00326
-6.01712,0.89091,-1.00123,-1.83210,-0.30941,2.25179,0.00326
-6.01831,0.89162,-1.00080,-1.83230,-0.30965,2.25108,0.00326
-6.01950,0.89233,-1.00037,-1.83250,-0.30988,2.25038,0.00326
-6.02069,0.89302,-0.99995,-1.83269,-0.31012,2.24969,0.00326
-6.02188,0.89371,-0.99953,-1.83289,-0.31034,2.24900,0.00326
-6.02307,0.89440,-0.99912,-1.83308,-0.31057,2.24832,0.00326
-6.02425,0.89508,-0.99871,-1.83326,-0.31079,2.24764,0.00326
-6.02544,0.89575,-0.99831,-1.83345,-0.31101,2.24697,0.00326
-6.02663,0.89641,-0.99792,-1.83363,-0.31123,2.24631,0.00326
-6.02782,0.89707,-0.99753,-1.83381,-0.31144,2.24565,0.00326
-6.02901,0.89773,-0.99714,-1.83398,-0.31166,2.24500,0.00326
-6.03020,0.89838,-0.99677,-1.83416,-0.31186,2.24435,0.00326
-6.03139,0.89902,-0.99639,-1.83433,-0.31207,2.24371,0.00326
-6.03258,0.89966,-0.99602,-1.83450,-0.31228,2.24308,0.00326
-6.03377,0.90029,-0.99566,-1.83466,-0.31248,2.24245,0.00326
-6.03495,0.90092,-0.99530,-1.83482,-0.31268,2.24182,0.00326
-6.03614,0.90154,-0.99495,-1.83499,-0.31287,2.24120,0.00326
-6.03733,0.90215,-0.99460,-1.83514,-0.31307,2.24059,0.00326
-6.03852,0.90247,-0.99442,-1.83523,-0.31317,2.24027,0.00326
-6.03971,0.90319,-0.99398,-1.83541,-0.31342,2.23956,0.00326
-6.04090,0.90390,-0.99356,-1.83560,-0.31366,2.23885,0.00327
-6.04209,0.90460,-0.99314,-1.83578,-0.31390,2.23814,0.00327
-6.04328,0.90530,-0.99272,-1.83596,-0.31414,2.23745,0.00327
-6.04447,0.90600,-0.99231,-1.83614,-0.31437,2.23676,0.00327
-6.04565,0.90669,-0.99191,-1.83632,-0.31460,2.23607,0.00327
-6.04684,0.90737,-0.99151,-1.83649,-0.31483,2.23539,0.00327
-6.04803,0.90804,-0.99112,-1.83666,-0.31506,2.23472,0.00327
-6.04922,0.90871,-0.99073,-1.83683,-0.31528,2.23405,0.00327
-6.05041,0.90938,-0.99035,-1.83699,-0.31550,2.23339,0.00327
-6.05160,0.91004,-0.98997,-1.83715,-0.31572,2.23273,0.00327
-6.05279,0.91069,-0.98960,-1.83731,-0.31594,2.23208,0.00327
-6.05398,0.91134,-0.98924,-1.83747,-0.31615,2.23144,0.00327
-6.05517,0.91198,-0.98887,-1.83763,-0.31636,2.23080,0.00327
-6.05635,0.91261,-0.98852,-1.83778,-0.31657,2.23016,0.00327
-6.05754,0.91324,-0.98816,-1.83793,-0.31677,2.22953,0.00327
-6.05873,0.91387,-0.98782,-1.83808,-0.31697,2.22891,0.00327
-6.05992,0.91449,-0.98747,-1.83823,-0.31717,2.22829,0.00327
-6.06111,0.91487,-0.98726,-1.83832,-0.31730,2.22791,0.00327
-6.06230,0.91559,-0.98684,-1.83849,-0.31755,2.22719,0.00327
-6.06349,0.91631,-0.98642,-1.83867,-0.31780,2.22648,0.00327
-6.06468,0.91702,-0.98600,-1.83884,-0.31804,2.22577,0.00327
-6.06587,0.91773,-0.98560,-1.83901,-0.31829,2.22507,0.00327
-6.06706,0.91842,-0.98519,-1.83917,-0.31853,2.22437,0.00328
-6.06824,0.91912,-0.98480,-1.83933,-0.31876,2.22368,0.00328
-6.06943,0.91981,-0.98440,-1.83950,-0.31900,2.22300,0.00328
-6.07062,0.92049,-0.98402,-1.83965,-0.31923,2.22232,0.00328
-6.07181,0.92116,-0.98364,-1.83981,-0.31946,2.22165,0.00328
-6.07300,0.92183,-0.98326,-1.83996,-0.31968,2.22098,0.00328
-6.07419,0.92250,-0.98289,-1.84012,-0.31991,2.22032,0.00328
-6.07538,0.92315,-0.98252,-1.84027,-0.32013,2.21966,0.00328
-6.07657,0.92381,-0.98216,-1.84041,-0.32034,2.21901,0.00328
-6.07776,0.92445,-0.98180,-1.84056,-0.32056,2.21837,0.00328
-6.07894,0.92510,-0.98145,-1.84070,-0.32077,2.21773,0.00328
-6.08013,0.92573,-0.98110,-1.84085,-0.32098,2.21709,0.00328
-6.08132,0.92636,-0.98076,-1.84098,-0.32119,2.21646,0.00328
-6.08251,0.92699,-0.98042,-1.84112,-0.32139,2.21584,0.00328
-6.08370,0.92761,-0.98009,-1.84126,-0.32159,2.21522,0.00328
-6.08489,0.92768,-0.98005,-1.84128,-0.32162,2.21515,0.00328
-6.08608,0.92841,-0.97962,-1.84146,-0.32186,2.21442,0.00328
-6.08727,0.92913,-0.97920,-1.84165,-0.32209,2.21371,0.00328
-6.08846,0.92985,-0.97879,-1.84183,-0.32233,2.21299,0.00328
-6.08964,0.93055,-0.97838,-1.84201,-0.32256,2.21229,0.00328
-6.09083,0.93126,-0.97798,-1.84219,-0.32278,2.21159,0.00328
-6.09202,0.93196,-0.97759,-1.84236,-0.32301,2.21089,0.00329
-6.09321,0.93265,-0.97720,-1.84254,-0.32323,2.21020,0.00329
-6.09440,0.93333,-0.97681,-1.84271,-0.32345,2.20952,0.00329
-6.09559,0.93401,-0.97643,-1.84287,-0.32367,2.20884,0.00329
-6.09678,0.93469,-0.97605,-1.84304,-0.32388,2.20817,0.00329
-6.09797,0.93536,-0.97568,-1.84320,-0.32409,2.20750,0.00329
-6.09916,0.93602,-0.97532,-1.84336,-0.32430,2.20684,0.00329
-6.10034,0.93668,-0.97496,-1.84352,-0.32451,2.20619,0.00329
-6.10153,0.93733,-0.97460,-1.84367,-0.32471,2.20554,0.00329
-6.10272,0.93798,-0.97425,-1.84383,-0.32492,2.20489,0.00329
-6.10391,0.93862,-0.97390,-1.84398,-0.32512,2.20425,0.00329
-6.10510,0.93926,-0.97356,-1.84413,-0.32531,2.20362,0.00329
-6.10629,0.93989,-0.97322,-1.84427,-0.32551,2.20299,0.00329
-6.10748,0.94051,-0.97289,-1.84442,-0.32570,2.20236,0.00329
-6.10867,0.94104,-0.97259,-1.84454,-0.32587,2.20183,0.00329
-6.10986,0.94200,-0.97199,-1.84482,-0.32619,2.20088,0.00329
-6.11105,0.94296,-0.97140,-1.84510,-0.32651,2.19994,0.00330
-6.11223,0.94390,-0.97082,-1.84537,-0.32683,2.19901,0.00330
-6.11342,0.94484,-0.97024,-1.84563,-0.32714,2.19808,0.00330
-6.11461,0.94577,-0.96967,-1.84589,-0.32745,2.19716,0.00330
-6.11580,0.94669,-0.96911,-1.84615,-0.32776,2.19624,0.00330
-6.11699,0.94761,-0.96856,-1.84641,-0.32806,2.19534,0.00331
-6.11818,0.94852,-0.96801,-1.84666,-0.32836,2.19444,0.00331
-6.11937,0.94942,-0.96747,-1.84690,-0.32866,2.19354,0.00331
-6.12056,0.95031,-0.96694,-1.84714,-0.32895,2.19266,0.00331
-6.12175,0.95120,-0.96642,-1.84738,-0.32924,2.19178,0.00331
-6.12293,0.95208,-0.96590,-1.84762,-0.32952,2.19091,0.00331
-6.12412,0.95295,-0.96539,-1.84785,-0.32980,2.19004,0.00332
-6.12531,0.95381,-0.96489,-1.84807,-0.33008,2.18918,0.00332
-6.12650,0.95467,-0.96439,-1.84830,-0.33036,2.18833,0.00332
-6.12769,0.95552,-0.96390,-1.84852,-0.33063,2.18748,0.00332
-6.12888,0.95637,-0.96342,-1.84874,-0.33090,2.18665,0.00332
-6.13007,0.95721,-0.96294,-1.84895,-0.33117,2.18581,0.00332
-6.13126,0.95804,-0.96247,-1.84916,-0.33143,2.18499,0.00332
-6.13245,0.95886,-0.96201,-1.84937,-0.33169,2.18417,0.00332
-6.13363,0.95968,-0.96155,-1.84958,-0.33195,2.18335,0.00333
-6.13482,0.96049,-0.96109,-1.84978,-0.33220,2.18255,0.00333
-6.13601,0.96130,-0.96065,-1.84998,-0.33245,2.18175,0.00333
-6.13720,0.96209,-0.96021,-1.85017,-0.33270,2.18095,0.00333
-6.13839,0.96289,-0.95977,-1.85036,-0.33294,2.18016,0.00333
-6.13958,0.96367,-0.95934,-1.85055,-0.33319,2.17938,0.00333
-6.14077,0.96445,-0.95892,-1.85074,-0.33343,2.17861,0.00333
-6.14196,0.96522,-0.95850,-1.85093,-0.33367,2.17784,0.00333
-6.14315,0.96599,-0.95809,-1.85111,-0.33390,2.17707,0.00333
-6.14433,0.96675,-0.95768,-1.85129,-0.33413,2.17631,0.00333
-6.14552,0.96751,-0.95728,-1.85146,-0.33436,2.17556,0.00333
-6.14671,0.96826,-0.95688,-1.85164,-0.33459,2.17481,0.00333
-6.14790,0.96900,-0.95649,-1.85181,-0.33481,2.17407,0.00333
-6.14909,0.96974,-0.95610,-1.85198,-0.33504,2.17334,0.00334
-6.15028,0.97047,-0.95572,-1.85215,-0.33526,2.17261,0.00334
-6.15147,0.97120,-0.95534,-1.85231,-0.33547,2.17188,0.00334
-6.15266,0.97192,-0.95497,-1.85247,-0.33569,2.17117,0.00334
-6.15385,0.97263,-0.95460,-1.85263,-0.33590,2.17045,0.00334
-6.15504,0.97334,-0.95424,-1.85279,-0.33611,2.16975,0.00334
-6.15622,0.97404,-0.95388,-1.85294,-0.33632,2.16904,0.00334
-6.15741,0.97474,-0.95352,-1.85310,-0.33652,2.16835,0.00334
-6.15860,0.97543,-0.95317,-1.85325,-0.33673,2.16766,0.00334
-6.15979,0.97612,-0.95283,-1.85340,-0.33693,2.16697,0.00334
-6.16098,0.97680,-0.95248,-1.85354,-0.33713,2.16629,0.00334
-6.16217,0.97748,-0.95215,-1.85369,-0.33732,2.16562,0.00334
-6.16336,0.97815,-0.95181,-1.85383,-0.33752,2.16495,0.00334
-6.16455,0.97881,-0.95148,-1.85397,-0.33771,2.16428,0.00334
-6.16574,0.97947,-0.95116,-1.85411,-0.33790,2.16362,0.00334
-6.16692,0.98013,-0.95084,-1.85425,-0.33809,2.16297,0.00334
-6.16811,0.98078,-0.95052,-1.85438,-0.33828,2.16232,0.00334
-6.16930,0.98142,-0.95021,-1.85451,-0.33846,2.16167,0.00334
-6.17049,0.98206,-0.94990,-1.85465,-0.33865,2.16103,0.00334
-6.17168,0.98270,-0.94959,-1.85478,-0.33883,2.16040,0.00334
-6.17287,0.98309,-0.94939,-1.85486,-0.33894,2.16000,0.00334
-6.17406,0.98391,-0.94896,-1.85503,-0.33921,2.15919,0.00334
-6.17525,0.98472,-0.94853,-1.85520,-0.33948,2.15839,0.00335
-6.17644,0.98552,-0.94810,-1.85536,-0.33974,2.15759,0.00335
-6.17762,0.98631,-0.94768,-1.85552,-0.34000,2.15680,0.00335
-6.17881,0.98710,-0.94727,-1.85569,-0.34025,2.15601,0.00335
-6.18000,0.98789,-0.94686,-1.85584,-0.34051,2.15523,0.00335
-6.18119,0.98867,-0.94645,-1.85600,-0.34076,2.15446,0.00335
-6.18238,0.98944,-0.94606,-1.85616,-0.34101,2.15369,0.00335
-6.18357,0.99021,-0.94566,-1.85631,-0.34125,2.15293,0.00335
-6.18476,0.99097,-0.94527,-1.85646,-0.34149,2.15217,0.00335
-6.18595,0.99172,-0.94489,-1.85661,-0.34173,2.15142,0.00336
-6.18714,0.99247,-0.94451,-1.85675,-0.34197,2.15067,0.00336
-6.18832,0.99321,-0.94413,-1.85690,-0.34221,2.14993,0.00336
-6.18951,0.99395,-0.94376,-1.85704,-0.34244,2.14920,0.00336
-6.19070,0.99468,-0.94340,-1.85718,-0.34267,2.14847,0.00336
-6.19189,0.99541,-0.94304,-1.85732,-0.34289,2.14774,0.00336
-6.19308,0.99613,-0.94268,-1.85745,-0.34312,2.14703,0.00336
-6.19427,0.99684,-0.94233,-1.85759,-0.34334,2.14631,0.00336
-6.19546,0.99755,-0.94198,-1.85772,-0.34356,2.14560,0.00336
-6.19665,0.99826,-0.94163,-1.85785,-0.34378,2.14490,0.00336
-6.19784,0.99896,-0.94129,-1.85798,-0.34399,2.14420,0.00336
-6.19903,0.99965,-0.94096,-1.85811,-0.34420,2.14351,0.00336
-6.20021,1.00034,-0.94063,-1.85823,-0.34441,2.14282,0.00336
-6.20140,1.00102,-0.94030,-1.85836,-0.34462,2.14214,0.00336
-6.20259,1.00170,-0.93997,-1.85848,-0.34483,2.14147,0.00337
-6.20378,1.00237,-0.93965,-1.85860,-0.34503,2.14079,0.00337
-6.20497,1.00304,-0.93934,-1.85872,-0.34523,2.14013,0.00337
-6.20616,1.00371,-0.93902,-1.85883,-0.34543,2.13946,0.00337
-6.20735,1.00436,-0.93871,-1.85895,-0.34563,2.13881,0.00337
-6.20854,1.00502,-0.93841,-1.85906,-0.34582,2.13815,0.00337
-6.20973,1.00566,-0.93811,-1.85918,-0.34602,2.13751,0.00337
-6.21091,1.00631,-0.93781,-1.85929,-0.34621,2.13686,0.00337
-6.21210,1.00695,-0.93751,-1.85940,-0.34640,2.13622,0.00337
-6.21329,1.00758,-0.93722,-1.85951,-0.34658,2.13559,0.00337
-6.21448,1.00786,-0.93708,-1.85956,-0.34667,2.13531,0.00337
-6.21567,1.00880,-0.93658,-1.85973,-0.34700,2.13438,0.00337
-6.21686,1.00973,-0.93608,-1.85990,-0.34733,2.13346,0.00337
-6.21805,1.01065,-0.93559,-1.86007,-0.34765,2.13255,0.00338
-6.21924,1.01156,-0.93511,-1.86024,-0.34797,2.13164,0.00338
-6.22043,1.01247,-0.93463,-1.86040,-0.34829,2.13074,0.00338
-6.22161,1.01337,-0.93416,-1.86056,-0.34860,2.12985,0.00338
-6.22280,1.01427,-0.93369,-1.86072,-0.34891,2.12896,0.00338
-6.22399,1.01516,-0.93323,-1.86088,-0.34922,2.12808,0.00339
-6.22518,1.01604,-0.93278,-1.86104,-0.34952,2.12721,0.00339
-6.22637,1.01691,-0.93233,-1.86119,-0.34982,2.12634,0.00339
-6.22756,1.01778,-0.93189,-1.86134,-0.35011,2.12547,0.00339
-6.22875,1.01865,-0.93145,-1.86149,-0.35040,2.12462,0.00339
-6.22994,1.01950,-0.93102,-1.86164,-0.35069,2.12377,0.00339
-6.23113,1.02035,-0.93059,-1.86178,-0.35098,2.12292,0.00340
-6.23231,1.02120,-0.93017,-1.86192,-0.35126,2.12208,0.00340
-6.23350,1.02204,-0.92975,-1.86206,-0.35154,2.12125,0.00340
-6.23469,1.02287,-0.92934,-1.86220,-0.35181,2.12042,0.00340
-6.23588,1.02369,-0.92893,-1.86234,-0.35209,2.11960,0.00340
-6.23707,1.02452,-0.92853,-1.86248,-0.35236,2.11879,0.00340
-6.23826,1.02533,-0.92813,-1.86261,-0.35262,2.11798,0.00340
-6.23945,1.02614,-0.92774,-1.86274,-0.35289,2.11717,0.00341
-6.24064,1.02694,-0.92735,-1.86287,-0.35315,2.11637,0.00341
-6.24183,1.02774,-0.92697,-1.86300,-0.35341,2.11558,0.00341
-6.24302,1.02853,-0.92659,-1.86312,-0.35366,2.11479,0.00341
-6.24420,1.02932,-0.92622,-1.86325,-0.35391,2.11401,0.00341
-6.24539,1.03010,-0.92585,-1.86337,-0.35416,2.11323,0.00341
-6.24658,1.03087,-0.92548,-1.86349,-0.35441,2.11246,0.00341
-6.24777,1.03164,-0.92512,-1.86361,-0.35466,2.11169,0.00341
-6.24896,1.03240,-0.92477,-1.86373,-0.35490,2.11093,0.00341
-6.25015,1.03316,-0.92441,-1.86385,-0.35514,2.11018,0.00341
-6.25134,1.03391,-0.92407,-1.86396,-0.35538,2.10943,0.00342
-6.25253,1.03466,-0.92372,-1.86408,-0.35561,2.10868,0.00342
-6.25372,1.03540,-0.92338,-1.86419,-0.35584,2.10794,0.00342
-6.25490,1.03614,-0.92304,-1.86430,-0.35607,2.10721,0.00342
-6.25609,1.03687,-0.92271,-1.86441,-0.35630,2.10648,0.00342
-6.25728,1.03760,-0.92238,-1.86452,-0.35652,2.10575,0.00342
-6.25847,1.03832,-0.92206,-1.86462,-0.35675,2.10503,0.00342
-6.25966,1.03903,-0.92173,-1.86473,-0.35697,2.10432,0.00342
-6.26085,1.03975,-0.92142,-1.86483,-0.35718,2.10361,0.00342
-6.26204,1.04045,-0.92110,-1.86494,-0.35740,2.10290,0.00342
-6.26323,1.04115,-0.92079,-1.86504,-0.35761,2.10220,0.00342
-6.26442,1.04185,-0.92048,-1.86514,-0.35782,2.10151,0.00342
-6.26560,1.04254,-0.92018,-1.86524,-0.35803,2.10082,0.00342
-6.26679,1.04323,-0.91988,-1.86533,-0.35824,2.10013,0.00342
-6.26798,1.04391,-0.91958,-1.86543,-0.35844,2.09945,0.00342
-6.26917,1.04458,-0.91929,-1.86553,-0.35865,2.09877,0.00343
-6.27036,1.04526,-0.91900,-1.86562,-0.35885,2.09810,0.00343
-6.27155,1.04592,-0.91871,-1.86571,-0.35905,2.09744,0.00343
-6.27274,1.04659,-0.91842,-1.86581,-0.35924,2.09677,0.00343
-6.27393,1.04725,-0.91814,-1.86590,-0.35944,2.09611,0.00343
-6.27512,1.04790,-0.91786,-1.86599,-0.35963,2.09546,0.00343
-6.27630,1.04855,-0.91759,-1.86607,-0.35982,2.09481,0.00343
-6.27749,1.04919,-0.91731,-1.86616,-0.36001,2.09417,0.00343
-6.27868,1.04983,-0.91704,-1.86625,-0.36020,2.09353,0.00343
-6.27987,1.05047,-0.91678,-1.86633,-0.36038,2.09289,0.00343
-6.28106,1.05110,-0.91651,-1.86642,-0.36057,2.09226,0.00343
-6.28225,1.05136,-0.91640,-1.86645,-0.36065,2.09199,0.00343
-6.28344,1.05211,-0.91606,-1.86656,-0.36088,2.09125,0.00343
-6.28463,1.05285,-0.91572,-1.86666,-0.36112,2.09052,0.00343
-6.28582,1.05358,-0.91539,-1.86677,-0.36135,2.08979,0.00343
-6.28701,1.05431,-0.91506,-1.86687,-0.36158,2.08906,0.00343
-6.28819,1.05503,-0.91474,-1.86697,-0.36181,2.08834,0.00344
-6.28938,1.05575,-0.91442,-1.86707,-0.36203,2.08762,0.00344
-6.29057,1.05647,-0.91410,-1.86717,-0.36225,2.08691,0.00344
-6.29176,1.05718,-0.91378,-1.86727,-0.36247,2.08620,0.00344
-6.29295,1.05788,-0.91347,-1.86736,-0.36269,2.08550,0.00344
-6.29414,1.05858,-0.91317,-1.86746,-0.36291,2.08480,0.00344
-6.29533,1.05928,-0.91286,-1.86755,-0.36312,2.08411,0.00344
-6.29652,1.05997,-0.91256,-1.86765,-0.36333,2.08342,0.00344
-6.29771,1.06065,-0.91226,-1.86774,-0.36354,2.08273,0.00344
-6.29889,1.06133,-0.91197,-1.86783,-0.36375,2.08205,0.00344
-6.30008,1.06201,-0.91168,-1.86792,-0.36396,2.08138,0.00344
-6.30127,1.06268,-0.91139,-1.86801,-0.36416,2.08071,0.00344
-6.30246,1.06335,-0.91110,-1.86809,-0.36436,2.08004,0.00345
-6.30365,1.06401,-0.91082,-1.86818,-0.36456,2.07938,0.00345
-6.30484,1.06467,-0.91054,-1.86826,-0.36476,2.07872,0.00345
-6.30603,1.06532,-0.91027,-1.86835,-0.36495,2.07807,0.00345
-6.30722,1.06597,-0.90999,-1.86843,-0.36515,2.07742,0.00345
-6.30841,1.06662,-0.90972,-1.86851,-0.36534,2.07677,0.00345
-6.30959,1.06726,-0.90946,-1.86860,-0.36553,2.07613,0.00345
-6.31078,1.06789,-0.90919,-1.86868,-0.36571,2.07550,0.00345
-6.31197,1.06853,-0.90893,-1.86875,-0.36590,2.07487,0.00345
-6.31316,1.06915,-0.90867,-1.86883,-0.36608,2.07424,0.00345
-6.31435,1.06972,-0.90843,-1.86891,-0.36625,2.07367,0.00345
-6.31554,1.07044,-0.90812,-1.86900,-0.36648,2.07295,0.00345
-6.31673,1.07115,-0.90780,-1.86909,-0.36670,2.07225,0.00345
-6.31792,1.07186,-0.90749,-1.86919,-0.36692,2.07154,0.00345
-6.31911,1.07256,-0.90719,-1.86928,-0.36714,2.07084,0.00346
-6.32029,1.07326,-0.90688,-1.86937,-0.36736,2.07015,0.00346
-6.32148,1.07395,-0.90658,-1.86946,-0.36757,2.06946,0.00346
-6.32267,1.07464,-0.90629,-1.86954,-0.36778,2.06877,0.00346
-6.32386,1.07532,-0.90599,-1.86963,-0.36799,2.06809,0.00346
-6.32505,1.07600,-0.90570,-1.86972,-0.36820,2.06742,0.00346
-6.32624,1.07667,-0.90542,-1.86980,-0.36841,2.06674,0.00346
-6.32743,1.07734,-0.90513,-1.86989,-0.36861,2.06607,0.00346
-6.32862,1.07801,-0.90485,-1.86997,-0.36881,2.06541,0.00346
-6.32981,1.07867,-0.90457,-1.87005,-0.36901,2.06475,0.00346
-6.33100,1.07932,-0.90430,-1.87013,-0.36921,2.06410,0.00346
-6.33218,1.07997,-0.90402,-1.87021,-0.36941,2.06344,0.00347
-6.33337,1.08062,-0.90375,-1.87029,-0.36960,2.06280,0.00347
-6.33456,1.08127,-0.90349,-1.87037,-0.36979,2.06216,0.00347
-6.33575,1.08191,-0.90322,-1.87045,-0.36998,2.06152,0.00347
-6.33694,1.08254,-0.90296,-1.87052,-0.37017,2.06088,0.00347
-6.33813,1.08317,-0.90270,-1.87060,-0.37036,2.06025,0.00347
-6.33932,1.08380,-0.90244,-1.87067,-0.37054,2.05962,0.00347
-6.34051,1.08442,-0.90219,-1.87075,-0.37073,2.05900,0.00347
-6.34170,1.08492,-0.90199,-1.87081,-0.37087,2.05850,0.00347
-6.34288,1.08559,-0.90171,-1.87089,-0.37108,2.05784,0.00347
-6.34407,1.08624,-0.90143,-1.87097,-0.37128,2.05718,0.00347
-6.34526,1.08690,-0.90115,-1.87105,-0.37147,2.05653,0.00347
-6.34645,1.08755,-0.90088,-1.87112,-0.37167,2.05588,0.00347
-6.34764,1.08820,-0.90061,-1.87120,-0.37187,2.05523,0.00348
-6.34883,1.08884,-0.90035,-1.87128,-0.37206,2.05459,0.00348
-6.35002,1.08948,-0.90009,-1.87135,-0.37225,2.05396,0.00348
-6.35121,1.09011,-0.89982,-1.87143,-0.37244,2.05332,0.00348
-6.35240,1.09074,-0.89957,-1.87150,-0.37263,2.05269,0.00348
-6.35358,1.09137,-0.89931,-1.87158,-0.37281,2.05207,0.00348
-6.35477,1.09199,-0.89906,-1.87165,-0.37299,2.05145,0.00348
-6.35596,1.09261,-0.89881,-1.87172,-0.37318,2.05083,0.00348
-6.35715,1.09274,-0.89875,-1.87173,-0.37322,2.05070,0.00348
-6.35834,1.09342,-0.89846,-1.87182,-0.37343,2.05002,0.00348
-6.35953,1.09410,-0.89817,-1.87190,-0.37364,2.04934,0.00348
-6.36072,1.09478,-0.89788,-1.87198,-0.37385,2.04866,0.00348
-6.36191,1.09545,-0.89760,-1.87206,-0.37406,2.04800,0.00349
-6.36310,1.09612,-0.89732,-1.87214,-0.37426,2.04733,0.00349
-6.36428,1.09678,-0.89704,-1.87222,-0.37446,2.04667,0.00349
-6.36547,1.09744,-0.89677,-1.87230,-0.37466,2.04601,0.00349
-6.36666,1.09810,-0.89649,-1.87237,-0.37486,2.04536,0.00349
-6.36785,1.09875,-0.89622,-1.87245,-0.37506,2.04471,0.00349
-6.36904,1.09939,-0.89596,-1.87252,-0.37526,2.04406,0.00349
-6.37023,1.10004,-0.89569,-1.87260,-0.37545,2.04342,0.00349
-6.37142,1.10068,-0.89543,-1.87267,-0.37564,2.04278,0.00349
-6.37261,1.10131,-0.89517,-1.87274,-0.37583,2.04215,0.00349
-6.37380,1.10194,-0.89492,-1.87281,-0.37602,2.04152,0.00350
-6.37499,1.10257,-0.89466,-1.87288,-0.37620,2.04090,0.00350
-6.37617,1.10319,-0.89441,-1.87295,-0.37639,2.04027,0.00350
-6.37736,1.10381,-0.89416,-1.87302,-0.37657,2.03966,0.00350
-6.37855,1.10442,-0.89392,-1.87309,-0.37675,2.03904,0.00350
-6.37974,1.10474,-0.89379,-1.87313,-0.37685,2.03873,0.00350
-6.38093,1.10542,-0.89350,-1.87321,-0.37706,2.03805,0.00350
-6.38212,1.10610,-0.89322,-1.87329,-0.37727,2.03738,0.00350
-6.38331,1.10677,-0.89293,-1.87336,-0.37747,2.03671,0.00350
-6.38450,1.10744,-0.89265,-1.87344,-0.37768,2.03604,0.00350
-6.38569,1.10810,-0.89238,-1.87352,-0.37788,2.03538,0.00350
-6.38687,1.10876,-0.89210,-1.87359,-0.37808,2.03472,0.00351
-6.38806,1.10942,-0.89183,-1.87367,-0.37828,2.03407,0.00351
-6.38925,1.11007,-0.89157,-1.87374,-0.37848,2.03342,0.00351
-6.39044,1.11072,-0.89130,-1.87381,-0.37868,2.03277,0.00351
-6.39163,1.11136,-0.89104,-1.87388,-0.37887,2.03213,0.00351
-6.39282,1.11200,-0.89078,-1.87395,-0.37906,2.03149,0.00351
-6.39401,1.11264,-0.89052,-1.87402,-0.37925,2.03086,0.00351
-6.39520,1.11327,-0.89026,-1.87409,-0.37944,2.03023,0.00351
-6.39639,1.11390,-0.89001,-1.87416,-0.37963,2.02960,0.00351
-6.39757,1.11452,-0.88976,-1.87423,-0.37981,2.02898,0.00351
-6.39876,1.11514,-0.88951,-1.87430,-0.38000,2.02836,0.00351
-6.39995,1.11576,-0.88927,-1.87436,-0.38018,2.02774,0.00352
-6.40114,1.11637,-0.88903,-1.87443,-0.38036,2.02713,0.00352
-6.40233,1.11698,-0.88879,-1.87450,-0.38054,2.02652,0.00352
-6.40352,1.11704,-0.88876,-1.87450,-0.38056,2.02645,0.00352
-6.40471,1.11770,-0.88849,-1.87457,-0.38076,2.02580,0.00352
-6.40590,1.11835,-0.88823,-1.87465,-0.38095,2.02516,0.00352
-6.40709,1.11899,-0.88796,-1.87472,-0.38115,2.02451,0.00352
-6.40827,1.11963,-0.88770,-1.87479,-0.38134,2.02388,0.00352
-6.40946,1.12027,-0.88745,-1.87486,-0.38153,2.02324,0.00352
-6.41065,1.12090,-0.88719,-1.87492,-0.38172,2.02261,0.00352
-6.41184,1.12153,-0.88694,-1.87499,-0.38191,2.02198,0.00352
-6.41303,1.12216,-0.88669,-1.87506,-0.38210,2.02136,0.00353
-6.41422,1.12278,-0.88644,-1.87512,-0.38228,2.02074,0.00353
-6.41541,1.12340,-0.88620,-1.87519,-0.38246,2.02012,0.00353
-6.41660,1.12401,-0.88595,-1.87525,-0.38264,2.01951,0.00353
-6.41779,1.12462,-0.88571,-1.87532,-0.38282,2.01890,0.00353
-6.41898,1.12523,-0.88547,-1.87538,-0.38300,2.01829,0.00353
-6.42016,1.12542,-0.88540,-1.87540,-0.38306,2.01810,0.00353
-6.42135,1.12614,-0.88509,-1.87548,-0.38329,2.01738,0.00353
-6.42254,1.12686,-0.88478,-1.87556,-0.38352,2.01667,0.00353
-6.42373,1.12757,-0.88448,-1.87564,-0.38374,2.01596,0.00353
-6.42492,1.12828,-0.88418,-1.87572,-0.38396,2.01526,0.00354
-6.42611,1.12899,-0.88389,-1.87580,-0.38418,2.01456,0.00354
-6.42730,1.12969,-0.88359,-1.87588,-0.38440,2.01386,0.00354
-6.42849,1.13038,-0.88330,-1.87595,-0.38462,2.01317,0.00354
-6.42968,1.13107,-0.88302,-1.87603,-0.38483,2.01248,0.00354
-6.43086,1.13176,-0.88273,-1.87610,-0.38505,2.01180,0.00354
-6.43205,1.13244,-0.88245,-1.87618,-0.38526,2.01112,0.00354
-6.43324,1.13312,-0.88217,-1.87625,-0.38547,2.01044,0.00355
-6.43443,1.13380,-0.88190,-1.87632,-0.38567,2.00977,0.00355
-6.43562,1.13447,-0.88162,-1.87639,-0.38588,2.00910,0.00355
-6.43681,1.13514,-0.88135,-1.87646,-0.38608,2.00843,0.00355
-6.43800,1.13580,-0.88108,-1.87653,-0.38628,2.00777,0.00355
-6.43919,1.13646,-0.88082,-1.87660,-0.38648,2.00712,0.00355
-6.44038,1.13712,-0.88056,-1.87667,-0.38668,2.00646,0.00355
-6.44156,1.13777,-0.88030,-1.87674,-0.38688,2.00581,0.00355
-6.44275,1.13842,-0.88004,-1.87680,-0.38707,2.00517,0.00355
-6.44394,1.13906,-0.87978,-1.87687,-0.38726,2.00452,0.00356
-6.44513,1.13970,-0.87953,-1.87693,-0.38745,2.00388,0.00356
-6.44632,1.14034,-0.87928,-1.87700,-0.38764,2.00325,0.00356
-6.44751,1.14097,-0.87903,-1.87706,-0.38783,2.00262,0.00356
-6.44870,1.14160,-0.87879,-1.87713,-0.38801,2.00199,0.00356
-6.44989,1.14223,-0.87854,-1.87719,-0.38820,2.00137,0.00356
-6.45108,1.14285,-0.87830,-1.87725,-0.38838,2.00074,0.00356
-6.45226,1.14347,-0.87806,-1.87731,-0.38856,2.00013,0.00356
-6.45345,1.14408,-0.87782,-1.87737,-0.38874,1.99951,0.00356
-6.45464,1.14470,-0.87759,-1.87743,-0.38892,1.99890,0.00356
-6.45583,1.14530,-0.87736,-1.87749,-0.38910,1.99829,0.00356
-6.45702,1.14591,-0.87713,-1.87755,-0.38927,1.99769,0.00357
-6.45821,1.14651,-0.87690,-1.87761,-0.38944,1.99709,0.00357
-6.45940,1.14705,-0.87669,-1.87766,-0.38960,1.99655,0.00357
-6.46059,1.14769,-0.87644,-1.87773,-0.38979,1.99591,0.00357
-6.46178,1.14833,-0.87619,-1.87779,-0.38998,1.99527,0.00357
-6.46297,1.14897,-0.87594,-1.87785,-0.39017,1.99464,0.00357
-6.46415,1.14960,-0.87569,-1.87791,-0.39036,1.99401,0.00357
-6.46534,1.15022,-0.87545,-1.87798,-0.39054,1.99338,0.00357
-6.46653,1.15085,-0.87521,-1.87804,-0.39072,1.99276,0.00357
-6.46772,1.15147,-0.87497,-1.87810,-0.39091,1.99214,0.00358
-6.46891,1.15209,-0.87473,-1.87816,-0.39109,1.99153,0.00358
-6.47010,1.15270,-0.87450,-1.87822,-0.39127,1.99092,0.00358
-6.47129,1.15331,-0.87426,-1.87827,-0.39144,1.99031,0.00358
-6.47248,1.15391,-0.87403,-1.87833,-0.39162,1.98970,0.00358
-6.47367,1.15452,-0.87381,-1.87839,-0.39179,1.98910,0.00358
-6.47485,1.15512,-0.87358,-1.87845,-0.39197,1.98850,0.00358
-6.47604,1.15571,-0.87335,-1.87850,-0.39214,1.98791,0.00358
-6.47723,1.15613,-0.87319,-1.87854,-0.39226,1.98749,0.00358
-6.47842,1.15677,-0.87295,-1.87860,-0.39245,1.98685,0.00358
-6.47961,1.15740,-0.87270,-1.87867,-0.39264,1.98622,0.00358
-6.48080,1.15803,-0.87245,-1.87873,-0.39282,1.98559,0.00359
-6.48199,1.15866,-0.87221,-1.87879,-0.39301,1.98497,0.00359
-6.48318,1.15928,-0.87197,-1.87885,-0.39319,1.98435,0.00359
-6.48437,1.15990,-0.87173,-1.87891,-0.39337,1.98373,0.00359
-6.48555,1.16052,-0.87150,-1.87896,-0.39355,1.98311,0.00359
-6.48674,1.16113,-0.87126,-1.87902,-0.39373,1.98250,0.00359
-6.48793,1.16174,-0.87103,-1.87908,-0.39391,1.98189,0.00359
-6.48912,1.16235,-0.87080,-1.87914,-0.39409,1.98129,0.00359
-6.49031,1.16295,-0.87057,-1.87919,-0.39426,1.98069,0.00359
-6.49150,1.16355,-0.87035,-1.87925,-0.39443,1.98009,0.00360
-6.49269,1.16415,-0.87012,-1.87930,-0.39461,1.97949,0.00360
-6.49388,1.16474,-0.86990,-1.87936,-0.39478,1.97890,0.00360
-6.49507,1.16534,-0.86968,-1.87941,-0.39495,1.97830,0.00360
-6.49625,1.16602,-0.86941,-1.87945,-0.39517,1.97763,0.00360
-6.49744,1.16670,-0.86915,-1.87950,-0.39540,1.97695,0.00360
-6.49863,1.16737,-0.86889,-1.87954,-0.39562,1.97628,0.00360
-6.49982,1.16804,-0.86863,-1.87958,-0.39584,1.97562,0.00360
-6.50101,1.16871,-0.86837,-1.87963,-0.39605,1.97496,0.00361
-6.50220,1.16937,-0.86812,-1.87967,-0.39627,1.97430,0.00361
-6.50339,1.17003,-0.86787,-1.87971,-0.39648,1.97364,0.00361
-6.50458,1.17068,-0.86762,-1.87975,-0.39669,1.97299,0.00361
-6.50577,1.17133,-0.86737,-1.87979,-0.39690,1.97234,0.00361
-6.50696,1.17198,-0.86713,-1.87983,-0.39710,1.97170,0.00361
-6.50814,1.17262,-0.86688,-1.87987,-0.39731,1.97106,0.00361
-6.50933,1.17326,-0.86664,-1.87992,-0.39751,1.97042,0.00361
-6.51052,1.17390,-0.86640,-1.87996,-0.39771,1.96978,0.00362
-6.51171,1.17454,-0.86617,-1.88000,-0.39791,1.96915,0.00362
-6.51290,1.17517,-0.86593,-1.88003,-0.39811,1.96852,0.00362
-6.51409,1.17579,-0.86570,-1.88007,-0.39830,1.96790,0.00362
-6.51528,1.17642,-0.86547,-1.88011,-0.39850,1.96728,0.00362
-6.51647,1.17704,-0.86524,-1.88015,-0.39869,1.96666,0.00362
-6.51766,1.17765,-0.86502,-1.88019,-0.39888,1.96604,0.00362
-6.51884,1.17827,-0.86479,-1.88023,-0.39907,1.96543,0.00362
-6.52003,1.17888,-0.86457,-1.88027,-0.39926,1.96482,0.00362
-6.52122,1.17948,-0.86435,-1.88031,-0.39944,1.96422,0.00363
-6.52241,1.18009,-0.86413,-1.88034,-0.39963,1.96362,0.00363
-6.52360,1.18069,-0.86391,-1.88038,-0.39981,1.96302,0.00363
-6.52479,1.18128,-0.86370,-1.88042,-0.39999,1.96242,0.00363
-6.52598,1.18188,-0.86348,-1.88045,-0.40017,1.96183,0.00363
-6.52717,1.18247,-0.86327,-1.88049,-0.40035,1.96124,0.00363
-6.52836,1.18306,-0.86306,-1.88053,-0.40052,1.96065,0.00363
-6.52954,1.18364,-0.86285,-1.88056,-0.40070,1.96007,0.00363
-6.53073,1.18422,-0.86265,-1.88060,-0.40087,1.95949,0.00363
-6.53192,1.18435,-0.86260,-1.88061,-0.40091,1.95936,0.00363
-6.53311,1.18499,-0.86236,-1.88065,-0.40111,1.95872,0.00363
-6.53430,1.18564,-0.86211,-1.88070,-0.40131,1.95808,0.00364
-6.53549,1.18628,-0.86187,-1.88074,-0.40151,1.95744,0.00364
-6.53668,1.18692,-0.86163,-1.88079,-0.40171,1.95681,0.00364
-6.53787,1.18755,-0.86140,-1.88083,-0.40190,1.95617,0.00364
-6.53906,1.18818,-0.86116,-1.88087,-0.40210,1.95555,0.00364
-6.54024,1.18881,-0.86093,-1.88092,-0.40229,1.95492,0.00364
-6.54143,1.18943,-0.86070,-1.88096,-0.40248,1.95430,0.00364
-6.54262,1.19005,-0.86047,-1.88100,-0.40267,1.95368,0.00364
-6.54381,1.19067,-0.86025,-1.88104,-0.40286,1.95306,0.00365
-6.54500,1.19129,-0.86002,-1.88109,-0.40304,1.95245,0.00365
-6.54619,1.19190,-0.85980,-1.88113,-0.40322,1.95184,0.00365
-6.54738,1.19251,-0.85958,-1.88117,-0.40341,1.95124,0.00365
-6.54857,1.19311,-0.85936,-1.88121,-0.40359,1.95063,0.00365
-6.54976,1.19371,-0.85914,-1.88125,-0.40377,1.95003,0.00365
-6.55095,1.19431,-0.85892,-1.88129,-0.40395,1.94944,0.00365
-6.55213,1.19491,-0.85871,-1.88133,-0.40412,1.94884,0.00365
-6.55332,1.19550,-0.85850,-1.88137,-0.40430,1.94825,0.00365
-6.55451,1.19609,-0.85829,-1.88141,-0.40447,1.94766,0.00365
-6.55570,1.19667,-0.85808,-1.88145,-0.40464,1.94708,0.00366
-6.55689,1.19726,-0.85787,-1.88149,-0.40481,1.94649,0.00366
-6.55808,1.19784,-0.85767,-1.88153,-0.40498,1.94592,0.00366
-6.55927,1.19841,-0.85746,-1.88156,-0.40515,1.94534,0.00366
-6.56046,1.19899,-0.85726,-1.88160,-0.40532,1.94476,0.00366
-6.56165,1.19917,-0.85720,-1.88161,-0.40537,1.94459,0.00366
-6.56283,1.19981,-0.85697,-1.88164,-0.40558,1.94395,0.00366
-6.56402,1.20044,-0.85674,-1.88166,-0.40579,1.94332,0.00366
-6.56521,1.20108,-0.85651,-1.88168,-0.40600,1.94269,0.00366
-6.56640,1.20171,-0.85628,-1.88171,-0.40621,1.94206,0.00367
-6.56759,1.20234,-0.85606,-1.88173,-0.40641,1.94143,0.00367
-6.56878,1.20296,-0.85584,-1.88175,-0.40661,1.94081,0.00367
-6.56997,1.20358,-0.85561,-1.88178,-0.40681,1.94019,0.00367
-6.57116,1.20420,-0.85540,-1.88180,-0.40701,1.93958,0.00367
-6.57235,1.20481,-0.85518,-1.88182,-0.40720,1.93897,0.00367
-6.57353,1.20542,-0.85496,-1.88185,-0.40740,1.93836,0.00367
-6.57472,1.20603,-0.85475,-1.88187,-0.40759,1.93775,0.00367
-6.57591,1.20664,-0.85454,-1.88189,-0.40778,1.93715,0.00367
-6.57710,1.20724,-0.85433,-1.88192,-0.40797,1.93655,0.00368
-6.57829,1.20784,-0.85412,-1.88194,-0.40816,1.93595,0.00368
-6.57948,1.20843,-0.85391,-1.88196,-0.40835,1.93536,0.00368
-6.58067,1.20903,-0.85371,-1.88199,-0.40853,1.93477,0.00368
-6.58186,1.20962,-0.85350,-1.88201,-0.40871,1.93418,0.00368
-6.58305,1.21020,-0.85330,-1.88203,-0.40890,1.93359,0.00368
-6.58423,1.21079,-0.85310,-1.88206,-0.40908,1.93301,0.00368
-6.58542,1.21137,-0.85290,-1.88208,-0.40925,1.93243,0.00368
-6.58661,1.21195,-0.85270,-1.88211,-0.40943,1.93185,0.00368
-6.58780,1.21252,-0.85251,-1.88213,-0.40961,1.93128,0.00369
-6.58899,1.21309,-0.85231,-1.88215,-0.40978,1.93071,0.00369
-6.59018,1.21366,-0.85212,-1.88218,-0.40995,1.93014,0.00369
-6.59137,1.21423,-0.85192,-1.88220,-0.41013,1.92957,0.00369
-6.59256,1.21463,-0.85179,-1.88222,-0.41025,1.92917,0.00369
-6.59375,1.21526,-0.85156,-1.88225,-0.41045,1.92854,0.00369
-6.59494,1.21589,-0.85133,-1.88228,-0.41064,1.92792,0.00369
-6.59612,1.21652,-0.85111,-1.88231,-0.41084,1.92730,0.00369
-6.59731,1.21714,-0.85089,-1.88234,-0.41103,1.92668,0.00369
-6.59850,1.21776,-0.85067,-1.88237,-0.41123,1.92606,0.00370
-6.59969,1.21837,-0.85045,-1.88240,-0.41142,1.92545,0.00370
-6.60088,1.21898,-0.85023,-1.88244,-0.41160,1.92484,0.00370
-6.60207,1.21959,-0.85001,-1.88247,-0.41179,1.92423,0.00370
-6.60326,1.22020,-0.84980,-1.88250,-0.41198,1.92363,0.00370
-6.60445,1.22080,-0.84959,-1.88253,-0.41216,1.92303,0.00370
-6.60564,1.22140,-0.84938,-1.88256,-0.41234,1.92243,0.00370
-6.60682,1.22200,-0.84917,-1.88259,-0.41253,1.92183,0.00370
-6.60801,1.22260,-0.84896,-1.88262,-0.41271,1.92124,0.00370
-6.60920,1.22319,-0.84876,-1.88265,-0.41288,1.92065,0.00371
-6.61039,1.22378,-0.84855,-1.88268,-0.41306,1.92006,0.00371
-6.61158,1.22436,-0.84835,-1.88271,-0.41324,1.91948,0.00371
-6.61277,1.22495,-0.84815,-1.88274,-0.41341,1.91890,0.00371
-6.61396,1.22553,-0.84795,-1.88277,-0.41358,1.91832,0.00371
-6.61515,1.22610,-0.84775,-1.88280,-0.41375,1.91774,0.00371
-6.61634,1.22668,-0.84755,-1.88283,-0.41392,1.91717,0.00371
-6.61752,1.22725,-0.84736,-1.88285,-0.41409,1.91660,0.00371
-6.61871,1.22782,-0.84717,-1.88288,-0.41426,1.91603,0.00371
-6.61990,1.22839,-0.84697,-1.88291,-0.41443,1.91546,0.00372
-6.62109,1.22895,-0.84678,-1.88294,-0.41459,1.91490,0.00372
-6.62228,1.22951,-0.84659,-1.88297,-0.41476,1.91434,0.00372
-6.62347,1.23007,-0.84640,-1.88300,-0.41492,1.91378,0.00372
-6.62466,1.23052,-0.84625,-1.88302,-0.41505,1.91333,0.00372
-6.62585,1.23112,-0.84604,-1.88306,-0.41523,1.91274,0.00372
-6.62704,1.23171,-0.84583,-1.88309,-0.41541,1.91214,0.00372
-6.62822,1.23231,-0.84563,-1.88312,-0.41558,1.91155,0.00372
-6.62941,1.23290,-0.84542,-1.88315,-0.41576,1.91096,0.00372
-6.63060,1.23348,-0.84522,-1.88319,-0.41593,1.91038,0.00373
-6.63179,1.23407,-0.84501,-1.88322,-0.41611,1.90979,0.00373
-6.63298,1.23465,-0.84481,-1.88325,-0.41628,1.90921,0.00373
-6.63417,1.23523,-0.84461,-1.88329,-0.41645,1.90864,0.00373
-6.63536,1.23581,-0.84441,-1.88332,-0.41662,1.90806,0.00373
-6.63655,1.23638,-0.84422,-1.88335,-0.41678,1.90749,0.00373
-6.63774,1.23695,-0.84402,-1.88338,-0.41695,1.90692,0.00373
-6.63893,1.23752,-0.84383,-1.88341,-0.41712,1.90635,0.00373
-6.64011,1.23808,-0.84363,-1.88344,-0.41728,1.90579,0.00373
-6.64130,1.23865,-0.84344,-1.88348,-0.41744,1.90523,0.00374
-6.64249,1.23921,-0.84325,-1.88351,-0.41760,1.90467,0.00374
-6.64368,1.23977,-0.84307,-1.88354,-0.41776,1.90411,0.00374
-6.64487,1.24032,-0.84288,-1.88357,-0.41792,1.90355,0.00374
-6.64606,1.24087,-0.84269,-1.88360,-0.41808,1.90300,0.00374
-6.64725,1.24142,-0.84251,-1.88363,-0.41824,1.90245,0.00374
-6.64844,1.24148,-0.84249,-1.88363,-0.41825,1.90240,0.00374
-6.64963,1.24205,-0.84229,-1.88367,-0.41842,1.90183,0.00374
-6.65081,1.24262,-0.84210,-1.88370,-0.41858,1.90126,0.00374
-6.65200,1.24318,-0.84191,-1.88373,-0.41875,1.90070,0.00374
-6.65319,1.24374,-0.84172,-1.88376,-0.41891,1.90014,0.00374
-6.65438,1.24430,-0.84153,-1.88379,-0.41907,1.89958,0.00375
-6.65557,1.24486,-0.84134,-1.88383,-0.41923,1.89903,0.00375
-6.65676,1.24541,-0.84115,-1.88386,-0.41938,1.89847,0.00375
-6.65795,1.24596,-0.84096,-1.88389,-0.41954,1.89792,0.00375
-6.65914,1.24651,-0.84078,-1.88392,-0.41970,1.89737,0.00375
-6.66033,1.24706,-0.84060,-1.88395,-0.41985,1.89683,0.00375
-6.66151,1.24763,-0.84040,-1.88399,-0.42002,1.89626,0.00375
-6.66270,1.24819,-0.84021,-1.88402,-0.42018,1.89570,0.00375
-6.66389,1.24875,-0.84002,-1.88405,-0.42034,1.89514,0.00375
-6.66508,1.24931,-0.83983,-1.88408,-0.42050,1.89458,0.00376
-6.66627,1.24987,-0.83964,-1.88412,-0.42066,1.89403,0.00376
-6.66746,1.25042,-0.83945,-1.88415,-0.42081,1.89347,0.00376
-6.66865,1.25097,-0.83927,-1.88418,-0.42097,1.89292,0.00376
-6.66984,1.25152,-0.83908,-1.88421,-0.42113,1.89238,0.00376
-6.67103,1.25207,-0.83890,-1.88425,-0.42128,1.89183,0.00376
-6.67221,1.25261,-0.83872,-1.88428,-0.42143,1.89129,0.00376
-6.67340,1.25278,-0.83866,-1.88429,-0.42148,1.89112,0.00376
-6.67459,1.25334,-0.83847,-1.88432,-0.42164,1.89056,0.00376
-6.67578,1.25390,-0.83828,-1.88435,-0.42180,1.89000,0.00377
-6.67697,1.25446,-0.83809,-1.88439,-0.42196,1.88945,0.00377
-6.67816,1.25501,-0.83790,-1.88442,-0.42212,1.88890,0.00377
-6.67935,1.25556,-0.83771,-1.88445,-0.42227,1.88834,0.00377
-6.68054,1.25611,-0.83753,-1.88449,-0.42243,1.88779,0.00377
-6.68173,1.25666,-0.83734,-1.88452,-0.42258,1.88725,0.00377
-6.68292,1.25721,-0.83716,-1.88455,-0.42274,1.88670,0.00377
-6.68410,1.25775,-0.83698,-1.88458,-0.42289,1.88616,0.00377
-6.68529,1.25829,-0.83680,-1.88462,-0.42304,1.88562,0.00377
-6.68648,1.25851,-0.83673,-1.88463,-0.42310,1.88541,0.00377
-6.68767,1.25907,-0.83654,-1.88466,-0.42326,1.88485,0.00378
-6.68886,1.25962,-0.83635,-1.88470,-0.42342,1.88429,0.00378
-6.69005,1.26018,-0.83616,-1.88473,-0.42357,1.88374,0.00378
-6.69124,1.26073,-0.83597,-1.88476,-0.42373,1.88319,0.00378
-6.69243,1.26128,-0.83579,-1.88480,-0.42388,1.88264,0.00378
-6.69362,1.26182,-0.83560,-1.88483,-0.42404,1.88210,0.00378
-6.69480,1.26237,-0.83542,-1.88486,-0.42419,1.88155,0.00378
-6.69599,1.26291,-0.83524,-1.88490,-0.42434,1.88101,0.00378
-6.69718,1.26345,-0.83506,-1.88493,-0.42449,1.88048,0.00378
-6.69837,1.26399,-0.83488,-1.88496,-0.42464,1.87994,0.00379
-6.69956,1.26431,-0.83476,-1.88501,-0.42471,1.87962,0.00379
-6.70075,1.26484,-0.83448,-1.88535,-0.42466,1.87909,0.00379
-6.70194,1.26537,-0.83420,-1.88568,-0.42462,1.87856,0.00379
-6.70313,1.26589,-0.83393,-1.88600,-0.42457,1.87803,0.00379
-6.70432,1.26642,-0.83366,-1.88632,-0.42453,1.87750,0.00379
-6.70550,1.26694,-0.83339,-1.88663,-0.42449,1.87698,0.00379
-6.70669,1.26746,-0.83312,-1.88694,-0.42445,1.87646,0.00379
-6.70788,1.26798,-0.83286,-1.88725,-0.42442,1.87594,0.00379
-6.70907,1.26849,-0.83260,-1.88755,-0.42439,1.87542,0.00379
-6.71026,1.26901,-0.83234,-1.88784,-0.42435,1.87491,0.00380
-6.71145,1.26952,-0.83208,-1.88813,-0.42433,1.87440,0.00380
-6.71264,1.27003,-0.83183,-1.88841,-0.42430,1.87389,0.00380
-6.71383,1.27053,-0.83158,-1.88869,-0.42427,1.87338,0.00380
-6.71502,1.27104,-0.83133,-1.88897,-0.42425,1.87288,0.00380
-6.71620,1.27154,-0.83108,-1.88924,-0.42423,1.87237,0.00380
-6.71739,1.27204,-0.83084,-1.88951,-0.42421,1.87187,0.00380
-6.71858,1.27254,-0.83060,-1.88977,-0.42419,1.87137,0.00380
-6.71977,1.27303,-0.83036,-1.89003,-0.42418,1.87087,0.00380
-6.72096,1.27353,-0.83012,-1.89028,-0.42416,1.87038,0.00381
-6.72215,1.27402,-0.82989,-1.89053,-0.42415,1.86989,0.00381
-6.72334,1.27451,-0.82966,-1.89078,-0.42414,1.86939,0.00381
-6.72453,1.27499,-0.82943,-1.89102,-0.42413,1.86891,0.00381
-6.72572,1.27533,-0.82926,-1.89121,-0.42411,1.86857,0.00381
-6.72691,1.27579,-0.82897,-1.89168,-0.42395,1.86810,0.00381
-6.72809,1.27625,-0.82868,-1.89213,-0.42379,1.86764,0.00381
-6.72928,1.27671,-0.82839,-1.89259,-0.42363,1.86718,0.00381
-6.73047,1.27716,-0.82811,-1.89303,-0.42347,1.86672,0.00381
-6.73166,1.27762,-0.82783,-1.89346,-0.42333,1.86627,0.00382
-6.73285,1.27807,-0.82755,-1.89389,-0.42318,1.86581,0.00382
-6.73404,1.27852,-0.82727,-1.89431,-0.42304,1.86536,0.00382
-6.73523,1.27896,-0.82700,-1.89473,-0.42290,1.86491,0.00382
-6.73642,1.27941,-0.82673,-1.89514,-0.42277,1.86446,0.00382
-6.73761,1.27985,-0.82647,-1.89554,-0.42264,1.86401,0.00382
-6.73879,1.28030,-0.82621,-1.89593,-0.42251,1.86356,0.00382
-6.73998,1.28074,-0.82595,-1.89632,-0.42239,1.86312,0.00382
-6.74117,1.28117,-0.82569,-1.89670,-0.42227,1.86268,0.00383
-6.74236,1.28161,-0.82543,-1.89707,-0.42215,1.86224,0.00383
-6.74355,1.28204,-0.82518,-1.89744,-0.42204,1.86180,0.00383
-6.74474,1.28248,-0.82493,-1.89780,-0.42193,1.86137,0.00383
-6.74593,1.28291,-0.82469,-1.89816,-0.42182,1.86093,0.00383
-6.74712,1.28334,-0.82445,-1.89851,-0.42172,1.86050,0.00383
-6.74831,1.28377,-0.82420,-1.89885,-0.42162,1.86007,0.00383
-6.74949,1.28419,-0.82397,-1.89919,-0.42152,1.85964,0.00383
-6.75068,1.28449,-0.82380,-1.89944,-0.42145,1.85934,0.00384
-6.75187,1.28489,-0.82352,-1.89993,-0.42124,1.85893,0.00384
-6.75306,1.28529,-0.82324,-1.90041,-0.42104,1.85853,0.00384
-6.75425,1.28568,-0.82297,-1.90089,-0.42084,1.85813,0.00384
-6.75544,1.28608,-0.82270,-1.90135,-0.42065,1.85773,0.00384
-6.75663,1.28647,-0.82244,-1.90181,-0.42046,1.85733,0.00384
-6.75782,1.28686,-0.82218,-1.90226,-0.42028,1.85693,0.00384
-6.75901,1.28726,-0.82192,-1.90270,-0.42010,1.85654,0.00384
-6.76019,1.28764,-0.82166,-1.90314,-0.41993,1.85614,0.00385
-6.76138,1.28803,-0.82141,-1.90357,-0.41976,1.85575,0.00385
-6.76257,1.28842,-0.82116,-1.90399,-0.41959,1.85536,0.00385
-6.76376,1.28880,-0.82091,-1.90440,-0.41943,1.85497,0.00385
-6.76495,1.28919,-0.82066,-1.90481,-0.41927,1.85458,0.00385
-6.76614,1.28957,-0.82042,-1.90521,-0.41912,1.85420,0.00385
-6.76733,1.28995,-0.82018,-1.90560,-0.41897,1.85381,0.00385
-6.76852,1.29033,-0.81995,-1.90598,-0.41882,1.85343,0.00386
-6.76971,1.29044,-0.81987,-1.90612,-0.41877,1.85331,0.00386
-6.77090,1.29082,-0.81958,-1.90666,-0.41852,1.85293,0.00386
-6.77208,1.29119,-0.81930,-1.90719,-0.41828,1.85255,0.00386
-6.77327,1.29156,-0.81901,-1.90771,-0.41804,1.85218,0.00386
-6.77446,1.29193,-0.81874,-1.90822,-0.41781,1.85180,0.00386
-6.77565,1.29230,-0.81846,-1.90873,-0.41759,1.85142,0.00386
-6.77684,1.29267,-0.81819,-1.90922,-0.41737,1.85105,0.00387
-6.77803,1.29304,-0.81792,-1.90971,-0.41715,1.85068,0.00387
-6.77922,1.29341,-0.81766,-1.91019,-0.41694,1.85031,0.00387
-6.78041,1.29377,-0.81740,-1.91066,-0.41673,1.84994,0.00387
-6.78160,1.29413,-0.81714,-1.91113,-0.41653,1.84957,0.00387
-6.78278,1.29449,-0.81688,-1.91158,-0.41634,1.84921,0.00387
-6.78397,1.29485,-0.81663,-1.91203,-0.41614,1.84884,0.00387
-6.78516,1.29521,-0.81638,-1.91247,-0.41596,1.84848,0.00388
-6.78635,1.29557,-0.81613,-1.91290,-0.41577,1.84812,0.00388
-6.78754,1.29593,-0.81589,-1.91333,-0.41559,1.84776,0.00388
-6.78873,1.29628,-0.81565,-1.91375,-0.41542,1.84740,0.00388
-6.78992,1.29663,-0.81541,-1.91416,-0.41525,1.84704,0.00388
-6.79111,1.29691,-0.81522,-1.91451,-0.41510,1.84676,0.00388
-6.79230,1.29724,-0.81491,-1.91516,-0.41476,1.84642,0.00389
-6.79348,1.29757,-0.81460,-1.91580,-0.41443,1.84609,0.00389
-6.79467,1.29789,-0.81430,-1.91643,-0.41411,1.84576,0.00389
-6.79586,1.29822,-0.81400,-1.91705,-0.41379,1.84543,0.00389
-6.79705,1.29854,-0.81371,-1.91766,-0.41348,1.84510,0.00389
-6.79824,1.29886,-0.81342,-1.91825,-0.41317,1.84477,0.00389
-6.79943,1.29918,-0.81314,-1.91884,-0.41288,1.84444,0.00390
-6.80062,1.29950,-0.81286,-1.91942,-0.41258,1.84412,0.00390
-6.80181,1.29982,-0.81258,-1.91999,-0.41230,1.84379,0.00390
-6.80300,1.30014,-0.81230,-1.92054,-0.41202,1.84347,0.00390
-6.80418,1.30045,-0.81203,-1.92109,-0.41174,1.84315,0.00390
-6.80537,1.30077,-0.81177,-1.92163,-0.41148,1.84283,0.00390
-6.80656,1.30108,-0.81150,-1.92216,-0.41121,1.84251,0.00391
-6.80775,1.30139,-0.81124,-1.92268,-0.41096,1.84219,0.00391
-6.80894,1.30170,-0.81099,-1.92319,-0.41071,1.84187,0.00391
-6.81013,1.30201,-0.81073,-1.92369,-0.41046,1.84156,0.00391
-6.81132,1.30232,-0.81048,-1.92419,-0.41022,1.84124,0.00391
-6.81251,1.30263,-0.81023,-1.92467,-0.40998,1.84093,0.00391
-6.81370,1.30294,-0.80999,-1.92515,-0.40975,1.84062,0.00392
-6.81489,1.30324,-0.80975,-1.92562,-0.40953,1.84031,0.00392
-6.81607,1.30355,-0.80951,-1.92608,-0.40930,1.84000,0.00392
-6.81726,1.30385,-0.80928,-1.92654,-0.40909,1.83969,0.00392
-6.81845,1.30415,-0.80904,-1.92698,-0.40888,1.83939,0.00392
-6.81964,1.30433,-0.80890,-1.92726,-0.40874,1.83920,0.00392
-6.82083,1.30463,-0.80862,-1.92786,-0.40843,1.83890,0.00393
-6.82202,1.30493,-0.80834,-1.92844,-0.40813,1.83859,0.00393
-6.82321,1.30523,-0.80806,-1.92902,-0.40783,1.83829,0.00393
-6.82440,1.30552,-0.80779,-1.92958,-0.40754,1.83799,0.00393
-6.82559,1.30582,-0.80752,-1.93014,-0.40726,1.83769,0.00393
-6.82677,1.30611,-0.80726,-1.93068,-0.40698,1.83739,0.00393
-6.82796,1.30640,-0.80700,-1.93122,-0.40671,1.83709,0.00394
-6.82915,1.30670,-0.80674,-1.93175,-0.40644,1.83679,0.00394
-6.83034,1.30699,-0.80648,-1.93227,-0.40618,1.83650,0.00394
-6.83153,1.30728,-0.80623,-1.93278,-0.40592,1.83620,0.00394
-6.83272,1.30756,-0.80599,-1.93328,-0.40567,1.83591,0.00394
-6.83391,1.30785,-0.80574,-1.93377,-0.40543,1.83562,0.00395
-6.83510,1.30814,-0.80550,-1.93425,-0.40519,1.83533,0.00395
-6.83629,1.30842,-0.80526,-1.93473,-0.40495,1.83504,0.00395
-6.83747,1.30871,-0.80503,-1.93520,-0.40472,1.83475,0.00395
-6.83866,1.30899,-0.80479,-1.93566,-0.40449,1.83446,0.00395
-6.83985,1.30927,-0.80456,-1.93612,-0.40426,1.83417,0.00396
-6.84104,1.30953,-0.80429,-1.93673,-0.40393,1.83391,0.00396
-6.84223,1.30979,-0.80402,-1.93732,-0.40361,1.83364,0.00396
-6.84342,1.31005,-0.80376,-1.93790,-0.40329,1.83338,0.00396
-6.84461,1.31030,-0.80350,-1.93848,-0.40298,1.83312,0.00396
-6.84580,1.31056,-0.80324,-1.93904,-0.40268,1.83286,0.00396
-6.84699,1.31081,-0.80299,-1.93959,-0.40238,1.83259,0.00397
-6.84818,1.31107,-0.80274,-1.94014,-0.40209,1.83233,0.00397
-6.84936,1.31132,-0.80250,-1.94067,-0.40180,1.83208,0.00397
-6.85055,1.31157,-0.80225,-1.94119,-0.40152,1.83182,0.00397
-6.85174,1.31182,-0.80201,-1.94171,-0.40125,1.83156,0.00397
-6.85293,1.31207,-0.80178,-1.94222,-0.40098,1.83131,0.00398
-6.85412,1.31232,-0.80154,-1.94272,-0.40071,1.83105,0.00398
-6.85531,1.31257,-0.80131,-1.94321,-0.40046,1.83080,0.00398
-6.85650,1.31282,-0.80109,-1.94369,-0.40020,1.83054,0.00398
-6.85769,1.31306,-0.80086,-1.94416,-0.39996,1.83029,0.00398
-6.85888,1.31316,-0.80077,-1.94436,-0.39985,1.83019,0.00398
-6.86006,1.31341,-0.80050,-1.94496,-0.39952,1.82994,0.00398
-6.86125,1.31365,-0.80024,-1.94555,-0.39919,1.82969,0.00399
-6.86244,1.31390,-0.79998,-1.94613,-0.39888,1.82944,0.00399
-6.86363,1.31414,-0.79973,-1.94670,-0.39856,1.82920,0.00399
-6.86482,1.31438,-0.79947,-1.94726,-0.39826,1.82895,0.00399
-6.86601,1.31462,-0.79923,-1.94781,-0.39796,1.82870,0.00399
-6.86720,1.31486,-0.79898,-1.94835,-0.39767,1.82846,0.00400
-6.86839,1.31510,-0.79874,-1.94888,-0.39738,1.82821,0.00400
-6.86958,1.31534,-0.79850,-1.94940,-0.39710,1.82797,0.00400
-6.87076,1.31557,-0.79827,-1.94991,-0.39682,1.82773,0.00400
-6.87195,1.31581,-0.79803,-1.95042,-0.39655,1.82749,0.00400
-6.87314,1.31605,-0.79780,-1.95091,-0.39629,1.82725,0.00401
-6.87433,1.31628,-0.79758,-1.95140,-0.39603,1.82701,0.00401
-6.87552,1.31651,-0.79736,-1.95188,-0.39577,1.82677,0.00401
-6.87671,1.31661,-0.79726,-1.95208,-0.39566,1.82667,0.00401
-6.87790,1.31684,-0.79701,-1.95266,-0.39534,1.82643,0.00401
-6.87909,1.31707,-0.79675,-1.95323,-0.39503,1.82620,0.00401
-6.88028,1.31730,-0.79650,-1.95380,-0.39472,1.82596,0.00402
-6.88146,1.31753,-0.79625,-1.95435,-0.39441,1.82573,0.00402
-6.88265,1.31776,-0.79601,-1.95489,-0.39411,1.82549,0.00402
-6.88384,1.31799,-0.79577,-1.95542,-0.39382,1.82526,0.00402
-6.88503,1.31822,-0.79553,-1.95595,-0.39354,1.82503,0.00402
-6.88622,1.31844,-0.79530,-1.95646,-0.39326,1.82479,0.00403
-6.88741,1.31867,-0.79507,-1.95697,-0.39298,1.82456,0.00403
-6.88860,1.31889,-0.79484,-1.95747,-0.39271,1.82433,0.00403
-6.88979,1.31912,-0.79462,-1.95795,-0.39245,1.82411,0.00403
-6.89098,1.31934,-0.79440,-1.95844,-0.39219,1.82388,0.00403
-6.89217,1.31939,-0.79435,-1.95854,-0.39214,1.82383,0.00403
-6.89335,1.31961,-0.79411,-1.95908,-0.39184,1.82360,0.00404
-6.89454,1.31983,-0.79387,-1.95961,-0.39155,1.82338,0.00404
-6.89573,1.32005,-0.79364,-1.96013,-0.39126,1.82315,0.00404
-6.89692,1.32027,-0.79341,-1.96064,-0.39098,1.82293,0.00404
-6.89811,1.32049,-0.79318,-1.96114,-0.39071,1.82270,0.00404
-6.89930,1.32071,-0.79296,-1.96164,-0.39044,1.82248,0.00404
-6.90049,1.32093,-0.79273,-1.96212,-0.39018,1.82226,0.00405
-6.90168,1.32103,-0.79262,-1.96237,-0.39004,1.82215,0.00405
-6.90287,1.32125,-0.79238,-1.96291,-0.38974,1.82193,0.00405
-6.90405,1.32147,-0.79215,-1.96344,-0.38945,1.82171,0.00405
-6.90524,1.32168,-0.79191,-1.96397,-0.38916,1.82149,0.00405
-6.90643,1.32189,-0.79168,-1.96448,-0.38888,1.82127,0.00405
-6.90762,1.32211,-0.79145,-1.96499,-0.38860,1.82105,0.00406
-6.90881,1.32232,-0.79123,-1.96548,-0.38833,1.82083,0.00406
-6.91000,1.32253,-0.79101,-1.96597,-0.38806,1.82062,0.00406
-6.91119,1.32266,-0.79088,-1.96627,-0.38790,1.82049,0.00406
-6.91238,1.32287,-0.79065,-1.96679,-0.38761,1.82027,0.00406
-6.91357,1.32308,-0.79042,-1.96730,-0.38733,1.82006,0.00407
-6.91475,1.32329,-0.79019,-1.96780,-0.38705,1.81984,0.00407
-6.91594,1.32350,-0.78997,-1.96829,-0.38678,1.81963,0.00407
-6.91713,1.32370,-0.78975,-1.96878,-0.38652,1.81942,0.00407
-6.91832,1.32373,-0.78973,-1.96883,-0.38649,1.81940,0.00407
-6.91951,1.32393,-0.78951,-1.96933,-0.38621,1.81919,0.00407
-6.92070,1.32414,-0.78929,-1.96982,-0.38594,1.81898,0.00407
-6.92189,1.32428,-0.78913,-1.97016,-0.38576,1.81883,0.00408
-6.92308,1.32449,-0.78891,-1.97066,-0.38548,1.81862,0.00408
-6.92427,1.32469,-0.78869,-1.97115,-0.38521,1.81841,0.00408
-6.92545,1.32481,-0.78856,-1.97144,-0.38505,1.81829,0.00408
-6.92664,1.32502,-0.78834,-1.97194,-0.38477,1.81808,0.00408
-6.92783,1.32522,-0.78812,-1.97243,-0.38450,1.81787,0.00408
-6.92902,1.32534,-0.78799,-1.97273,-0.38434,1.81775,0.00409
-6.93021,1.32554,-0.78776,-1.97323,-0.38406,1.81754,0.00409
-6.93140,1.32574,-0.78755,-1.97372,-0.38379,1.81734,0.00409
-6.93259,1.32586,-0.78742,-1.97401,-0.38363,1.81722,0.00409
-6.93378,1.32596,-0.78728,-1.97436,-0.38341,1.81712,0.00409
-6.93497,1.32590,-0.78728,-1.97446,-0.38331,1.81717,0.00409
-6.93616,1.32529,-0.78745,-1.97497,-0.38264,1.81774,0.00409
-6.93734,1.32467,-0.78761,-1.97547,-0.38198,1.81831,0.00409
-6.93853,1.32406,-0.78778,-1.97596,-0.38133,1.81888,0.00409
-6.93972,1.32345,-0.78794,-1.97644,-0.38069,1.81945,0.00409
-6.94091,1.32284,-0.78811,-1.97691,-0.38005,1.82002,0.00408
-6.94210,1.32223,-0.78828,-1.97737,-0.37942,1.82059,0.00408
-6.94329,1.32163,-0.78845,-1.97782,-0.37880,1.82117,0.00408
-6.94448,1.32102,-0.78862,-1.97827,-0.37819,1.82174,0.00408
-6.94567,1.32041,-0.78879,-1.97870,-0.37759,1.82231,0.00408
-6.94686,1.31981,-0.78896,-1.97913,-0.37699,1.82288,0.00408
-6.94804,1.31920,-0.78914,-1.97955,-0.37640,1.82345,0.00408
-6.94923,1.31860,-0.78931,-1.97996,-0.37582,1.82401,0.00408
-6.95042,1.31800,-0.78948,-1.98036,-0.37524,1.82458,0.00407
-6.95161,1.31740,-0.78966,-1.98076,-0.37468,1.82515,0.00407
-6.95280,1.31680,-0.78983,-1.98114,-0.37411,1.82572,0.00407
-6.95399,1.31620,-0.79001,-1.98152,-0.37356,1.82629,0.00407
-6.95518,1.31561,-0.79018,-1.98189,-0.37301,1.82685,0.00407
-6.95637,1.31501,-0.79036,-1.98226,-0.37247,1.82742,0.00407
-6.95756,1.31442,-0.79053,-1.98262,-0.37194,1.82799,0.00407
-6.95874,1.31382,-0.79071,-1.98297,-0.37141,1.82855,0.00407
-6.95993,1.31323,-0.79089,-1.98331,-0.37089,1.82912,0.00407
-6.96112,1.31264,-0.79107,-1.98365,-0.37037,1.82968,0.00407
-6.96231,1.31205,-0.79124,-1.98398,-0.36986,1.83024,0.00406
-6.96350,1.31146,-0.79142,-1.98430,-0.36936,1.83081,0.00406
-6.96469,1.31087,-0.79160,-1.98462,-0.36886,1.83137,0.00406
-6.96588,1.31029,-0.79178,-1.98493,-0.36837,1.83193,0.00406
-6.96707,1.30970,-0.79196,-1.98523,-0.36789,1.83249,0.00406
-6.96826,1.30912,-0.79214,-1.98553,-0.36741,1.83305,0.00406
-6.96944,1.30854,-0.79232,-1.98583,-0.36693,1.83361,0.00406
-6.97063,1.30796,-0.79250,-1.98611,-0.36647,1.83417,0.00406
-6.97182,1.30738,-0.79268,-1.98640,-0.36600,1.83473,0.00406
-6.97301,1.30680,-0.79286,-1.98667,-0.36555,1.83528,0.00406
-6.97420,1.30622,-0.79304,-1.98694,-0.36509,1.83584,0.00405
-6.97539,1.30565,-0.79322,-1.98721,-0.36465,1.83639,0.00405
-6.97658,1.30507,-0.79340,-1.98747,-0.36420,1.83695,0.00405
-6.97777,1.30450,-0.79358,-1.98772,-0.36377,1.83750,0.00405
-6.97896,1.30393,-0.79376,-1.98797,-0.36333,1.83805,0.00405
-6.98015,1.30336,-0.79394,-1.98821,-0.36291,1.83860,0.00405
-6.98133,1.30279,-0.79412,-1.98845,-0.36248,1.83915,0.00405
-6.98252,1.30222,-0.79430,-1.98869,-0.36207,1.83970,0.00405
-6.98371,1.30166,-0.79448,-1.98892,-0.36165,1.84025,0.00405
-6.98490,1.30109,-0.79466,-1.98914,-0.36125,1.84080,0.00405
-6.98609,1.30053,-0.79484,-1.98936,-0.36084,1.84135,0.00405
-6.98728,1.29997,-0.79503,-1.98958,-0.36044,1.84189,0.00405
-6.98847,1.29941,-0.79521,-1.98979,-0.36005,1.84244,0.00405
-6.98966,1.29885,-0.79539,-1.99000,-0.35966,1.84298,0.00404
-6.99085,1.29829,-0.79557,-1.99020,-0.35927,1.84352,0.00404
-6.99203,1.29774,-0.79575,-1.99040,-0.35889,1.84406,0.00404
-6.99322,1.29718,-0.79593,-1.99059,-0.35851,1.84460,0.00404
-6.99441,1.29663,-0.79611,-1.99078,-0.35814,1.84514,0.00404
-6.99560,1.29608,-0.79629,-1.99097,-0.35777,1.84568,0.00404
-6.99679,1.29553,-0.79647,-1.99115,-0.35740,1.84621,0.00404
-6.99798,1.29498,-0.79665,-1.99133,-0.35704,1.84675,0.00404
-6.99917,1.29443,-0.79683,-1.99150,-0.35668,1.84728,0.00404
-7.00036,1.29389,-0.79701,-1.99167,-0.35633,1.84782,0.00404
-7.00155,1.29334,-0.79719,-1.99184,-0.35598,1.84835,0.00404
-7.00273,1.29280,-0.79737,-1.99201,-0.35563,1.84888,0.00404
-7.00392,1.29226,-0.79755,-1.99217,-0.35529,1.84941,0.00404
-7.00511,1.29172,-0.79773,-1.99232,-0.35495,1.84994,0.00404
-7.00630,1.29118,-0.79790,-1.99248,-0.35461,1.85046,0.00404
-7.00749,1.29065,-0.79808,-1.99263,-0.35428,1.85099,0.00403
-7.00868,1.29011,-0.79826,-1.99277,-0.35395,1.85151,0.00403
-7.00987,1.28958,-0.79844,-1.99292,-0.35363,1.85204,0.00403
-7.01106,1.28905,-0.79862,-1.99306,-0.35330,1.85256,0.00403
-7.01225,1.28852,-0.79879,-1.99320,-0.35298,1.85308,0.00403
-7.01343,1.28799,-0.79897,-1.99333,-0.35267,1.85360,0.00403
-7.01462,1.28746,-0.79915,-1.99346,-0.35236,1.85412,0.00403
-7.01581,1.28693,-0.79933,-1.99359,-0.35205,1.85463,0.00403
-7.01700,1.28641,-0.79950,-1.99372,-0.35174,1.85515,0.00403
-7.01819,1.28589,-0.79968,-1.99384,-0.35144,1.85566,0.00403
-7.01938,1.28537,-0.79985,-1.99396,-0.35114,1.85618,0.00403
-7.02057,1.28485,-0.80003,-1.99408,-0.35084,1.85669,0.00403
-7.02176,1.28433,-0.80020,-1.99420,-0.35055,1.85720,0.00403
-7.02295,1.28381,-0.80038,-1.99431,-0.35025,1.85771,0.00403
-7.02414,1.28330,-0.80055,-1.99442,-0.34997,1.85821,0.00403
-7.02532,1.28279,-0.80073,-1.99453,-0.34968,1.85872,0.00403
-7.02651,1.28227,-0.80090,-1.99463,-0.34940,1.85922,0.00403
-7.02770,1.28176,-0.80108,-1.99473,-0.34912,1.85973,0.00403
-7.02889,1.28126,-0.80125,-1.99483,-0.34884,1.86023,0.00402
-7.03008,1.28075,-0.80142,-1.99493,-0.34857,1.86073,0.00402
-7.03127,1.28024,-0.80159,-1.99503,-0.34829,1.86123,0.00402
-7.03246,1.28006,-0.80166,-1.99505,-0.34820,1.86141,0.00402
-7.03365,1.27925,-0.80200,-1.99513,-0.34778,1.86220,0.00402
-7.03484,1.27843,-0.80233,-1.99521,-0.34737,1.86300,0.00402
-7.03602,1.27762,-0.80266,-1.99529,-0.34696,1.86379,0.00402
-7.03721,1.27682,-0.80299,-1.99536,-0.34655,1.86458,0.00402
-7.03840,1.27601,-0.80332,-1.99543,-0.34615,1.86537,0.00401
-7.03959,1.27521,-0.80365,-1.99550,-0.34575,1.86615,0.00401
-7.04078,1.27440,-0.80398,-1.99557,-0.34535,1.86694,0.00401
-7.04197,1.27361,-0.80430,-1.99563,-0.34496,1.86772,0.00401
-7.04316,1.27281,-0.80463,-1.99569,-0.34457,1.86850,0.00401
-7.04435,1.27201,-0.80495,-1.99575,-0.34418,1.86928,0.00400
-7.04554,1.27122,-0.80527,-1.99581,-0.34380,1.87006,0.00400
-7.04672,1.27043,-0.80559,-1.99587,-0.34342,1.87084,0.00400
-7.04791,1.26964,-0.80591,-1.99592,-0.34304,1.87161,0.00400
-7.04910,1.26886,-0.80623,-1.99597,-0.34267,1.87238,0.00400
-7.05029,1.26808,-0.80655,-1.99602,-0.34230,1.87315,0.00400
-7.05148,1.26729,-0.80686,-1.99607,-0.34193,1.87392,0.00399
-7.05267,1.26652,-0.80718,-1.99612,-0.34157,1.87468,0.00399
-7.05386,1.26574,-0.80749,-1.99616,-0.34120,1.87545,0.00399
-7.05505,1.26497,-0.80780,-1.99620,-0.34085,1.87621,0.00399
-7.05624,1.26420,-0.80811,-1.99624,-0.34049,1.87697,0.00399
-7.05742,1.26343,-0.80842,-1.99628,-0.34014,1.87773,0.00399
-7.05861,1.26266,-0.80873,-1.99632,-0.33979,1.87848,0.00398
-7.05980,1.26190,-0.80904,-1.99636,-0.33944,1.87923,0.00398
-7.06099,1.26114,-0.80934,-1.99639,-0.33910,1.87999,0.00398
-7.06218,1.26038,-0.80965,-1.99642,-0.33876,1.88073,0.00398
-7.06337,1.25962,-0.80995,-1.99646,-0.33842,1.88148,0.00398
-7.06456,1.25887,-0.81025,-1.99649,-0.33808,1.88223,0.00398
-7.06575,1.25811,-0.81055,-1.99651,-0.33775,1.88297,0.00397
-7.06694,1.25737,-0.81085,-1.99654,-0.33742,1.88371,0.00397
-7.06813,1.25662,-0.81115,-1.99657,-0.33709,1.88445,0.00397
-7.06931,1.25587,-0.81145,-1.99659,-0.33677,1.88518,0.00397
-7.07050,1.25513,-0.81174,-1.99661,-0.33644,1.88592,0.00397
-7.07169,1.25439,-0.81204,-1.99664,-0.33612,1.88665,0.00397
-7.07288,1.25366,-0.81233,-1.99666,-0.33580,1.88738,0.00397
-7.07407,1.25292,-0.81262,-1.99667,-0.33549,1.88810,0.00396
-7.07526,1.25219,-0.81292,-1.99669,-0.33518,1.88883,0.00396
-7.07645,1.25146,-0.81321,-1.99671,-0.33487,1.88955,0.00396
-7.07764,1.25074,-0.81349,-1.99672,-0.33456,1.89027,0.00396
-7.07883,1.25001,-0.81378,-1.99674,-0.33425,1.89099,0.00396
-7.08001,1.24929,-0.81407,-1.99675,-0.33395,1.89170,0.00396
-7.08120,1.24857,-0.81435,-1.99676,-0.33365,1.89242,0.00396
-7.08239,1.24786,-0.81464,-1.99677,-0.33335,1.89313,0.00395
-7.08358,1.24714,-0.81492,-1.99678,-0.33305,1.89383,0.00395
-7.08477,1.24643,-0.81520,-1.99679,-0.33276,1.89454,0.00395
-7.08596,1.24572,-0.81548,-1.99680,-0.33247,1.89524,0.00395
-7.08715,1.24502,-0.81576,-1.99681,-0.33218,1.89594,0.00395
-7.08834,1.24431,-0.81604,-1.99681,-0.33189,1.89664,0.00395
-7.08953,1.24361,-0.81631,-1.99682,-0.33160,1.89734,0.00395
-7.09071,1.24291,-0.81659,-1.99682,-0.33132,1.89803,0.00395
-7.09190,1.24222,-0.81686,-1.99682,-0.33104,1.89873,0.00394
-7.09309,1.24152,-0.81714,-1.99683,-0.33076,1.89941,0.00394
-7.09428,1.24083,-0.81741,-1.99683,-0.33048,1.90010,0.00394
-7.09547,1.24015,-0.81768,-1.99683,-0.33021,1.90079,0.00394
-7.09666,1.23946,-0.81795,-1.99683,-0.32993,1.90147,0.00394
-7.09785,1.23878,-0.81822,-1.99682,-0.32966,1.90215,0.00394
-7.09904,1.23810,-0.81848,-1.99682,-0.32939,1.90282,0.00394
-7.10023,1.23742,-0.81875,-1.99682,-0.32913,1.90350,0.00394
-7.10141,1.23674,-0.81901,-1.99682,-0.32886,1.90417,0.00393
-7.10260,1.23607,-0.81928,-1.99681,-0.32860,1.90484,0.00393
-7.10379,1.23540,-0.81954,-1.99681,-0.32834,1.90551,0.00393
-7.10498,1.23473,-0.81980,-1.99680,-0.32808,1.90617,0.00393
-7.10617,1.23407,-0.82006,-1.99679,-0.32782,1.90684,0.00393
-7.10736,1.23341,-0.82032,-1.99679,-0.32757,1.90750,0.00393
-7.10855,1.23275,-0.82058,-1.99678,-0.32731,1.90815,0.00393
-7.10974,1.23209,-0.82083,-1.99677,-0.32706,1.90881,0.00393
-7.11093,1.23144,-0.82109,-1.99676,-0.32681,1.90946,0.00392
-7.11212,1.23079,-0.82134,-1.99675,-0.32656,1.91011,0.00392
-7.11330,1.23014,-0.82160,-1.99674,-0.32631,1.91076,0.00392
-7.11449,1.22949,-0.82185,-1.99673,-0.32607,1.91140,0.00392
-7.11568,1.22885,-0.82210,-1.99671,-0.32583,1.91205,0.00392
-7.11687,1.22821,-0.82235,-1.99670,-0.32559,1.91269,0.00392
-7.11806,1.22757,-0.82260,-1.99669,-0.32535,1.91332,0.00392
-7.11925,1.22693,-0.82285,-1.99668,-0.32511,1.91396,0.00392
-7.12044,1.22630,-0.82309,-1.99666,-0.32487,1.91459,0.00392
-7.12163,1.22567,-0.82334,-1.99665,-0.32464,1.91522,0.00391
-7.12282,1.22504,-0.82358,-1.99663,-0.32440,1.91585,0.00391
-7.12400,1.22441,-0.82382,-1.99662,-0.32417,1.91647,0.00391
-7.12519,1.22379,-0.82407,-1.99660,-0.32394,1.91710,0.00391
-7.12638,1.22317,-0.82431,-1.99658,-0.32371,1.91772,0.00391
-7.12757,1.22255,-0.82455,-1.99657,-0.32349,1.91833,0.00391
-7.12876,1.22194,-0.82478,-1.99655,-0.32326,1.91895,0.00391
-7.12995,1.22132,-0.82502,-1.99653,-0.32304,1.91956,0.00391
-7.13114,1.22071,-0.82526,-1.99651,-0.32282,1.92017,0.00391
-7.13233,1.22011,-0.82549,-1.99650,-0.32260,1.92078,0.00391
-7.13352,1.21950,-0.82573,-1.99648,-0.32238,1.92139,0.00390
-7.13470,1.21890,-0.82596,-1.99646,-0.32216,1.92199,0.00390
-7.13589,1.21830,-0.82619,-1.99644,-0.32195,1.92259,0.00390
-7.13708,1.21770,-0.82642,-1.99642,-0.32173,1.92319,0.00390
-7.13827,1.21711,-0.82665,-1.99640,-0.32152,1.92378,0.00390
-7.13946,1.21651,-0.82688,-1.99638,-0.32131,1.92437,0.00390
-7.14065,1.21592,-0.82711,-1.99635,-0.32110,1.92496,0.00390
-7.14184,1.21534,-0.82733,-1.99633,-0.32089,1.92555,0.00390
-7.14303,1.21475,-0.82756,-1.99631,-0.32068,1.92614,0.00390
-7.14422,1.21417,-0.82778,-1.99629,-0.32047,1.92672,0.00390
-7.14540,1.21359,-0.82801,-1.99627,-0.32027,1.92730,0.00389
-7.14659,1.21301,-0.82823,-1.99624,-0.32007,1.92788,0.00389
-7.14778,1.21244,-0.82845,-1.99622,-0.31987,1.92845,0.00389
-7.14897,1.21202,-0.82861,-1.99620,-0.31972,1.92887,0.00389
-7.15016,1.21129,-0.82892,-1.99618,-0.31943,1.92960,0.00389
-7.15135,1.21056,-0.82923,-1.99616,-0.31914,1.93033,0.00389
-7.15254,1.20983,-0.82953,-1.99613,-0.31886,1.93105,0.00389
-7.15373,1.20910,-0.82984,-1.99611,-0.31858,1.93177,0.00388
-7.15492,1.20838,-0.83014,-1.99608,-0.31830,1.93249,0.00388
-7.15611,1.20766,-0.83044,-1.99605,-0.31802,1.93320,0.00388
-7.15729,1.20695,-0.83074,-1.99603,-0.31774,1.93391,0.00388
-7.15848,1.20624,-0.83104,-1.99600,-0.31747,1.93462,0.00388
-7.15967,1.20553,-0.83133,-1.99597,-0.31720,1.93533,0.00388
-7.16086,1.20482,-0.83163,-1.99594,-0.31693,1.93603,0.00388
-7.16205,1.20412,-0.83192,-1.99592,-0.31666,1.93673,0.00387
-7.16324,1.20342,-0.83221,-1.99589,-0.31639,1.93743,0.00387
-7.16443,1.20272,-0.83250,-1.99586,-0.31613,1.93812,0.00387
-7.16562,1.20202,-0.83279,-1.99583,-0.31587,1.93881,0.00387
-7.16681,1.20133,-0.83308,-1.99580,-0.31561,1.93950,0.00387
-7.16799,1.20064,-0.83336,-1.99577,-0.31535,1.94019,0.00387
-7.16918,1.19996,-0.83364,-1.99574,-0.31510,1.94087,0.00386
-7.17037,1.19928,-0.83393,-1.99571,-0.31484,1.94155,0.00386
-7.17156,1.19860,-0.83421,-1.99567,-0.31459,1.94223,0.00386
-7.17275,1.19792,-0.83448,-1.99564,-0.31434,1.94290,0.00386
-7.17394,1.19725,-0.83476,-1.99561,-0.31409,1.94357,0.00386
-7.17513,1.19658,-0.83504,-1.99558,-0.31385,1.94424,0.00386
-7.17632,1.19591,-0.83531,-1.99555,-0.31360,1.94491,0.00386
-7.17751,1.19525,-0.83558,-1.99551,-0.31336,1.94557,0.00385
-7.17869,1.19459,-0.83585,-1.99548,-0.31312,1.94623,0.00385
-7.17988,1.19393,-0.83612,-1.99545,-0.31288,1.94688,0.00385
-7.18107,1.19328,-0.83639,-1.99541,-0.31264,1.94754,0.00385
-7.18226,1.19263,-0.83665,-1.99538,-0.31241,1.94819,0.00385
-7.18345,1.19198,-0.83692,-1.99535,-0.31217,1.94883,0.00385
-7.18464,1.19133,-0.83718,-1.99531,-0.31194,1.94948,0.00385
-7.18583,1.19069,-0.83744,-1.99528,-0.31171,1.95012,0.00385
-7.18702,1.19005,-0.83770,-1.99524,-0.31148,1.95076,0.00384
-7.18821,1.18942,-0.83796,-1.99521,-0.31125,1.95140,0.00384
-7.18939,1.18878,-0.83822,-1.99517,-0.31103,1.95203,0.00384
-7.19058,1.18815,-0.83848,-1.99514,-0.31080,1.95266,0.00384
-7.19177,1.18753,-0.83873,-1.99510,-0.31058,1.95329,0.00384
-7.19296,1.18690,-0.83898,-1.99507,-0.31036,1.95391,0.00384
-7.19415,1.18628,-0.83923,-1.99503,-0.31014,1.95453,0.00384
-7.19534,1.18566,-0.83948,-1.99500,-0.30992,1.95515,0.00384
-7.19653,1.18505,-0.83973,-1.99496,-0.30970,1.95577,0.00383
-7.19772,1.18443,-0.83998,-1.99493,-0.30949,1.95638,0.00383
-7.19891,1.18382,-0.84023,-1.99489,-0.30928,1.95699,0.00383
-7.20010,1.18322,-0.84047,-1.99485,-0.30907,1.95760,0.00383
-7.20128,1.18261,-0.84071,-1.99482,-0.30886,1.95820,0.00383
-7.20247,1.18201,-0.84095,-1.99478,-0.30865,1.95880,0.00383
-7.20366,1.18142,-0.84119,-1.99474,-0.30844,1.95940,0.00383
-7.20485,1.18082,-0.84143,-1.99471,-0.30823,1.96000,0.00383
-7.20604,1.18023,-0.84167,-1.99467,-0.30803,1.96059,0.00383
-7.20723,1.17964,-0.84191,-1.99463,-0.30783,1.96118,0.00382
-7.20842,1.17954,-0.84196,-1.99463,-0.30778,1.96128,0.00382
-7.20961,1.17847,-0.84248,-1.99454,-0.30735,1.96233,0.00382
-7.21080,1.17742,-0.84299,-1.99445,-0.30692,1.96337,0.00382
-7.21198,1.17636,-0.84351,-1.99436,-0.30649,1.96440,0.00381
-7.21317,1.17532,-0.84402,-1.99428,-0.30607,1.96544,0.00381
-7.21436,1.17427,-0.84452,-1.99419,-0.30565,1.96646,0.00381
-7.21555,1.17324,-0.84502,-1.99410,-0.30523,1.96749,0.00380
-7.21674,1.17220,-0.84552,-1.99401,-0.30482,1.96851,0.00380
-7.21793,1.17118,-0.84602,-1.99393,-0.30441,1.96952,0.00380
-7.21912,1.17015,-0.84651,-1.99384,-0.30400,1.97053,0.00379
-7.22031,1.16913,-0.84700,-1.99375,-0.30360,1.97154,0.00379
-7.22150,1.16812,-0.84748,-1.99367,-0.30320,1.97254,0.00379
-7.22268,1.16711,-0.84796,-1.99358,-0.30280,1.97354,0.00378
-7.22387,1.16611,-0.84844,-1.99349,-0.30241,1.97453,0.00378
-7.22506,1.16511,-0.84892,-1.99340,-0.30202,1.97552,0.00378
-7.22625,1.16411,-0.84939,-1.99332,-0.30163,1.97650,0.00378
-7.22744,1.16312,-0.84986,-1.99323,-0.30125,1.97748,0.00377
-7.22863,1.16214,-0.85032,-1.99314,-0.30087,1.97846,0.00377
-7.22982,1.16116,-0.85078,-1.99306,-0.30049,1.97943,0.00377
-7.23101,1.16018,-0.85124,-1.99297,-0.30012,1.98040,0.00376
-7.23220,1.15921,-0.85170,-1.99288,-0.29974,1.98136,0.00376
-7.23338,1.15825,-0.85215,-1.99280,-0.29938,1.98231,0.00376
-7.23457,1.15729,-0.85260,-1.99271,-0.29901,1.98327,0.00376
-7.23576,1.15633,-0.85305,-1.99262,-0.29865,1.98422,0.00375
-7.23695,1.15538,-0.85349,-1.99254,-0.29829,1.98516,0.00375
-7.23814,1.15444,-0.85393,-1.99245,-0.29793,1.98610,0.00375
-7.23933,1.15349,-0.85437,-1.99236,-0.29758,1.98703,0.00375
-7.24052,1.15256,-0.85480,-1.99228,-0.29722,1.98796,0.00374
-7.24171,1.15163,-0.85523,-1.99219,-0.29688,1.98889,0.00374
-7.24290,1.15070,-0.85566,-1.99211,-0.29653,1.98981,0.00374
-7.24409,1.14978,-0.85608,-1.99202,-0.29619,1.99072,0.00374
-7.24527,1.14886,-0.85651,-1.99194,-0.29585,1.99164,0.00373
-7.24646,1.14795,-0.85692,-1.99185,-0.29551,1.99254,0.00373
-7.24765,1.14704,-0.85734,-1.99177,-0.29518,1.99345,0.00373
-7.24884,1.14614,-0.85775,-1.99168,-0.29484,1.99434,0.00373
-7.25003,1.14524,-0.85816,-1.99160,-0.29451,1.99524,0.00373
-7.25122,1.14435,-0.85857,-1.99152,-0.29419,1.99612,0.00372
-7.25241,1.14346,-0.85898,-1.99143,-0.29386,1.99701,0.00372
-7.25360,1.14258,-0.85938,-1.99135,-0.29354,1.99789,0.00372
-7.25479,1.14170,-0.85978,-1.99126,-0.29322,1.99876,0.00372
-7.25597,1.14083,-0.86017,-1.99118,-0.29291,1.99963,0.00371
-7.25716,1.13996,-0.86057,-1.99110,-0.29259,2.00050,0.00371
-7.25835,1.13909,-0.86096,-1.99102,-0.29228,2.00136,0.00371
-7.25954,1.13823,-0.86134,-1.99093,-0.29197,2.00222,0.00371
-7.26073,1.13738,-0.86173,-1.99085,-0.29167,2.00307,0.00371
-7.26192,1.13653,-0.86211,-1.99077,-0.29136,2.00392,0.00370
-7.26311,1.13569,-0.86249,-1.99069,-0.29106,2.00476,0.00370
-7.26430,1.13485,-0.86287,-1.99061,-0.29076,2.00560,0.00370
-7.26549,1.13401,-0.86324,-1.99052,-0.29046,2.00643,0.00370
-7.26667,1.13318,-0.86361,-1.99044,-0.29017,2.00726,0.00370
-7.26786,1.13235,-0.86398,-1.99036,-0.28988,2.00809,0.00370
-7.26905,1.13153,-0.86435,-1.99028,-0.28959,2.00891,0.00369
-7.27024,1.13072,-0.86471,-1.99020,-0.28930,2.00972,0.00369
-7.27143,1.12990,-0.86507,-1.99012,-0.28902,2.01053,0.00369
-7.27262,1.12910,-0.86543,-1.99004,-0.28873,2.01134,0.00369
-7.27381,1.12829,-0.86579,-1.98996,-0.28845,2.01214,0.00369
-7.27500,1.12750,-0.86614,-1.98988,-0.28817,2.01294,0.00369
-7.27619,1.12670,-0.86649,-1.98981,-0.28790,2.01374,0.00368
-7.27737,1.12591,-0.86684,-1.98973,-0.28762,2.01452,0.00368
-7.27856,1.12513,-0.86719,-1.98965,-0.28735,2.01531,0.00368
-7.27975,1.12435,-0.86753,-1.98957,-0.28708,2.01609,0.00368
-7.28094,1.12357,-0.86787,-1.98949,-0.28681,2.01686,0.00368
-7.28213,1.12280,-0.86821,-1.98942,-0.28655,2.01764,0.00368
-7.28332,1.12204,-0.86854,-1.98934,-0.28629,2.01840,0.00368
-7.28451,1.12128,-0.86888,-1.98926,-0.28603,2.01916,0.00367
-7.28570,1.12052,-0.86921,-1.98919,-0.28577,2.01992,0.00367
-7.28689,1.11977,-0.86954,-1.98911,-0.28551,2.02068,0.00367
-7.28808,1.11902,-0.86986,-1.98903,-0.28525,2.02143,0.00367
-7.28926,1.11827,-0.87019,-1.98896,-0.28500,2.02217,0.00367
-7.29045,1.11754,-0.87051,-1.98888,-0.28475,2.02291,0.00367
-7.29164,1.11680,-0.87083,-1.98881,-0.28450,2.02365,0.00367
-7.29283,1.11607,-0.87115,-1.98873,-0.28425,2.02438,0.00366
-7.29402,1.11535,-0.87146,-1.98866,-0.28401,2.02511,0.00366
-7.29521,1.11462,-0.87178,-1.98859,-0.28377,2.02583,0.00366
-7.29640,1.11391,-0.87209,-1.98851,-0.28353,2.02655,0.00366
-7.29759,1.11319,-0.87239,-1.98844,-0.28329,2.02726,0.00366
-7.29878,1.11249,-0.87270,-1.98837,-0.28305,2.02797,0.00366
-7.29996,1.11178,-0.87300,-1.98830,-0.28281,2.02868,0.00366
-7.30115,1.11108,-0.87330,-1.98822,-0.28258,2.02938,0.00366
-7.30234,1.11039,-0.87360,-1.98815,-0.28235,2.03008,0.00365
-7.30353,1.10970,-0.87390,-1.98808,-0.28212,2.03077,0.00365
-7.30472,1.10901,-0.87420,-1.98801,-0.28189,2.03146,0.00365
-7.30591,1.10833,-0.87449,-1.98794,-0.28167,2.03215,0.00365
-7.30710,1.10765,-0.87478,-1.98787,-0.28144,2.03283,0.00365
-7.30829,1.10697,-0.87507,-1.98780,-0.28122,2.03350,0.00365
-7.30948,1.10630,-0.87536,-1.98773,-0.28100,2.03418,0.00365
-7.31066,1.10564,-0.87564,-1.98766,-0.28078,2.03485,0.00365
-7.31185,1.10498,-0.87592,-1.98759,-0.28056,2.03551,0.00365
-7.31304,1.10432,-0.87620,-1.98752,-0.28035,2.03617,0.00365
-7.31423,1.10367,-0.87648,-1.98745,-0.28013,2.03683,0.00364
-7.31542,1.10302,-0.87676,-1.98738,-0.27992,2.03748,0.00364
-7.31661,1.10237,-0.87703,-1.98732,-0.27971,2.03813,0.00364
-7.31780,1.10173,-0.87730,-1.98725,-0.27950,2.03877,0.00364
-7.31899,1.10109,-0.87757,-1.98718,-0.27929,2.03941,0.00364
-7.32018,1.10046,-0.87784,-1.98712,-0.27909,2.04005,0.00364
-7.32136,1.09983,-0.87811,-1.98705,-0.27888,2.04068,0.00364
-7.32255,1.09921,-0.87837,-1.98698,-0.27868,2.04131,0.00364
-7.32374,1.09873,-0.87859,-1.98693,-0.27852,2.04179,0.00364
-7.32493,1.09765,-0.87916,-1.98678,-0.27810,2.04286,0.00363
-7.32612,1.09658,-0.87972,-1.98662,-0.27769,2.04391,0.00363
-7.32731,1.09551,-0.88028,-1.98647,-0.27728,2.04497,0.00363
-7.32850,1.09446,-0.88083,-1.98632,-0.27687,2.04601,0.00362
-7.32969,1.09340,-0.88138,-1.98617,-0.27647,2.04706,0.00362
-7.33088,1.09236,-0.88193,-1.98602,-0.27607,2.04809,0.00362
-7.33207,1.09132,-0.88247,-1.98588,-0.27568,2.04912,0.00361
-7.33325,1.09029,-0.88300,-1.98573,-0.27529,2.05014,0.00361
-7.33444,1.08927,-0.88353,-1.98558,-0.27490,2.05116,0.00361
-7.33563,1.08825,-0.88406,-1.98544,-0.27452,2.05217,0.00360
-7.33682,1.08723,-0.88458,-1.98530,-0.27414,2.05317,0.00360
-7.33801,1.08623,-0.88510,-1.98515,-0.27376,2.05417,0.00360
-7.33920,1.08523,-0.88561,-1.98501,-0.27339,2.05516,0.00359
-7.34039,1.08424,-0.88612,-1.98487,-0.27302,2.05615,0.00359
-7.34158,1.08325,-0.88662,-1.98473,-0.27265,2.05713,0.00359
-7.34277,1.08227,-0.88712,-1.98459,-0.27229,2.05810,0.00359
-7.34395,1.08130,-0.88761,-1.98445,-0.27193,2.05907,0.00358
-7.34514,1.08033,-0.88810,-1.98432,-0.27157,2.06003,0.00358
-7.34633,1.07937,-0.88859,-1.98418,-0.27122,2.06099,0.00358
-7.34752,1.07841,-0.88907,-1.98405,-0.27087,2.06194,0.00358
-7.34871,1.07747,-0.88955,-1.98391,-0.27052,2.06288,0.00357
-7.34990,1.07652,-0.89002,-1.98378,-0.27018,2.06382,0.00357
-7.35109,1.07559,-0.89049,-1.98365,-0.26984,2.06475,0.00357
-7.35228,1.07466,-0.89096,-1.98352,-0.26950,2.06567,0.00357
-7.35347,1.07373,-0.89142,-1.98339,-0.26917,2.06659,0.00356
-7.35465,1.07282,-0.89188,-1.98326,-0.26884,2.06751,0.00356
-7.35584,1.07191,-0.89233,-1.98313,-0.26851,2.06842,0.00356
-7.35703,1.07100,-0.89278,-1.98300,-0.26818,2.06932,0.00356
-7.35822,1.07010,-0.89322,-1.98287,-0.26786,2.07021,0.00356
-7.35941,1.06921,-0.89366,-1.98275,-0.26754,2.07110,0.00355
-7.36060,1.06832,-0.89410,-1.98262,-0.26723,2.07199,0.00355
-7.36179,1.06744,-0.89454,-1.98250,-0.26691,2.07287,0.00355
-7.36298,1.06657,-0.89497,-1.98237,-0.26660,2.07374,0.00355
-7.36417,1.06570,-0.89539,-1.98225,-0.26630,2.07461,0.00355
-7.36535,1.06484,-0.89581,-1.98213,-0.26599,2.07547,0.00354
-7.36654,1.06398,-0.89623,-1.98201,-0.26569,2.07632,0.00354
-7.36773,1.06313,-0.89665,-1.98189,-0.26539,2.07717,0.00354
-7.36892,1.06229,-0.89706,-1.98177,-0.26510,2.07802,0.00354
-7.37011,1.06145,-0.89747,-1.98165,-0.26480,2.07885,0.00354
-7.37130,1.06061,-0.89787,-1.98153,-0.26451,2.07969,0.00353
-7.37249,1.05979,-0.89827,-1.98142,-0.26422,2.08051,0.00353
-7.37368,1.05897,-0.89867,-1.98130,-0.26394,2.08133,0.00353
-7.37487,1.05815,-0.89906,-1.98119,-0.26366,2.08215,0.00353
-7.37606,1.05734,-0.89945,-1.98107,-0.26338,2.08296,0.00353
-7.37724,1.05654,-0.89984,-1.98096,-0.26310,2.08376,0.00353
-7.37843,1.05574,-0.90022,-1.98085,-0.26282,2.08456,0.00353
-7.37962,1.05495,-0.90060,-1.98074,-0.26255,2.08536,0.00352
-7.38081,1.05416,-0.90098,-1.98063,-0.26228,2.08614,0.00352
-7.38200,1.05338,-0.90135,-1.98052,-0.26202,2.08693,0.00352
-7.38319,1.05260,-0.90172,-1.98041,-0.26175,2.08770,0.00352
-7.38438,1.05183,-0.90208,-1.98030,-0.26149,2.08847,0.00352
-7.38557,1.05107,-0.90245,-1.98019,-0.26123,2.08924,0.00352
-7.38676,1.05031,-0.90281,-1.98009,-0.26097,2.09000,0.00352
-7.38794,1.04955,-0.90316,-1.97998,-0.26072,2.09076,0.00351
-7.38913,1.04881,-0.90352,-1.97988,-0.26046,2.09151,0.00351
-7.39032,1.04806,-0.90387,-1.97977,-0.26021,2.09225,0.00351
-7.39151,1.04733,-0.90422,-1.97967,-0.25996,2.09299,0.00351
-7.39270,1.04659,-0.90456,-1.97957,-0.25972,2.09372,0.00351
-7.39389,1.04587,-0.90490,-1.97946,-0.25947,2.09445,0.00351
-7.39508,1.04515,-0.90524,-1.97936,-0.25923,2.09518,0.00351
-7.39627,1.04443,-0.90558,-1.97926,-0.25899,2.09589,0.00351
-7.39746,1.04372,-0.90591,-1.97916,-0.25876,2.09661,0.00351
-7.39864,1.04301,-0.90624,-1.97907,-0.25852,2.09732,0.00350
-7.39983,1.04231,-0.90656,-1.97897,-0.25829,2.09802,0.00350
-7.40102,1.04162,-0.90689,-1.97887,-0.25806,2.09872,0.00350
-7.40221,1.04093,-0.90721,-1.97877,-0.25783,2.09941,0.00350
-7.40340,1.04024,-0.90752,-1.97868,-0.25761,2.10010,0.00350
-7.40459,1.03956,-0.90784,-1.97858,-0.25738,2.10078,0.00350
-7.40578,1.03889,-0.90815,-1.97849,-0.25716,2.10146,0.00350
-7.40697,1.03822,-0.90846,-1.97840,-0.25694,2.10213,0.00350
-7.40816,1.03755,-0.90877,-1.97830,-0.25672,2.10280,0.00350
-7.40934,1.03689,-0.90907,-1.97821,-0.25651,2.10346,0.00350
-7.41053,1.03624,-0.90937,-1.97812,-0.25629,2.10412,0.00350
-7.41172,1.03559,-0.90967,-1.97803,-0.25608,2.10477,0.00350
-7.41291,1.03494,-0.90997,-1.97794,-0.25587,2.10542,0.00349
-7.41410,1.03430,-0.91026,-1.97785,-0.25566,2.10607,0.00349
-7.41529,1.03367,-0.91055,-1.97776,-0.25546,2.10670,0.00349
-7.41648,1.03345,-0.91066,-1.97773,-0.25538,2.10692,0.00349
-7.41767,1.03253,-0.91115,-1.97758,-0.25504,2.10783,0.00349
-7.41886,1.03162,-0.91164,-1.97742,-0.25470,2.10874,0.00349
-7.42005,1.03072,-0.91213,-1.97727,-0.25436,2.10964,0.00348
-7.42123,1.02982,-0.91261,-1.97712,-0.25402,2.11053,0.00348
-7.42242,1.02893,-0.91309,-1.97698,-0.25369,2.11141,0.00348
-7.42361,1.02805,-0.91356,-1.97683,-0.25337,2.11229,0.00348
-7.42480,1.02717,-0.91402,-1.97668,-0.25304,2.11317,0.00348
-7.42599,1.02630,-0.91448,-1.97654,-0.25272,2.11403,0.00347
-7.42718,1.02544,-0.91494,-1.97639,-0.25241,2.11489,0.00347
-7.42837,1.02458,-0.91539,-1.97625,-0.25209,2.11575,0.00347
-7.42956,1.02373,-0.91584,-1.97611,-0.25178,2.11659,0.00347
-7.43075,1.02289,-0.91629,-1.97597,-0.25148,2.11743,0.00346
-7.43193,1.02205,-0.91673,-1.97583,-0.25117,2.11827,0.00346
-7.43312,1.02122,-0.91716,-1.97570,-0.25087,2.11910,0.00346
-7.43431,1.02040,-0.91759,-1.97556,-0.25057,2.11992,0.00346
-7.43550,1.01958,-0.91802,-1.97543,-0.25028,2.12073,0.00346
-7.43669,1.01877,-0.91844,-1.97529,-0.24999,2.12154,0.00346
-7.43788,1.01796,-0.91886,-1.97516,-0.24970,2.12235,0.00345
-7.43907,1.01716,-0.91927,-1.97503,-0.24941,2.12315,0.00345
-7.44026,1.01637,-0.91968,-1.97490,-0.24913,2.12394,0.00345
-7.44145,1.01559,-0.92009,-1.97477,-0.24885,2.12472,0.00345
-7.44263,1.01480,-0.92049,-1.97464,-0.24857,2.12550,0.00345
-7.44382,1.01403,-0.92089,-1.97451,-0.24830,2.12628,0.00345
-7.44501,1.01326,-0.92128,-1.97439,-0.24803,2.12705,0.00344
-7.44620,1.01250,-0.92167,-1.97426,-0.24776,2.12781,0.00344
-7.44739,1.01174,-0.92206,-1.97414,-0.24749,2.12856,0.00344
-7.44858,1.01099,-0.92244,-1.97402,-0.24723,2.12931,0.00344
-7.44977,1.01025,-0.92282,-1.97389,-0.24697,2.13006,0.00344
-7.45096,1.00951,-0.92319,-1.97377,-0.24671,2.13080,0.00344
-7.45215,1.00878,-0.92356,-1.97366,-0.24646,2.13153,0.00344
-7.45333,1.00805,-0.92393,-1.97354,-0.24621,2.13226,0.00343
-7.45452,1.00733,-0.92429,-1.97342,-0.24596,2.13298,0.00343
-7.45571,1.00662,-0.92465,-1.97330,-0.24571,2.13370,0.00343
-7.45690,1.00591,-0.92501,-1.97319,-0.24546,2.13441,0.00343
-7.45809,1.00520,-0.92536,-1.97307,-0.24522,2.13511,0.00343
-7.45928,1.00450,-0.92571,-1.97296,-0.24498,2.13581,0.00343
-7.46047,1.00381,-0.92606,-1.97285,-0.24474,2.13651,0.00343
-7.46166,1.00312,-0.92640,-1.97274,-0.24451,2.13720,0.00343
-7.46285,1.00244,-0.92674,-1.97263,-0.24428,2.13788,0.00343
-7.46404,1.00177,-0.92708,-1.97252,-0.24405,2.13856,0.00342
-7.46522,1.00110,-0.92741,-1.97241,-0.24382,2.13923,0.00342
-7.46641,1.00043,-0.92774,-1.97230,-0.24359,2.13990,0.00342
-7.46760,0.99977,-0.92806,-1.97220,-0.24337,2.14056,0.00342
-7.46879,0.99912,-0.92839,-1.97209,-0.24315,2.14121,0.00342
-7.46998,0.99847,-0.92871,-1.97199,-0.24293,2.14187,0.00342
-7.47117,0.99782,-0.92902,-1.97188,-0.24271,2.14251,0.00342
-7.47236,0.99719,-0.92933,-1.97178,-0.24250,2.14315,0.00342
-7.47355,0.99645,-0.92972,-1.97165,-0.24224,2.14389,0.00342
-7.47474,0.99483,-0.93078,-1.97130,-0.24153,2.14548,0.00341
-7.47592,0.99323,-0.93182,-1.97095,-0.24084,2.14706,0.00340
-7.47711,0.99163,-0.93286,-1.97061,-0.24015,2.14863,0.00339
-7.47830,0.99005,-0.93388,-1.97026,-0.23948,2.15018,0.00339
-7.47949,0.98848,-0.93489,-1.96992,-0.23881,2.15173,0.00338
-7.48068,0.98693,-0.93589,-1.96958,-0.23814,2.15326,0.00337
-7.48187,0.98539,-0.93688,-1.96925,-0.23749,2.15478,0.00336
-7.48306,0.98386,-0.93786,-1.96892,-0.23684,2.15628,0.00336
-7.48425,0.98234,-0.93883,-1.96859,-0.23621,2.15778,0.00335
-7.48544,0.98084,-0.93979,-1.96826,-0.23558,2.15926,0.00334
-7.48662,0.97935,-0.94074,-1.96794,-0.23495,2.16073,0.00334
-7.48781,0.97788,-0.94167,-1.96761,-0.23434,2.16219,0.00333
-7.48900,0.97641,-0.94260,-1.96730,-0.23373,2.16363,0.00332
-7.49019,0.97496,-0.94351,-1.96698,-0.23313,2.16507,0.00332
-7.49138,0.97352,-0.94442,-1.96667,-0.23254,2.16649,0.00331
-7.49257,0.97210,-0.94531,-1.96636,-0.23195,2.16790,0.00331
-7.49376,0.97068,-0.94620,-1.96605,-0.23137,2.16930,0.00330
-7.49495,0.96928,-0.94708,-1.96574,-0.23080,2.17068,0.00330
-7.49614,0.96789,-0.94794,-1.96544,-0.23024,2.17206,0.00329
-7.49732,0.96652,-0.94880,-1.96514,-0.22968,2.17342,0.00328
-7.49851,0.96515,-0.94964,-1.96485,-0.22913,2.17477,0.00328
-7.49970,0.96380,-0.95048,-1.96455,-0.22858,2.17611,0.00327
-7.50089,0.96246,-0.95131,-1.96426,-0.22804,2.17744,0.00327
-7.50208,0.96114,-0.95213,-1.96397,-0.22751,2.17876,0.00327
-7.50327,0.95982,-0.95294,-1.96368,-0.22699,2.18006,0.00326
-7.50446,0.95852,-0.95374,-1.96340,-0.22647,2.18136,0.00326
-7.50565,0.95723,-0.95453,-1.96312,-0.22596,2.18264,0.00325
-7.50684,0.95595,-0.95531,-1.96284,-0.22545,2.18391,0.00325
-7.50803,0.95468,-0.95608,-1.96256,-0.22495,2.18517,0.00324
-7.50921,0.95342,-0.95685,-1.96229,-0.22446,2.18642,0.00324
-7.51040,0.95218,-0.95760,-1.96202,-0.22397,2.18766,0.00324
-7.51159,0.95094,-0.95835,-1.96175,-0.22349,2.18888,0.00323
-7.51278,0.94972,-0.95909,-1.96148,-0.22301,2.19010,0.00323
-7.51397,0.94851,-0.95982,-1.96122,-0.22254,2.19130,0.00323
-7.51516,0.94731,-0.96054,-1.96096,-0.22207,2.19250,0.00322
-7.51635,0.94612,-0.96126,-1.96070,-0.22162,2.19368,0.00322
-7.51754,0.94494,-0.96196,-1.96045,-0.22116,2.19485,0.00322
-7.51873,0.94378,-0.96266,-1.96019,-0.22071,2.19602,0.00321
-7.51991,0.94262,-0.96335,-1.95994,-0.22027,2.19717,0.00321
-7.52110,0.94148,-0.96403,-1.95969,-0.21983,2.19831,0.00321
-7.52229,0.94034,-0.96471,-1.95945,-0.21940,2.19944,0.00320
-7.52348,0.93922,-0.96537,-1.95920,-0.21898,2.20056,0.00320
-7.52467,0.93811,-0.96603,-1.95896,-0.21855,2.20167,0.00320
-7.52586,0.93701,-0.96668,-1.95872,-0.21814,2.20277,0.00320
-7.52705,0.93592,-0.96733,-1.95848,-0.21773,2.20386,0.00319
-7.52824,0.93484,-0.96796,-1.95825,-0.21732,2.20494,0.00319
-7.52943,0.93376,-0.96859,-1.95802,-0.21692,2.20601,0.00319
-7.53061,0.93270,-0.96922,-1.95779,-0.21652,2.20707,0.00319
-7.53180,0.93165,-0.96983,-1.95756,-0.21613,2.20812,0.00319
-7.53299,0.93061,-0.97044,-1.95733,-0.21574,2.20916,0.00318
-7.53418,0.92958,-0.97104,-1.95711,-0.21536,2.21019,0.00318
-7.53537,0.92856,-0.97163,-1.95689,-0.21498,2.21121,0.00318
-7.53656,0.92755,-0.97222,-1.95667,-0.21461,2.21222,0.00318
-7.53775,0.92655,-0.97280,-1.95645,-0.21424,2.21322,0.00318
-7.53894,0.92556,-0.97337,-1.95624,-0.21388,2.21421,0.00318
-7.54013,0.92458,-0.97394,-1.95603,-0.21352,2.21519,0.00317
-7.54131,0.92361,-0.97450,-1.95582,-0.21316,2.21617,0.00317
-7.54250,0.92264,-0.97505,-1.95561,-0.21281,2.21713,0.00317
-7.54369,0.92169,-0.97560,-1.95540,-0.21247,2.21808,0.00317
-7.54488,0.92075,-0.97614,-1.95520,-0.21212,2.21903,0.00317
-7.54607,0.91981,-0.97668,-1.95500,-0.21179,2.21997,0.00317
-7.54726,0.91888,-0.97721,-1.95480,-0.21145,2.22089,0.00317
-7.54845,0.91797,-0.97773,-1.95460,-0.21112,2.22181,0.00317
-7.54964,0.91706,-0.97824,-1.95440,-0.21080,2.22272,0.00316
-7.55083,0.91616,-0.97876,-1.95421,-0.21047,2.22362,0.00316
-7.55202,0.91527,-0.97926,-1.95402,-0.21016,2.22452,0.00316
-7.55320,0.91439,-0.97976,-1.95383,-0.20984,2.22540,0.00316
-7.55439,0.91352,-0.98025,-1.95364,-0.20953,2.22628,0.00316
-7.55558,0.91265,-0.98074,-1.95345,-0.20922,2.22714,0.00316
-7.55677,0.91180,-0.98122,-1.95327,-0.20892,2.22800,0.00316
-7.55796,0.91095,-0.98170,-1.95309,-0.20862,2.22885,0.00316
-7.55915,0.91011,-0.98217,-1.95291,-0.20833,2.22970,0.00316
-7.56034,0.90928,-0.98263,-1.95273,-0.20804,2.23053,0.00316
-7.56153,0.90846,-0.98309,-1.95255,-0.20775,2.23136,0.00316
-7.56272,0.90765,-0.98354,-1.95238,-0.20746,2.23217,0.00316
-7.56390,0.90684,-0.98399,-1.95221,-0.20718,2.23298,0.00316
-7.56509,0.90604,-0.98444,-1.95204,-0.20690,2.23378,0.00316
-7.56628,0.90525,-0.98487,-1.95187,-0.20663,2.23458,0.00316
-7.56747,0.90447,-0.98531,-1.95170,-0.20636,2.23537,0.00316
-7.56866,0.90370,-0.98574,-1.95153,-0.20609,2.23614,0.00316
-7.56985,0.90293,-0.98616,-1.95137,-0.20582,2.23691,0.00316
-7.57104,0.90217,-0.98658,-1.95121,-0.20556,2.23768,0.00316
-7.57223,0.90142,-0.98699,-1.95105,-0.20530,2.23843,0.00316
-7.57342,0.90068,-0.98740,-1.95089,-0.20505,2.23918,0.00316
-7.57460,0.89994,-0.98780,-1.95073,-0.20479,2.23992,0.00316
-7.57579,0.89921,-0.98820,-1.95058,-0.20455,2.24066,0.00316
-7.57698,0.89849,-0.98860,-1.95042,-0.20430,2.24138,0.00316
-7.57817,0.89778,-0.98899,-1.95027,-0.20406,2.24210,0.00316
-7.57936,0.89707,-0.98937,-1.95012,-0.20382,2.24282,0.00316
-7.58055,0.89637,-0.98975,-1.94997,-0.20358,2.24352,0.00316
-7.58174,0.89568,-0.99013,-1.94983,-0.20334,2.24422,0.00316
-7.58293,0.89499,-0.99050,-1.94968,-0.20311,2.24491,0.00316
-7.58412,0.89431,-0.99087,-1.94954,-0.20288,2.24559,0.00316
-7.58530,0.89364,-0.99123,-1.94939,-0.20266,2.24627,0.00316
-7.58649,0.89297,-0.99159,-1.94925,-0.20243,2.24694,0.00316
-7.58768,0.89232,-0.99194,-1.94911,-0.20221,2.24761,0.00316
-7.58887,0.89166,-0.99229,-1.94898,-0.20200,2.24826,0.00316
-7.59006,0.89102,-0.99264,-1.94884,-0.20178,2.24891,0.00316
-7.59125,0.89038,-0.99298,-1.94870,-0.20157,2.24956,0.00316
-7.59244,0.88972,-0.99334,-1.94856,-0.20134,2.25022,0.00316
-7.59363,0.88881,-0.99393,-1.94831,-0.20101,2.25113,0.00316
-7.59482,0.88790,-0.99451,-1.94806,-0.20067,2.25203,0.00316
-7.59601,0.88701,-0.99508,-1.94781,-0.20034,2.25293,0.00315
-7.59719,0.88613,-0.99565,-1.94757,-0.20002,2.25381,0.00315
-7.59838,0.88525,-0.99620,-1.94733,-0.19970,2.25468,0.00315
-7.59957,0.88439,-0.99675,-1.94709,-0.19938,2.25555,0.00315
-7.60076,0.88353,-0.99730,-1.94686,-0.19907,2.25640,0.00315
-7.60195,0.88268,-0.99783,-1.94663,-0.19876,2.25725,0.00315
-7.60314,0.88184,-0.99836,-1.94640,-0.19846,2.25809,0.00314
-7.60433,0.88101,-0.99889,-1.94617,-0.19816,2.25892,0.00314
-7.60552,0.88019,-0.99940,-1.94595,-0.19786,2.25974,0.00314
-7.60671,0.87938,-0.99991,-1.94572,-0.19757,2.26056,0.00314
-7.60789,0.87857,-1.00042,-1.94551,-0.19728,2.26136,0.00314
-7.60908,0.87778,-1.00092,-1.94529,-0.19699,2.26216,0.00314
-7.61027,0.87699,-1.00141,-1.94508,-0.19671,2.26295,0.00314
-7.61146,0.87621,-1.00189,-1.94487,-0.19643,2.26373,0.00314
-7.61265,0.87544,-1.00237,-1.94466,-0.19616,2.26450,0.00313
-7.61384,0.87467,-1.00284,-1.94445,-0.19589,2.26527,0.00313
-7.61503,0.87392,-1.00331,-1.94425,-0.19562,2.26602,0.00313
-7.61622,0.87317,-1.00377,-1.94405,-0.19535,2.26677,0.00313
-7.61741,0.87243,-1.00423,-1.94385,-0.19509,2.26752,0.00313
-7.61859,0.87170,-1.00467,-1.94365,-0.19484,2.26825,0.00313
-7.61978,0.87097,-1.00512,-1.94346,-0.19458,2.26898,0.00313
-7.62097,0.87025,-1.00556,-1.94327,-0.19433,2.26970,0.00313
-7.62216,0.86954,-1.00599,-1.94308,-0.19409,2.27041,0.00313
-7.62335,0.86884,-1.00642,-1.94289,-0.19384,2.27111,0.00313
-7.62454,0.86815,-1.00684,-1.94271,-0.19360,2.27181,0.00313
-7.62573,0.86746,-1.00725,-1.94252,-0.19336,2.27250,0.00313
-7.62692,0.86678,-1.00766,-1.94234,-0.19313,2.27318,0.00313
-7.62811,0.86611,-1.00807,-1.94216,-0.19289,2.27386,0.00313
-7.62929,0.86544,-1.00847,-1.94199,-0.19267,2.27453,0.00313
-7.63048,0.86478,-1.00887,-1.94181,-0.19244,2.27519,0.00313
-7.63167,0.86413,-1.00926,-1.94164,-0.19222,2.27584,0.00313
-7.63286,0.86349,-1.00964,-1.94147,-0.19200,2.27649,0.00313
-7.63405,0.86285,-1.01002,-1.94131,-0.19178,2.27713,0.00313
-7.63524,0.86222,-1.01040,-1.94114,-0.19156,2.27777,0.00313
-7.63643,0.86159,-1.01077,-1.94098,-0.19135,2.27840,0.00313
-7.63762,0.86097,-1.01114,-1.94081,-0.19114,2.27902,0.00313
-7.63881,0.86036,-1.01150,-1.94065,-0.19094,2.27963,0.00313
-7.64000,0.86012,-1.01166,-1.94058,-0.19084,2.27987,0.00313
-7.64118,0.85894,-1.01254,-1.94021,-0.19034,2.28104,0.00312
-7.64237,0.85777,-1.01340,-1.93984,-0.18984,2.28220,0.00312
-7.64356,0.85662,-1.01426,-1.93948,-0.18935,2.28334,0.00311
-7.64475,0.85548,-1.01510,-1.93912,-0.18887,2.28447,0.00310
-7.64594,0.85435,-1.01593,-1.93877,-0.18839,2.28559,0.00310
-7.64713,0.85323,-1.01676,-1.93841,-0.18792,2.28670,0.00309
-7.64832,0.85213,-1.01757,-1.93807,-0.18746,2.28779,0.00309
-7.64951,0.85103,-1.01837,-1.93772,-0.18700,2.28888,0.00308
-7.65070,0.84995,-1.01915,-1.93738,-0.18655,2.28995,0.00308
-7.65188,0.84889,-1.01993,-1.93705,-0.18611,2.29101,0.00307
-7.65307,0.84783,-1.02070,-1.93672,-0.18567,2.29206,0.00307
-7.65426,0.84679,-1.02146,-1.93639,-0.18524,2.29310,0.00307
-7.65545,0.84575,-1.02220,-1.93607,-0.18482,2.29412,0.00306
-7.65664,0.84473,-1.02294,-1.93575,-0.18440,2.29514,0.00306
-7.65783,0.84372,-1.02367,-1.93543,-0.18399,2.29614,0.00306
-7.65902,0.84272,-1.02438,-1.93512,-0.18358,2.29713,0.00305
-7.66021,0.84174,-1.02509,-1.93481,-0.18318,2.29812,0.00305
-7.66140,0.84076,-1.02579,-1.93451,-0.18278,2.29909,0.00305
-7.66258,0.83980,-1.02648,-1.93421,-0.18239,2.30005,0.00304
-7.66377,0.83884,-1.02716,-1.93391,-0.18201,2.30100,0.00304
-7.66496,0.83790,-1.02783,-1.93361,-0.18163,2.30194,0.00304
-7.66615,0.83697,-1.02849,-1.93332,-0.18126,2.30287,0.00303
-7.66734,0.83604,-1.02914,-1.93304,-0.18089,2.30379,0.00303
-7.66853,0.83513,-1.02978,-1.93275,-0.18053,2.30470,0.00303
-7.66972,0.83423,-1.03042,-1.93247,-0.18017,2.30560,0.00303
-7.67091,0.83334,-1.03104,-1.93220,-0.17982,2.30648,0.00302
-7.67210,0.83246,-1.03166,-1.93192,-0.17947,2.30736,0.00302
-7.67328,0.83159,-1.03227,-1.93165,-0.17913,2.30823,0.00302
-7.67447,0.83073,-1.03287,-1.93139,-0.17879,2.30909,0.00302
-7.67566,0.82988,-1.03346,-1.93112,-0.17846,2.30994,0.00302
-7.67685,0.82903,-1.03405,-1.93086,-0.17813,2.31079,0.00302
-7.67804,0.82820,-1.03462,-1.93061,-0.17781,2.31162,0.00301
-7.67923,0.82738,-1.03519,-1.93035,-0.17749,2.31244,0.00301
-7.68042,0.82657,-1.03575,-1.93010,-0.17718,2.31325,0.00301
-7.68161,0.82576,-1.03630,-1.92985,-0.17687,2.31406,0.00301
-7.68280,0.82497,-1.03685,-1.92961,-0.17656,2.31485,0.00301
-7.68399,0.82418,-1.03739,-1.92937,-0.17626,2.31564,0.00301
-7.68517,0.82340,-1.03792,-1.92913,-0.17596,2.31642,0.00301
-7.68636,0.82264,-1.03844,-1.92889,-0.17567,2.31718,0.00301
-7.68755,0.82188,-1.03896,-1.92866,-0.17538,2.31794,0.00301
-7.68874,0.82113,-1.03947,-1.92843,-0.17510,2.31870,0.00301
-7.68993,0.82038,-1.03997,-1.92820,-0.17482,2.31944,0.00300
-7.69112,0.81965,-1.04047,-1.92798,-0.17454,2.32017,0.00300
-7.69231,0.81893,-1.04096,-1.92776,-0.17427,2.32090,0.00300
-7.69350,0.81821,-1.04144,-1.92754,-0.17400,2.32162,0.00300
-7.69469,0.81750,-1.04192,-1.92733,-0.17374,2.32233,0.00300
-7.69587,0.81680,-1.04239,-1.92711,-0.17348,2.32303,0.00300
-7.69706,0.81611,-1.04285,-1.92690,-0.17322,2.32373,0.00300
-7.69825,0.81542,-1.04331,-1.92669,-0.17297,2.32441,0.00300
-7.69944,0.81475,-1.04376,-1.92649,-0.17272,2.32509,0.00300
-7.70063,0.81408,-1.04420,-1.92629,-0.17247,2.32576,0.00300
-7.70182,0.81342,-1.04464,-1.92609,-0.17223,2.32643,0.00300
-7.70301,0.81276,-1.04507,-1.92589,-0.17199,2.32708,0.00300
-7.70420,0.81212,-1.04550,-1.92569,-0.17175,2.32773,0.00300
-7.70539,0.81148,-1.04592,-1.92550,-0.17152,2.32837,0.00300
-7.70657,0.81085,-1.04634,-1.92531,-0.17129,2.32901,0.00300
-7.70776,0.81023,-1.04675,-1.92512,-0.17106,2.32963,0.00300
-7.70895,0.80961,-1.04715,-1.92494,-0.17084,2.33025,0.00300
-7.71014,0.80900,-1.04755,-1.92476,-0.17062,2.33087,0.00300
-7.71133,0.80840,-1.04794,-1.92457,-0.17040,2.33147,0.00301
-7.71252,0.80780,-1.04833,-1.92440,-0.17018,2.33207,0.00301
-7.71371,0.80721,-1.04871,-1.92422,-0.16997,2.33266,0.00301
-7.71490,0.80678,-1.04900,-1.92409,-0.16982,2.33310,0.00301
-7.71609,0.80598,-1.04959,-1.92382,-0.16949,2.33389,0.00300
-7.71727,0.80519,-1.05017,-1.92355,-0.16917,2.33468,0.00300
-7.71846,0.80442,-1.05075,-1.92329,-0.16886,2.33546,0.00300
-7.71965,0.80364,-1.05131,-1.92303,-0.16855,2.33623,0.00300
-7.72084,0.80288,-1.05187,-1.92278,-0.16824,2.33699,0.00300
-7.72203,0.80213,-1.05242,-1.92252,-0.16794,2.33774,0.00300
-7.72322,0.80139,-1.05296,-1.92228,-0.16765,2.33848,0.00299
-7.72441,0.80065,-1.05350,-1.92203,-0.16735,2.33922,0.00299
-7.72560,0.79993,-1.05402,-1.92179,-0.16707,2.33994,0.00299
-7.72679,0.79921,-1.05454,-1.92155,-0.16678,2.34066,0.00299
-7.72798,0.79850,-1.05506,-1.92131,-0.16650,2.34137,0.00299
-7.72916,0.79780,-1.05556,-1.92108,-0.16623,2.34207,0.00299
-7.73035,0.79710,-1.05606,-1.92085,-0.16596,2.34276,0.00299
-7.73154,0.79642,-1.05655,-1.92062,-0.16569,2.34345,0.00299
-7.73273,0.79574,-1.05704,-1.92039,-0.16543,2.34413,0.00299
-7.73392,0.79508,-1.05751,-1.92017,-0.16517,2.34479,0.00299
-7.73511,0.79442,-1.05799,-1.91995,-0.16491,2.34546,0.00298
-7.73630,0.79376,-1.05845,-1.91974,-0.16466,2.34611,0.00298
-7.73749,0.79312,-1.05891,-1.91952,-0.16441,2.34676,0.00298
-7.73868,0.79248,-1.05936,-1.91931,-0.16417,2.34739,0.00298
-7.73986,0.79185,-1.05980,-1.91911,-0.16393,2.34803,0.00298
-7.74105,0.79123,-1.06024,-1.91890,-0.16369,2.34865,0.00298
-7.74224,0.79061,-1.06068,-1.91870,-0.16345,2.34927,0.00298
-7.74343,0.79001,-1.06110,-1.91850,-0.16322,2.34988,0.00298
-7.74462,0.78941,-1.06152,-1.91830,-0.16300,2.35048,0.00298
-7.74581,0.78881,-1.06194,-1.91811,-0.16277,2.35107,0.00298
-7.74700,0.78823,-1.06235,-1.91791,-0.16255,2.35166,0.00298
-7.74819,0.78765,-1.06275,-1.91772,-0.16233,2.35224,0.00298
-7.74938,0.78708,-1.06315,-1.91754,-0.16212,2.35282,0.00298
-7.75056,0.78651,-1.06354,-1.91735,-0.16191,2.35339,0.00298
-7.75175,0.78642,-1.06361,-1.91732,-0.16187,2.35348,0.00298
-7.75294,0.78551,-1.06436,-1.91697,-0.16147,2.35438,0.00298
-7.75413,0.78461,-1.06509,-1.91663,-0.16108,2.35528,0.00298
-7.75532,0.78372,-1.06581,-1.91629,-0.16070,2.35616,0.00297
-7.75651,0.78284,-1.06652,-1.91596,-0.16032,2.35703,0.00297
-7.75770,0.78197,-1.06722,-1.91563,-0.15994,2.35789,0.00296
-7.75889,0.78112,-1.06791,-1.91531,-0.15958,2.35874,0.00296
-7.76008,0.78027,-1.06859,-1.91499,-0.15922,2.35958,0.00296
-7.76127,0.77944,-1.06926,-1.91467,-0.15886,2.36042,0.00295
-7.76245,0.77861,-1.06992,-1.91436,-0.15851,2.36124,0.00295
-7.76364,0.77780,-1.07057,-1.91405,-0.15817,2.36205,0.00295
-7.76483,0.77699,-1.07122,-1.91375,-0.15783,2.36285,0.00295
-7.76602,0.77620,-1.07185,-1.91345,-0.15749,2.36364,0.00294
-7.76721,0.77541,-1.07247,-1.91315,-0.15716,2.36443,0.00294
-7.76840,0.77463,-1.07309,-1.91286,-0.15684,2.36520,0.00294
-7.76959,0.77387,-1.07369,-1.91257,-0.15652,2.36596,0.00294
-7.77078,0.77311,-1.07429,-1.91229,-0.15621,2.36672,0.00293
-7.77197,0.77236,-1.07488,-1.91200,-0.15590,2.36746,0.00293
-7.77315,0.77163,-1.07545,-1.91173,-0.15559,2.36820,0.00293
-7.77434,0.77090,-1.07602,-1.91145,-0.15529,2.36893,0.00293
-7.77553,0.77018,-1.07659,-1.91118,-0.15500,2.36965,0.00293
-7.77672,0.76947,-1.07714,-1.91092,-0.15471,2.37036,0.00293
-7.77791,0.76876,-1.07769,-1.91065,-0.15442,2.37106,0.00293
-7.77910,0.76807,-1.07823,-1.91040,-0.15414,2.37175,0.00292
-7.78029,0.76738,-1.07876,-1.91014,-0.15386,2.37244,0.00292
-7.78148,0.76671,-1.07928,-1.90989,-0.15359,2.37311,0.00292
-7.78267,0.76604,-1.07979,-1.90964,-0.15332,2.37378,0.00292
-7.78385,0.76538,-1.08030,-1.90939,-0.15305,2.37444,0.00292
-7.78504,0.76473,-1.08080,-1.90915,-0.15279,2.37509,0.00292
-7.78623,0.76408,-1.08129,-1.90891,-0.15254,2.37574,0.00292
-7.78742,0.76345,-1.08178,-1.90867,-0.15228,2.37638,0.00292
-7.78861,0.76282,-1.08226,-1.90844,-0.15203,2.37700,0.00292
-7.78980,0.76220,-1.08273,-1.90821,-0.15179,2.37763,0.00292
-7.79099,0.76159,-1.08319,-1.90799,-0.15155,2.37824,0.00292
-7.79218,0.76098,-1.08365,-1.90776,-0.15131,2.37885,0.00292
-7.79337,0.76038,-1.08410,-1.90754,-0.15107,2.37944,0.00292
-7.79455,0.75979,-1.08455,-1.90732,-0.15084,2.38004,0.00292
-7.79574,0.75921,-1.08499,-1.90711,-0.15061,2.38062,0.00292
-7.79693,0.75864,-1.08542,-1.90690,-0.15039,2.38120,0.00292
-7.79812,0.75807,-1.08584,-1.90669,-0.15017,2.38177,0.00292
-7.79931,0.75751,-1.08626,-1.90648,-0.14995,2.38233,0.00292
-7.80050,0.75695,-1.08668,-1.90628,-0.14974,2.38289,0.00292
-7.80169,0.75640,-1.08708,-1.90608,-0.14953,2.38344,0.00292
-7.80288,0.75593,-1.08745,-1.90590,-0.14934,2.38391,0.00292
-7.80407,0.75500,-1.08826,-1.90550,-0.14892,2.38483,0.00292
-7.80526,0.75408,-1.08907,-1.90511,-0.14851,2.38574,0.00291
-7.80644,0.75318,-1.08986,-1.90472,-0.14811,2.38664,0.00291
-7.80763,0.75229,-1.09064,-1.90434,-0.14771,2.38753,0.00290
-7.80882,0.75140,-1.09141,-1.90396,-0.14732,2.38840,0.00290
-7.81001,0.75053,-1.09216,-1.90359,-0.14694,2.38927,0.00289
-7.81120,0.74967,-1.09291,-1.90322,-0.14656,2.39012,0.00289
-7.81239,0.74882,-1.09364,-1.90286,-0.14619,2.39097,0.00289
-7.81358,0.74799,-1.09437,-1.90250,-0.14582,2.39180,0.00288
-7.81477,0.74716,-1.09508,-1.90215,-0.14546,2.39262,0.00288
-7.81596,0.74634,-1.09578,-1.90180,-0.14511,2.39343,0.00288
-7.81714,0.74554,-1.09647,-1.90146,-0.14476,2.39424,0.00287
-7.81833,0.74474,-1.09715,-1.90112,-0.14442,2.39503,0.00287
-7.81952,0.74396,-1.09782,-1.90078,-0.14408,2.39581,0.00287
-7.82071,0.74318,-1.09848,-1.90045,-0.14375,2.39658,0.00286
-7.82190,0.74242,-1.09913,-1.90013,-0.14342,2.39734,0.00286
-7.82309,0.74166,-1.09977,-1.89981,-0.14310,2.39810,0.00286
-7.82428,0.74092,-1.10040,-1.89949,-0.14278,2.39884,0.00286
-7.82547,0.74018,-1.10103,-1.89918,-0.14247,2.39957,0.00286
-7.82666,0.73946,-1.10164,-1.89887,-0.14216,2.40030,0.00285
-7.82784,0.73874,-1.10224,-1.89857,-0.14186,2.40101,0.00285
-7.82903,0.73803,-1.10283,-1.89827,-0.14157,2.40172,0.00285
-7.83022,0.73733,-1.10342,-1.89797,-0.14127,2.40242,0.00285
-7.83141,0.73664,-1.10400,-1.89768,-0.14099,2.40310,0.00285
-7.83260,0.73596,-1.10456,-1.89739,-0.14070,2.40378,0.00285
-7.83379,0.73529,-1.10512,-1.89711,-0.14042,2.40446,0.00285
-7.83498,0.73463,-1.10567,-1.89683,-0.14015,2.40512,0.00285
-7.83617,0.73397,-1.10621,-1.89655,-0.13988,2.40577,0.00285
-7.83736,0.73333,-1.10675,-1.89628,-0.13962,2.40642,0.00284
-7.83854,0.73269,-1.10727,-1.89601,-0.13935,2.40706,0.00284
-7.83973,0.73206,-1.10779,-1.89575,-0.13910,2.40769,0.00284
-7.84092,0.73144,-1.10830,-1.89548,-0.13884,2.40831,0.00284
-7.84211,0.73083,-1.10881,-1.89523,-0.13860,2.40892,0.00284
-7.84330,0.73022,-1.10930,-1.89497,-0.13835,2.40953,0.00284
-7.84449,0.72962,-1.10979,-1.89472,-0.13811,2.41013,0.00284
-7.84568,0.72903,-1.11027,-1.89448,-0.13787,2.41072,0.00284
-7.84687,0.72845,-1.11074,-1.89423,-0.13764,2.41130,0.00284
-7.84806,0.72788,-1.11121,-1.89399,-0.13741,2.41188,0.00284
-7.84925,0.72731,-1.11167,-1.89376,-0.13718,2.41244,0.00284
-7.85043,0.72675,-1.11212,-1.89352,-0.13696,2.41301,0.00285
-7.85162,0.72620,-1.11256,-1.89329,-0.13674,2.41356,0.00285
-7.85281,0.72565,-1.11300,-1.89306,-0.13652,2.41411,0.00285
-7.85400,0.72511,-1.11343,-1.89284,-0.13631,2.41465,0.00285
-7.85519,0.72458,-1.11386,-1.89262,-0.13610,2.41518,0.00285
-7.85638,0.72406,-1.11428,-1.89240,-0.13590,2.41571,0.00285
-7.85757,0.72354,-1.11469,-1.89219,-0.13569,2.41623,0.00285
-7.85876,0.72342,-1.11480,-1.89214,-0.13564,2.41635,0.00285
-7.85995,0.72271,-1.11542,-1.89183,-0.13532,2.41705,0.00285
-7.86113,0.72202,-1.11603,-1.89154,-0.13500,2.41775,0.00284
-7.86232,0.72133,-1.11664,-1.89124,-0.13469,2.41843,0.00284
-7.86351,0.72065,-1.11723,-1.89095,-0.13438,2.41911,0.00284
-7.86470,0.71998,-1.11782,-1.89067,-0.13408,2.41978,0.00284
-7.86589,0.71932,-1.11840,-1.89039,-0.13378,2.42044,0.00284
-7.86708,0.71867,-1.11897,-1.89011,-0.13349,2.42109,0.00283
-7.86827,0.71803,-1.11953,-1.88983,-0.13320,2.42173,0.00283
-7.86946,0.71739,-1.12008,-1.88956,-0.13292,2.42236,0.00283
-7.87065,0.71677,-1.12062,-1.88930,-0.13264,2.42299,0.00283
-7.87183,0.71615,-1.12115,-1.88903,-0.13236,2.42360,0.00283
-7.87302,0.71554,-1.12168,-1.88877,-0.13209,2.42421,0.00283
-7.87421,0.71494,-1.12220,-1.88852,-0.13183,2.42482,0.00283
-7.87540,0.71434,-1.12271,-1.88827,-0.13157,2.42541,0.00283
-7.87659,0.71376,-1.12321,-1.88802,-0.13131,2.42600,0.00283
-7.87778,0.71318,-1.12371,-1.88777,-0.13106,2.42657,0.00283
-7.87897,0.71261,-1.12420,-1.88753,-0.13081,2.42714,0.00283
-7.88016,0.71204,-1.12468,-1.88729,-0.13057,2.42771,0.00283
-7.88135,0.71149,-1.12515,-1.88706,-0.13032,2.42826,0.00283
-7.88253,0.71094,-1.12561,-1.88682,-0.13009,2.42881,0.00283
-7.88372,0.71040,-1.12607,-1.88660,-0.12985,2.42936,0.00283
-7.88491,0.70986,-1.12652,-1.88637,-0.12963,2.42989,0.00283
-7.88610,0.70934,-1.12697,-1.88615,-0.12940,2.43042,0.00283
-7.88729,0.70882,-1.12741,-1.88593,-0.12918,2.43094,0.00283
-7.88848,0.70830,-1.12784,-1.88571,-0.12896,2.43145,0.00283
-7.88967,0.70780,-1.12826,-1.88550,-0.12874,2.43196,0.00283
-7.89086,0.70730,-1.12868,-1.88529,-0.12853,2.43246,0.00283
-7.89205,0.70716,-1.12882,-1.88522,-0.12846,2.43260,0.00283
-7.89324,0.70578,-1.13026,-1.88450,-0.12776,2.43395,0.00281
-7.89442,0.70443,-1.13167,-1.88378,-0.12707,2.43529,0.00280
-7.89561,0.70309,-1.13306,-1.88308,-0.12639,2.43661,0.00278
-7.89680,0.70178,-1.13442,-1.88239,-0.12573,2.43790,0.00277
-7.89799,0.70048,-1.13577,-1.88171,-0.12508,2.43918,0.00276
-7.89918,0.69921,-1.13710,-1.88103,-0.12443,2.44044,0.00274
-7.90037,0.69795,-1.13840,-1.88036,-0.12381,2.44168,0.00273
-7.90156,0.69671,-1.13968,-1.87971,-0.12319,2.44291,0.00272
-7.90275,0.69549,-1.14094,-1.87906,-0.12258,2.44412,0.00271
-7.90394,0.69428,-1.14219,-1.87841,-0.12199,2.44531,0.00270
-7.90512,0.69309,-1.14341,-1.87778,-0.12140,2.44648,0.00269
-7.90631,0.69193,-1.14461,-1.87716,-0.12083,2.44764,0.00268
-7.90750,0.69077,-1.14580,-1.87654,-0.12027,2.44878,0.00267
-7.90869,0.68964,-1.14696,-1.87593,-0.11971,2.44990,0.00266
-7.90988,0.68852,-1.14811,-1.87533,-0.11917,2.45101,0.00265
-7.91107,0.68742,-1.14924,-1.87474,-0.11864,2.45210,0.00264
-7.91226,0.68633,-1.15035,-1.87416,-0.11811,2.45318,0.00263
-7.91345,0.68526,-1.15145,-1.87358,-0.11760,2.45424,0.00263
-7.91464,0.68420,-1.15252,-1.87301,-0.11709,2.45529,0.00262
-7.91582,0.68316,-1.15358,-1.87245,-0.11660,2.45632,0.00261
-7.91701,0.68214,-1.15462,-1.87190,-0.11611,2.45734,0.00261
-7.91820,0.68113,-1.15565,-1.87135,-0.11563,2.45834,0.00260
-7.91939,0.68013,-1.15666,-1.87081,-0.11516,2.45933,0.00259
-7.92058,0.67915,-1.15765,-1.87028,-0.11470,2.46030,0.00259
-7.92177,0.67819,-1.15863,-1.86976,-0.11424,2.46126,0.00258
-7.92296,0.67723,-1.15959,-1.86924,-0.11380,2.46221,0.00258
-7.92415,0.67630,-1.16054,-1.86873,-0.11336,2.46314,0.00257
-7.92534,0.67537,-1.16147,-1.86823,-0.11293,2.46406,0.00257
-7.92652,0.67446,-1.16239,-1.86773,-0.11251,2.46497,0.00257
-7.92771,0.67356,-1.16329,-1.86724,-0.11209,2.46586,0.00256
-7.92890,0.67268,-1.16418,-1.86676,-0.11169,2.46675,0.00256
-7.93009,0.67180,-1.16505,-1.86629,-0.11129,2.46762,0.00256
-7.93128,0.67094,-1.16591,-1.86582,-0.11089,2.46847,0.00255
-7.93247,0.67010,-1.16676,-1.86535,-0.11051,2.46932,0.00255
-7.93366,0.66926,-1.16759,-1.86490,-0.11013,2.47015,0.00255
-7.93485,0.66844,-1.16841,-1.86445,-0.10975,2.47097,0.00255
-7.93604,0.66763,-1.16922,-1.86401,-0.10939,2.47178,0.00255
-7.93723,0.66683,-1.17001,-1.86357,-0.10903,2.47258,0.00254
-7.93841,0.66604,-1.17080,-1.86314,-0.10867,2.47337,0.00254
-7.93960,0.66526,-1.17156,-1.86271,-0.10833,2.47414,0.00254
-7.94079,0.66450,-1.17232,-1.86229,-0.10799,2.47491,0.00254
-7.94198,0.66374,-1.17306,-1.86188,-0.10765,2.47566,0.00254
-7.94317,0.66300,-1.17380,-1.86147,-0.10732,2.47640,0.00254
-7.94436,0.66226,-1.17452,-1.86107,-0.10700,2.47714,0.00254
-7.94555,0.66154,-1.17523,-1.86068,-0.10668,2.47786,0.00254
-7.94674,0.66083,-1.17593,-1.86029,-0.10637,2.47857,0.00254
-7.94793,0.66013,-1.17661,-1.85990,-0.10606,2.47927,0.00254
-7.94911,0.65944,-1.17729,-1.85952,-0.10576,2.47997,0.00254
-7.95030,0.65875,-1.17795,-1.85915,-0.10546,2.48065,0.00254
-7.95149,0.65808,-1.17861,-1.85878,-0.10517,2.48132,0.00254
-7.95268,0.65742,-1.17925,-1.85842,-0.10488,2.48199,0.00254
-7.95387,0.65677,-1.17989,-1.85806,-0.10460,2.48264,0.00254
-7.95506,0.65612,-1.18051,-1.85771,-0.10432,2.48328,0.00254
-7.95625,0.65549,-1.18112,-1.85736,-0.10405,2.48392,0.00254
-7.95744,0.65487,-1.18173,-1.85702,-0.10378,2.48455,0.00254
-7.95863,0.65425,-1.18232,-1.85668,-0.10352,2.48517,0.00255
-7.95981,0.65364,-1.18291,-1.85635,-0.10326,2.48578,0.00255
-7.96100,0.65304,-1.18348,-1.85602,-0.10301,2.48638,0.00255
-7.96219,0.65245,-1.18405,-1.85570,-0.10276,2.48697,0.00255
-7.96338,0.65187,-1.18461,-1.85538,-0.10251,2.48755,0.00255
-7.96457,0.65130,-1.18516,-1.85507,-0.10227,2.48813,0.00255
-7.96576,0.65073,-1.18569,-1.85476,-0.10204,2.48870,0.00256
-7.96695,0.65018,-1.18623,-1.85445,-0.10180,2.48926,0.00256
-7.96814,0.64963,-1.18675,-1.85415,-0.10157,2.48981,0.00256
-7.96933,0.64909,-1.18726,-1.85386,-0.10135,2.49035,0.00256
-7.97051,0.64855,-1.18777,-1.85357,-0.10113,2.49089,0.00257
-7.97170,0.64803,-1.18827,-1.85328,-0.10091,2.49142,0.00257
-7.97289,0.64751,-1.18876,-1.85300,-0.10070,2.49194,0.00257
-7.97408,0.64700,-1.18924,-1.85272,-0.10049,2.49245,0.00257
-7.97527,0.64649,-1.18971,-1.85244,-0.10028,2.49296,0.00258
-7.97646,0.64600,-1.19018,-1.85217,-0.10008,2.49346,0.00258
-7.97765,0.64551,-1.19064,-1.85191,-0.09988,2.49395,0.00258
-7.97884,0.64502,-1.19109,-1.85164,-0.09968,2.49444,0.00259
-7.98003,0.64455,-1.19154,-1.85138,-0.09949,2.49492,0.00259
-7.98122,0.64408,-1.19198,-1.85113,-0.09930,2.49539,0.00259
-7.98240,0.64362,-1.19241,-1.85088,-0.09911,2.49586,0.00259
-7.98359,0.64314,-1.19286,-1.85061,-0.09892,2.49634,0.00260
-7.98478,0.64246,-1.19358,-1.85019,-0.09861,2.49702,0.00260
-7.98597,0.64179,-1.19429,-1.84978,-0.09832,2.49768,0.00259
-7.98716,0.64114,-1.19498,-1.84937,-0.09803,2.49834,0.00259
-7.98835,0.64049,-1.19567,-1.84897,-0.09774,2.49899,0.00259
-7.98954,0.63985,-1.19634,-1.84857,-0.09746,2.49962,0.00259
-7.99073,0.63922,-1.19701,-1.84818,-0.09718,2.50025,0.00259
-7.99192,0.63860,-1.19766,-1.84780,-0.09691,2.50087,0.00259
-7.99310,0.63799,-1.19830,-1.84742,-0.09665,2.50148,0.00259
-7.99429,0.63739,-1.19893,-1.84705,-0.09639,2.50209,0.00259
-7.99548,0.63679,-1.19955,-1.84668,-0.09613,2.50268,0.00259
-7.99667,0.63621,-1.20016,-1.84632,-0.09588,2.50327,0.00259
-7.99786,0.63563,-1.20076,-1.84596,-0.09563,2.50384,0.00259
-7.99905,0.63506,-1.20135,-1.84561,-0.09538,2.50441,0.00259
-8.00024,0.63450,-1.20194,-1.84527,-0.09514,2.50497,0.00259
-8.00143,0.63395,-1.20251,-1.84492,-0.09491,2.50552,0.00259
-8.00262,0.63341,-1.20307,-1.84459,-0.09468,2.50607,0.00259
-8.00380,0.63287,-1.20363,-1.84426,-0.09445,2.50660,0.00259
-8.00499,0.63235,-1.20417,-1.84393,-0.09423,2.50713,0.00259
-8.00618,0.63183,-1.20471,-1.84361,-0.09401,2.50766,0.00259
-8.00737,0.63131,-1.20523,-1.84329,-0.09379,2.50817,0.00259
-8.00856,0.63081,-1.20575,-1.84298,-0.09358,2.50868,0.00260
-8.00975,0.63031,-1.20626,-1.84267,-0.09337,2.50918,0.00260
-8.01094,0.62982,-1.20676,-1.84237,-0.09317,2.50967,0.00260
-8.01213,0.62934,-1.20726,-1.84207,-0.09297,2.51015,0.00260
-8.01332,0.62886,-1.20774,-1.84178,-0.09277,2.51063,0.00260
-8.01450,0.62839,-1.20822,-1.84149,-0.09258,2.51110,0.00260
-8.01569,0.62793,-1.20869,-1.84121,-0.09239,2.51157,0.00261
-8.01688,0.62747,-1.20915,-1.84093,-0.09220,2.51203,0.00261
-8.01807,0.62702,-1.20961,-1.84065,-0.09201,2.51248,0.00261
-8.01926,0.62658,-1.21006,-1.84038,-0.09183,2.51292,0.00261
-8.02045,0.62614,-1.21050,-1.84011,-0.09166,2.51336,0.00261
-8.02164,0.62571,-1.21093,-1.83984,-0.09148,2.51380,0.00262
-8.02283,0.62560,-1.21106,-1.83977,-0.09143,2.51391,0.00262
-8.02402,0.62490,-1.21186,-1.83928,-0.09111,2.51461,0.00261
-8.02521,0.62421,-1.21266,-1.83880,-0.09080,2.51529,0.00261
-8.02639,0.62353,-1.21344,-1.83833,-0.09049,2.51597,0.00260
-8.02758,0.62286,-1.21421,-1.83786,-0.09019,2.51664,0.00260
-8.02877,0.62220,-1.21496,-1.83740,-0.08990,2.51729,0.00260
-8.02996,0.62155,-1.21570,-1.83695,-0.08961,2.51794,0.00260
-8.03115,0.62091,-1.21644,-1.83650,-0.08932,2.51858,0.00259
-8.03234,0.62027,-1.21715,-1.83606,-0.08904,2.51921,0.00259
-8.03353,0.61965,-1.21786,-1.83563,-0.08877,2.51983,0.00259
-8.03472,0.61904,-1.21856,-1.83520,-0.08850,2.52044,0.00259
-8.03591,0.61844,-1.21924,-1.83478,-0.08823,2.52104,0.00258
-8.03709,0.61784,-1.21991,-1.83436,-0.08797,2.52163,0.00258
-8.03828,0.61726,-1.22057,-1.83395,-0.08772,2.52222,0.00258
-8.03947,0.61668,-1.22122,-1.83355,-0.08747,2.52279,0.00258
-8.04066,0.61611,-1.22186,-1.83316,-0.08722,2.52336,0.00258
-8.04185,0.61555,-1.22249,-1.83277,-0.08698,2.52392,0.00258
-8.04304,0.61500,-1.22311,-1.83238,-0.08674,2.52447,0.00258
-8.04423,0.61446,-1.22372,-1.83200,-0.08651,2.52501,0.00258
-8.04542,0.61393,-1.22432,-1.83163,-0.08628,2.52555,0.00258
-8.04661,0.61340,-1.22491,-1.83126,-0.08606,2.52607,0.00258
-8.04779,0.61288,-1.22549,-1.83090,-0.08583,2.52659,0.00258
-8.04898,0.61237,-1.22606,-1.83054,-0.08562,2.52711,0.00258
-8.05017,0.61186,-1.22662,-1.83019,-0.08540,2.52761,0.00258
-8.05136,0.61137,-1.22717,-1.82985,-0.08520,2.52811,0.00258
-8.05255,0.61088,-1.22771,-1.82951,-0.08499,2.52860,0.00258
-8.05374,0.61040,-1.22824,-1.82917,-0.08479,2.52908,0.00258
-8.05493,0.60992,-1.22877,-1.82884,-0.08459,2.52956,0.00258
-8.05612,0.60946,-1.22928,-1.82852,-0.08440,2.53002,0.00258
-8.05731,0.60899,-1.22979,-1.82820,-0.08420,2.53049,0.00258
-8.05849,0.60854,-1.23029,-1.82788,-0.08402,2.53094,0.00259
-8.05968,0.60809,-1.23078,-1.82757,-0.08383,2.53139,0.00259
-8.06087,0.60765,-1.23126,-1.82726,-0.08365,2.53183,0.00259
-8.06206,0.60722,-1.23174,-1.82696,-0.08347,2.53227,0.00259
-8.06325,0.60679,-1.23221,-1.82667,-0.08330,2.53270,0.00259
-8.06444,0.60637,-1.23266,-1.82637,-0.08313,2.53312,0.00259
-8.06563,0.60596,-1.23312,-1.82609,-0.08296,2.53354,0.00260
-8.06682,0.60555,-1.23356,-1.82580,-0.08279,2.53395,0.00260
-8.06801,0.60512,-1.23403,-1.82550,-0.08262,2.53438,0.00260
-8.06920,0.60450,-1.23478,-1.82501,-0.08236,2.53499,0.00260
-8.07038,0.60389,-1.23552,-1.82452,-0.08211,2.53560,0.00259
-8.07157,0.60329,-1.23625,-1.82404,-0.08186,2.53620,0.00259
-8.07276,0.60270,-1.23697,-1.82357,-0.08162,2.53679,0.00259
-8.07395,0.60211,-1.23767,-1.82310,-0.08138,2.53737,0.00259
-8.07514,0.60154,-1.23836,-1.82264,-0.08114,2.53794,0.00259
-8.07633,0.60097,-1.23904,-1.82219,-0.08091,2.53851,0.00258
-8.07752,0.60042,-1.23971,-1.82174,-0.08069,2.53906,0.00258
-8.07871,0.59987,-1.24037,-1.82131,-0.08047,2.53961,0.00258
-8.07990,0.59933,-1.24101,-1.82087,-0.08025,2.54015,0.00258
-8.08108,0.59879,-1.24165,-1.82045,-0.08004,2.54068,0.00258
-8.08227,0.59827,-1.24228,-1.82003,-0.07983,2.54120,0.00258
-8.08346,0.59775,-1.24289,-1.81962,-0.07962,2.54172,0.00258
-8.08465,0.59724,-1.24350,-1.81921,-0.07942,2.54223,0.00258
-8.08584,0.59674,-1.24409,-1.81881,-0.07922,2.54273,0.00258
-8.08703,0.59625,-1.24468,-1.81842,-0.07903,2.54322,0.00258
-8.08822,0.59576,-1.24525,-1.81803,-0.07883,2.54371,0.00258
-8.08941,0.59529,-1.24582,-1.81765,-0.07865,2.54419,0.00258
-8.09060,0.59481,-1.24637,-1.81728,-0.07846,2.54466,0.00258
-8.09178,0.59435,-1.24692,-1.81691,-0.07828,2.54512,0.00258
-8.09297,0.59389,-1.24746,-1.81654,-0.07810,2.54558,0.00258
-8.09416,0.59344,-1.24799,-1.81618,-0.07793,2.54603,0.00258
-8.09535,0.59300,-1.24851,-1.81583,-0.07776,2.54648,0.00258
-8.09654,0.59256,-1.24902,-1.81548,-0.07759,2.54692,0.00258
-8.09773,0.59213,-1.24952,-1.81514,-0.07743,2.54735,0.00258
-8.09892,0.59171,-1.25002,-1.81480,-0.07726,2.54777,0.00259
-8.10011,0.59129,-1.25050,-1.81447,-0.07711,2.54819,0.00259
-8.10130,0.59088,-1.25098,-1.81414,-0.07695,2.54860,0.00259
-8.10248,0.59047,-1.25145,-1.81382,-0.07680,2.54901,0.00259
-8.10367,0.59007,-1.25191,-1.81351,-0.07665,2.54941,0.00259
-8.10486,0.58968,-1.25237,-1.81319,-0.07650,2.54981,0.00259
-8.10605,0.58929,-1.25282,-1.81289,-0.07635,2.55020,0.00260
-8.10724,0.58890,-1.25328,-1.81257,-0.07620,2.55059,0.00260
-8.10843,0.58837,-1.25393,-1.81211,-0.07601,2.55112,0.00260
-8.10962,0.58786,-1.25458,-1.81166,-0.07581,2.55163,0.00259
-8.11081,0.58735,-1.25521,-1.81121,-0.07563,2.55213,0.00259
-8.11200,0.58685,-1.25583,-1.81077,-0.07544,2.55263,0.00259
-8.11319,0.58636,-1.25644,-1.81034,-0.07526,2.55312,0.00259
-8.11437,0.58587,-1.25704,-1.80992,-0.07508,2.55361,0.00259
-8.11556,0.58540,-1.25763,-1.80950,-0.07490,2.55409,0.00259
-8.11675,0.58493,-1.25822,-1.80909,-0.07473,2.55455,0.00259
-8.11794,0.58446,-1.25879,-1.80868,-0.07456,2.55502,0.00259
-8.11913,0.58401,-1.25935,-1.80828,-0.07440,2.55547,0.00259
-8.12032,0.58356,-1.25990,-1.80789,-0.07423,2.55592,0.00259
-8.12151,0.58312,-1.26045,-1.80750,-0.07407,2.55636,0.00259
-8.12270,0.58268,-1.26098,-1.80712,-0.07392,2.55680,0.00259
-8.12389,0.58225,-1.26151,-1.80675,-0.07376,2.55723,0.00259
-8.12507,0.58183,-1.26202,-1.80638,-0.07361,2.55765,0.00259
-8.12626,0.58142,-1.26253,-1.80602,-0.07346,2.55807,0.00260
-8.12745,0.58101,-1.26303,-1.80566,-0.07332,2.55848,0.00260
-8.12864,0.58060,-1.26352,-1.80531,-0.07317,2.55888,0.00260
-8.12983,0.58021,-1.26400,-1.80496,-0.07303,2.55928,0.00260
-8.13102,0.57981,-1.26448,-1.80462,-0.07290,2.55967,0.00260
-8.13221,0.57943,-1.26494,-1.80428,-0.07276,2.56006,0.00260
-8.13340,0.57905,-1.26540,-1.80395,-0.07263,2.56044,0.00260
-8.13459,0.57868,-1.26586,-1.80363,-0.07250,2.56082,0.00261
-8.13577,0.57831,-1.26630,-1.80331,-0.07237,2.56119,0.00261
-8.13696,0.57818,-1.26646,-1.80319,-0.07233,2.56131,0.00261
-8.13815,0.57767,-1.26713,-1.80270,-0.07214,2.56183,0.00261
-8.13934,0.57716,-1.26779,-1.80222,-0.07196,2.56233,0.00260
-8.14053,0.57665,-1.26845,-1.80174,-0.07178,2.56283,0.00260
-8.14172,0.57616,-1.26909,-1.80128,-0.07161,2.56333,0.00260
-8.14291,0.57567,-1.26972,-1.80081,-0.07143,2.56381,0.00260
-8.14410,0.57520,-1.27034,-1.80036,-0.07127,2.56429,0.00260
-8.14529,0.57472,-1.27095,-1.79991,-0.07110,2.56476,0.00260
-8.14647,0.57426,-1.27155,-1.79947,-0.07094,2.56522,0.00260
-8.14766,0.57380,-1.27214,-1.79904,-0.07078,2.56568,0.00260
-8.14885,0.57335,-1.27272,-1.79861,-0.07063,2.56613,0.00260
-8.15004,0.57291,-1.27329,-1.79819,-0.07047,2.56657,0.00260
-8.15123,0.57247,-1.27385,-1.79778,-0.07032,2.56701,0.00260
-8.15242,0.57205,-1.27440,-1.79737,-0.07018,2.56744,0.00260
-8.15361,0.57162,-1.27494,-1.79697,-0.07003,2.56786,0.00260
-8.15480,0.57121,-1.27547,-1.79658,-0.06989,2.56828,0.00260
-8.15599,0.57080,-1.27600,-1.79619,-0.06975,2.56869,0.00260
-8.15718,0.57039,-1.27651,-1.79581,-0.06962,2.56909,0.00260
-8.15836,0.56999,-1.27702,-1.79543,-0.06948,2.56949,0.00260
-8.15955,0.56960,-1.27752,-1.79506,-0.06935,2.56988,0.00260
-8.16074,0.56922,-1.27800,-1.79470,-0.06922,2.57027,0.00260
-8.16193,0.56884,-1.27849,-1.79434,-0.06910,2.57065,0.00260
-8.16312,0.56846,-1.27896,-1.79399,-0.06897,2.57102,0.00260
-8.16431,0.56809,-1.27942,-1.79364,-0.06885,2.57139,0.00261
-8.16550,0.56773,-1.27988,-1.79330,-0.06873,2.57176,0.00261
-8.16669,0.56737,-1.28033,-1.79296,-0.06862,2.57212,0.00261
-8.16788,0.56704,-1.28075,-1.79265,-0.06850,2.57245,0.00261
-8.16906,0.56654,-1.28143,-1.79216,-0.06832,2.57295,0.00261
-8.17025,0.56605,-1.28209,-1.79168,-0.06813,2.57343,0.00260
-8.17144,0.56557,-1.28274,-1.79121,-0.06795,2.57392,0.00260
-8.17263,0.56509,-1.28338,-1.79075,-0.06777,2.57439,0.00260
-8.17382,0.56462,-1.28401,-1.79029,-0.06760,2.57486,0.00260
-8.17501,0.56416,-1.28463,-1.78984,-0.06743,2.57532,0.00260
-8.17620,0.56371,-1.28524,-1.78940,-0.06726,2.57577,0.00259
-8.17739,0.56326,-1.28584,-1.78897,-0.06709,2.57622,0.00259
-8.17858,0.56282,-1.28643,-1.78854,-0.06693,2.57666,0.00259
-8.17976,0.56239,-1.28701,-1.78812,-0.06677,2.57709,0.00259
-8.18095,0.56196,-1.28758,-1.78770,-0.06662,2.57752,0.00259
-8.18214,0.56154,-1.28814,-1.78729,-0.06647,2.57794,0.00259
-8.18333,0.56113,-1.28869,-1.78689,-0.06632,2.57835,0.00259
-8.18452,0.56072,-1.28923,-1.78649,-0.06617,2.57876,0.00259
-8.18571,0.56032,-1.28976,-1.78610,-0.06603,2.57916,0.00259
-8.18690,0.55992,-1.29028,-1.78572,-0.06588,2.57955,0.00259
-8.18809,0.55953,-1.29080,-1.78534,-0.06575,2.57994,0.00259
-8.18928,0.55915,-1.29130,-1.78497,-0.06561,2.58033,0.00259
-8.19046,0.55877,-1.29180,-1.78460,-0.06548,2.58070,0.00259
-8.19165,0.55840,-1.29228,-1.78424,-0.06535,2.58108,0.00259
-8.19284,0.55804,-1.29276,-1.78389,-0.06522,2.58144,0.00259
-8.19403,0.55768,-1.29324,-1.78354,-0.06509,2.58180,0.00259
-8.19522,0.55732,-1.29370,-1.78320,-0.06497,2.58216,0.00259
-8.19641,0.55697,-1.29416,-1.78286,-0.06485,2.58251,0.00259
-8.19760,0.55663,-1.29460,-1.78252,-0.06473,2.58285,0.00260
-8.19879,0.55641,-1.29489,-1.78231,-0.06466,2.58307,0.00260
-8.19998,0.55596,-1.29553,-1.78183,-0.06450,2.58352,0.00259
-8.20117,0.55551,-1.29615,-1.78136,-0.06435,2.58397,0.00259
-8.20235,0.55506,-1.29677,-1.78089,-0.06419,2.58442,0.00259
-8.20354,0.55463,-1.29737,-1.78043,-0.06405,2.58485,0.00259
-8.20473,0.55420,-1.29796,-1.77998,-0.06390,2.58528,0.00259
-8.20592,0.55377,-1.29855,-1.77954,-0.06376,2.58570,0.00259
-8.20711,0.55336,-1.29912,-1.77910,-0.06362,2.58612,0.00259
-8.20830,0.55295,-1.29969,-1.77867,-0.06349,2.58653,0.00259
-8.20949,0.55254,-1.30024,-1.77825,-0.06335,2.58693,0.00259
-8.21068,0.55215,-1.30079,-1.77783,-0.06322,2.58733,0.00259
-8.21187,0.55175,-1.30132,-1.77742,-0.06309,2.58772,0.00259
-8.21305,0.55137,-1.30185,-1.77702,-0.06297,2.58811,0.00259
-8.21424,0.55099,-1.30237,-1.77662,-0.06284,2.58848,0.00259
-8.21543,0.55062,-1.30288,-1.77623,-0.06272,2.58886,0.00259
-8.21662,0.55025,-1.30338,-1.77585,-0.06260,2.58923,0.00259
-8.21781,0.54989,-1.30387,-1.77547,-0.06249,2.58959,0.00259
-8.21900,0.54953,-1.30435,-1.77510,-0.06237,2.58995,0.00259
-8.22019,0.54918,-1.30483,-1.77473,-0.06226,2.59030,0.00259
-8.22138,0.54883,-1.30530,-1.77437,-0.06215,2.59064,0.00259
-8.22257,0.54849,-1.30576,-1.77401,-0.06204,2.59098,0.00259
-8.22375,0.54816,-1.30621,-1.77366,-0.06194,2.59132,0.00259
-8.22494,0.54783,-1.30665,-1.77332,-0.06184,2.59165,0.00260
-8.22613,0.54778,-1.30672,-1.77327,-0.06182,2.59170,0.00259
-8.22732,0.54733,-1.30737,-1.77276,-0.06167,2.59215,0.00259
-8.22851,0.54688,-1.30802,-1.77226,-0.06153,2.59260,0.00259
-8.22970,0.54644,-1.30865,-1.77176,-0.06139,2.59304,0.00259
-8.23089,0.54600,-1.30927,-1.77128,-0.06125,2.59347,0.00259
-8.23208,0.54558,-1.30989,-1.77080,-0.06112,2.59390,0.00259
-8.23327,0.54516,-1.31049,-1.77033,-0.06099,2.59432,0.00259
-8.23445,0.54474,-1.31108,-1.76986,-0.06086,2.59473,0.00258
-8.23564,0.54433,-1.31166,-1.76941,-0.06073,2.59514,0.00258
-8.23683,0.54393,-1.31223,-1.76896,-0.06061,2.59554,0.00258
-8.23802,0.54354,-1.31279,-1.76852,-0.06048,2.59593,0.00258
-8.23921,0.54315,-1.31334,-1.76808,-0.06037,2.59632,0.00258
-8.24040,0.54277,-1.31389,-1.76766,-0.06025,2.59670,0.00258
-8.24159,0.54239,-1.31442,-1.76723,-0.06013,2.59708,0.00258
-8.24278,0.54202,-1.31494,-1.76682,-0.06002,2.59745,0.00258
-8.24397,0.54165,-1.31546,-1.76641,-0.05991,2.59782,0.00258
-8.24516,0.54129,-1.31596,-1.76601,-0.05980,2.59818,0.00258
-8.24634,0.54094,-1.31646,-1.76562,-0.05970,2.59853,0.00258
-8.24753,0.54059,-1.31695,-1.76523,-0.05960,2.59888,0.00258
-8.24872,0.54025,-1.31743,-1.76484,-0.05949,2.59922,0.00259
-8.24991,0.53991,-1.31791,-1.76447,-0.05939,2.59956,0.00259
-8.25110,0.53958,-1.31837,-1.76410,-0.05930,2.59989,0.00259
-8.25229,0.53925,-1.31883,-1.76373,-0.05920,2.60022,0.00259
-8.25348,0.53893,-1.31928,-1.76337,-0.05911,2.60055,0.00259
-8.25467,0.53867,-1.31965,-1.76308,-0.05903,2.60081,0.00259
-8.25586,0.53826,-1.32024,-1.76260,-0.05892,2.60121,0.00259
-8.25704,0.53786,-1.32083,-1.76212,-0.05880,2.60161,0.00259
-8.25823,0.53747,-1.32140,-1.76166,-0.05869,2.60201,0.00259
-8.25942,0.53708,-1.32197,-1.76120,-0.05858,2.60239,0.00259
-8.26061,0.53670,-1.32252,-1.76075,-0.05848,2.60277,0.00259
-8.26180,0.53632,-1.32307,-1.76031,-0.05837,2.60315,0.00259
-8.26299,0.53595,-1.32360,-1.75987,-0.05827,2.60352,0.00259
-8.26418,0.53559,-1.32413,-1.75944,-0.05817,2.60388,0.00259
-8.26537,0.53523,-1.32465,-1.75902,-0.05807,2.60424,0.00259
-8.26656,0.53488,-1.32516,-1.75860,-0.05798,2.60459,0.00259
-8.26774,0.53453,-1.32566,-1.75819,-0.05788,2.60494,0.00259
-8.26893,0.53419,-1.32615,-1.75779,-0.05779,2.60528,0.00259
-8.27012,0.53385,-1.32664,-1.75739,-0.05770,2.60562,0.00259
-8.27131,0.53352,-1.32711,-1.75700,-0.05761,2.60595,0.00259
-8.27250,0.53320,-1.32758,-1.75662,-0.05753,2.60628,0.00259
-8.27369,0.53288,-1.32804,-1.75624,-0.05744,2.60660,0.00259
-8.27488,0.53256,-1.32849,-1.75587,-0.05736,2.60691,0.00259
-8.27607,0.53225,-1.32894,-1.75550,-0.05728,2.60723,0.00259
-8.27726,0.53218,-1.32905,-1.75541,-0.05726,2.60730,0.00259
-8.27844,0.53175,-1.32970,-1.75483,-0.05718,2.60773,0.00259
-8.27963,0.53133,-1.33034,-1.75426,-0.05710,2.60815,0.00259
-8.28082,0.53091,-1.33098,-1.75371,-0.05702,2.60856,0.00259
-8.28201,0.53050,-1.33160,-1.75316,-0.05695,2.60897,0.00259
-8.28320,0.53010,-1.33221,-1.75262,-0.05687,2.60937,0.00259
-8.28439,0.52970,-1.33281,-1.75209,-0.05680,2.60977,0.00259
-8.28558,0.52931,-1.33340,-1.75157,-0.05673,2.61016,0.00259
-8.28677,0.52893,-1.33398,-1.75105,-0.05666,2.61054,0.00259
-8.28796,0.52855,-1.33455,-1.75055,-0.05660,2.61092,0.00259
-8.28915,0.52818,-1.33511,-1.75005,-0.05653,2.61129,0.00259
-8.29033,0.52781,-1.33566,-1.74956,-0.05647,2.61166,0.00259
-8.29152,0.52745,-1.33620,-1.74908,-0.05640,2.61202,0.00259
-8.29271,0.52709,-1.33674,-1.74860,-0.05634,2.61238,0.00259
-8.29390,0.52674,-1.33726,-1.74814,-0.05628,2.61272,0.00260
-8.29509,0.52640,-1.33777,-1.74768,-0.05622,2.61307,0.00260
-8.29628,0.52606,-1.33828,-1.74723,-0.05617,2.61341,0.00260
-8.29747,0.52573,-1.33877,-1.74678,-0.05611,2.61374,0.00260
-8.29866,0.52540,-1.33926,-1.74634,-0.05606,2.61407,0.00260
-8.29985,0.52508,-1.33974,-1.74591,-0.05600,2.61439,0.00260
-8.30103,0.52476,-1.34021,-1.74549,-0.05595,2.61471,0.00260
-8.30222,0.52445,-1.34068,-1.74507,-0.05590,2.61502,0.00260
-8.30341,0.52414,-1.34113,-1.74466,-0.05585,2.61533,0.00261
-8.30460,0.52384,-1.34158,-1.74426,-0.05580,2.61564,0.00261
-8.30579,0.52354,-1.34202,-1.74386,-0.05576,2.61594,0.00261
-8.30698,0.52347,-1.34213,-1.74377,-0.05575,2.61601,0.00261
-8.30817,0.52307,-1.34276,-1.74319,-0.05569,2.61641,0.00261
-8.30936,0.52267,-1.34338,-1.74263,-0.05563,2.61681,0.00261
-8.31055,0.52228,-1.34399,-1.74207,-0.05557,2.61719,0.00261
-8.31173,0.52190,-1.34459,-1.74153,-0.05552,2.61758,0.00261
-8.31292,0.52152,-1.34517,-1.74099,-0.05547,2.61796,0.00261
-8.31411,0.52115,-1.34575,-1.74046,-0.05541,2.61833,0.00261
-8.31530,0.52078,-1.34632,-1.73994,-0.05536,2.61869,0.00261
-8.31649,0.52042,-1.34688,-1.73943,-0.05532,2.61905,0.00261
-8.31768,0.52007,-1.34743,-1.73893,-0.05527,2.61941,0.00261
-8.31887,0.51972,-1.34797,-1.73843,-0.05522,2.61976,0.00261
-8.32006,0.51937,-1.34850,-1.73794,-0.05518,2.62010,0.00261
-8.32125,0.51903,-1.34902,-1.73746,-0.05513,2.62044,0.00261
-8.32243,0.51870,-1.34953,-1.73699,-0.05509,2.62077,0.00261
-8.32362,0.51837,-1.35003,-1.73653,-0.05505,2.62110,0.00261
-8.32481,0.51805,-1.35053,-1.73607,-0.05501,2.62143,0.00261
-8.32600,0.51774,-1.35101,-1.73562,-0.05497,2.62174,0.00261
-8.32719,0.51742,-1.35149,-1.73518,-0.05493,2.62206,0.00262
-8.32838,0.51712,-1.35196,-1.73474,-0.05489,2.62236,0.00262
-8.32957,0.51681,-1.35242,-1.73432,-0.05485,2.62267,0.00262
-8.33076,0.51652,-1.35288,-1.73389,-0.05482,2.62297,0.00262
-8.33195,0.51622,-1.35332,-1.73348,-0.05478,2.62326,0.00262
-8.33314,0.51593,-1.35376,-1.73307,-0.05475,2.62355,0.00262
-8.33432,0.51590,-1.35382,-1.73301,-0.05474,2.62359,0.00262
-8.33551,0.51552,-1.35443,-1.73244,-0.05470,2.62397,0.00262
-8.33670,0.51514,-1.35503,-1.73188,-0.05467,2.62434,0.00262
-8.33789,0.51477,-1.35562,-1.73133,-0.05463,2.62471,0.00262
-8.33908,0.51441,-1.35620,-1.73078,-0.05460,2.62507,0.00262
-8.34027,0.51405,-1.35676,-1.73025,-0.05456,2.62543,0.00262
-8.34146,0.51370,-1.35732,-1.72972,-0.05453,2.62578,0.00262
-8.34265,0.51336,-1.35787,-1.72920,-0.05450,2.62613,0.00262
-8.34384,0.51302,-1.35841,-1.72869,-0.05446,2.62647,0.00262
-8.34502,0.51268,-1.35894,-1.72819,-0.05443,2.62680,0.00262
-8.34621,0.51235,-1.35946,-1.72769,-0.05440,2.62713,0.00262
-8.34740,0.51203,-1.35997,-1.72721,-0.05438,2.62746,0.00263
-8.34859,0.51171,-1.36048,-1.72673,-0.05435,2.62778,0.00263
-8.34978,0.51139,-1.36097,-1.72626,-0.05432,2.62809,0.00263
-8.35097,0.51109,-1.36146,-1.72579,-0.05430,2.62840,0.00263
-8.35216,0.51078,-1.36193,-1.72534,-0.05427,2.62871,0.00263
-8.35335,0.51048,-1.36240,-1.72489,-0.05425,2.62901,0.00263
-8.35454,0.51019,-1.36287,-1.72445,-0.05422,2.62930,0.00263
-8.35572,0.50990,-1.36332,-1.72402,-0.05420,2.62959,0.00263
-8.35691,0.50961,-1.36377,-1.72359,-0.05418,2.62988,0.00263
-8.35810,0.50933,-1.36420,-1.72317,-0.05416,2.63016,0.00264
-8.35929,0.50924,-1.36435,-1.72303,-0.05415,2.63025,0.00264
-8.36048,0.50889,-1.36491,-1.72250,-0.05411,2.63060,0.00264
-8.36167,0.50855,-1.36547,-1.72197,-0.05408,2.63094,0.00264
-8.36286,0.50821,-1.36602,-1.72145,-0.05405,2.63128,0.00263
-8.36405,0.50788,-1.36656,-1.72095,-0.05402,2.63162,0.00263
-8.36524,0.50755,-1.36709,-1.72045,-0.05399,2.63194,0.00263
-8.36642,0.50723,-1.36761,-1.71995,-0.05396,2.63227,0.00263
-8.36761,0.50691,-1.36812,-1.71947,-0.05393,2.63258,0.00264
-8.36880,0.50660,-1.36862,-1.71899,-0.05390,2.63290,0.00264
-8.36999,0.50629,-1.36911,-1.71852,-0.05388,2.63320,0.00264
-8.37118,0.50599,-1.36960,-1.71806,-0.05385,2.63351,0.00264
-8.37237,0.50569,-1.37007,-1.71761,-0.05382,2.63381,0.00264
-8.37356,0.50540,-1.37054,-1.71716,-0.05380,2.63410,0.00264
-8.37475,0.50511,-1.37100,-1.71672,-0.05378,2.63439,0.00264
-8.37594,0.50483,-1.37145,-1.71629,-0.05375,2.63467,0.00264
-8.37713,0.50455,-1.37190,-1.71586,-0.05373,2.63495,0.00264
-8.37831,0.50428,-1.37234,-1.71544,-0.05371,2.63523,0.00264
-8.37950,0.50424,-1.37239,-1.71539,-0.05371,2.63526,0.00264
-8.38069,0.50391,-1.37294,-1.71487,-0.05368,2.63559,0.00264
-8.38188,0.50358,-1.37348,-1.71436,-0.05365,2.63592,0.00264
-8.38307,0.50326,-1.37401,-1.71386,-0.05362,2.63624,0.00264
-8.38426,0.50294,-1.37452,-1.71336,-0.05360,2.63656,0.00264
-8.38545,0.50263,-1.37504,-1.71287,-0.05357,2.63687,0.00264
-8.38664,0.50233,-1.37554,-1.71239,-0.05355,2.63718,0.00264
-8.38783,0.50202,-1.37603,-1.71192,-0.05353,2.63748,0.00264
-8.38901,0.50173,-1.37651,-1.71146,-0.05350,2.63778,0.00264
-8.39020,0.50144,-1.37699,-1.71100,-0.05348,2.63807,0.00264
-8.39139,0.50115,-1.37746,-1.71055,-0.05346,2.63836,0.00264
-8.39258,0.50087,-1.37792,-1.71011,-0.05344,2.63864,0.00264
-8.39377,0.50059,-1.37837,-1.70967,-0.05342,2.63892,0.00264
-8.39496,0.50031,-1.37882,-1.70924,-0.05340,2.63920,0.00264
-8.39615,0.50004,-1.37925,-1.70882,-0.05338,2.63947,0.00265
-8.39734,0.50001,-1.37931,-1.70876,-0.05338,2.63950,0.00265
-8.39853,0.49965,-1.37992,-1.70818,-0.05336,2.63986,0.00264
-8.39971,0.49930,-1.38052,-1.70760,-0.05335,2.64021,0.00264
-8.40090,0.49895,-1.38110,-1.70703,-0.05333,2.64056,0.00264
-8.40209,0.49861,-1.38168,-1.70647,-0.05331,2.64090,0.00264
-8.40328,0.49828,-1.38224,-1.70592,-0.05330,2.64123,0.00264
-8.40447,0.49795,-1.38280,-1.70537,-0.05328,2.64156,0.00264
-8.40566,0.49762,-1.38334,-1.70484,-0.05327,2.64188,0.00264
-8.40685,0.49731,-1.38388,-1.70432,-0.05325,2.64220,0.00264
-8.40804,0.49699,-1.38441,-1.70380,-0.05324,2.64252,0.00264
-8.40923,0.49668,-1.38493,-1.70329,-0.05323,2.64283,0.00264
-8.41041,0.49638,-1.38544,-1.70279,-0.05322,2.64313,0.00264
-8.41160,0.49608,-1.38594,-1.70230,-0.05321,2.64343,0.00264
-8.41279,0.49579,-1.38643,-1.70181,-0.05320,2.64372,0.00264
-8.41398,0.49550,-1.38691,-1.70134,-0.05319,2.64402,0.00264
-8.41517,0.49521,-1.38739,-1.70087,-0.05318,2.64430,0.00264
-8.41636,0.49493,-1.38785,-1.70041,-0.05317,2.64458,0.00264
-8.41755,0.49466,-1.38831,-1.69996,-0.05316,2.64486,0.00264
-8.41874,0.49439,-1.38877,-1.69951,-0.05315,2.64513,0.00264
-8.41993,0.49412,-1.38921,-1.69907,-0.05315,2.64540,0.00265
-8.42112,0.49386,-1.38964,-1.69864,-0.05314,2.64566,0.00265
-8.42230,0.49377,-1.38979,-1.69850,-0.05314,2.64575,0.00265
-8.42349,0.49345,-1.39033,-1.69797,-0.05313,2.64606,0.00265
-8.42468,0.49314,-1.39086,-1.69744,-0.05312,2.64638,0.00265
-8.42587,0.49283,-1.39139,-1.69692,-0.05310,2.64668,0.00264
-8.42706,0.49253,-1.39191,-1.69642,-0.05309,2.64699,0.00264
-8.42825,0.49223,-1.39241,-1.69592,-0.05309,2.64729,0.00264
-8.42944,0.49194,-1.39291,-1.69542,-0.05308,2.64758,0.00264
-8.43063,0.49165,-1.39340,-1.69494,-0.05307,2.64787,0.00264
-8.43182,0.49137,-1.39388,-1.69446,-0.05306,2.64815,0.00265
-8.43300,0.49109,-1.39436,-1.69400,-0.05305,2.64843,0.00265
-8.43419,0.49082,-1.39482,-1.69354,-0.05305,2.64871,0.00265
-8.43538,0.49055,-1.39528,-1.69308,-0.05304,2.64898,0.00265
-8.43657,0.49028,-1.39573,-1.69264,-0.05304,2.64925,0.00265
-8.43776,0.49002,-1.39617,-1.69220,-0.05303,2.64951,0.00265
-8.43895,0.48976,-1.39662,-1.69176,-0.05302,2.64977,0.00265
-8.44014,0.48945,-1.39714,-1.69126,-0.05300,2.65007,0.00265
-8.44133,0.48916,-1.39766,-1.69076,-0.05297,2.65037,0.00265
-8.44252,0.48886,-1.39816,-1.69028,-0.05295,2.65067,0.00265
-8.44370,0.48857,-1.39866,-1.68980,-0.05293,2.65096,0.00264
-8.44489,0.48829,-1.39915,-1.68933,-0.05291,2.65124,0.00264
-8.44608,0.48801,-1.39963,-1.68887,-0.05289,2.65152,0.00264
-8.44727,0.48773,-1.40010,-1.68842,-0.05287,2.65180,0.00264
-8.44846,0.48746,-1.40057,-1.68797,-0.05285,2.65207,0.00264
-8.44965,0.48720,-1.40102,-1.68753,-0.05283,2.65234,0.00264
-8.45084,0.48694,-1.40147,-1.68710,-0.05281,2.65260,0.00264
-8.45203,0.48668,-1.40191,-1.68667,-0.05280,2.65286,0.00264
-8.45322,0.48652,-1.40218,-1.68642,-0.05279,2.65301,0.00264
-8.45440,0.48625,-1.40265,-1.68597,-0.05276,2.65328,0.00264
-8.45559,0.48599,-1.40311,-1.68554,-0.05274,2.65355,0.00264
-8.45678,0.48572,-1.40356,-1.68511,-0.05272,2.65381,0.00264
-8.45797,0.48546,-1.40400,-1.68468,-0.05270,2.65407,0.00264
-8.45916,0.48523,-1.40440,-1.68431,-0.05268,2.65430,0.00264
-8.46035,0.48497,-1.40485,-1.68388,-0.05265,2.65456,0.00264
-8.46154,0.48472,-1.40529,-1.68346,-0.05263,2.65482,0.00264
-8.46273,0.48459,-1.40551,-1.68325,-0.05262,2.65495,0.00264
-8.46392,0.48433,-1.40596,-1.68283,-0.05259,2.65521,0.00264
-8.46511,0.48408,-1.40640,-1.68241,-0.05257,2.65547,0.00264
-8.46629,0.48395,-1.40662,-1.68220,-0.05255,2.65559,0.00264
-8.46748,0.48369,-1.40707,-1.68178,-0.05253,2.65585,0.00264
-8.46867,0.48344,-1.40751,-1.68136,-0.05250,2.65611,0.00264
-8.46986,0.48331,-1.40773,-1.68115,-0.05248,2.65624,0.00264
-8.47105,0.48305,-1.40818,-1.68073,-0.05246,2.65650,0.00264
-8.47224,0.48280,-1.40862,-1.68032,-0.05243,2.65675,0.00264
-8.47343,0.48267,-1.40884,-1.68011,-0.05241,2.65688,0.00264
-8.47462,0.48241,-1.40929,-1.67969,-0.05238,2.65714,0.00264
-8.47581,0.48216,-1.40974,-1.67928,-0.05235,2.65739,0.00264
-8.47699,0.48200,-1.41000,-1.67905,-0.05231,2.65754,0.00263
-8.47818,0.48174,-1.41045,-1.67884,-0.05209,2.65780,0.00263
-8.47937,0.48149,-1.41089,-1.67863,-0.05187,2.65806,0.00262
-8.48056,0.48123,-1.41132,-1.67842,-0.05166,2.65831,0.00261
-8.48175,0.48098,-1.41174,-1.67821,-0.05144,2.65856,0.00260
-8.48294,0.48093,-1.41183,-1.67819,-0.05138,2.65861,0.00260
-8.48413,0.48067,-1.41226,-1.67822,-0.05094,2.65887,0.00258
-8.48532,0.48042,-1.41268,-1.67824,-0.05051,2.65912,0.00257
-8.48651,0.48017,-1.41310,-1.67827,-0.05009,2.65937,0.00255
-8.48769,0.47992,-1.41350,-1.67829,-0.04967,2.65961,0.00254
-8.48888,0.47968,-1.41391,-1.67831,-0.04926,2.65985,0.00253
-8.49007,0.47944,-1.41430,-1.67833,-0.04886,2.66009,0.00251
-8.49126,0.47921,-1.41469,-1.67835,-0.04846,2.66032,0.00250
-8.49245,0.47898,-1.41507,-1.67837,-0.04808,2.66055,0.00249
-8.49364,0.47875,-1.41544,-1.67839,-0.04770,2.66078,0.00248
-8.49483,0.47853,-1.41581,-1.67841,-0.04732,2.66100,0.00247
-8.49602,0.47831,-1.41617,-1.67843,-0.04695,2.66122,0.00246
-8.49721,0.47809,-1.41653,-1.67844,-0.04659,2.66143,0.00245
-8.49839,0.47788,-1.41687,-1.67846,-0.04624,2.66164,0.00244
-8.49958,0.47767,-1.41722,-1.67847,-0.04589,2.66185,0.00243
-8.50077,0.47763,-1.41729,-1.67850,-0.04580,2.66189,0.00242
-8.50196,0.47741,-1.41764,-1.67876,-0.04520,2.66211,0.00241
-8.50315,0.47719,-1.41798,-1.67902,-0.04462,2.66232,0.00239
-8.50434,0.47698,-1.41832,-1.67927,-0.04405,2.66253,0.00237
-8.50553,0.47677,-1.41866,-1.67952,-0.04349,2.66273,0.00235
-8.50672,0.47657,-1.41899,-1.67976,-0.04293,2.66294,0.00234
-8.50791,0.47637,-1.41931,-1.67999,-0.04239,2.66314,0.00232
-8.50910,0.47617,-1.41962,-1.68023,-0.04185,2.66333,0.00231
-8.51028,0.47597,-1.41994,-1.68045,-0.04133,2.66352,0.00230
-8.51147,0.47578,-1.42024,-1.68068,-0.04081,2.66371,0.00228
-8.51266,0.47559,-1.42054,-1.68090,-0.04031,2.66390,0.00227
-8.51385,0.47541,-1.42084,-1.68111,-0.03981,2.66408,0.00226
-8.51504,0.47523,-1.42113,-1.68132,-0.03932,2.66426,0.00225
-8.51623,0.47505,-1.42141,-1.68153,-0.03884,2.66444,0.00224
-8.51742,0.47487,-1.42169,-1.68173,-0.03836,2.66461,0.00223
-8.51861,0.47470,-1.42197,-1.68193,-0.03790,2.66479,0.00222
-8.51980,0.47453,-1.42224,-1.68213,-0.03744,2.66495,0.00221
-8.52098,0.47436,-1.42250,-1.68232,-0.03699,2.66512,0.00221
-8.52217,0.47420,-1.42276,-1.68251,-0.03655,2.66528,0.00220
-8.52336,0.47403,-1.42302,-1.68269,-0.03612,2.66544,0.00219
-8.52455,0.47388,-1.42327,-1.68287,-0.03569,2.66560,0.00218
-8.52574,0.47372,-1.42352,-1.68308,-0.03525,2.66576,0.00218
-8.52693,0.47355,-1.42378,-1.68349,-0.03458,2.66592,0.00216
-8.52812,0.47338,-1.42404,-1.68391,-0.03393,2.66608,0.00215
-8.52931,0.47322,-1.42430,-1.68431,-0.03329,2.66624,0.00213
-8.53050,0.47306,-1.42455,-1.68471,-0.03266,2.66640,0.00212
-8.53168,0.47290,-1.42479,-1.68509,-0.03204,2.66656,0.00210
-8.53287,0.47275,-1.42503,-1.68548,-0.03143,2.66671,0.00209
-8.53406,0.47259,-1.42527,-1.68585,-0.03083,2.66686,0.00208
-8.53525,0.47245,-1.42550,-1.68622,-0.03024,2.66700,0.00207
-8.53644,0.47230,-1.42573,-1.68658,-0.02966,2.66715,0.00206
-8.53763,0.47215,-1.42595,-1.68694,-0.02909,2.66729,0.00205
-8.53882,0.47201,-1.42617,-1.68728,-0.02853,2.66743,0.00204
-8.54001,0.47187,-1.42639,-1.68763,-0.02798,2.66757,0.00203
-8.54120,0.47173,-1.42660,-1.68796,-0.02744,2.66770,0.00202
-8.54238,0.47160,-1.42681,-1.68829,-0.02691,2.66783,0.00202
-8.54357,0.47147,-1.42701,-1.68862,-0.02639,2.66796,0.00201
-8.54476,0.47134,-1.42722,-1.68893,-0.02588,2.66809,0.00200
-8.54595,0.47121,-1.42741,-1.68925,-0.02537,2.66822,0.00200
-8.54714,0.47108,-1.42761,-1.68955,-0.02488,2.66834,0.00199
-8.54833,0.47096,-1.42780,-1.68985,-0.02439,2.66846,0.00199
-8.54952,0.47084,-1.42799,-1.69015,-0.02391,2.66858,0.00199
-8.55071,0.47072,-1.42817,-1.69044,-0.02344,2.66870,0.00198
-8.55190,0.47060,-1.42835,-1.69072,-0.02297,2.66881,0.00198
-8.55309,0.47049,-1.42853,-1.69100,-0.02252,2.66893,0.00198
-8.55427,0.47041,-1.42866,-1.69121,-0.02219,2.66901,0.00197
-8.55546,0.47028,-1.42885,-1.69163,-0.02159,2.66913,0.00196
-8.55665,0.47016,-1.42904,-1.69203,-0.02100,2.66925,0.00196
-8.55784,0.47004,-1.42923,-1.69243,-0.02042,2.66937,0.00195
-8.55903,0.46992,-1.42941,-1.69282,-0.01985,2.66948,0.00194
-8.56022,0.46980,-1.42959,-1.69321,-0.01929,2.66960,0.00193
-8.56141,0.46969,-1.42977,-1.69359,-0.01874,2.66971,0.00193
-8.56260,0.46958,-1.42995,-1.69396,-0.01820,2.66982,0.00192
-8.56379,0.46947,-1.43012,-1.69432,-0.01767,2.66992,0.00192
-8.56497,0.46936,-1.43029,-1.69468,-0.01715,2.67003,0.00191
-8.56616,0.46925,-1.43045,-1.69503,-0.01664,2.67014,0.00191
-8.56735,0.46915,-1.43062,-1.69538,-0.01613,2.67024,0.00191
-8.56854,0.46904,-1.43078,-1.69572,-0.01563,2.67034,0.00190
-8.56973,0.46894,-1.43093,-1.69605,-0.01515,2.67044,0.00190
-8.57092,0.46884,-1.43109,-1.69638,-0.01467,2.67053,0.00190
-8.57211,0.46874,-1.43124,-1.69670,-0.01419,2.67063,0.00190
-8.57330,0.46865,-1.43139,-1.69702,-0.01373,2.67072,0.00190
-8.57449,0.46858,-1.43149,-1.69726,-0.01339,2.67079,0.00189
-8.57567,0.46847,-1.43166,-1.69778,-0.01270,2.67089,0.00188
-8.57686,0.46837,-1.43183,-1.69830,-0.01203,2.67099,0.00187
-8.57805,0.46826,-1.43199,-1.69881,-0.01137,2.67109,0.00186
-8.57924,0.46816,-1.43215,-1.69931,-0.01072,2.67119,0.00185
-8.58043,0.46806,-1.43231,-1.69980,-0.01008,2.67129,0.00185
-8.58162,0.46796,-1.43246,-1.70028,-0.00945,2.67138,0.00184
-8.58281,0.46787,-1.43261,-1.70075,-0.00884,2.67148,0.00183
-8.58400,0.46777,-1.43276,-1.70122,-0.00823,2.67157,0.00183
-8.58519,0.46768,-1.43291,-1.70167,-0.00763,2.67166,0.00182
-8.58637,0.46759,-1.43305,-1.70212,-0.00705,2.67175,0.00182
-8.58756,0.46750,-1.43319,-1.70256,-0.00647,2.67183,0.00181
-8.58875,0.46741,-1.43333,-1.70299,-0.00590,2.67192,0.00181
-8.58994,0.46732,-1.43347,-1.70342,-0.00535,2.67200,0.00180
-8.59113,0.46724,-1.43360,-1.70384,-0.00480,2.67208,0.00180
-8.59232,0.46715,-1.43373,-1.70425,-0.00426,2.67216,0.00180
-8.59351,0.46707,-1.43386,-1.70465,-0.00373,2.67224,0.00180
-8.59470,0.46699,-1.43399,-1.70504,-0.00321,2.67232,0.00179
-8.59589,0.46691,-1.43411,-1.70543,-0.00270,2.67240,0.00179
-8.59708,0.46683,-1.43424,-1.70581,-0.00219,2.67247,0.00179
-8.59826,0.46676,-1.43436,-1.70619,-0.00170,2.67255,0.00179
-8.59945,0.46668,-1.43448,-1.70655,-0.00121,2.67262,0.00179
-8.60064,0.46661,-1.43459,-1.70692,-0.00073,2.67269,0.00179
-8.60183,0.46653,-1.43471,-1.70727,-0.00026,2.67276,0.00179
-8.60302,0.46648,-1.43479,-1.70754,0.00009,2.67281,0.00179
-8.60421,0.46640,-1.43493,-1.70810,0.00078,2.67289,0.00178
-8.60540,0.46632,-1.43506,-1.70865,0.00146,2.67297,0.00178
-8.60659,0.46623,-1.43519,-1.70920,0.00212,2.67305,0.00177
-8.60778,0.46615,-1.43532,-1.70973,0.00278,2.67312,0.00176
-8.60896,0.46608,-1.43545,-1.71025,0.00343,2.67320,0.00175
-8.61015,0.46600,-1.43558,-1.71077,0.00406,2.67327,0.00175
-8.61134,0.46592,-1.43570,-1.71127,0.00468,2.67334,0.00174
-8.61253,0.46585,-1.43582,-1.71177,0.00530,2.67341,0.00174
-8.61372,0.46578,-1.43594,-1.71226,0.00590,2.67348,0.00174
-8.61491,0.46570,-1.43606,-1.71273,0.00649,2.67355,0.00173
-8.61610,0.46563,-1.43618,-1.71321,0.00708,2.67361,0.00173
-8.61729,0.46557,-1.43629,-1.71367,0.00765,2.67368,0.00173
-8.61848,0.46550,-1.43640,-1.71412,0.00821,2.67374,0.00172
-8.61966,0.46543,-1.43651,-1.71457,0.00877,2.67381,0.00172
-8.62085,0.46537,-1.43662,-1.71500,0.00931,2.67387,0.00172
-8.62204,0.46530,-1.43673,-1.71543,0.00985,2.67393,0.00172
-8.62323,0.46524,-1.43683,-1.71586,0.01037,2.67399,0.00172
-8.62442,0.46518,-1.43693,-1.71627,0.01089,2.67405,0.00172
-8.62561,0.46512,-1.43703,-1.71668,0.01140,2.67410,0.00172
-8.62680,0.46506,-1.43713,-1.71708,0.01190,2.67416,0.00172
-8.62799,0.46500,-1.43723,-1.71747,0.01239,2.67422,0.00172
-8.62918,0.46494,-1.43732,-1.71786,0.01288,2.67427,0.00173
-8.63036,0.46488,-1.43742,-1.71824,0.01335,2.67432,0.00173
-8.63155,0.46483,-1.43751,-1.71863,0.01384,2.67438,0.00173
-8.63274,0.46476,-1.43763,-1.71913,0.01445,2.67444,0.00172
-8.63393,0.46470,-1.43774,-1.71963,0.01506,2.67450,0.00172
-8.63512,0.46463,-1.43785,-1.72012,0.01566,2.67456,0.00172
-8.63631,0.46457,-1.43796,-1.72059,0.01624,2.67462,0.00171
-8.63750,0.46451,-1.43807,-1.72106,0.01682,2.67468,0.00171
-8.63869,0.46445,-1.43818,-1.72153,0.01739,2.67474,0.00171
-8.63988,0.46439,-1.43828,-1.72198,0.01794,2.67479,0.00171
-8.64107,0.46433,-1.43839,-1.72243,0.01849,2.67485,0.00171
-8.64225,0.46427,-1.43849,-1.72286,0.01903,2.67490,0.00171
-8.64344,0.46421,-1.43859,-1.72329,0.01956,2.67495,0.00171
-8.64463,0.46416,-1.43868,-1.72372,0.02008,2.67500,0.00171
-8.64582,0.46410,-1.43878,-1.72413,0.02059,2.67505,0.00171
-8.64701,0.46405,-1.43887,-1.72454,0.02109,2.67510,0.00171
-8.64820,0.46400,-1.43897,-1.72494,0.02159,2.67515,0.00171
-8.64939,0.46395,-1.43906,-1.72533,0.02208,2.67520,0.00171
-8.65058,0.46390,-1.43915,-1.72572,0.02255,2.67525,0.00171
-8.65177,0.46385,-1.43923,-1.72610,0.02303,2.67530,0.00172
-8.65295,0.46384,-1.43925,-1.72619,0.02313,2.67531,0.00172
-8.65414,0.46378,-1.43937,-1.72670,0.02375,2.67536,0.00171
-8.65533,0.46372,-1.43948,-1.72720,0.02436,2.67542,0.00171
-8.65652,0.46366,-1.43959,-1.72769,0.02496,2.67547,0.00170
-8.65771,0.46360,-1.43970,-1.72817,0.02554,2.67552,0.00170
-8.65890,0.46354,-1.43980,-1.72865,0.02612,2.67558,0.00170
-8.66009,0.46349,-1.43991,-1.72911,0.02669,2.67563,0.00170
-8.66128,0.46344,-1.44001,-1.72957,0.02725,2.67568,0.00170
-8.66247,0.46338,-1.44011,-1.73002,0.02780,2.67573,0.00170
-8.66365,0.46333,-1.44021,-1.73046,0.02834,2.67577,0.00169
-8.66484,0.46328,-1.44030,-1.73089,0.02887,2.67582,0.00169
-8.66603,0.46323,-1.44040,-1.73132,0.02939,2.67587,0.00169
-8.66722,0.46318,-1.44049,-1.73174,0.02990,2.67591,0.00170
-8.66841,0.46313,-1.44058,-1.73215,0.03041,2.67596,0.00170
-8.66960,0.46308,-1.44067,-1.73255,0.03090,2.67600,0.00170
-8.67079,0.46304,-1.44076,-1.73295,0.03139,2.67605,0.00170
-8.67198,0.46299,-1.44085,-1.73334,0.03187,2.67609,0.00170
-8.67317,0.46295,-1.44093,-1.73372,0.03234,2.67613,0.00170
-8.67436,0.46293,-1.44096,-1.73385,0.03249,2.67614,0.00171
-8.67554,0.46289,-1.44105,-1.73434,0.03307,2.67618,0.00170
-8.67673,0.46284,-1.44114,-1.73482,0.03364,2.67623,0.00170
-8.67792,0.46280,-1.44123,-1.73529,0.03419,2.67627,0.00170
-8.67911,0.46275,-1.44131,-1.73575,0.03474,2.67631,0.00170
-8.68030,0.46271,-1.44140,-1.73621,0.03528,2.67634,0.00170
-8.68149,0.46267,-1.44148,-1.73665,0.03581,2.67638,0.00170
-8.68268,0.46263,-1.44156,-1.73709,0.03633,2.67642,0.00170
-8.68387,0.46259,-1.44164,-1.73753,0.03685,2.67646,0.00170
-8.68506,0.46255,-1.44172,-1.73795,0.03735,2.67649,0.00170
-8.68624,0.46251,-1.44179,-1.73837,0.03785,2.67653,0.00170
-8.68743,0.46247,-1.44187,-1.73877,0.03833,2.67656,0.00170
-8.68862,0.46243,-1.44194,-1.73918,0.03881,2.67659,0.00171
-8.68981,0.46240,-1.44202,-1.73957,0.03928,2.67663,0.00171
-8.69100,0.46239,-1.44204,-1.73970,0.03943,2.67664,0.00171
-8.69219,0.46235,-1.44212,-1.74016,0.03997,2.67667,0.00171
-8.69338,0.46231,-1.44219,-1.74061,0.04050,2.67670,0.00171
-8.69457,0.46228,-1.44226,-1.74106,0.04102,2.67674,0.00171
-8.69576,0.46224,-1.44234,-1.74150,0.04153,2.67677,0.00171
-8.69694,0.46221,-1.44241,-1.74193,0.04203,2.67680,0.00171
-8.69813,0.46217,-1.44248,-1.74235,0.04252,2.67683,0.00171
-8.69932,0.46214,-1.44255,-1.74276,0.04301,2.67686,0.00171
-8.70051,0.46211,-1.44261,-1.74317,0.04349,2.67689,0.00172
-8.70170,0.46208,-1.44268,-1.74357,0.04396,2.67691,0.00172
-8.70289,0.46207,-1.44269,-1.74366,0.04406,2.67692,0.00172
-8.70408,0.46204,-1.44276,-1.74411,0.04458,2.67695,0.00172
-8.70527,0.46201,-1.44283,-1.74455,0.04509,2.67697,0.00172
-8.70646,0.46198,-1.44290,-1.74498,0.04559,2.67700,0.00172
-8.70764,0.46195,-1.44296,-1.74541,0.04608,2.67703,0.00172
-8.70883,0.46192,-1.44303,-1.74582,0.04656,2.67705,0.00172
-8.71002,0.46189,-1.44309,-1.74624,0.04704,2.67708,0.00173
-8.71121,0.46186,-1.44315,-1.74664,0.04751,2.67710,0.00173
-8.71240,0.46186,-1.44316,-1.74668,0.04756,2.67711,0.00173
-8.71359,0.46183,-1.44322,-1.74712,0.04806,2.67713,0.00173
-8.71478,0.46180,-1.44328,-1.74754,0.04855,2.67716,0.00173
-8.71597,0.46177,-1.44334,-1.74796,0.04903,2.67718,0.00173
-8.71716,0.46175,-1.44340,-1.74837,0.04950,2.67720,0.00173
-8.71835,0.46173,-1.44345,-1.74870,0.04988,2.67722,0.00174
-8.71953,0.46170,-1.44351,-1.74914,0.05038,2.67724,0.00174
-8.72072,0.46167,-1.44357,-1.74956,0.05087,2.67727,0.00174
-8.72191,0.46165,-1.44363,-1.74999,0.05135,2.67729,0.00174
-8.72310,0.46162,-1.44369,-1.75040,0.05182,2.67731,0.00174
-8.72429,0.46160,-1.44373,-1.75073,0.05220,2.67733,0.00174
-8.72548,0.46158,-1.44379,-1.75115,0.05268,2.67735,0.00174
-8.72667,0.46156,-1.44385,-1.75156,0.05315,2.67737,0.00175
-8.72786,0.46154,-1.44388,-1.75176,0.05338,2.67738,0.00175
-8.72905,0.46152,-1.44393,-1.75218,0.05386,2.67740,0.00175
-8.73023,0.46150,-1.44399,-1.75260,0.05433,2.67742,0.00175
-8.73142,0.46149,-1.44402,-1.75280,0.05456,2.67743,0.00175
-8.73261,0.46146,-1.44407,-1.75322,0.05504,2.67744,0.00175
-8.73380,0.46144,-1.44413,-1.75363,0.05551,2.67746,0.00175
-8.73499,0.46143,-1.44415,-1.75380,0.05570,2.67747,0.00176
-8.73618,0.46141,-1.44420,-1.75422,0.05618,2.67749,0.00176
-8.73737,0.46139,-1.44426,-1.75464,0.05665,2.67751,0.00176
-8.73856,0.46139,-1.44426,-1.75487,0.05689,2.67750,0.00176
-8.73975,0.46150,-1.44404,-1.75560,0.05740,2.67740,0.00176
-8.74093,0.46160,-1.44383,-1.75631,0.05791,2.67729,0.00177
-8.74212,0.46170,-1.44362,-1.75701,0.05840,2.67719,0.00177
-8.74331,0.46180,-1.44342,-1.75770,0.05889,2.67709,0.00178
-8.74450,0.46190,-1.44321,-1.75838,0.05937,2.67699,0.00178
-8.74569,0.46200,-1.44302,-1.75904,0.05985,2.67689,0.00179
-8.74688,0.46209,-1.44282,-1.75970,0.06031,2.67679,0.00179
-8.74807,0.46219,-1.44263,-1.76034,0.06077,2.67670,0.00180
-8.74926,0.46228,-1.44244,-1.76097,0.06122,2.67660,0.00180
-8.75045,0.46237,-1.44226,-1.76159,0.06166,2.67651,0.00181
-8.75163,0.46246,-1.44208,-1.76220,0.06209,2.67642,0.00182
-8.75282,0.46255,-1.44190,-1.76280,0.06252,2.67632,0.00182
-8.75401,0.46264,-1.44173,-1.76339,0.06294,2.67623,0.00183
-8.75520,0.46273,-1.44155,-1.76397,0.06336,2.67614,0.00183
-8.75639,0.46282,-1.44138,-1.76454,0.06376,2.67606,0.00184
-8.75758,0.46290,-1.44122,-1.76510,0.06416,2.67597,0.00185
-8.75877,0.46299,-1.44105,-1.76564,0.06455,2.67589,0.00186
-8.75996,0.46308,-1.44088,-1.76617,0.06491,2.67579,0.00186
-8.76115,0.46331,-1.44039,-1.76705,0.06531,2.67556,0.00187
-8.76234,0.46354,-1.43991,-1.76792,0.06571,2.67533,0.00188
-8.76352,0.46377,-1.43944,-1.76877,0.06611,2.67510,0.00190
-8.76471,0.46400,-1.43898,-1.76961,0.06649,2.67488,0.00191
-8.76590,0.46422,-1.43852,-1.77043,0.06687,2.67466,0.00192
-8.76709,0.46444,-1.43808,-1.77124,0.06725,2.67444,0.00193
-8.76828,0.46465,-1.43764,-1.77204,0.06762,2.67422,0.00194
-8.76947,0.46487,-1.43721,-1.77282,0.06798,2.67401,0.00195
-8.77066,0.46508,-1.43678,-1.77359,0.06833,2.67380,0.00196
-8.77185,0.46529,-1.43636,-1.77434,0.06868,2.67359,0.00197
-8.77304,0.46549,-1.43595,-1.77508,0.06902,2.67339,0.00198
-8.77422,0.46569,-1.43555,-1.77581,0.06936,2.67319,0.00199
-8.77541,0.46589,-1.43515,-1.77653,0.06969,2.67299,0.00201
-8.77660,0.46609,-1.43476,-1.77724,0.07002,2.67279,0.00202
-8.77779,0.46628,-1.43438,-1.77793,0.07034,2.67260,0.00203
-8.77898,0.46647,-1.43401,-1.77861,0.07066,2.67241,0.00204
-8.78017,0.46666,-1.43364,-1.77928,0.07097,2.67222,0.00205
-8.78136,0.46684,-1.43327,-1.77994,0.07127,2.67204,0.00206
-8.78255,0.46703,-1.43291,-1.78058,0.07157,2.67185,0.00207
-8.78374,0.46720,-1.43256,-1.78122,0.07187,2.67167,0.00208
-8.78492,0.46738,-1.43222,-1.78184,0.07216,2.67150,0.00209
-8.78611,0.46756,-1.43188,-1.78246,0.07244,2.67132,0.00210
-8.78730,0.46773,-1.43154,-1.78306,0.07272,2.67115,0.00211
-8.78849,0.46790,-1.43122,-1.78365,0.07300,2.67098,0.00212
-8.78968,0.46807,-1.43089,-1.78424,0.07327,2.67081,0.00213
-8.79087,0.46823,-1.43058,-1.78481,0.07353,2.67064,0.00214
-8.79206,0.46839,-1.43026,-1.78537,0.07379,2.67048,0.00215
-8.79325,0.46855,-1.42996,-1.78593,0.07405,2.67032,0.00216
-8.79444,0.46861,-1.42985,-1.78605,0.07407,2.67027,0.00216
-8.79562,0.46911,-1.42882,-1.78722,0.07424,2.66977,0.00219
-8.79681,0.46960,-1.42781,-1.78838,0.07441,2.66928,0.00221
-8.79800,0.47009,-1.42682,-1.78952,0.07457,2.66880,0.00223
-8.79919,0.47057,-1.42584,-1.79063,0.07474,2.66833,0.00226
-8.80038,0.47105,-1.42488,-1.79173,0.07489,2.66786,0.00228
-8.80157,0.47152,-1.42393,-1.79281,0.07505,2.66739,0.00230
-8.80276,0.47198,-1.42300,-1.79387,0.07520,2.66693,0.00232
-8.80395,0.47244,-1.42209,-1.79491,0.07535,2.66648,0.00234
-8.80514,0.47289,-1.42119,-1.79593,0.07549,2.66604,0.00236
-8.80633,0.47333,-1.42031,-1.79694,0.07563,2.66560,0.00238
-8.80751,0.47377,-1.41944,-1.79793,0.07577,2.66516,0.00240
-8.80870,0.47420,-1.41859,-1.79890,0.07591,2.66473,0.00242
-8.80989,0.47463,-1.41775,-1.79985,0.07604,2.66431,0.00244
-8.81108,0.47505,-1.41692,-1.80079,0.07617,2.66389,0.00245
-8.81227,0.47547,-1.41611,-1.80171,0.07630,2.66348,0.00247
-8.81346,0.47588,-1.41532,-1.80262,0.07643,2.66308,0.00249
-8.81465,0.47628,-1.41453,-1.80351,0.07655,2.66267,0.00250
-8.81584,0.47668,-1.41376,-1.80438,0.07667,2.66228,0.00252
-8.81703,0.47707,-1.41301,-1.80524,0.07679,2.66189,0.00254
-8.81821,0.47746,-1.41226,-1.80609,0.07690,2.66150,0.00255
-8.81940,0.47784,-1.41153,-1.80692,0.07701,2.66112,0.00257
-8.82059,0.47822,-1.41081,-1.80773,0.07713,2.66075,0.00258
-8.82178,0.47859,-1.41010,-1.80853,0.07723,2.66038,0.00259
-8.82297,0.47896,-1.40941,-1.80932,0.07734,2.66001,0.00261
-8.82416,0.47932,-1.40872,-1.81010,0.07744,2.65965,0.00262
-8.82535,0.47968,-1.40805,-1.81086,0.07755,2.65930,0.00263
-8.82654,0.48003,-1.40739,-1.81161,0.07765,2.65895,0.00265
-8.82773,0.48038,-1.40674,-1.81234,0.07774,2.65860,0.00266
-8.82891,0.48072,-1.40611,-1.81306,0.07784,2.65826,0.00267
-8.83010,0.48106,-1.40548,-1.81377,0.07793,2.65792,0.00268
-8.83129,0.48139,-1.40486,-1.81447,0.07803,2.65759,0.00269
-8.83248,0.48172,-1.40426,-1.81516,0.07812,2.65727,0.00270
-8.83367,0.48204,-1.40366,-1.81583,0.07820,2.65694,0.00272
-8.83486,0.48236,-1.40307,-1.81649,0.07829,2.65662,0.00273
-8.83605,0.48267,-1.40250,-1.81714,0.07838,2.65631,0.00274
-8.83724,0.48298,-1.40193,-1.81778,0.07846,2.65600,0.00275
-8.83843,0.48329,-1.40138,-1.81841,0.07854,2.65569,0.00276
-8.83961,0.48359,-1.40083,-1.81903,0.07862,2.65539,0.00277
-8.84080,0.48389,-1.40029,-1.81964,0.07870,2.65510,0.00277
-8.84199,0.48418,-1.39976,-1.82024,0.07878,2.65480,0.00278
-8.84318,0.48447,-1.39924,-1.82082,0.07885,2.65451,0.00279
-8.84437,0.48475,-1.39873,-1.82140,0.07893,2.65423,0.00280
-8.84556,0.48503,-1.39823,-1.82197,0.07900,2.65395,0.00281
-8.84675,0.48531,-1.39774,-1.82252,0.07907,2.65367,0.00282
-8.84794,0.48558,-1.39725,-1.82307,0.07914,2.65340,0.00283
-8.84913,0.48585,-1.39677,-1.82361,0.07921,2.65313,0.00283
-8.85032,0.48612,-1.39630,-1.82414,0.07928,2.65286,0.00284
-8.85150,0.48638,-1.39584,-1.82466,0.07934,2.65260,0.00285
-8.85269,0.48664,-1.39539,-1.82517,0.07941,2.65234,0.00285
-8.85388,0.48689,-1.39494,-1.82568,0.07947,2.65209,0.00286
-8.85507,0.48714,-1.39451,-1.82617,0.07953,2.65183,0.00287
-8.85626,0.48739,-1.39408,-1.82666,0.07959,2.65159,0.00287
-8.85745,0.48763,-1.39365,-1.82713,0.07965,2.65134,0.00288
-8.85864,0.48791,-1.39315,-1.82766,0.07969,2.65106,0.00289
-8.85983,0.48856,-1.39192,-1.82873,0.07955,2.65042,0.00291
-8.86102,0.48920,-1.39071,-1.82977,0.07941,2.64979,0.00294
-8.86220,0.48983,-1.38951,-1.83080,0.07926,2.64917,0.00296
-8.86339,0.49045,-1.38834,-1.83181,0.07912,2.64856,0.00299
-8.86458,0.49106,-1.38719,-1.83280,0.07898,2.64795,0.00301
-8.86577,0.49167,-1.38606,-1.83377,0.07884,2.64735,0.00303
-8.86696,0.49227,-1.38494,-1.83473,0.07871,2.64676,0.00305
-8.86815,0.49286,-1.38385,-1.83567,0.07857,2.64618,0.00307
-8.86934,0.49344,-1.38277,-1.83659,0.07844,2.64560,0.00309
-8.87053,0.49402,-1.38171,-1.83750,0.07830,2.64503,0.00311
-8.87172,0.49458,-1.38067,-1.83839,0.07817,2.64447,0.00313
-8.87290,0.49514,-1.37965,-1.83927,0.07804,2.64391,0.00314
-8.87409,0.49570,-1.37864,-1.84013,0.07791,2.64337,0.00316
-8.87528,0.49624,-1.37765,-1.84097,0.07778,2.64283,0.00317
-8.87647,0.49678,-1.37668,-1.84180,0.07765,2.64229,0.00319
-8.87766,0.49731,-1.37573,-1.84262,0.07753,2.64177,0.00320
-8.87885,0.49783,-1.37479,-1.84342,0.07740,2.64125,0.00322
-8.88004,0.49835,-1.37386,-1.84421,0.07728,2.64073,0.00323
-8.88123,0.49886,-1.37295,-1.84498,0.07716,2.64023,0.00324
-8.88242,0.49937,-1.37206,-1.84574,0.07704,2.63973,0.00326
-8.88360,0.49986,-1.37118,-1.84649,0.07692,2.63924,0.00327
-8.88479,0.50035,-1.37032,-1.84722,0.07680,2.63875,0.00328
-8.88598,0.50083,-1.36947,-1.84795,0.07668,2.63827,0.00329
-8.88717,0.50131,-1.36864,-1.84865,0.07656,2.63779,0.00330
-8.88836,0.50178,-1.36782,-1.84935,0.07645,2.63733,0.00331
-8.88955,0.50225,-1.36701,-1.85004,0.07634,2.63686,0.00332
-8.89074,0.50270,-1.36622,-1.85071,0.07623,2.63641,0.00333
-8.89193,0.50316,-1.36544,-1.85137,0.07612,2.63596,0.00334
-8.89312,0.50360,-1.36468,-1.85202,0.07601,2.63552,0.00335
-8.89431,0.50404,-1.36393,-1.85266,0.07590,2.63508,0.00336
-8.89549,0.50447,-1.36319,-1.85328,0.07579,2.63465,0.00336
-8.89668,0.50490,-1.36246,-1.85390,0.07569,2.63422,0.00337
-8.89787,0.50532,-1.36174,-1.85451,0.07558,2.63380,0.00338
-8.89906,0.50574,-1.36104,-1.85510,0.07548,2.63338,0.00338
-8.90025,0.50615,-1.36035,-1.85569,0.07538,2.63298,0.00339
-8.90144,0.50655,-1.35967,-1.85626,0.07528,2.63257,0.00340
-8.90263,0.50695,-1.35900,-1.85683,0.07518,2.63217,0.00340
-8.90382,0.50735,-1.35834,-1.85738,0.07508,2.63178,0.00341
-8.90501,0.50774,-1.35770,-1.85793,0.07499,2.63139,0.00341
-8.90619,0.50812,-1.35706,-1.85846,0.07489,2.63101,0.00342
-8.90738,0.50850,-1.35644,-1.85899,0.07480,2.63063,0.00342
-8.90857,0.50887,-1.35583,-1.85951,0.07470,2.63026,0.00343
-8.90976,0.50924,-1.35522,-1.86002,0.07461,2.62989,0.00343
-8.91095,0.50960,-1.35463,-1.86052,0.07452,2.62953,0.00343
-8.91214,0.50996,-1.35405,-1.86101,0.07443,2.62917,0.00344
-8.91333,0.51031,-1.35348,-1.86149,0.07435,2.62882,0.00344
-8.91452,0.51066,-1.35291,-1.86197,0.07426,2.62847,0.00344
-8.91571,0.51100,-1.35236,-1.86244,0.07417,2.62813,0.00345
-8.91689,0.51134,-1.35181,-1.86290,0.07409,2.62779,0.00345
-8.91808,0.51167,-1.35128,-1.86335,0.07401,2.62746,0.00345
-8.91927,0.51200,-1.35075,-1.86379,0.07392,2.62713,0.00345
-8.92046,0.51232,-1.35024,-1.86423,0.07384,2.62680,0.00346
-8.92165,0.51264,-1.34973,-1.86466,0.07376,2.62648,0.00346
-8.92284,0.51296,-1.34923,-1.86508,0.07368,2.62617,0.00346
-8.92403,0.51327,-1.34874,-1.86549,0.07361,2.62585,0.00346
-8.92522,0.51357,-1.34825,-1.86590,0.07353,2.62555,0.00346
-8.92641,0.51387,-1.34778,-1.86630,0.07346,2.62524,0.00346
-8.92759,0.51417,-1.34731,-1.86669,0.07338,2.62494,0.00346
-8.92878,0.51447,-1.34685,-1.86708,0.07331,2.62465,0.00346
-8.92997,0.51476,-1.34640,-1.86746,0.07324,2.62436,0.00347
-8.93116,0.51479,-1.34634,-1.86751,0.07322,2.62432,0.00347
-8.93235,0.51518,-1.34571,-1.86802,0.07311,2.62394,0.00347
-8.93354,0.51556,-1.34510,-1.86851,0.07299,2.62356,0.00347
-8.93473,0.51593,-1.34449,-1.86900,0.07288,2.62319,0.00348
-8.93592,0.51630,-1.34390,-1.86949,0.07277,2.62282,0.00348
-8.93711,0.51666,-1.34331,-1.86996,0.07266,2.62246,0.00348
-8.93830,0.51702,-1.34274,-1.87042,0.07255,2.62210,0.00349
-8.93948,0.51737,-1.34217,-1.87088,0.07245,2.62175,0.00349
-8.94067,0.51772,-1.34162,-1.87133,0.07234,2.62140,0.00349
-8.94186,0.51806,-1.34107,-1.87177,0.07224,2.62106,0.00350
-8.94305,0.51840,-1.34053,-1.87221,0.07214,2.62072,0.00350
-8.94424,0.51873,-1.34001,-1.87263,0.07204,2.62039,0.00350
-8.94543,0.51906,-1.33949,-1.87305,0.07194,2.62006,0.00350
-8.94662,0.51939,-1.33898,-1.87346,0.07184,2.61973,0.00350
-8.94781,0.51971,-1.33848,-1.87387,0.07174,2.61941,0.00350
-8.94900,0.52002,-1.33798,-1.87427,0.07165,2.61910,0.00351
-8.95018,0.52033,-1.33750,-1.87466,0.07155,2.61878,0.00351
-8.95137,0.52064,-1.33702,-1.87505,0.07146,2.61848,0.00351
-8.95256,0.52094,-1.33655,-1.87542,0.07137,2.61817,0.00351
-8.95375,0.52124,-1.33609,-1.87580,0.07128,2.61787,0.00351
-8.95494,0.52151,-1.33567,-1.87613,0.07119,2.61760,0.00351
-8.95613,0.52215,-1.33459,-1.87695,0.07095,2.61697,0.00352
-8.95732,0.52278,-1.33353,-1.87776,0.07070,2.61635,0.00354
-8.95851,0.52340,-1.33249,-1.87855,0.07046,2.61574,0.00355
-8.95970,0.52401,-1.33146,-1.87932,0.07022,2.61513,0.00356
-8.96088,0.52461,-1.33046,-1.88008,0.06999,2.61454,0.00357
-8.96207,0.52521,-1.32947,-1.88083,0.06975,2.61394,0.00358
-8.96326,0.52580,-1.32849,-1.88157,0.06952,2.61336,0.00359
-8.96445,0.52638,-1.32754,-1.88229,0.06930,2.61278,0.00360
-8.96564,0.52696,-1.32660,-1.88300,0.06907,2.61222,0.00361
-8.96683,0.52752,-1.32567,-1.88370,0.06885,2.61165,0.00362
-8.96802,0.52808,-1.32476,-1.88439,0.06864,2.61110,0.00363
-8.96921,0.52863,-1.32387,-1.88506,0.06842,2.61055,0.00363
-8.97040,0.52918,-1.32299,-1.88572,0.06821,2.61001,0.00364
-8.97158,0.52972,-1.32212,-1.88637,0.06800,2.60948,0.00365
-8.97277,0.53025,-1.32127,-1.88701,0.06779,2.60895,0.00365
-8.97396,0.53077,-1.32044,-1.88764,0.06759,2.60843,0.00366
-8.97515,0.53129,-1.31961,-1.88825,0.06738,2.60792,0.00366
-8.97634,0.53180,-1.31881,-1.88886,0.06719,2.60741,0.00367
-8.97753,0.53230,-1.31801,-1.88946,0.06699,2.60691,0.00367
-8.97872,0.53280,-1.31723,-1.89004,0.06680,2.60642,0.00368
-8.97991,0.53329,-1.31646,-1.89062,0.06661,2.60593,0.00368
-8.98110,0.53377,-1.31571,-1.89118,0.06642,2.60545,0.00369
-8.98229,0.53425,-1.31497,-1.89174,0.06623,2.60497,0.00369
-8.98347,0.53472,-1.31424,-1.89228,0.06605,2.60450,0.00369
-8.98466,0.53518,-1.31352,-1.89282,0.06587,2.60404,0.00370
-8.98585,0.53564,-1.31281,-1.89335,0.06569,2.60358,0.00370
-8.98704,0.53609,-1.31212,-1.89387,0.06551,2.60313,0.00370
-8.98823,0.53654,-1.31144,-1.89438,0.06534,2.60269,0.00370
-8.98942,0.53698,-1.31076,-1.89488,0.06517,2.60225,0.00370
-8.99061,0.53742,-1.31010,-1.89537,0.06500,2.60182,0.00371
-8.99180,0.53784,-1.30946,-1.89585,0.06484,2.60139,0.00371
-8.99299,0.53827,-1.30882,-1.89633,0.06467,2.60097,0.00371
-8.99417,0.53868,-1.30819,-1.89679,0.06451,2.60055,0.00371
-8.99536,0.53910,-1.30758,-1.89725,0.06435,2.60014,0.00371
-8.99655,0.53950,-1.30697,-1.89770,0.06419,2.59973,0.00371
-8.99774,0.53990,-1.30637,-1.89815,0.06404,2.59933,0.00371
-8.99893,0.54030,-1.30579,-1.89858,0.06389,2.59894,0.00371
-9.00012,0.54069,-1.30521,-1.89901,0.06374,2.59855,0.00371
-9.00131,0.54107,-1.30464,-1.89943,0.06359,2.59816,0.00371
-9.00250,0.54145,-1.30409,-1.89984,0.06344,2.59778,0.00371
-9.00369,0.54183,-1.30354,-1.90025,0.06330,2.59741,0.00371
-9.00487,0.54220,-1.30300,-1.90065,0.06316,2.59704,0.00371
-9.00606,0.54256,-1.30247,-1.90104,0.06302,2.59667,0.00371
-9.00725,0.54292,-1.30195,-1.90143,0.06288,2.59631,0.00371
-9.00844,0.54328,-1.30144,-1.90181,0.06275,2.59596,0.00371
-9.00963,0.54363,-1.30094,-1.90218,0.06261,2.59561,0.00370
-9.01082,0.54397,-1.30044,-1.90255,0.06248,2.59526,0.00370
-9.01201,0.54431,-1.29995,-1.90291,0.06235,2.59492,0.00370
-9.01320,0.54465,-1.29948,-1.90327,0.06222,2.59459,0.00370
-9.01439,0.54498,-1.29900,-1.90361,0.06210,2.59425,0.00370
-9.01557,0.54530,-1.29854,-1.90396,0.06197,2.59393,0.00370
-9.01676,0.54549,-1.29828,-1.90416,0.06190,2.59374,0.00370
-9.01795,0.54602,-1.29746,-1.90478,0.06171,2.59321,0.00370
-9.01914,0.54655,-1.29665,-1.90540,0.06153,2.59269,0.00370
-9.02033,0.54707,-1.29586,-1.90601,0.06134,2.59217,0.00371
-9.02152,0.54759,-1.29508,-1.90660,0.06116,2.59166,0.00371
-9.02271,0.54809,-1.29432,-1.90719,0.06098,2.59115,0.00371
-9.02390,0.54859,-1.29357,-1.90776,0.06080,2.59066,0.00371
-9.02509,0.54909,-1.29283,-1.90833,0.06063,2.59016,0.00372
-9.02628,0.54958,-1.29210,-1.90888,0.06046,2.58968,0.00372
-9.02746,0.55006,-1.29138,-1.90943,0.06029,2.58920,0.00372
-9.02865,0.55054,-1.29068,-1.90996,0.06012,2.58873,0.00372
-9.02984,0.55100,-1.28999,-1.91049,0.05995,2.58826,0.00372
-9.03103,0.55147,-1.28931,-1.91101,0.05979,2.58780,0.00372
-9.03222,0.55192,-1.28864,-1.91152,0.05963,2.58734,0.00372
-9.03341,0.55238,-1.28798,-1.91202,0.05947,2.58689,0.00373
-9.03460,0.55282,-1.28734,-1.91251,0.05931,2.58645,0.00373
-9.03579,0.55326,-1.28670,-1.91299,0.05916,2.58601,0.00373
-9.03698,0.55369,-1.28607,-1.91347,0.05900,2.58558,0.00373
-9.03816,0.55412,-1.28546,-1.91394,0.05885,2.58515,0.00373
-9.03935,0.55454,-1.28485,-1.91440,0.05871,2.58473,0.00373
-9.04054,0.55496,-1.28426,-1.91485,0.05856,2.58431,0.00373
-9.04173,0.55537,-1.28367,-1.91529,0.05842,2.58390,0.00372
-9.04292,0.55578,-1.28310,-1.91573,0.05827,2.58350,0.00372
-9.04411,0.55618,-1.28253,-1.91615,0.05813,2.58310,0.00372
-9.04530,0.55657,-1.28198,-1.91658,0.05799,2.58270,0.00372
-9.04649,0.55696,-1.28143,-1.91699,0.05786,2.58232,0.00372
-9.04768,0.55735,-1.28089,-1.91740,0.05772,2.58193,0.00372
-9.04886,0.55772,-1.28036,-1.91780,0.05759,2.58155,0.00372
-9.05005,0.55810,-1.27984,-1.91819,0.05746,2.58118,0.00372
-9.05124,0.55847,-1.27933,-1.91858,0.05733,2.58081,0.00372
-9.05243,0.55883,-1.27883,-1.91896,0.05720,2.58044,0.00371
-9.05362,0.55919,-1.27834,-1.91933,0.05708,2.58008,0.00371
-9.05481,0.55955,-1.27785,-1.91970,0.05696,2.57973,0.00371
-9.05600,0.55990,-1.27737,-1.92006,0.05683,2.57938,0.00371
-9.05719,0.56024,-1.27690,-1.92041,0.05671,2.57903,0.00371
-9.05838,0.56058,-1.27644,-1.92076,0.05660,2.57869,0.00370
-9.05956,0.56081,-1.27612,-1.92100,0.05652,2.57846,0.00370
-9.06075,0.56139,-1.27526,-1.92165,0.05631,2.57789,0.00371
-9.06194,0.56197,-1.27442,-1.92230,0.05611,2.57732,0.00371
-9.06313,0.56254,-1.27358,-1.92293,0.05591,2.57675,0.00371
-9.06432,0.56310,-1.27276,-1.92355,0.05571,2.57620,0.00372
-9.06551,0.56365,-1.27196,-1.92416,0.05552,2.57565,0.00372
-9.06670,0.56420,-1.27117,-1.92476,0.05533,2.57510,0.00372
-9.06789,0.56474,-1.27039,-1.92535,0.05514,2.57457,0.00373
-9.06908,0.56527,-1.26962,-1.92593,0.05495,2.57404,0.00373
-9.07027,0.56580,-1.26887,-1.92650,0.05476,2.57351,0.00373
-9.07145,0.56631,-1.26813,-1.92706,0.05458,2.57300,0.00373
-9.07264,0.56683,-1.26740,-1.92761,0.05440,2.57249,0.00373
-9.07383,0.56733,-1.26668,-1.92815,0.05422,2.57198,0.00374
-9.07502,0.56783,-1.26598,-1.92868,0.05405,2.57149,0.00374
-9.07621,0.56833,-1.26528,-1.92920,0.05388,2.57100,0.00374
-9.07740,0.56881,-1.26460,-1.92971,0.05371,2.57051,0.00374
-9.07859,0.56929,-1.26393,-1.93022,0.05354,2.57003,0.00374
-9.07978,0.56977,-1.26327,-1.93071,0.05337,2.56956,0.00374
-9.08097,0.57024,-1.26262,-1.93120,0.05321,2.56909,0.00374
-9.08215,0.57070,-1.26198,-1.93168,0.05305,2.56863,0.00374
-9.08334,0.57116,-1.26136,-1.93215,0.05289,2.56818,0.00374
-9.08453,0.57161,-1.26074,-1.93261,0.05273,2.56773,0.00374
-9.08572,0.57205,-1.26013,-1.93307,0.05257,2.56729,0.00374
-9.08691,0.57249,-1.25954,-1.93352,0.05242,2.56685,0.00374
-9.08810,0.57292,-1.25895,-1.93395,0.05227,2.56642,0.00374
-9.08929,0.57335,-1.25837,-1.93439,0.05212,2.56599,0.00374
-9.09048,0.57377,-1.25781,-1.93481,0.05198,2.56557,0.00374
-9.09167,0.57419,-1.25725,-1.93523,0.05183,2.56515,0.00373
-9.09285,0.57460,-1.25670,-1.93564,0.05169,2.56474,0.00373
-9.09404,0.57500,-1.25616,-1.93604,0.05155,2.56434,0.00373
-9.09523,0.57540,-1.25563,-1.93644,0.05141,2.56394,0.00373
-9.09642,0.57580,-1.25510,-1.93683,0.05127,2.56354,0.00373
-9.09761,0.57619,-1.25459,-1.93721,0.05114,2.56315,0.00373
-9.09880,0.57657,-1.25409,-1.93759,0.05100,2.56277,0.00373
-9.09999,0.57695,-1.25359,-1.93796,0.05087,2.56239,0.00372
-9.10118,0.57733,-1.25310,-1.93832,0.05074,2.56201,0.00372
-9.10237,0.57770,-1.25262,-1.93868,0.05062,2.56164,0.00372
-9.10355,0.57806,-1.25215,-1.93903,0.05049,2.56128,0.00372
-9.10474,0.57842,-1.25168,-1.93937,0.05037,2.56092,0.00372
-9.10593,0.57879,-1.25119,-1.93973,0.05023,2.56055,0.00372
-9.10712,0.57964,-1.24995,-1.94058,0.04984,2.55971,0.00373
-9.10831,0.58048,-1.24873,-1.94141,0.04946,2.55888,0.00374
-9.10950,0.58131,-1.24753,-1.94222,0.04909,2.55806,0.00375
-9.11069,0.58213,-1.24635,-1.94302,0.04872,2.55725,0.00376
-9.11188,0.58294,-1.24519,-1.94381,0.04835,2.55645,0.00377
-9.11307,0.58374,-1.24404,-1.94458,0.04799,2.55566,0.00378
-9.11426,0.58453,-1.24292,-1.94534,0.04763,2.55488,0.00379
-9.11544,0.58532,-1.24181,-1.94609,0.04728,2.55410,0.00380
-9.11663,0.58609,-1.24073,-1.94682,0.04693,2.55334,0.00381
-9.11782,0.58685,-1.23966,-1.94754,0.04658,2.55258,0.00381
-9.11901,0.58761,-1.23861,-1.94825,0.04624,2.55184,0.00382
-9.12020,0.58835,-1.23757,-1.94894,0.04591,2.55110,0.00383
-9.12139,0.58909,-1.23655,-1.94963,0.04558,2.55037,0.00384
-9.12258,0.58982,-1.23555,-1.95030,0.04525,2.54965,0.00384
-9.12377,0.59054,-1.23457,-1.95096,0.04492,2.54894,0.00385
-9.12496,0.59125,-1.23360,-1.95160,0.04461,2.54823,0.00385
-9.12614,0.59195,-1.23265,-1.95224,0.04429,2.54754,0.00386
-9.12733,0.59264,-1.23171,-1.95287,0.04398,2.54685,0.00386
-9.12852,0.59332,-1.23079,-1.95348,0.04367,2.54617,0.00386
-9.12971,0.59400,-1.22988,-1.95408,0.04337,2.54550,0.00387
-9.13090,0.59467,-1.22899,-1.95468,0.04307,2.54484,0.00387
-9.13209,0.59533,-1.22811,-1.95526,0.04278,2.54418,0.00388
-9.13328,0.59598,-1.22725,-1.95583,0.04249,2.54353,0.00388
-9.13447,0.59662,-1.22640,-1.95639,0.04220,2.54289,0.00388
-9.13566,0.59726,-1.22557,-1.95695,0.04192,2.54226,0.00388
-9.13684,0.59789,-1.22475,-1.95749,0.04164,2.54164,0.00388
-9.13803,0.59851,-1.22394,-1.95802,0.04137,2.54102,0.00389
-9.13922,0.59912,-1.22314,-1.95855,0.04109,2.54041,0.00389
-9.14041,0.59973,-1.22236,-1.95907,0.04083,2.53981,0.00389
-9.14160,0.60033,-1.22159,-1.95957,0.04056,2.53921,0.00389
-9.14279,0.60092,-1.22084,-1.96007,0.04030,2.53863,0.00389
-9.14398,0.60150,-1.22009,-1.96056,0.04005,2.53805,0.00389
-9.14517,0.60208,-1.21936,-1.96104,0.03979,2.53747,0.00389
-9.14636,0.60265,-1.21864,-1.96151,0.03954,2.53690,0.00389
-9.14754,0.60321,-1.21793,-1.96198,0.03930,2.53634,0.00389
-9.14873,0.60376,-1.21724,-1.96244,0.03905,2.53579,0.00389
-9.14992,0.60431,-1.21655,-1.96289,0.03881,2.53525,0.00389
-9.15111,0.60485,-1.21588,-1.96333,0.03858,2.53471,0.00389
-9.15230,0.60539,-1.21522,-1.96376,0.03834,2.53417,0.00389
-9.15349,0.60591,-1.21456,-1.96419,0.03811,2.53365,0.00389
-9.15468,0.60643,-1.21392,-1.96461,0.03789,2.53313,0.00389
-9.15587,0.60695,-1.21329,-1.96502,0.03766,2.53261,0.00389
-9.15706,0.60746,-1.21267,-1.96542,0.03744,2.53210,0.00388
-9.15825,0.60796,-1.21206,-1.96582,0.03723,2.53160,0.00388
-9.15943,0.60846,-1.21146,-1.96621,0.03701,2.53111,0.00388
-9.16062,0.60894,-1.21087,-1.96660,0.03680,2.53062,0.00388
-9.16181,0.60943,-1.21029,-1.96698,0.03659,2.53014,0.00388
-9.16300,0.60990,-1.20971,-1.96735,0.03639,2.52966,0.00387
-9.16419,0.61038,-1.20915,-1.96771,0.03619,2.52919,0.00387
-9.16538,0.61084,-1.20860,-1.96807,0.03599,2.52872,0.00387
-9.16657,0.61130,-1.20805,-1.96843,0.03579,2.52826,0.00387
-9.16776,0.61175,-1.20752,-1.96878,0.03560,2.52781,0.00387
-9.16895,0.61220,-1.20699,-1.96912,0.03540,2.52736,0.00386
-9.17013,0.61264,-1.20647,-1.96945,0.03522,2.52692,0.00386
-9.17132,0.61308,-1.20596,-1.96978,0.03503,2.52648,0.00386
-9.17251,0.61351,-1.20546,-1.97011,0.03485,2.52605,0.00385
-9.17370,0.61394,-1.20496,-1.97043,0.03467,2.52562,0.00385
-9.17489,0.61436,-1.20448,-1.97074,0.03449,2.52520,0.00385
-9.17608,0.61477,-1.20400,-1.97105,0.03431,2.52479,0.00385
-9.17727,0.61518,-1.20353,-1.97135,0.03414,2.52437,0.00384
-9.17846,0.61559,-1.20307,-1.97165,0.03397,2.52397,0.00384
-9.17965,0.61576,-1.20287,-1.97179,0.03390,2.52380,0.00384
-9.18083,0.61629,-1.20223,-1.97223,0.03370,2.52327,0.00384
-9.18202,0.61681,-1.20160,-1.97267,0.03350,2.52275,0.00384
-9.18321,0.61732,-1.20098,-1.97310,0.03331,2.52224,0.00384
-9.18440,0.61783,-1.20037,-1.97352,0.03312,2.52174,0.00383
-9.18559,0.61833,-1.19977,-1.97394,0.03293,2.52124,0.00383
-9.18678,0.61882,-1.19918,-1.97434,0.03274,2.52074,0.00383
-9.18797,0.61931,-1.19860,-1.97474,0.03256,2.52026,0.00383
-9.18916,0.61979,-1.19803,-1.97514,0.03238,2.51977,0.00383
-9.19035,0.62027,-1.19747,-1.97553,0.03220,2.51930,0.00383
-9.19153,0.62074,-1.19691,-1.97591,0.03202,2.51883,0.00382
-9.19272,0.62120,-1.19637,-1.97628,0.03185,2.51836,0.00382
-9.19391,0.62166,-1.19583,-1.97665,0.03168,2.51791,0.00382
-9.19510,0.62211,-1.19531,-1.97701,0.03151,2.51745,0.00382
-9.19629,0.62256,-1.19479,-1.97737,0.03134,2.51701,0.00381
-9.19748,0.62300,-1.19428,-1.97772,0.03118,2.51656,0.00381
-9.19867,0.62344,-1.19378,-1.97806,0.03101,2.51613,0.00381
-9.19986,0.62387,-1.19329,-1.97840,0.03085,2.51570,0.00381
-9.20105,0.62429,-1.19280,-1.97874,0.03070,2.51527,0.00380
-9.20224,0.62471,-1.19232,-1.97906,0.03054,2.51485,0.00380
-9.20342,0.62513,-1.19185,-1.97939,0.03039,2.51444,0.00380
-9.20461,0.62554,-1.19139,-1.97970,0.03023,2.51403,0.00380
-9.20580,0.62584,-1.19103,-1.97993,0.03011,2.51373,0.00380
-9.20699,0.62682,-1.18976,-1.98069,0.02960,2.51276,0.00381
-9.20818,0.62778,-1.18851,-1.98143,0.02910,2.51181,0.00382
-9.20937,0.62873,-1.18728,-1.98216,0.02860,2.51087,0.00383
-9.21056,0.62968,-1.18606,-1.98287,0.02811,2.50994,0.00384
-9.21175,0.63061,-1.18487,-1.98357,0.02763,2.50902,0.00385
-9.21294,0.63153,-1.18370,-1.98426,0.02715,2.50811,0.00386
-9.21412,0.63245,-1.18254,-1.98494,0.02668,2.50721,0.00387
-9.21531,0.63335,-1.18140,-1.98560,0.02621,2.50632,0.00388
-9.21650,0.63424,-1.18029,-1.98626,0.02575,2.50544,0.00389
-9.21769,0.63512,-1.17919,-1.98690,0.02530,2.50457,0.00390
-9.21888,0.63599,-1.17810,-1.98753,0.02485,2.50370,0.00390
-9.22007,0.63686,-1.17704,-1.98815,0.02441,2.50285,0.00391
-9.22126,0.63771,-1.17599,-1.98876,0.02397,2.50201,0.00392
-9.22245,0.63855,-1.17496,-1.98936,0.02354,2.50117,0.00392
-9.22364,0.63938,-1.17395,-1.98994,0.02312,2.50035,0.00393
-9.22482,0.64021,-1.17295,-1.99052,0.02270,2.49953,0.00393
-9.22601,0.64102,-1.17197,-1.99109,0.02229,2.49873,0.00394
-9.22720,0.64183,-1.17100,-1.99165,0.02188,2.49793,0.00394
-9.22839,0.64262,-1.17005,-1.99219,0.02148,2.49714,0.00395
-9.22958,0.64341,-1.16911,-1.99273,0.02108,2.49636,0.00395
-9.23077,0.64419,-1.16819,-1.99326,0.02069,2.49559,0.00396
-9.23196,0.64495,-1.16729,-1.99378,0.02030,2.49483,0.00396
-9.23315,0.64571,-1.16639,-1.99429,0.01992,2.49407,0.00396
-9.23434,0.64647,-1.16552,-1.99479,0.01954,2.49333,0.00396
-9.23552,0.64721,-1.16466,-1.99529,0.01917,2.49259,0.00397
-9.23671,0.64794,-1.16381,-1.99577,0.01881,2.49186,0.00397
-9.23790,0.64867,-1.16297,-1.99625,0.01844,2.49114,0.00397
-9.23909,0.64939,-1.16215,-1.99672,0.01809,2.49043,0.00397
-9.24028,0.65009,-1.16134,-1.99718,0.01774,2.48972,0.00397
-9.24147,0.65079,-1.16054,-1.99763,0.01739,2.48903,0.00397
-9.24266,0.65149,-1.15976,-1.99807,0.01705,2.48834,0.00397
-9.24385,0.65217,-1.15899,-1.99851,0.01671,2.48766,0.00397
-9.24504,0.65285,-1.15823,-1.99894,0.01638,2.48698,0.00397
-9.24623,0.65352,-1.15748,-1.99936,0.01605,2.48632,0.00397
-9.24741,0.65418,-1.15675,-1.99978,0.01573,2.48566,0.00397
-9.24860,0.65483,-1.15603,-2.00019,0.01541,2.48501,0.00397
-9.24979,0.65548,-1.15531,-2.00059,0.01510,2.48437,0.00397
-9.25098,0.65611,-1.15461,-2.00098,0.01479,2.48373,0.00397
-9.25217,0.65674,-1.15392,-2.00137,0.01448,2.48310,0.00397
-9.25336,0.65737,-1.15325,-2.00175,0.01418,2.48248,0.00397
-9.25455,0.65798,-1.15258,-2.00213,0.01388,2.48187,0.00397
-9.25574,0.65859,-1.15192,-2.00249,0.01359,2.48126,0.00397
-9.25693,0.65919,-1.15128,-2.00286,0.01330,2.48066,0.00397
-9.25811,0.65979,-1.15064,-2.00321,0.01301,2.48007,0.00397
-9.25930,0.66038,-1.15001,-2.00356,0.01273,2.47948,0.00396
-9.26049,0.66096,-1.14940,-2.00391,0.01246,2.47890,0.00396
-9.26168,0.66153,-1.14879,-2.00425,0.01218,2.47833,0.00396
-9.26287,0.66210,-1.14819,-2.00458,0.01191,2.47777,0.00396
-9.26406,0.66266,-1.14761,-2.00491,0.01165,2.47721,0.00396
-9.26525,0.66321,-1.14703,-2.00523,0.01138,2.47665,0.00395
-9.26644,0.66376,-1.14646,-2.00555,0.01113,2.47611,0.00395
-9.26763,0.66430,-1.14590,-2.00586,0.01087,2.47557,0.00395
-9.26881,0.66483,-1.14535,-2.00616,0.01062,2.47503,0.00395
-9.27000,0.66536,-1.14481,-2.00647,0.01037,2.47450,0.00395
-9.27119,0.66588,-1.14427,-2.00676,0.01013,2.47398,0.00394
-9.27238,0.66640,-1.14375,-2.00705,0.00989,2.47347,0.00394
-9.27357,0.66690,-1.14323,-2.00734,0.00965,2.47296,0.00394
-9.27476,0.66741,-1.14272,-2.00762,0.00942,2.47245,0.00393
-9.27595,0.66791,-1.14222,-2.00790,0.00919,2.47196,0.00393
-9.27714,0.66840,-1.14173,-2.00817,0.00896,2.47146,0.00393
-9.27833,0.66888,-1.14124,-2.00844,0.00874,2.47098,0.00393
-9.27951,0.66936,-1.14076,-2.00870,0.00852,2.47050,0.00392
-9.28070,0.66984,-1.14029,-2.00896,0.00830,2.47002,0.00392
-9.28189,0.67030,-1.13983,-2.00922,0.00808,2.46955,0.00392
-9.28308,0.67077,-1.13937,-2.00947,0.00787,2.46909,0.00391
-9.28427,0.67097,-1.13917,-2.00958,0.00778,2.46889,0.00391
-9.28546,0.67158,-1.13851,-2.00994,0.00748,2.46828,0.00391
-9.28665,0.67219,-1.13786,-2.01030,0.00718,2.46767,0.00391
-9.28784,0.67279,-1.13723,-2.01064,0.00689,2.46707,0.00391
-9.28903,0.67339,-1.13660,-2.01099,0.00660,2.46648,0.00391
-9.29022,0.67398,-1.13598,-2.01132,0.00632,2.46589,0.00391
-9.29140,0.67456,-1.13537,-2.01166,0.00603,2.46531,0.00391
-9.29259,0.67513,-1.13478,-2.01198,0.00576,2.46474,0.00391
-9.29378,0.67570,-1.13419,-2.01230,0.00549,2.46417,0.00391
-9.29497,0.67626,-1.13361,-2.01262,0.00522,2.46361,0.00391
-9.29616,0.67682,-1.13304,-2.01293,0.00495,2.46306,0.00391
-9.29735,0.67737,-1.13248,-2.01323,0.00469,2.46251,0.00390
-9.29854,0.67791,-1.13192,-2.01353,0.00443,2.46197,0.00390
-9.29973,0.67845,-1.13138,-2.01383,0.00418,2.46143,0.00390
-9.30092,0.67898,-1.13084,-2.01412,0.00393,2.46091,0.00390
-9.30210,0.67950,-1.13032,-2.01440,0.00368,2.46038,0.00390
-9.30329,0.68002,-1.12980,-2.01468,0.00344,2.45987,0.00390
-9.30448,0.68053,-1.12929,-2.01496,0.00320,2.45936,0.00389
-9.30567,0.68103,-1.12878,-2.01523,0.00296,2.45885,0.00389
-9.30686,0.68153,-1.12829,-2.01550,0.00273,2.45835,0.00389
-9.30805,0.68203,-1.12780,-2.01576,0.00250,2.45786,0.00389
-9.30924,0.68251,-1.12732,-2.01602,0.00227,2.45737,0.00389
-9.31043,0.68300,-1.12685,-2.01627,0.00204,2.45689,0.00388
-9.31162,0.68347,-1.12638,-2.01652,0.00182,2.45641,0.00388
-9.31280,0.68394,-1.12593,-2.01677,0.00161,2.45594,0.00388
-9.31399,0.68429,-1.12557,-2.01695,0.00143,2.45560,0.00388
-9.31518,0.68538,-1.12432,-2.01754,0.00078,2.45452,0.00389
-9.31637,0.68646,-1.12309,-2.01811,0.00013,2.45346,0.00390
-9.31756,0.68753,-1.12187,-2.01868,-0.00051,2.45240,0.00391
-9.31875,0.68859,-1.12068,-2.01924,-0.00114,2.45136,0.00393
-9.31994,0.68964,-1.11950,-2.01979,-0.00176,2.45032,0.00393
-9.32113,0.69068,-1.11835,-2.02032,-0.00237,2.44930,0.00394
-9.32232,0.69170,-1.11721,-2.02085,-0.00298,2.44829,0.00395
-9.32350,0.69272,-1.11609,-2.02137,-0.00358,2.44729,0.00396
-9.32469,0.69373,-1.11498,-2.02188,-0.00417,2.44629,0.00397
-9.32588,0.69472,-1.11390,-2.02238,-0.00475,2.44531,0.00398
-9.32707,0.69570,-1.11283,-2.02287,-0.00532,2.44434,0.00398
-9.32826,0.69668,-1.11178,-2.02335,-0.00589,2.44338,0.00399
-9.32945,0.69764,-1.11074,-2.02383,-0.00645,2.44242,0.00400
-9.33064,0.69859,-1.10972,-2.02429,-0.00700,2.44148,0.00400
-9.33183,0.69954,-1.10872,-2.02475,-0.00754,2.44055,0.00401
-9.33302,0.70047,-1.10773,-2.02520,-0.00808,2.43962,0.00401
-9.33421,0.70140,-1.10676,-2.02564,-0.00860,2.43871,0.00402
-9.33539,0.70231,-1.10580,-2.02608,-0.00913,2.43781,0.00402
-9.33658,0.70321,-1.10486,-2.02651,-0.00964,2.43691,0.00402
-9.33777,0.70411,-1.10393,-2.02693,-0.01015,2.43603,0.00403
-9.33896,0.70499,-1.10302,-2.02734,-0.01065,2.43515,0.00403
-9.34015,0.70587,-1.10212,-2.02775,-0.01114,2.43428,0.00403
-9.34134,0.70673,-1.10124,-2.02814,-0.01163,2.43342,0.00404
-9.34253,0.70759,-1.10037,-2.02854,-0.01211,2.43257,0.00404
-9.34372,0.70844,-1.09951,-2.02892,-0.01258,2.43173,0.00404
-9.34491,0.70928,-1.09867,-2.02930,-0.01305,2.43090,0.00404
-9.34609,0.71011,-1.09784,-2.02967,-0.01351,2.43008,0.00405
-9.34728,0.71093,-1.09702,-2.03004,-0.01396,2.42926,0.00405
-9.34847,0.71174,-1.09621,-2.03040,-0.01441,2.42845,0.00405
-9.34966,0.71254,-1.09542,-2.03075,-0.01485,2.42766,0.00405
-9.35085,0.71334,-1.09464,-2.03110,-0.01529,2.42687,0.00405
-9.35204,0.71412,-1.09387,-2.03144,-0.01572,2.42609,0.00405
-9.35323,0.71490,-1.09312,-2.03178,-0.01614,2.42531,0.00405
-9.35442,0.71567,-1.09237,-2.03211,-0.01656,2.42455,0.00405
-9.35561,0.71643,-1.09164,-2.03244,-0.01697,2.42379,0.00405
-9.35679,0.71719,-1.09092,-2.03276,-0.01738,2.42304,0.00405
-9.35798,0.71793,-1.09020,-2.03307,-0.01778,2.42230,0.00405
-9.35917,0.71867,-1.08950,-2.03338,-0.01818,2.42157,0.00405
-9.36036,0.71940,-1.08882,-2.03369,-0.01857,2.42084,0.00405
-9.36155,0.72012,-1.08814,-2.03398,-0.01895,2.42013,0.00405
-9.36274,0.72083,-1.08747,-2.03428,-0.01933,2.41942,0.00405
-9.36393,0.72153,-1.08681,-2.03457,-0.01971,2.41871,0.00404
-9.36512,0.72223,-1.08616,-2.03485,-0.02007,2.41802,0.00404
-9.36631,0.72292,-1.08552,-2.03513,-0.02044,2.41733,0.00404
-9.36749,0.72360,-1.08490,-2.03541,-0.02080,2.41665,0.00404
-9.36868,0.72428,-1.08428,-2.03568,-0.02115,2.41598,0.00404
-9.36987,0.72495,-1.08367,-2.03595,-0.02150,2.41531,0.00404
-9.37106,0.72561,-1.08307,-2.03621,-0.02184,2.41465,0.00403
-9.37225,0.72626,-1.08248,-2.03647,-0.02218,2.41400,0.00403
-9.37344,0.72691,-1.08190,-2.03672,-0.02252,2.41335,0.00403
-9.37463,0.72755,-1.08132,-2.03697,-0.02285,2.41272,0.00403
-9.37582,0.72818,-1.08076,-2.03722,-0.02317,2.41208,0.00403
-9.37701,0.72880,-1.08020,-2.03746,-0.02349,2.41146,0.00402
-9.37820,0.72942,-1.07965,-2.03770,-0.02381,2.41084,0.00402
-9.37938,0.73003,-1.07912,-2.03793,-0.02412,2.41023,0.00402
-9.38057,0.73064,-1.07858,-2.03816,-0.02443,2.40963,0.00402
-9.38176,0.73124,-1.07806,-2.03839,-0.02473,2.40903,0.00401
-9.38295,0.73183,-1.07755,-2.03861,-0.02503,2.40844,0.00401
-9.38414,0.73242,-1.07704,-2.03883,-0.02532,2.40785,0.00401
-9.38533,0.73299,-1.07654,-2.03905,-0.02561,2.40727,0.00401
-9.38652,0.73357,-1.07605,-2.03926,-0.02590,2.40670,0.00400
-9.38771,0.73413,-1.07556,-2.03947,-0.02618,2.40613,0.00400
-9.38890,0.73469,-1.07508,-2.03968,-0.02646,2.40557,0.00400
-9.39008,0.73525,-1.07461,-2.03988,-0.02674,2.40502,0.00399
-9.39127,0.73579,-1.07415,-2.04008,-0.02701,2.40447,0.00399
-9.39246,0.73634,-1.07369,-2.04028,-0.02727,2.40393,0.00399
-9.39365,0.73687,-1.07324,-2.04047,-0.02754,2.40339,0.00398
-9.39484,0.73740,-1.07280,-2.04066,-0.02780,2.40286,0.00398
-9.39603,0.73793,-1.07237,-2.04085,-0.02805,2.40233,0.00398
-9.39722,0.73815,-1.07217,-2.04093,-0.02817,2.40211,0.00398
-9.39841,0.73883,-1.07156,-2.04119,-0.02853,2.40143,0.00398
-9.39960,0.73950,-1.07095,-2.04144,-0.02889,2.40076,0.00398
-9.40078,0.74017,-1.07035,-2.04169,-0.02925,2.40010,0.00398
-9.40197,0.74083,-1.06976,-2.04193,-0.02960,2.39945,0.00397
-9.40316,0.74148,-1.06918,-2.04217,-0.02995,2.39880,0.00397
-9.40435,0.74212,-1.06861,-2.04240,-0.03029,2.39816,0.00397
-9.40554,0.74276,-1.06804,-2.04264,-0.03063,2.39752,0.00397
-9.40673,0.74339,-1.06749,-2.04286,-0.03096,2.39689,0.00397
-9.40792,0.74401,-1.06694,-2.04309,-0.03128,2.39627,0.00397
-9.40911,0.74463,-1.06640,-2.04331,-0.03161,2.39566,0.00397
-9.41030,0.74524,-1.06587,-2.04353,-0.03193,2.39505,0.00397
-9.41148,0.74584,-1.06535,-2.04374,-0.03224,2.39445,0.00397
-9.41267,0.74644,-1.06484,-2.04395,-0.03255,2.39385,0.00396
-9.41386,0.74703,-1.06433,-2.04416,-0.03285,2.39326,0.00396
-9.41505,0.74762,-1.06383,-2.04436,-0.03316,2.39268,0.00396
-9.41624,0.74820,-1.06334,-2.04456,-0.03345,2.39210,0.00396
-9.41743,0.74877,-1.06285,-2.04476,-0.03375,2.39153,0.00396
-9.41862,0.74933,-1.06238,-2.04495,-0.03403,2.39096,0.00396
-9.41981,0.74989,-1.06191,-2.04515,-0.03432,2.39040,0.00395
-9.42100,0.75045,-1.06144,-2.04533,-0.03460,2.38985,0.00395
-9.42219,0.75100,-1.06099,-2.04552,-0.03488,2.38930,0.00395
-9.42337,0.75154,-1.06054,-2.04570,-0.03515,2.38876,0.00395
-9.42456,0.75207,-1.06009,-2.04588,-0.03542,2.38822,0.00395
-9.42575,0.75260,-1.05966,-2.04606,-0.03568,2.38769,0.00394
-9.42694,0.75296,-1.05936,-2.04618,-0.03587,2.38734,0.00394
-9.42813,0.75383,-1.05853,-2.04650,-0.03637,2.38648,0.00395
-9.42932,0.75470,-1.05772,-2.04682,-0.03687,2.38562,0.00395
-9.43051,0.75555,-1.05692,-2.04713,-0.03736,2.38477,0.00395
-9.43170,0.75640,-1.05613,-2.04743,-0.03784,2.38393,0.00396
-9.43289,0.75724,-1.05535,-2.04773,-0.03832,2.38310,0.00396
-9.43407,0.75807,-1.05458,-2.04803,-0.03879,2.38228,0.00396
-9.43526,0.75889,-1.05383,-2.04832,-0.03926,2.38146,0.00397
-9.43645,0.75971,-1.05309,-2.04861,-0.03971,2.38066,0.00397
-9.43764,0.76051,-1.05236,-2.04889,-0.04017,2.37986,0.00397
-9.43883,0.76131,-1.05164,-2.04916,-0.04061,2.37907,0.00397
-9.44002,0.76210,-1.05093,-2.04944,-0.04105,2.37828,0.00397
-9.44121,0.76288,-1.05023,-2.04970,-0.04148,2.37751,0.00398
-9.44240,0.76366,-1.04954,-2.04997,-0.04191,2.37674,0.00398
-9.44359,0.76442,-1.04886,-2.05023,-0.04233,2.37598,0.00398
-9.44477,0.76518,-1.04819,-2.05048,-0.04275,2.37523,0.00398
-9.44596,0.76593,-1.04753,-2.05073,-0.04316,2.37448,0.00398
-9.44715,0.76668,-1.04689,-2.05098,-0.04356,2.37375,0.00398
-9.44834,0.76741,-1.04625,-2.05122,-0.04396,2.37301,0.00398
-9.44953,0.76814,-1.04562,-2.05146,-0.04436,2.37229,0.00398
-9.45072,0.76886,-1.04500,-2.05170,-0.04475,2.37158,0.00398
-9.45191,0.76957,-1.04439,-2.05193,-0.04513,2.37087,0.00398
-9.45310,0.77028,-1.04379,-2.05216,-0.04551,2.37016,0.00398
-9.45429,0.77098,-1.04319,-2.05238,-0.04588,2.36947,0.00398
-9.45547,0.77167,-1.04261,-2.05260,-0.04625,2.36878,0.00398
-9.45666,0.77235,-1.04204,-2.05282,-0.04661,2.36810,0.00398
-9.45785,0.77303,-1.04147,-2.05303,-0.04697,2.36743,0.00398
-9.45904,0.77370,-1.04091,-2.05324,-0.04732,2.36676,0.00398
-9.46023,0.77436,-1.04036,-2.05345,-0.04767,2.36610,0.00398
-9.46142,0.77502,-1.03982,-2.05365,-0.04801,2.36544,0.00398
-9.46261,0.77567,-1.03928,-2.05386,-0.04835,2.36480,0.00398
-9.46380,0.77631,-1.03876,-2.05405,-0.04868,2.36416,0.00398
-9.46499,0.77695,-1.03824,-2.05425,-0.04901,2.36352,0.00397
-9.46618,0.77758,-1.03773,-2.05444,-0.04934,2.36289,0.00397
-9.46736,0.77820,-1.03722,-2.05463,-0.04966,2.36227,0.00397
-9.46855,0.77882,-1.03673,-2.05481,-0.04997,2.36166,0.00397
-9.46974,0.77943,-1.03624,-2.05500,-0.05028,2.36105,0.00397
-9.47093,0.78003,-1.03576,-2.05518,-0.05059,2.36044,0.00397
-9.47212,0.78063,-1.03528,-2.05536,-0.05089,2.35985,0.00397
-9.47331,0.78122,-1.03482,-2.05553,-0.05119,2.35925,0.00396
-9.47450,0.78181,-1.03435,-2.05570,-0.05149,2.35867,0.00396
-9.47569,0.78239,-1.03390,-2.05587,-0.05178,2.35809,0.00396
-9.47688,0.78296,-1.03345,-2.05604,-0.05207,2.35752,0.00396
-9.47806,0.78353,-1.03301,-2.05620,-0.05235,2.35695,0.00396
-9.47925,0.78409,-1.03258,-2.05636,-0.05263,2.35639,0.00395
-9.48044,0.78465,-1.03215,-2.05652,-0.05290,2.35583,0.00395
-9.48163,0.78520,-1.03172,-2.05668,-0.05318,2.35528,0.00395
-9.48282,0.78534,-1.03161,-2.05673,-0.05325,2.35514,0.00395
-9.48401,0.78620,-1.03086,-2.05701,-0.05372,2.35429,0.00395
-9.48520,0.78704,-1.03012,-2.05729,-0.05418,2.35346,0.00396
-9.48639,0.78788,-1.02939,-2.05756,-0.05463,2.35263,0.00396
-9.48758,0.78871,-1.02867,-2.05783,-0.05508,2.35181,0.00396
-9.48876,0.78953,-1.02796,-2.05810,-0.05553,2.35099,0.00396
-9.48995,0.79035,-1.02727,-2.05836,-0.05596,2.35018,0.00396
-9.49114,0.79115,-1.02658,-2.05862,-0.05640,2.34939,0.00397
-9.49233,0.79195,-1.02590,-2.05887,-0.05682,2.34859,0.00397
-9.49352,0.79274,-1.02524,-2.05912,-0.05724,2.34781,0.00397
-9.49471,0.79352,-1.02458,-2.05937,-0.05765,2.34703,0.00397
-9.49590,0.79430,-1.02393,-2.05961,-0.05806,2.34627,0.00397
-9.49709,0.79506,-1.02330,-2.05985,-0.05847,2.34550,0.00397
-9.49828,0.79582,-1.02267,-2.06008,-0.05886,2.34475,0.00397
-9.49946,0.79657,-1.02205,-2.06031,-0.05926,2.34400,0.00397
-9.50065,0.79732,-1.02144,-2.06054,-0.05964,2.34326,0.00397
-9.50184,0.79806,-1.02084,-2.06076,-0.06003,2.34253,0.00397
-9.50303,0.79879,-1.02025,-2.06098,-0.06040,2.34180,0.00397
-9.50422,0.79951,-1.01966,-2.06120,-0.06078,2.34109,0.00397
-9.50541,0.80022,-1.01909,-2.06141,-0.06114,2.34037,0.00397
-9.50660,0.80093,-1.01852,-2.06162,-0.06150,2.33967,0.00397
-9.50779,0.80164,-1.01796,-2.06182,-0.06186,2.33897,0.00397
-9.50898,0.80233,-1.01741,-2.06203,-0.06221,2.33828,0.00397
-9.51017,0.80302,-1.01687,-2.06223,-0.06256,2.33759,0.00397
-9.51135,0.80370,-1.01633,-2.06242,-0.06291,2.33692,0.00397
-9.51254,0.80437,-1.01580,-2.06262,-0.06324,2.33624,0.00397
-9.51373,0.80504,-1.01528,-2.06281,-0.06358,2.33558,0.00397
-9.51492,0.80570,-1.01477,-2.06300,-0.06391,2.33492,0.00397
-9.51611,0.80636,-1.01427,-2.06318,-0.06423,2.33427,0.00397
-9.51730,0.80701,-1.01377,-2.06337,-0.06455,2.33362,0.00397
-9.51849,0.80765,-1.01328,-2.06354,-0.06487,2.33298,0.00397
-9.51968,0.80828,-1.01279,-2.06372,-0.06518,2.33235,0.00396
-9.52087,0.80891,-1.01232,-2.06390,-0.06549,2.33172,0.00396
-9.52205,0.80954,-1.01185,-2.06407,-0.06579,2.33110,0.00396
-9.52324,0.81015,-1.01138,-2.06424,-0.06609,2.33048,0.00396
-9.52443,0.81076,-1.01093,-2.06440,-0.06639,2.32987,0.00396
-9.52562,0.81137,-1.01048,-2.06457,-0.06668,2.32927,0.00396
-9.52681,0.81197,-1.01003,-2.06473,-0.06697,2.32867,0.00396
-9.52800,0.81256,-1.00959,-2.06489,-0.06726,2.32808,0.00396
-9.52919,0.81315,-1.00916,-2.06505,-0.06754,2.32749,0.00395
-9.53038,0.81373,-1.00874,-2.06520,-0.06781,2.32691,0.00395
-9.53157,0.81430,-1.00832,-2.06535,-0.06809,2.32634,0.00395
-9.53275,0.81487,-1.00790,-2.06550,-0.06836,2.32577,0.00395
-9.53394,0.81518,-1.00768,-2.06558,-0.06851,2.32546,0.00395
-9.53513,0.81596,-1.00705,-2.06576,-0.06896,2.32469,0.00395
-9.53632,0.81674,-1.00643,-2.06594,-0.06940,2.32392,0.00395
-9.53751,0.81751,-1.00581,-2.06612,-0.06984,2.32315,0.00395
-9.53870,0.81827,-1.00521,-2.06629,-0.07027,2.32240,0.00396
-9.53989,0.81902,-1.00462,-2.06646,-0.07069,2.32165,0.00396
-9.54108,0.81977,-1.00403,-2.06663,-0.07111,2.32091,0.00396
-9.54227,0.82051,-1.00345,-2.06680,-0.07153,2.32018,0.00396
-9.54345,0.82124,-1.00288,-2.06696,-0.07194,2.31945,0.00396
-9.54464,0.82196,-1.00232,-2.06712,-0.07234,2.31873,0.00396
-9.54583,0.82268,-1.00177,-2.06728,-0.07274,2.31802,0.00396
-9.54702,0.82339,-1.00123,-2.06744,-0.07313,2.31731,0.00396
-9.54821,0.82410,-1.00069,-2.06759,-0.07351,2.31661,0.00396
-9.54940,0.82480,-1.00016,-2.06774,-0.07390,2.31591,0.00396
-9.55059,0.82549,-0.99964,-2.06789,-0.07427,2.31523,0.00396
-9.55178,0.82617,-0.99912,-2.06804,-0.07464,2.31455,0.00396
-9.55297,0.82685,-0.99861,-2.06819,-0.07501,2.31387,0.00396
-9.55416,0.82752,-0.99811,-2.06833,-0.07537,2.31320,0.00396
-9.55534,0.82819,-0.99762,-2.06847,-0.07573,2.31254,0.00396
-9.55653,0.82885,-0.99713,-2.06861,-0.07608,2.31188,0.00396
-9.55772,0.82950,-0.99665,-2.06875,-0.07642,2.31123,0.00396
-9.55891,0.83014,-0.99618,-2.06888,-0.07677,2.31059,0.00396
-9.56010,0.83078,-0.99571,-2.06902,-0.07710,2.30995,0.00396
-9.56129,0.83142,-0.99525,-2.06915,-0.07744,2.30932,0.00396
-9.56248,0.83205,-0.99480,-2.06928,-0.07777,2.30869,0.00396
-9.56367,0.83267,-0.99435,-2.06941,-0.07809,2.30807,0.00396
-9.56486,0.83328,-0.99391,-2.06953,-0.07841,2.30746,0.00396
-9.56604,0.83389,-0.99348,-2.06966,-0.07873,2.30685,0.00396
-9.56723,0.83450,-0.99305,-2.06978,-0.07904,2.30625,0.00396
-9.56842,0.83510,-0.99263,-2.06990,-0.07934,2.30565,0.00396
-9.56961,0.83569,-0.99221,-2.07002,-0.07965,2.30506,0.00396
-9.57080,0.83628,-0.99180,-2.07014,-0.07995,2.30447,0.00395
-9.57199,0.83686,-0.99139,-2.07025,-0.08024,2.30389,0.00395
-9.57318,0.83743,-0.99099,-2.07037,-0.08053,2.30332,0.00395
-9.57437,0.83757,-0.99089,-2.07039,-0.08061,2.30318,0.00395
-9.57556,0.83835,-0.99030,-2.07053,-0.08107,2.30241,0.00395
-9.57674,0.83911,-0.98971,-2.07066,-0.08152,2.30165,0.00396
-9.57793,0.83988,-0.98913,-2.07079,-0.08197,2.30090,0.00396
-9.57912,0.84063,-0.98856,-2.07092,-0.08242,2.30015,0.00396
-9.58031,0.84138,-0.98800,-2.07105,-0.08285,2.29941,0.00396
-9.58150,0.84212,-0.98745,-2.07117,-0.08328,2.29867,0.00396
-9.58269,0.84285,-0.98690,-2.07130,-0.08371,2.29794,0.00396
-9.58388,0.84358,-0.98636,-2.07142,-0.08413,2.29722,0.00396
-9.58507,0.84430,-0.98583,-2.07154,-0.08454,2.29651,0.00397
-9.58626,0.84501,-0.98531,-2.07166,-0.08495,2.29580,0.00397
-9.58745,0.84572,-0.98479,-2.07178,-0.08535,2.29510,0.00397
-9.58863,0.84642,-0.98428,-2.07189,-0.08575,2.29440,0.00397
-9.58982,0.84711,-0.98378,-2.07201,-0.08614,2.29371,0.00397
-9.59101,0.84780,-0.98329,-2.07212,-0.08653,2.29303,0.00397
-9.59220,0.84848,-0.98280,-2.07223,-0.08691,2.29235,0.00397
-9.59339,0.84916,-0.98232,-2.07234,-0.08728,2.29168,0.00397
-9.59458,0.84982,-0.98184,-2.07245,-0.08765,2.29101,0.00397
-9.59577,0.85049,-0.98137,-2.07255,-0.08802,2.29035,0.00397
-9.59696,0.85114,-0.98091,-2.07266,-0.08838,2.28970,0.00397
-9.59815,0.85179,-0.98045,-2.07276,-0.08874,2.28905,0.00397
-9.59933,0.85244,-0.98001,-2.07286,-0.08909,2.28841,0.00397
-9.60052,0.85307,-0.97956,-2.07297,-0.08943,2.28778,0.00397
-9.60171,0.85371,-0.97912,-2.07307,-0.08978,2.28715,0.00397
-9.60290,0.85433,-0.97869,-2.07316,-0.09011,2.28652,0.00397
-9.60409,0.85495,-0.97827,-2.07326,-0.09045,2.28590,0.00397
-9.60528,0.85557,-0.97785,-2.07336,-0.09077,2.28529,0.00397
-9.60647,0.85618,-0.97743,-2.07345,-0.09110,2.28468,0.00397
-9.60766,0.85678,-0.97703,-2.07355,-0.09142,2.28408,0.00396
-9.60885,0.85738,-0.97662,-2.07364,-0.09173,2.28348,0.00396
-9.61003,0.85797,-0.97623,-2.07373,-0.09204,2.28289,0.00396
-9.61122,0.85856,-0.97583,-2.07382,-0.09235,2.28231,0.00396
-9.61241,0.85917,-0.97542,-2.07391,-0.09268,2.28170,0.00396
-9.61360,0.86002,-0.97478,-2.07404,-0.09319,2.28086,0.00396
-9.61479,0.86086,-0.97415,-2.07417,-0.09369,2.28003,0.00397
-9.61598,0.86169,-0.97352,-2.07430,-0.09419,2.27920,0.00397
-9.61717,0.86252,-0.97291,-2.07442,-0.09468,2.27838,0.00397
-9.61836,0.86334,-0.97230,-2.07455,-0.09517,2.27757,0.00397
-9.61955,0.86415,-0.97170,-2.07467,-0.09565,2.27677,0.00398
-9.62073,0.86496,-0.97111,-2.07479,-0.09612,2.27597,0.00398
-9.62192,0.86576,-0.97053,-2.07491,-0.09658,2.27518,0.00398
-9.62311,0.86655,-0.96996,-2.07502,-0.09704,2.27439,0.00398
-9.62430,0.86733,-0.96939,-2.07514,-0.09749,2.27361,0.00398
-9.62549,0.86811,-0.96884,-2.07525,-0.09794,2.27284,0.00398
-9.62668,0.86888,-0.96829,-2.07536,-0.09838,2.27208,0.00399
-9.62787,0.86965,-0.96774,-2.07547,-0.09882,2.27132,0.00399
-9.62906,0.87040,-0.96721,-2.07558,-0.09925,2.27057,0.00399
-9.63025,0.87115,-0.96668,-2.07569,-0.09967,2.26982,0.00399
-9.63144,0.87190,-0.96616,-2.07580,-0.10009,2.26909,0.00399
-9.63262,0.87263,-0.96565,-2.07590,-0.10050,2.26835,0.00399
-9.63381,0.87336,-0.96514,-2.07601,-0.10091,2.26763,0.00399
-9.63500,0.87409,-0.96464,-2.07611,-0.10131,2.26691,0.00399
-9.63619,0.87480,-0.96415,-2.07621,-0.10170,2.26620,0.00399
-9.63738,0.87552,-0.96366,-2.07631,-0.10209,2.26549,0.00399
-9.63857,0.87622,-0.96318,-2.07641,-0.10248,2.26479,0.00399
-9.63976,0.87692,-0.96271,-2.07650,-0.10286,2.26409,0.00399
-9.64095,0.87761,-0.96224,-2.07660,-0.10324,2.26340,0.00399
-9.64214,0.87830,-0.96178,-2.07669,-0.10361,2.26272,0.00399
-9.64332,0.87898,-0.96133,-2.07679,-0.10397,2.26204,0.00399
-9.64451,0.87965,-0.96088,-2.07688,-0.10433,2.26137,0.00399
-9.64570,0.88032,-0.96044,-2.07697,-0.10469,2.26071,0.00399
-9.64689,0.88098,-0.96000,-2.07706,-0.10504,2.26005,0.00399
-9.64808,0.88164,-0.95957,-2.07715,-0.10539,2.25939,0.00399
-9.64927,0.88229,-0.95914,-2.07724,-0.10573,2.25875,0.00399
-9.65046,0.88293,-0.95872,-2.07733,-0.10607,2.25810,0.00399
-9.65165,0.88357,-0.95831,-2.07741,-0.10640,2.25747,0.00399
-9.65284,0.88421,-0.95790,-2.07750,-0.10673,2.25684,0.00399
-9.65402,0.88483,-0.95750,-2.07758,-0.10705,2.25621,0.00399
-9.65521,0.88546,-0.95710,-2.07766,-0.10737,2.25559,0.00398
-9.65640,0.88607,-0.95671,-2.07775,-0.10769,2.25497,0.00398
-9.65759,0.88668,-0.95632,-2.07783,-0.10800,2.25436,0.00398
-9.65878,0.88729,-0.95594,-2.07791,-0.10831,2.25376,0.00398
-9.65997,0.88789,-0.95556,-2.07799,-0.10861,2.25316,0.00398
-9.66116,0.88848,-0.95519,-2.07806,-0.10891,2.25257,0.00398
-9.66235,0.88863,-0.95509,-2.07808,-0.10899,2.25242,0.00398
-9.66354,0.88948,-0.95448,-2.07821,-0.10947,2.25158,0.00398
-9.66472,0.89032,-0.95389,-2.07834,-0.10994,2.25075,0.00398
-9.66591,0.89115,-0.95330,-2.07846,-0.11041,2.24993,0.00399
-9.66710,0.89198,-0.95272,-2.07858,-0.11087,2.24911,0.00399
-9.66829,0.89280,-0.95215,-2.07870,-0.11133,2.24830,0.00399
-9.66948,0.89361,-0.95158,-2.07882,-0.11178,2.24749,0.00399
-9.67067,0.89441,-0.95103,-2.07893,-0.11222,2.24669,0.00399
-9.67186,0.89521,-0.95048,-2.07905,-0.11266,2.24590,0.00399
-9.67305,0.89600,-0.94993,-2.07916,-0.11309,2.24511,0.00399
-9.67424,0.89679,-0.94940,-2.07927,-0.11351,2.24434,0.00399
-9.67543,0.89757,-0.94887,-2.07939,-0.11393,2.24356,0.00400
-9.67661,0.89834,-0.94835,-2.07949,-0.11435,2.24280,0.00400
-9.67780,0.89910,-0.94784,-2.07960,-0.11476,2.24204,0.00400
-9.67899,0.89986,-0.94733,-2.07971,-0.11516,2.24128,0.00400
-9.68018,0.90062,-0.94683,-2.07981,-0.11556,2.24054,0.00400
-9.68137,0.90136,-0.94634,-2.07992,-0.11596,2.23980,0.00400
-9.68256,0.90210,-0.94585,-2.08002,-0.11635,2.23906,0.00400
-9.68375,0.90283,-0.94537,-2.08012,-0.11673,2.23833,0.00400
-9.68494,0.90356,-0.94490,-2.08022,-0.11711,2.23761,0.00400
-9.68613,0.90428,-0.94443,-2.08032,-0.11748,2.23689,0.00400
-9.68731,0.90500,-0.94397,-2.08042,-0.11785,2.23618,0.00400
-9.68850,0.90571,-0.94351,-2.08051,-0.11822,2.23548,0.00400
-9.68969,0.90641,-0.94306,-2.08061,-0.11858,2.23478,0.00400
-9.69088,0.90710,-0.94262,-2.08070,-0.11893,2.23408,0.00400
-9.69207,0.90780,-0.94218,-2.08079,-0.11928,2.23340,0.00400
-9.69326,0.90848,-0.94174,-2.08088,-0.11963,2.23271,0.00400
-9.69445,0.90916,-0.94132,-2.08097,-0.11997,2.23204,0.00400
-9.69564,0.90983,-0.94090,-2.08106,-0.12031,2.23137,0.00400
-9.69683,0.91050,-0.94048,-2.08115,-0.12064,2.23070,0.00400
-9.69801,0.91116,-0.94007,-2.08124,-0.12097,2.23004,0.00400
-9.69920,0.91182,-0.93966,-2.08133,-0.12129,2.22939,0.00400
-9.70039,0.91247,-0.93926,-2.08141,-0.12161,2.22874,0.00400
-9.70158,0.91311,-0.93887,-2.08150,-0.12193,2.22810,0.00399
-9.70277,0.91375,-0.93848,-2.08158,-0.12224,2.22746,0.00399
-9.70396,0.91439,-0.93809,-2.08166,-0.12255,2.22682,0.00399
-9.70515,0.91502,-0.93771,-2.08174,-0.12286,2.22620,0.00399
-9.70634,0.91564,-0.93733,-2.08182,-0.12316,2.22557,0.00399
-9.70753,0.91626,-0.93696,-2.08190,-0.12345,2.22496,0.00399
-9.70871,0.91687,-0.93660,-2.08198,-0.12375,2.22434,0.00399
-9.70990,0.91748,-0.93623,-2.08206,-0.12404,2.22374,0.00399
-9.71109,0.91792,-0.93597,-2.08212,-0.12425,2.22330,0.00399
-9.71228,0.91869,-0.93546,-2.08223,-0.12465,2.22253,0.00399
-9.71347,0.91946,-0.93495,-2.08234,-0.12505,2.22177,0.00399
-9.71466,0.92023,-0.93445,-2.08245,-0.12544,2.22101,0.00399
-9.71585,0.92098,-0.93396,-2.08256,-0.12583,2.22026,0.00399
-9.71704,0.92173,-0.93348,-2.08266,-0.12621,2.21951,0.00399
-9.71823,0.92248,-0.93300,-2.08277,-0.12659,2.21877,0.00399
-9.71942,0.92322,-0.93253,-2.08287,-0.12696,2.21804,0.00399
-9.72060,0.92395,-0.93206,-2.08298,-0.12732,2.21731,0.00399
-9.72179,0.92467,-0.93160,-2.08308,-0.12769,2.21659,0.00399
-9.72298,0.92539,-0.93115,-2.08318,-0.12805,2.21587,0.00399
-9.72417,0.92611,-0.93070,-2.08328,-0.12840,2.21516,0.00399
-9.72536,0.92682,-0.93026,-2.08337,-0.12875,2.21446,0.00399
-9.72655,0.92752,-0.92982,-2.08347,-0.12909,2.21376,0.00399
-9.72774,0.92822,-0.92939,-2.08357,-0.12943,2.21307,0.00399
-9.72893,0.92891,-0.92896,-2.08366,-0.12977,2.21238,0.00399
-9.73012,0.92959,-0.92854,-2.08375,-0.13010,2.21170,0.00399
-9.73130,0.93027,-0.92813,-2.08384,-0.13043,2.21102,0.00399
-9.73249,0.93094,-0.92772,-2.08394,-0.13076,2.21035,0.00399
-9.73368,0.93161,-0.92731,-2.08402,-0.13108,2.20968,0.00399
-9.73487,0.93228,-0.92691,-2.08411,-0.13139,2.20902,0.00399
-9.73606,0.93293,-0.92652,-2.08420,-0.13170,2.20837,0.00399
-9.73725,0.93359,-0.92613,-2.08429,-0.13201,2.20772,0.00399
-9.73844,0.93423,-0.92574,-2.08437,-0.13232,2.20707,0.00399
-9.73963,0.93487,-0.92536,-2.08446,-0.13262,2.20643,0.00399
-9.74082,0.93551,-0.92498,-2.08454,-0.13291,2.20580,0.00399
-9.74200,0.93614,-0.92461,-2.08462,-0.13321,2.20517,0.00399
-9.74319,0.93677,-0.92425,-2.08471,-0.13350,2.20454,0.00399
-9.74438,0.93739,-0.92388,-2.08479,-0.13379,2.20393,0.00399
-9.74557,0.93800,-0.92353,-2.08487,-0.13407,2.20331,0.00399
-9.74676,0.93861,-0.92317,-2.08495,-0.13435,2.20270,0.00399
-9.74795,0.93887,-0.92302,-2.08498,-0.13447,2.20244,0.00399
-9.74914,0.93963,-0.92254,-2.08508,-0.13485,2.20169,0.00399
-9.75033,0.94039,-0.92206,-2.08519,-0.13523,2.20094,0.00399
-9.75152,0.94113,-0.92159,-2.08529,-0.13560,2.20020,0.00399
-9.75270,0.94188,-0.92113,-2.08539,-0.13596,2.19946,0.00399
-9.75389,0.94261,-0.92067,-2.08549,-0.13633,2.19873,0.00399
-9.75508,0.94334,-0.92022,-2.08559,-0.13668,2.19800,0.00399
-9.75627,0.94407,-0.91977,-2.08568,-0.13704,2.19728,0.00399
-9.75746,0.94479,-0.91933,-2.08578,-0.13739,2.19657,0.00399
-9.75865,0.94550,-0.91890,-2.08587,-0.13773,2.19586,0.00399
-9.75984,0.94621,-0.91847,-2.08597,-0.13807,2.19516,0.00399
-9.76103,0.94691,-0.91804,-2.08606,-0.13841,2.19446,0.00400
-9.76222,0.94760,-0.91762,-2.08615,-0.13874,2.19377,0.00400
-9.76341,0.94829,-0.91721,-2.08624,-0.13907,2.19308,0.00400
-9.76459,0.94898,-0.91680,-2.08633,-0.13939,2.19240,0.00400
-9.76578,0.94966,-0.91640,-2.08642,-0.13971,2.19172,0.00400
-9.76697,0.95033,-0.91600,-2.08650,-0.14003,2.19105,0.00400
-9.76816,0.95100,-0.91560,-2.08659,-0.14034,2.19039,0.00400
-9.76935,0.95166,-0.91522,-2.08668,-0.14065,2.18972,0.00400
-9.77054,0.95232,-0.91483,-2.08676,-0.14096,2.18907,0.00400
-9.77173,0.95297,-0.91445,-2.08684,-0.14126,2.18842,0.00400
-9.77292,0.95362,-0.91408,-2.08693,-0.14155,2.18777,0.00400
-9.77411,0.95426,-0.91370,-2.08701,-0.14185,2.18713,0.00400
-9.77529,0.95490,-0.91334,-2.08709,-0.14214,2.18650,0.00399
-9.77648,0.95553,-0.91298,-2.08717,-0.14243,2.18587,0.00399
-9.77767,0.95616,-0.91262,-2.08724,-0.14271,2.18524,0.00399
-9.77886,0.95678,-0.91227,-2.08732,-0.14299,2.18462,0.00399
-9.78005,0.95740,-0.91192,-2.08740,-0.14327,2.18400,0.00399
-9.78124,0.95801,-0.91157,-2.08748,-0.14354,2.18339,0.00399
-9.78243,0.95828,-0.91142,-2.08751,-0.14366,2.18313,0.00399
-9.78362,0.95906,-0.91093,-2.08759,-0.14407,2.18235,0.00399
-9.78481,0.95984,-0.91045,-2.08767,-0.14447,2.18158,0.00400
-9.78599,0.96062,-0.90998,-2.08776,-0.14487,2.18081,0.00400
-9.78718,0.96138,-0.90951,-2.08784,-0.14526,2.18005,0.00400
-9.78837,0.96215,-0.90904,-2.08792,-0.14564,2.17929,0.00400
-9.78956,0.96290,-0.90858,-2.08800,-0.14602,2.17854,0.00400
-9.79075,0.96365,-0.90813,-2.08808,-0.14640,2.17780,0.00400
-9.79194,0.96440,-0.90769,-2.08816,-0.14677,2.17706,0.00400
-9.79313,0.96514,-0.90724,-2.08823,-0.14714,2.17632,0.00400
-9.79432,0.96587,-0.90681,-2.08831,-0.14750,2.17559,0.00400
-9.79551,0.96660,-0.90638,-2.08839,-0.14786,2.17487,0.00401
-9.79669,0.96732,-0.90595,-2.08846,-0.14821,2.17415,0.00401
-9.79788,0.96804,-0.90553,-2.08853,-0.14856,2.17344,0.00401
-9.79907,0.96875,-0.90512,-2.08861,-0.14891,2.17273,0.00401
-9.80026,0.96945,-0.90471,-2.08868,-0.14925,2.17203,0.00401
-9.80145,0.97016,-0.90430,-2.08875,-0.14959,2.17133,0.00401
-9.80264,0.97085,-0.90390,-2.08882,-0.14992,2.17064,0.00401
-9.80383,0.97154,-0.90351,-2.08889,-0.15025,2.16996,0.00401
-9.80502,0.97222,-0.90312,-2.08896,-0.15057,2.16928,0.00401
-9.80621,0.97290,-0.90273,-2.08903,-0.15090,2.16860,0.00401
-9.80740,0.97358,-0.90235,-2.08910,-0.15121,2.16793,0.00401
-9.80858,0.97425,-0.90197,-2.08917,-0.15153,2.16726,0.00401
-9.80977,0.97491,-0.90160,-2.08923,-0.15184,2.16660,0.00401
-9.81096,0.97557,-0.90123,-2.08930,-0.15214,2.16594,0.00401
-9.81215,0.97622,-0.90087,-2.08937,-0.15245,2.16529,0.00401
-9.81334,0.97687,-0.90051,-2.08943,-0.15274,2.16465,0.00401
-9.81453,0.97751,-0.90015,-2.08950,-0.15304,2.16401,0.00401
-9.81572,0.97815,-0.89980,-2.08956,-0.15333,2.16337,0.00401
-9.81691,0.97878,-0.89945,-2.08962,-0.15362,2.16274,0.00401
-9.81810,0.97941,-0.89911,-2.08969,-0.15391,2.16211,0.00401
-9.81928,0.98004,-0.89877,-2.08975,-0.15419,2.16149,0.00401
-9.82047,0.98066,-0.89844,-2.08981,-0.15447,2.16087,0.00401
-9.82166,0.98127,-0.89811,-2.08987,-0.15474,2.16025,0.00401
-9.82285,0.98166,-0.89789,-2.08991,-0.15492,2.15987,0.00401
-9.82404,0.98245,-0.89743,-2.08995,-0.15534,2.15909,0.00401
-9.82523,0.98323,-0.89697,-2.09000,-0.15576,2.15831,0.00401
-9.82642,0.98401,-0.89651,-2.09004,-0.15618,2.15754,0.00401
-9.82761,0.98478,-0.89606,-2.09008,-0.15658,2.15678,0.00402
-9.82880,0.98555,-0.89562,-2.09013,-0.15699,2.15602,0.00402
-9.82998,0.98631,-0.89518,-2.09017,-0.15739,2.15526,0.00402
-9.83117,0.98706,-0.89474,-2.09022,-0.15778,2.15451,0.00402
-9.83236,0.98781,-0.89431,-2.09026,-0.15817,2.15377,0.00402
-9.83355,0.98855,-0.89389,-2.09030,-0.15855,2.15303,0.00402
-9.83474,0.98929,-0.89347,-2.09035,-0.15893,2.15230,0.00402
-9.83593,0.99003,-0.89306,-2.09039,-0.15930,2.15157,0.00402
-9.83712,0.99075,-0.89265,-2.09043,-0.15967,2.15085,0.00402
-9.83831,0.99148,-0.89224,-2.09047,-0.16004,2.15013,0.00403
-9.83950,0.99219,-0.89185,-2.09052,-0.16040,2.14942,0.00403
-9.84068,0.99290,-0.89145,-2.09056,-0.16076,2.14871,0.00403
-9.84187,0.99361,-0.89106,-2.09060,-0.16111,2.14801,0.00403
-9.84306,0.99431,-0.89068,-2.09064,-0.16145,2.14731,0.00403
-9.84425,0.99501,-0.89029,-2.09068,-0.16180,2.14662,0.00403
-9.84544,0.99570,-0.88992,-2.09072,-0.16214,2.14593,0.00403
-9.84663,0.99638,-0.88954,-2.09076,-0.16247,2.14525,0.00403
-9.84782,0.99706,-0.88918,-2.09081,-0.16280,2.14457,0.00403
-9.84901,0.99774,-0.88881,-2.09085,-0.16313,2.14390,0.00403
-9.85020,0.99841,-0.88845,-2.09089,-0.16346,2.14323,0.00403
-9.85139,0.99908,-0.88810,-2.09093,-0.16378,2.14256,0.00403
-9.85257,0.99974,-0.88775,-2.09097,-0.16409,2.14191,0.00403
-9.85376,1.00039,-0.88740,-2.09101,-0.16440,2.14125,0.00403
-9.85495,1.00104,-0.88705,-2.09105,-0.16471,2.14060,0.00403
-9.85614,1.00169,-0.88671,-2.09109,-0.16502,2.13996,0.00403
-9.85733,1.00233,-0.88638,-2.09113,-0.16532,2.13932,0.00403
-9.85852,1.00297,-0.88604,-2.09116,-0.16562,2.13868,0.00403
-9.85971,1.00360,-0.88572,-2.09120,-0.16591,2.13805,0.00403
-9.86090,1.00423,-0.88539,-2.09124,-0.16620,2.13743,0.00403
-9.86209,1.00485,-0.88507,-2.09128,-0.16649,2.13680,0.00403
-9.86327,1.00547,-0.88475,-2.09132,-0.16677,2.13619,0.00403
-9.86446,1.00609,-0.88444,-2.09136,-0.16705,2.13557,0.00403
-9.86565,1.00659,-0.88418,-2.09139,-0.16729,2.13507,0.00403
-9.86684,1.00733,-0.88376,-2.09142,-0.16767,2.13433,0.00403
-9.86803,1.00807,-0.88336,-2.09145,-0.16805,2.13360,0.00403
-9.86922,1.00880,-0.88295,-2.09148,-0.16843,2.13287,0.00404
-9.87041,1.00953,-0.88255,-2.09151,-0.16880,2.13215,0.00404
-9.87160,1.01025,-0.88216,-2.09154,-0.16917,2.13143,0.00404
-9.87279,1.01097,-0.88177,-2.09157,-0.16953,2.13072,0.00404
-9.87397,1.01168,-0.88139,-2.09160,-0.16989,2.13001,0.00404
-9.87516,1.01239,-0.88101,-2.09163,-0.17024,2.12931,0.00404
-9.87635,1.01309,-0.88063,-2.09166,-0.17059,2.12861,0.00404
-9.87754,1.01379,-0.88026,-2.09169,-0.17094,2.12792,0.00404
-9.87873,1.01448,-0.87989,-2.09172,-0.17128,2.12723,0.00404
-9.87992,1.01517,-0.87953,-2.09175,-0.17162,2.12654,0.00404
-9.88111,1.01586,-0.87917,-2.09178,-0.17195,2.12586,0.00404
-9.88230,1.01653,-0.87881,-2.09181,-0.17228,2.12519,0.00404
-9.88349,1.01721,-0.87846,-2.09184,-0.17260,2.12452,0.00404
-9.88467,1.01787,-0.87811,-2.09187,-0.17293,2.12385,0.00404
-9.88586,1.01854,-0.87777,-2.09190,-0.17324,2.12319,0.00404
-9.88705,1.01920,-0.87743,-2.09193,-0.17356,2.12254,0.00404
-9.88824,1.01985,-0.87709,-2.09196,-0.17387,2.12188,0.00405
-9.88943,1.02050,-0.87676,-2.09199,-0.17418,2.12124,0.00405
-9.89062,1.02115,-0.87643,-2.09202,-0.17448,2.12059,0.00405
-9.89181,1.02179,-0.87610,-2.09205,-0.17478,2.11996,0.00405
-9.89300,1.02242,-0.87578,-2.09208,-0.17507,2.11932,0.00405
-9.89419,1.02305,-0.87546,-2.09211,-0.17537,2.11869,0.00405
-9.89538,1.02368,-0.87515,-2.09214,-0.17566,2.11807,0.00405
-9.89656,1.02430,-0.87483,-2.09217,-0.17594,2.11745,0.00405
-9.89775,1.02492,-0.87453,-2.09220,-0.17623,2.11683,0.00405
-9.89894,1.02554,-0.87422,-2.09223,-0.17651,2.11622,0.00405
-9.90013,1.02614,-0.87392,-2.09226,-0.17678,2.11561,0.00405
-9.90132,1.02635,-0.87381,-2.09227,-0.17688,2.11541,0.00405
-9.90251,1.02713,-0.87338,-2.09227,-0.17731,2.11463,0.00405
-9.90370,1.02792,-0.87296,-2.09228,-0.17773,2.11385,0.00405
-9.90489,1.02869,-0.87253,-2.09229,-0.17814,2.11308,0.00405
-9.90608,1.02947,-0.87212,-2.09231,-0.17855,2.11232,0.00405
-9.90726,1.03023,-0.87170,-2.09232,-0.17895,2.11155,0.00405
-9.90845,1.03100,-0.87130,-2.09233,-0.17935,2.11080,0.00406
-9.90964,1.03175,-0.87089,-2.09234,-0.17975,2.11005,0.00406
-9.91083,1.03250,-0.87049,-2.09235,-0.18014,2.10930,0.00406
-9.91202,1.03325,-0.87010,-2.09236,-0.18052,2.10856,0.00406
-9.91321,1.03399,-0.86971,-2.09238,-0.18090,2.10783,0.00406
-9.91440,1.03473,-0.86932,-2.09239,-0.18128,2.10710,0.00406
-9.91559,1.03546,-0.86894,-2.09240,-0.18165,2.10637,0.00406
-9.91678,1.03618,-0.86857,-2.09242,-0.18202,2.10565,0.00406
-9.91796,1.03691,-0.86819,-2.09243,-0.18238,2.10493,0.00406
-9.91915,1.03762,-0.86782,-2.09244,-0.18274,2.10422,0.00407
-9.92034,1.03833,-0.86746,-2.09246,-0.18309,2.10351,0.00407
-9.92153,1.03904,-0.86710,-2.09247,-0.18344,2.10281,0.00407
-9.92272,1.03974,-0.86674,-2.09249,-0.18379,2.10211,0.00407
-9.92391,1.04044,-0.86639,-2.09250,-0.18413,2.10142,0.00407
-9.92510,1.04113,-0.86604,-2.09252,-0.18447,2.10073,0.00407
-9.92629,1.04182,-0.86569,-2.09253,-0.18480,2.10005,0.00407
-9.92748,1.04250,-0.86535,-2.09255,-0.18513,2.09937,0.00407
-9.92866,1.04318,-0.86501,-2.09257,-0.18546,2.09869,0.00407
-9.92985,1.04385,-0.86468,-2.09258,-0.18578,2.09802,0.00407
-9.93104,1.04452,-0.86434,-2.09260,-0.18610,2.09736,0.00407
-9.93223,1.04519,-0.86402,-2.09262,-0.18641,2.09669,0.00407
-9.93342,1.04585,-0.86369,-2.09263,-0.18672,2.09604,0.00407
-9.93461,1.04650,-0.86337,-2.09265,-0.18703,2.09538,0.00407
-9.93580,1.04715,-0.86305,-2.09267,-0.18734,2.09473,0.00407
-9.93699,1.04780,-0.86274,-2.09269,-0.18764,2.09409,0.00407
-9.93818,1.04844,-0.86243,-2.09270,-0.18794,2.09345,0.00407
-9.93937,1.04908,-0.86212,-2.09272,-0.18823,2.09281,0.00407
-9.94055,1.04972,-0.86181,-2.09274,-0.18852,2.09218,0.00407
-9.94174,1.05035,-0.86151,-2.09276,-0.18881,2.09155,0.00407
-9.94293,1.05097,-0.86121,-2.09278,-0.18909,2.09093,0.00407
-9.94412,1.05159,-0.86092,-2.09280,-0.18937,2.09031,0.00407
-9.94531,1.05221,-0.86062,-2.09282,-0.18965,2.08969,0.00407
-9.94650,1.05282,-0.86033,-2.09284,-0.18993,2.08908,0.00407
-9.94769,1.05343,-0.86005,-2.09286,-0.19020,2.08847,0.00407
-9.94888,1.05398,-0.85979,-2.09287,-0.19044,2.08792,0.00407
-9.95007,1.05463,-0.85947,-2.09290,-0.19074,2.08728,0.00408
-9.95125,1.05527,-0.85916,-2.09293,-0.19102,2.08664,0.00408
-9.95244,1.05591,-0.85884,-2.09296,-0.19131,2.08600,0.00408
-9.95363,1.05655,-0.85854,-2.09299,-0.19159,2.08537,0.00408
-9.95482,1.05718,-0.85823,-2.09302,-0.19187,2.08474,0.00408
-9.95601,1.05780,-0.85793,-2.09305,-0.19215,2.08411,0.00408
-9.95720,1.05842,-0.85763,-2.09308,-0.19242,2.08349,0.00408
-9.95839,1.05904,-0.85734,-2.09311,-0.19269,2.08288,0.00408
-9.95958,1.05966,-0.85704,-2.09314,-0.19295,2.08226,0.00408
-9.96077,1.06027,-0.85675,-2.09317,-0.19322,2.08165,0.00408
-9.96195,1.06087,-0.85647,-2.09320,-0.19348,2.08105,0.00408
-9.96314,1.06106,-0.85638,-2.09321,-0.19356,2.08087,0.00408
-9.96433,1.06168,-0.85608,-2.09325,-0.19383,2.08024,0.00408
-9.96552,1.06230,-0.85578,-2.09328,-0.19410,2.07963,0.00408
-9.96671,1.06292,-0.85549,-2.09332,-0.19436,2.07901,0.00408
-9.96790,1.06353,-0.85520,-2.09335,-0.19462,2.07840,0.00408
-9.96909,1.06414,-0.85491,-2.09339,-0.19488,2.07780,0.00408
-9.97028,1.06462,-0.85468,-2.09342,-0.19509,2.07731,0.00408
-9.97147,1.06524,-0.85438,-2.09345,-0.19535,2.07669,0.00408
-9.97265,1.06586,-0.85408,-2.09349,-0.19562,2.07607,0.00408
-9.97384,1.06648,-0.85378,-2.09353,-0.19588,2.07546,0.00408
-9.97503,1.06709,-0.85349,-2.09357,-0.19613,2.07485,0.00408
-9.97622,1.06770,-0.85320,-2.09361,-0.19639,2.07424,0.00408
-9.97741,1.06831,-0.85291,-2.09365,-0.19664,2.07363,0.00408
-9.97860,1.06893,-0.85262,-2.09367,-0.19692,2.07301,0.00408
-9.97979,1.06955,-0.85232,-2.09369,-0.19720,2.07240,0.00408
-9.98098,1.07016,-0.85203,-2.09371,-0.19747,2.07178,0.00408
-9.98217,1.07077,-0.85174,-2.09373,-0.19774,2.07117,0.00408
-9.98336,1.07138,-0.85146,-2.09376,-0.19801,2.07057,0.00408
-9.98454,1.07198,-0.85117,-2.09378,-0.19827,2.06997,0.00408
-9.98573,1.07235,-0.85101,-2.09379,-0.19843,2.06961,0.00408
-9.98692,1.07297,-0.85071,-2.09379,-0.19872,2.06899,0.00408
-9.98811,1.07358,-0.85043,-2.09380,-0.19901,2.06837,0.00408
-9.98930,1.07420,-0.85014,-2.09381,-0.19929,2.06776,0.00408
-9.99049,1.07480,-0.84986,-2.09381,-0.19957,2.06716,0.00409
-9.99168,1.07541,-0.84958,-2.09382,-0.19985,2.06656,0.00409
-9.99287,1.07601,-0.84930,-2.09383,-0.20012,2.06596,0.00409
-9.99406,1.07643,-0.84911,-2.09383,-0.20031,2.06554,0.00409
-9.99524,1.07705,-0.84882,-2.09385,-0.20059,2.06492,0.00409
-9.99643,1.07766,-0.84853,-2.09386,-0.20087,2.06431,0.00409
-9.99762,1.07827,-0.84825,-2.09387,-0.20114,2.06370,0.00409
-9.99881,1.07887,-0.84796,-2.09389,-0.20142,2.06310,0.00409
-10.00000,1.07948,-0.84769,-2.09390,-0.20168,2.06250,0.00409
diff --git a/python/examples/data/path_in_pixels.csv b/python/examples/data/path_in_pixels.csv
deleted file mode 100644
index de74278eaa4f4f11ef4452b86a49db22fd6d29e7..0000000000000000000000000000000000000000
--- a/python/examples/data/path_in_pixels.csv
+++ /dev/null
@@ -1,20 +0,0 @@
-0.11902,0.81172
-0.12940,0.79825
-0.16945,0.76234
-0.23471,0.68903
-0.31331,0.61572
-0.34001,0.58579
-0.36522,0.56335
-0.43938,0.50649
-0.44976,0.49602
-0.48090,0.47208
-0.51798,0.45413
-0.53578,0.44216
-0.55803,0.43019
-0.57138,0.42121
-0.58621,0.40924
-0.59362,0.40326
-0.60104,0.39428
-0.62329,0.35837
-0.63070,0.34640
-0.63070,0.34640
diff --git a/python/examples/optimal_control/path_following_mpc.py b/python/examples/optimal_control/path_following_mpc.py
deleted file mode 100644
index 5563f2931939f7cd394200daebe69a3128d96b40..0000000000000000000000000000000000000000
--- a/python/examples/optimal_control/path_following_mpc.py
+++ /dev/null
@@ -1,82 +0,0 @@
-# PYTHON_ARGCOMPLETE_OK
-import numpy as np
-import time
-import argparse, argcomplete
-from functools import partial
-from smc.managers import getMinimalArgParser, ControlLoopManager, RobotManager
-from smc.optimal_control.get_ocp_args import get_OCP_args
-from smc.optimal_control.crocoddyl_optimal_control import (
-    createCrocoEEPathFollowingOCP,
-    solveCrocoOCP,
-)
-from smc.optimal_control.crocoddyl_mpc import (
-    CrocoEndEffectorPathFollowingMPCControlLoop,
-    CrocoEndEffectorPathFollowingMPC,
-)
-from smc.basics.basics import followKinematicJointTrajP
-from smc.util.logging_utils import LogManager
-from smc.visualize.visualize import plotFromDict
-from smc.clik.clik import getClikArgs
-import pinocchio as pin
-import crocoddyl
-import importlib.util
-
-
-def path(T_w_e, i):
-    # 2) do T_mobile_base_ee_pos to get
-    # end-effector reference frame(s)
-
-    # generate bullshit just to see it works
-    path = []
-    t = i * robot.dt
-    for i in range(args.n_knots):
-        t += 0.01
-        new = T_w_e.copy()
-        translation = 2 * np.array([np.cos(t / 20), np.sin(t / 20), 0.3])
-        new.translation = translation
-        path.append(new)
-    return path
-
-
-def get_args():
-    parser = getMinimalArgParser()
-    parser = get_OCP_args(parser)
-    parser = getClikArgs(parser)  # literally just for goal error
-    argcomplete.autocomplete(parser)
-    args = parser.parse_args()
-    return args
-
-
-if __name__ == "__main__":
-    args = get_args()
-    if importlib.util.find_spec("mim_solvers"):
-        import mim_solvers
-    robot = RobotManager(args)
-    # time.sleep(5)
-
-    # create and solve the optimal control problem of
-    # getting from current to goal end-effector position.
-    # reference is position and velocity reference (as a dictionary),
-    # while solver is a crocoddyl object containing a lot more information
-    # starting state
-    x0 = np.concatenate([robot.getQ(), robot.getQd()])
-    robot._step()
-
-    problem = createCrocoEEPathFollowingOCP(args, robot, x0)
-    CrocoEndEffectorPathFollowingMPC(args, robot, x0, path)
-
-    print("final position:")
-    print(robot.getT_w_e())
-
-    if args.save_log:
-        robot.log_manager.plotAllControlLoops()
-
-    if not args.pinocchio_only:
-        robot.stopRobot()
-
-    if args.visualize_manipulator:
-        robot.killManipulatorVisualizer()
-
-    if args.save_log:
-        robot.log_manager.saveLog()
-    # loop_manager.stopHandler(None, None)
diff --git a/python/smc/control/cartesian_space/cartesian_space_trajectory_following.py b/python/smc/control/cartesian_space/cartesian_space_trajectory_following.py
index 3626c7c86679a74a6bf42ee7dac5488fafaa78b3..6eaf3697bc17419cb3dd4f34edea8eb8e390a452 100644
--- a/python/smc/control/cartesian_space/cartesian_space_trajectory_following.py
+++ b/python/smc/control/cartesian_space/cartesian_space_trajectory_following.py
@@ -5,13 +5,7 @@ from functools import partial
 import pinocchio as pin
 import numpy as np
 
-from importlib.util import find_spec
-
-if find_spec("shapely"):
-    from smc.path_generation.planner import (
-        path2D_to_timed_SE3,
-        pathPointFromPathParam,
-    )
+from smc.path_generation.path_math.path_to_trajectory import path2D_to_timed_SE3
 
 
 def cartesianPathFollowingWithPlannerControlLoop(
@@ -27,7 +21,7 @@ def cartesianPathFollowingWithPlannerControlLoop(
     save_past_dict = {}
 
     q = robot.q
-    T_w_e = robot.T_w_e()
+    T_w_e = robot.T_w_e
     p = T_w_e.translation[:2]
     path_planner.sendFreshestCommand({"p": p})
 
diff --git a/python/smc/control/control_loop_manager.py b/python/smc/control/control_loop_manager.py
index d85d12ffa3c6b2f4a2bac3ba1909c3e263fac69b..47fc612eb8aa89277ededead202ad800336745c2 100644
--- a/python/smc/control/control_loop_manager.py
+++ b/python/smc/control/control_loop_manager.py
@@ -71,6 +71,9 @@ class ControlLoopManager:
         self.args = args
         self.iter_n = 0
         self.past_data = {}
+        # NOTE: viz update rate is a magic number that seems to work fine and i don't have 
+        # any plans to make it smarter
+        self.viz_update_rate = int(np.ceil(self.args.ctrl_freq / 25))
         # save_past_dict has to have the key and 1 example of what you're saving
         # so that it's type can be inferred (but we're in python so types don't really work).
         # the good thing is this way you also immediatelly put in the initial values
@@ -132,7 +135,7 @@ class ControlLoopManager:
         # but if not, we want to control the speed of the simulation,
         # and how much we're plotting.
         # so this should be an argument that is use ONLY if we're in simulation
-        if i % 20 == 0:
+        if i % self.viz_update_rate == 0:
             # don't send what wasn't ready
             if self.args.visualizer:
                 if self.robot_manager.robot_name != "yumi":
diff --git a/python/smc/control/joint_space/joint_space_trajectory_following.py b/python/smc/control/joint_space/joint_space_trajectory_following.py
index a787aee06b0521407e3eeeccbc62633ddf159a12..dc5ee95caff0ac889d611b87bbe027f3f9eb1969 100644
--- a/python/smc/control/joint_space/joint_space_trajectory_following.py
+++ b/python/smc/control/joint_space/joint_space_trajectory_following.py
@@ -67,11 +67,7 @@ def followKinematicJointTrajPControlLoop(
             reference["vs"][t_index_lower] * time_difference,
         )
 
-    # TODO: why not use pin.difference for both?
-    if robot.robot_name == "ur5e":
-        error_q = q_ref - q
-    if robot.robot_name == "heron":
-        error_q = pin.difference(robot.model, q, q_ref)  # / robot.dt
+    error_q = pin.difference(robot.model, q, q_ref)
     error_v = v_ref - v
     Kp = 1.0
     Kd = 0.5
@@ -98,7 +94,7 @@ def followKinematicJointTrajP(args, robot, reference):
         followKinematicJointTrajPControlLoop, args.stop_at_final, robot, reference
     )
     log_item = {
-        "error_qs": np.zeros(robot.model.nq),
+        "error_qs": np.zeros(robot.model.nv),  # differences live in the tangent space
         "error_vs": np.zeros(robot.model.nv),
         "qs": np.zeros(robot.model.nq),
         "vs": np.zeros(robot.model.nv),
diff --git a/python/smc/control/optimal_control/abstract_croco_ocp.py b/python/smc/control/optimal_control/abstract_croco_ocp.py
index 867d3517e9464ef477ccf5719e1d2b10b066045b..fd68018311921e0e560de9a3d89a49e111a969a6 100644
--- a/python/smc/control/optimal_control/abstract_croco_ocp.py
+++ b/python/smc/control/optimal_control/abstract_croco_ocp.py
@@ -223,7 +223,6 @@ class CrocoOCP(abc.ABC):
             0.0,
         )
 
-
     @abc.abstractmethod
     def constructTaskObjectiveFunction(self, goal) -> None: ...
 
@@ -242,10 +241,10 @@ class CrocoOCP(abc.ABC):
         # solver = crocoddyl.SolverIpopt(problem)
         # TODO: select other solvers from arguments
         self.solver = crocoddyl.SolverBoxFDDP(self.problem)
-        # TODO: make these callbacks optional
-        self.solver.setCallbacks(
-            [crocoddyl.CallbackVerbose(), crocoddyl.CallbackLogger()]
-        )
+        if self.args.debug_prints:
+            self.solver.setCallbacks(
+                [crocoddyl.CallbackVerbose(), crocoddyl.CallbackLogger()]
+            )
 
     # NOTE: used by csqp
     def createMimSolver(self) -> None:
@@ -259,10 +258,10 @@ class CrocoOCP(abc.ABC):
         # solver = mim_solvers.SolverSQP(problem)
         # TODO: select other solvers from arguments
         self.solver = mim_solvers.SolverCSQP(self.problem)
-        # TODO: make these callbacks optional
-        self.solver.setCallbacks(
-            [mim_solvers.CallbackVerbose(), mim_solvers.CallbackLogger()]
-        )
+        if self.args.debug_prints:
+            self.solver.setCallbacks(
+                [mim_solvers.CallbackVerbose(), mim_solvers.CallbackLogger()]
+            )
 
     # this shouldn't really depend on x0 but i can't be bothered
     def solveOCP(self, x0: np.ndarray) -> tuple[dict, Any]:
diff --git a/python/smc/control/optimal_control/croco_mpc_path_following.py b/python/smc/control/optimal_control/croco_mpc_path_following.py
index 7e63a890ca0ee3d8ad5b1a5b124eaea70f9c2a65..2ce182ff2d0830430f0514728d23e93c2d2b336e 100644
--- a/python/smc/control/optimal_control/croco_mpc_path_following.py
+++ b/python/smc/control/optimal_control/croco_mpc_path_following.py
@@ -5,6 +5,11 @@ from smc.control.optimal_control.path_following_croco_ocp import (
     CrocoEEPathFollowingOCP,
     BaseAndEEPathFollowingOCP,
 )
+from smc.path_generation.path_math.path2d_to_6d import (
+    path2D_to_SE3_fixed,
+    path2D_to_SE3_with_transition_from_current_pose,
+)
+from smc.path_generation.path_math.path_to_trajectory import path2D_timed
 
 import crocoddyl
 import numpy as np
@@ -20,14 +25,6 @@ if importlib.util.find_spec("mim_solvers"):
             "mim_solvers installation is broken, rebuild and reinstall it if you want it"
         )
 
-# TODO: put others here too
-if importlib.util.find_spec("shapely"):
-    from smc.path_generation.planner import (
-        path2D_timed,
-        pathPointFromPathParam,
-        path2D_to_SE3,
-    )
-
 
 def CrocoEndEffectorPathFollowingMPCControlLoop(
     args,
@@ -35,7 +32,7 @@ def CrocoEndEffectorPathFollowingMPCControlLoop(
     solver: crocoddyl.SolverBoxFDDP,
     path_planner: ProcessManager,
     t,
-    past_data,
+    _,
 ):
     """
     CrocoPathFollowingMPCControlLoop
@@ -51,7 +48,7 @@ def CrocoEndEffectorPathFollowingMPCControlLoop(
     save_past_dict = {}
 
     q = robot.q
-    T_w_e = robot.getT_w_e()
+    T_w_e = robot.T_w_e
     p = T_w_e.translation[:2]
 
     # NOTE: it's pointless to recalculate the path every time
@@ -64,7 +61,7 @@ def CrocoEndEffectorPathFollowingMPCControlLoop(
         data = path_planner.getData()
         if data == None:
             if args.debug_prints:
-                print("CTRL: got no path so not i won't move")
+                print("CTRL: got no path so i won't move")
             robot.sendVelocityCommand(np.zeros(robot.model.nv))
             log_item["qs"] = q.reshape((robot.model.nq,))
             log_item["dqs"] = robot.v.reshape((robot.model.nv,))
@@ -82,11 +79,12 @@ def CrocoEndEffectorPathFollowingMPCControlLoop(
         path2D = path2D_timed(args, path2D_untimed, max_base_v)
 
         # create a 3D reference out of the path
-        pathSE3 = path2D_to_SE3(path2D, args.handlebar_height)
+        pathSE3 = path2D_to_SE3_fixed(path2D, args.handlebar_height)
 
     # TODO: EVIL AND HAS TO BE REMOVED FROM HERE
-    if args.visualize_manipulator:
-        if t % 20 == 0:
+    if args.visualizer:
+        # if t % 20 == 0:
+        if t % int(np.ceil(args.ctrl_freq / 25)) == 0:
             robot.visualizer_manager.sendCommand({"frame_path": pathSE3})
 
     x0 = np.concatenate([robot.q, robot.v])
@@ -130,11 +128,8 @@ def CrocoEndEffectorPathFollowingMPC(args, robot, x0, path_planner):
     are actually extracted from the state x(q,dq).
     """
 
-    problem = createCrocoEEPathFollowingOCP(args, robot, x0)
-    if args.solver == "boxfddp":
-        solver = crocoddyl.SolverBoxFDDP(problem)
-    if args.solver == "csqp":
-        solver = mim_solvers.SolverCSQP(problem)
+    ocp = CrocoEEPathFollowingOCP(args, robot, x0)
+    solver = ocp.getSolver()
 
     # technically should be done in controlloop because now
     # it's solved 2 times before the first command,
@@ -277,7 +272,7 @@ def BaseAndEEPathFollowingMPCControlLoop(
         pathSE3_handlebar_left.append(goal_transform.act(pathSE3))
         pathSE3_handlebar_right.append(goal_transform.inverse().act(pathSE3))
 
-    if args.visualize_manipulator:
+    if args.visualizer:
         if iter_n % 20 == 0:
             robot.visualizer_manager.sendCommand({"path": path_base})
             robot.visualizer_manager.sendCommand({"frame_path": pathSE3_handlebar})
diff --git a/python/smc/control/optimal_control/point_to_point_croco_ocp.py b/python/smc/control/optimal_control/point_to_point_croco_ocp.py
index 39c6e19bc4c3c2901c5ce751e6c286c2aa109ba5..6748a091ba9b0a778eb15ea2bbd425a5fbd95017 100644
--- a/python/smc/control/optimal_control/point_to_point_croco_ocp.py
+++ b/python/smc/control/optimal_control/point_to_point_croco_ocp.py
@@ -17,7 +17,6 @@ class SingleArmIKOCP(CrocoOCP):
         T_w_goal: pin.SE3,
     ):
         super().__init__(args, robot, x0, T_w_goal)
-        self.constructTaskObjectiveFunction(T_w_goal)
 
     def constructTaskObjectiveFunction(self, goal):
         T_w_goal = goal
@@ -49,8 +48,12 @@ class SingleArmIKOCP(CrocoOCP):
             self.state, frameVelocityResidual
         )
         for i in range(self.args.n_knots):
-            self.runningCostModels[i].addCost("gripperPose", goalTrackingCost, 1e2)
-        self.terminalCostModel.addCost("gripperPose", goalTrackingCost, 1e2)
+            self.runningCostModels[i].addCost(
+                "gripperPose" + str(i), goalTrackingCost, 1e2
+            )
+        self.terminalCostModel.addCost(
+            "gripperPose" + str(self.args.n_knots), goalTrackingCost, 1e2
+        )
         self.terminalCostModel.addCost("velFinal", frameVelocityCost, 1e3)
 
 
@@ -99,9 +102,17 @@ class DualArmIKOCP(CrocoOCP):
             self.state, frameVelocityResidual_r
         )
         for i in range(self.args.n_knots):
-            self.runningCostModels[i].addCost("gripperPose_l", goalTrackingCost_l, 1e2)
-            self.runningCostModels[i].addCost("gripperPose_r", goalTrackingCost_r, 1e2)
-        self.terminalCostModel.addCost("gripperPose_l", goalTrackingCost_l, 1e2)
-        self.terminalCostModel.addCost("gripperPose_r", goalTrackingCost_r, 1e2)
+            self.runningCostModels[i].addCost(
+                "gripperPose_l" + str(i), goalTrackingCost_l, 1e2
+            )
+            self.runningCostModels[i].addCost(
+                "gripperPose_r" + str(i), goalTrackingCost_r, 1e2
+            )
+        self.terminalCostModel.addCost(
+            "gripperPose_l" + str(self.args.n_knots), goalTrackingCost_l, 1e2
+        )
+        self.terminalCostModel.addCost(
+            "gripperPose_r" + str(self.args.n_knots), goalTrackingCost_r, 1e2
+        )
         self.terminalCostModel.addCost("velFinal_l", frameVelocityCost_l, 1e3)
         self.terminalCostModel.addCost("velFinal_r", frameVelocityCost_r, 1e3)
diff --git a/python/smc/path_generation/OLD_sebas_path_generator_WITH_EVERYTHING.py b/python/smc/path_generation/OLD_sebas_path_generator_WITH_EVERYTHING.py
new file mode 100644
index 0000000000000000000000000000000000000000..3f6bea641f44fc51f0e53b42a80b03483a24d882
--- /dev/null
+++ b/python/smc/path_generation/OLD_sebas_path_generator_WITH_EVERYTHING.py
@@ -0,0 +1,629 @@
+from typing import List
+from abc import ABC, abstractmethod
+
+import numpy as np
+from starworlds.obstacles import StarshapedObstacle
+from starworlds.starshaped_hull import cluster_and_starify, ObstacleCluster
+from starworlds.utils.misc import tic, toc
+import shapely
+import yaml
+
+import matplotlib.pyplot as plt
+import matplotlib.collections as plt_col
+
+
+
+### mobile_robot.py
+
+class MobileRobot(ABC):
+
+    def __init__(self, nu, nx, width, name, u_min=None, u_max=None, x_min=None, x_max=None):
+        """
+        nx : int            number of state variables
+        nu : int            number of input variables
+        baseline : float    distance between the wheels
+        name : str          the name of the robot
+        u_min : np.ndarray  minimum input value
+        u_max : np.ndarray  maximum input value
+        x_min : np.ndarray  minimum state value
+        x_max : np.ndarray  maximum state value
+        """
+        self.nx = nx
+        self.nu = nu
+        self.width = width
+        self.name = name
+        def valid_u_bound(bound): return bound is not None and len(bound) == self.nu
+        def valid_q_bound(bound): return bound is not None and len(bound) == self.nx
+        self.u_min = u_min if valid_u_bound(u_min) else [-np.inf] * self.nu
+        self.u_max = u_max if valid_u_bound(u_max) else [np.inf] * self.nu
+        self.x_min = x_min if valid_q_bound(x_min) else [-np.inf] * self.nx
+        self.x_max = x_max if valid_q_bound(x_max) else [np.inf] * self.nx
+
+    @abstractmethod
+    def f(self, x, u):
+        """ Forward dynamics ? """
+        pass
+
+    @abstractmethod
+    def h(self, q):
+        """ Forward kinematics """
+        pass
+
+    @abstractmethod
+    def vel_min(self):
+        pass
+
+    @abstractmethod
+    def vel_max(self):
+        pass
+
+    def move(self, x, u, dt):
+        u_sat = np.clip(u, self.u_min, self.u_max)
+        x_next = x + np.array(self.f(x, u_sat)) * dt
+        x_next = np.clip(x_next, self.x_min, self.x_max)
+        return x_next, u_sat
+
+
+class Unicycle(MobileRobot):
+
+    def __init__(self, width, vel_min=None, vel_max=None, name='robot'):
+        self.vmax = vel_max[0]
+        super().__init__(nu=2, nx=3, width=width, name=name, u_min=vel_min, u_max=vel_max)
+
+    def f(self, x, u):
+        return [u[0] * np.cos(x[2]),  # vx
+                u[0] * np.sin(x[2]),  # vy
+                u[1]]                 # wz
+
+    def h(self, x):
+        return x[:2]  # x, y
+
+    def vel_min(self):
+        return self.u_min
+
+    def vel_max(self):
+        return self.u_max
+
+    def init_plot(self, ax=None, color='b', alpha=0.7, markersize=10):
+        handles, ax = super(Unicycle, self).init_plot(ax=ax, color=color, alpha=alpha)
+        handles += ax.plot(0, 0, marker=(3, 0, np.rad2deg(0)), markersize=markersize, color=color)
+        handles += ax.plot(0, 0, marker=(2, 0, np.rad2deg(0)), markersize=0.5*markersize, color='w')
+        return handles, ax
+
+    def update_plot(self, x, handles):
+        super(Unicycle, self).update_plot(x, handles)
+        handles[1].set_data([x[0]], [x[1]])
+        handles[1].set_marker((3, 0, np.rad2deg(x[2]-np.pi/2)))
+        handles[1].set_markersize(handles[1].get_markersize())
+        handles[2].set_data([x[0]], [x[1]])
+        handles[2].set_marker((2, 0, np.rad2deg(x[2]-np.pi/2)))
+        handles[2].set_markersize(handles[2].get_markersize())
+
+
+
+### tunnel_mpc_controller.py
+
+class SceneUpdater():
+    
+    def __init__(self, params: dict, verbosity=0):
+        self.params = params
+        self.verbosity = verbosity
+        self.reset()
+
+    def reset(self):
+        self.obstacle_clusters : List[ObstacleCluster] = None
+        self.free_star = None
+    
+    # workspace_modification.py
+
+    # TODO: Check why computational time varies so much for same static scene
+    @staticmethod
+    def workspace_modification(obstacles, p, pg, rho0, max_compute_time, hull_epsilon, gamma=0.5, make_convex=0, obstacle_clusters_prev=None, free_star_prev=None, verbosity=0):
+
+        # Clearance variable initialization
+        rho = rho0 / gamma  # First rho should be rho0
+        t_init = tic()
+
+        while True:
+            if toc(t_init) > max_compute_time:
+                if verbosity > 0:
+                    print("[Workspace modification]: Max compute time in rho iteration.")
+                break
+
+            # Reduce rho
+            rho *= gamma
+
+            # Pad obstacles with rho
+            obstacles_rho = [o.dilated_obstacle(padding=rho, id="duplicate") for o in obstacles]
+
+            # TODO: Fix boundaries
+            free_rho = shapely.geometry.box(-20, -20, 20, 20)
+            for o in obstacles_rho:
+                free_rho = free_rho.difference(o.polygon())
+
+            # TODO: Check buffering fix
+            # Find P0
+            Bp = shapely.geometry.Point(p).buffer(0.95 * rho)
+            initial_reference_set = Bp.intersection(free_rho.buffer(-0.1 * rho))
+
+            if not initial_reference_set.is_empty:
+                break
+
+        # Initial and goal reference position selection
+        r0_sh, _ = shapely.ops.nearest_points(initial_reference_set, shapely.geometry.Point(p))
+        r0 = np.array(r0_sh.coords[0])
+        rg_sh, _ = shapely.ops.nearest_points(free_rho, shapely.geometry.Point(pg))
+        rg = np.array(rg_sh.coords[0])
+
+
+        # TODO: Check more thoroughly
+        if free_star_prev is not None:
+            free_star_prev = free_star_prev.buffer(-1e-4)
+        if free_star_prev is not None and free_star_prev.contains(r0_sh) and free_star_prev.contains(rg_sh) and free_rho.contains(free_star_prev):# not any([free_star_prev.covers(o.polygon()) for o in obstacles_rho]):
+            if verbosity > 1:
+                print("[Workspace modification]: Reuse workspace from previous time step.")
+            obstacle_clusters = obstacle_clusters_prev
+            exit_flag = 10
+        else:
+            # Apply cluster and starify
+            obstacle_clusters, obstacle_timing, exit_flag, n_iter = \
+                cluster_and_starify(obstacles_rho, r0, rg, hull_epsilon, max_compute_time=max_compute_time-toc(t_init),
+                                    previous_clusters=obstacle_clusters_prev,
+                                    make_convex=make_convex, verbose=verbosity)
+
+        free_star = shapely.geometry.box(-20, -20, 20, 20)
+        for o in obstacle_clusters:
+            free_star = free_star.difference(o.polygon())
+
+        compute_time = toc(t_init)
+        return obstacle_clusters, r0, rg, rho, free_star, compute_time, exit_flag
+
+    def update(self, p: np.ndarray, pg: np.ndarray, obstacles) -> tuple[np.ndarray, np.ndarray, float, list[StarshapedObstacle]]:
+        # Update obstacles
+        if not self.params['use_prev_workspace']:
+            self.free_star = None
+        self.obstacle_clusters, r0, rg, rho, self.free_star, _, _ = SceneUpdater.workspace_modification(
+            obstacles, p, pg, self.params['rho0'], self.params['max_obs_compute_time'],
+            self.params['hull_epsilon'], self.params['gamma'],
+            make_convex=self.params['make_convex'], obstacle_clusters_prev=self.obstacle_clusters,
+            free_star_prev=self.free_star, verbosity=self.verbosity)
+        obstacles_star : List[StarshapedObstacle] = [o.cluster_obstacle for o in self.obstacle_clusters]
+        # Make sure all polygon representations are computed
+        [o._compute_polygon_representation() for o in obstacles_star]
+        
+        return r0, rg, rho, obstacles_star
+
+
+class PathGenerator():
+    
+    def __init__(self, params: dict, verbosity=0):
+        self.params = params
+        self.verbosity = verbosity
+        self.reset()
+
+    def reset(self):
+        self.target_path = []
+    
+    ### soads.py
+
+    # TODO: Check if can make more computationally efficient
+    @staticmethod
+    def soads_f(r, rg, obstacles: List[StarshapedObstacle], adapt_obstacle_velocity=False, unit_magnitude=False, crep=1., reactivity=1., tail_effect=False, convergence_tolerance=1e-4, d=False):
+        goal_vector = rg - r
+        goal_dist = np.linalg.norm(goal_vector)
+        if goal_dist < convergence_tolerance:
+            return 0 * r
+
+        No = len(obstacles)
+        fa = goal_vector / goal_dist  # Attractor dynamics
+        if No == 0:
+            return fa
+
+        ef = [-fa[1], fa[0]]
+        Rf = np.vstack((fa, ef)).T
+
+        mu = [obs.reference_direction(r) for obs in obstacles]
+        normal = [obs.normal(r) for obs in obstacles]
+        gamma = [obs.distance_function(r) for obs in obstacles]
+        # Compute weights
+        w = PathGenerator.compute_weights(gamma, weightPow=1)
+
+        # Compute obstacle velocities
+        xd_o = np.zeros((2, No))
+        if adapt_obstacle_velocity:
+            for i, obs in enumerate(obstacles):
+                xd_o[:, i] = obs.vel_intertial_frame(r)
+
+        kappa = 0.
+        f_mag = 0.
+        for i in range(No):
+            # Compute basis matrix
+            E = np.zeros((2, 2))
+            E[:, 0] = mu[i]
+            E[:, 1] = [-normal[i][1], normal[i][0]]
+            # Compute eigenvalues
+            D = np.zeros((2, 2))
+            D[0, 0] = 1 - crep / (gamma[i] ** (1 / reactivity)) if tail_effect or normal[i].dot(fa) < 0. else 1
+            D[1, 1] = 1 + 1 / gamma[i] ** (1 / reactivity)
+            # Compute modulation
+            M = E.dot(D).dot(np.linalg.inv(E))
+            # f_i = M.dot(fa)
+            f_i = M.dot(fa - xd_o[:, i]) + xd_o[:, i]
+            # Compute contribution to velocity magnitude
+            f_i_abs = np.linalg.norm(f_i)
+            f_mag += w[i] * f_i_abs
+            # Compute contribution to velocity direction
+            nu_i = f_i / f_i_abs
+            nu_i_hat = Rf.T.dot(nu_i)
+            kappa_i = np.arccos(np.clip(nu_i_hat[0], -1, 1)) * np.sign(nu_i_hat[1])
+            kappa += w[i] * kappa_i
+        kappa_norm = abs(kappa)
+        f_o = Rf.dot([np.cos(kappa_norm), np.sin(kappa_norm) / kappa_norm * kappa]) if kappa_norm > 0. else fa
+
+        if unit_magnitude:
+            f_mag = 1.
+        return f_mag * f_o
+
+    @staticmethod
+    def compute_weights(
+        distMeas,
+        N=0,
+        distMeas_lowerLimit=1,
+        weightType="inverseGamma",
+        weightPow=2,
+    ):
+        """Compute weights based on a distance measure (with no upper limit)"""
+        distMeas = np.array(distMeas)
+        n_points = distMeas.shape[0]
+
+        critical_points = distMeas <= distMeas_lowerLimit
+
+        if np.sum(critical_points):  # at least one
+            if np.sum(critical_points) == 1:
+                w = critical_points * 1.0
+                return w
+            else:
+                # TODO: continuous weighting function
+                # warnings.warn("Implement continuity of weighting function.")
+                w = critical_points * 1.0 / np.sum(critical_points)
+                return w
+
+        distMeas = distMeas - distMeas_lowerLimit
+        w = (1 / distMeas) ** weightPow
+        if np.sum(w) == 0:
+            return w
+        w = w / np.sum(w)  # Normalization
+        return w
+
+    ### path_generator.py
+
+    @staticmethod
+    def pol2pos(path_pol, s):
+        n_pol = len(path_pol) // 2 - 1
+        return [sum([path_pol[j * (n_pol + 1) + i] * s ** (n_pol - i) for i in range(n_pol + 1)]) for j in range(2)]
+
+    @staticmethod
+    def path_generator(r0, rg, obstacles, dp_max, N, dt, max_compute_time, n_pol, ds_decay_rate=0.5,
+                       ds_increase_rate=2., max_nr_steps=1000, convergence_tolerance=1e-5, P_prev=None, s_prev=None,
+                       reactivity=1., crep=1., tail_effect=False, reference_step_size=0.5, verbosity=0):
+        """
+        r0 : np.ndarray                       initial reference position
+        rg : np.ndarray                       goal reference position
+        obstacles : list[StarshapedObstacle]  obstacles in the scene
+        dp_max : float                        maximum position increment (i.e. vmax * dt)
+        N : int                               ???
+        dt : float                            time step
+        max_compute_time : float              timeout for computation
+        n_pol : int                           degree of the polynomial that fits the reference  ???
+        ds_decay_rate : float                 ???
+        ds_increase_rate : float              ???
+        max_nr_steps : int                    computation steps threshold
+        convergence_tolerance : float         ???
+        P_prev : np.ndarray                   previous path  ???
+        s_prev : np.ndarray                   previous path time  ???
+        reactivity : float                    ???
+        crep : float                          ???
+        tail_effect : bool                    ???
+        reference_step_size : float           ???
+        verbosity : int                       you guessed it...
+        """
+        
+        t0 = tic()
+
+        # Initialize
+        ds = 1
+        s = np.zeros(max_nr_steps)
+        r = np.zeros((max_nr_steps, r0.size))
+        if P_prev is not None:
+            i = P_prev.shape[0]
+            r[:i, :] = P_prev
+            s[:i] = s_prev
+        else:
+            i = 1
+            r[0, :] = r0
+
+        while True:
+            dist_to_goal = np.linalg.norm(r[i - 1, :] - rg)
+            # Check exit conditions
+            if dist_to_goal < convergence_tolerance:
+                if verbosity > 1:
+                    print(f"[Path Generator]: Path converged. {int(100 * (s[i - 1] / N))}% of path completed.")
+                break
+            if s[i - 1] >= N:
+                if verbosity > 1:
+                    print(f"[Path Generator]: Completed path length. {int(100 * (s[i - 1] / N))}% of path completed.")
+                break
+            if toc(t0) > max_compute_time:
+                if verbosity > 1:
+                    print(f"[Path Generator]: Max compute time in path integrator. {int(100 * (s[i - 1] / N))}% of path completed.")
+                break
+            if i >= max_nr_steps:
+                if verbosity > 1:
+                    print(f"[Path Generator]: Max steps taken in path integrator. {int(100 * (s[i - 1] / N))}% of path completed.")
+                break
+
+            # Movement using SOADS dynamics
+            dr = min(dp_max, dist_to_goal) * PathGenerator.soads_f(r[i - 1, :], rg, obstacles, adapt_obstacle_velocity=False,
+                                                                   unit_magnitude=True, crep=crep,
+                                                                   reactivity=reactivity, tail_effect=tail_effect,
+                                                                   convergence_tolerance=convergence_tolerance)
+
+            r[i, :] = r[i - 1, :] + dr * ds
+
+            ri_in_obstacle = False
+            while any([o.interior_point(r[i, :]) for o in obstacles]):
+                if verbosity > 1:
+                    print("[Path Generator]: Path inside obstacle. Reducing integration step from {:5f} to {:5f}.".format(ds, ds*ds_decay_rate))
+                ds *= ds_decay_rate
+                r[i, :] = r[i - 1, :] + dr * ds
+                # Additional compute time check
+                if toc(t0) > max_compute_time:
+                    ri_in_obstacle = True
+                    break
+            if ri_in_obstacle:
+                continue
+
+            # Update travelled distance
+            s[i] = s[i - 1] + ds
+            # Try to increase step rate again
+            ds = min(ds_increase_rate * ds, 1)
+            # Increase iteration counter
+            i += 1
+
+        r = r[:i, :]
+        s = s[:i]
+
+        # Evenly spaced path
+        s_vec = np.arange(0, s[-1] + reference_step_size, reference_step_size)
+        xs, ys = np.interp(s_vec, s, r[:, 0]), np.interp(s_vec, s, r[:, 1])
+        # Append not finished path with fixed final position
+        s_vec = np.append(s_vec, np.arange(s[-1] + reference_step_size, N + reference_step_size, reference_step_size))
+        xs = np.append(xs, xs[-1] * np.ones(len(s_vec)-len(xs)))
+        ys = np.append(ys, ys[-1] * np.ones(len(s_vec)-len(ys)))
+
+        reference_path = [el for p in zip(xs, ys) for el in p]  # [x0 y0 x1 y1 ...]
+
+        # TODO: Fix when close to goal
+        # TODO: Adjust for short arc length, skip higher order terms..
+        path_pol = np.polyfit(s_vec, reference_path[::2], n_pol).tolist() + \
+                np.polyfit(s_vec, reference_path[1::2], n_pol).tolist()  # [px0 px1 ... pxn py0 py1 ... pyn]
+        # Force init position to be correct
+        path_pol[n_pol] = reference_path[0]
+        path_pol[-1] = reference_path[1]
+
+        # Compute polyfit approximation error
+        epsilon = [np.linalg.norm(np.array(reference_path[2 * i:2 * (i + 1)]) - np.array(PathGenerator.pol2pos(path_pol, s_vec[i]))) for i in range(N + 1)]
+
+        compute_time = toc(t0)
+        
+        """
+        path_pol : np.ndarray   the polynomial approximation of `reference_path`
+        epsilon : [float]       approximation error between the polynomial fit and the actual path
+        reference_path : list   the actual path (used for P_prev later on) in [x1, y1, x2, y2, ...] format
+        compute_time : float    overall timing of this function
+        """
+        return path_pol, epsilon, reference_path, compute_time
+        
+    def prepare_prev(self, p: np.ndarray, rho: float, obstacles_star: List[StarshapedObstacle]):
+        P_prev = np.array([self.target_path[::2], self.target_path[1::2]]).T
+        # Shift path to start at point closest to robot position
+        P_prev = P_prev[np.argmin(np.linalg.norm(p - P_prev, axis=1)):, :]
+        # P_prev[0, :] = self.r0
+        if np.linalg.norm(p - P_prev[0, :]) > rho:
+            if self.verbosity > 0:
+                print("[Path Generator]: No reuse of previous path. Path not within distance rho from robot.")
+            P_prev = None
+        else:
+            for r in P_prev:
+                if any([o.interior_point(r) for o in obstacles_star]):
+                    if self.verbosity > 0:
+                        print("[Path Generator]: No reuse of previous path. Path not collision-free.")
+                    P_prev = None
+
+        if P_prev is not None:
+            # Cut off stand still padding in previous path
+            P_prev_stepsize = np.linalg.norm(np.diff(P_prev, axis=0), axis=1)
+            s_prev = np.hstack((0, np.cumsum(P_prev_stepsize) / self.params['dp_max']))
+            P_prev_mask = [True] + (P_prev_stepsize > 1e-8).tolist()
+            P_prev = P_prev[P_prev_mask, :]
+            s_prev = s_prev[P_prev_mask]
+        else:
+            s_prev = None
+        
+        return P_prev, s_prev
+    
+    def update(self, p: np.ndarray, r0: np.ndarray, rg: np.ndarray, rho: float, obstacles_star: List[StarshapedObstacle]) -> tuple[List[float], float]:
+        # Buffer previous target path
+        if self.params['buffer'] and self.target_path:
+            P_prev, s_prev = self.prepare_prev(p, rho, obstacles_star)
+        else:
+            P_prev, s_prev = None, None
+        # Generate the new path
+        path_pol, epsilon, self.target_path, _ = PathGenerator.path_generator(
+            r0, rg, obstacles_star, self.params['dp_max'], self.params['N'],
+            self.params['dt'], self.params['max_compute_time'], self.params['n_pol'],
+            ds_decay_rate=0.5, ds_increase_rate=2., max_nr_steps=1000, P_prev=P_prev, s_prev=s_prev,
+            reactivity=self.params['reactivity'], crep=self.params['crep'],
+            convergence_tolerance=self.params['convergence_tolerance'], verbosity=self.verbosity)
+        return path_pol, epsilon
+
+
+class MpcController():
+    
+    def __init__(self, params: dict, robot, verbosity=0):
+        self.params = params
+        self.robot = robot
+        # self.mpc_solver = TunnelMpc(params, robot)
+        self.verbosity = verbosity
+        self.reset()
+
+    def reset(self):
+        # self.mpc_solver.reset()
+        self.u_prev = [0] * self.robot.nu
+    
+    def check_convergence(self, p: np.ndarray, pg: np.ndarray):
+        return np.linalg.norm(p - pg) < self.params['convergence_margin']
+
+    def e_max(self, rho, epsilon):
+        if rho > 0:
+            e_max = rho - max(epsilon)
+        else:
+            e_max = 1.e6
+        return e_max
+    
+    def ref(self, path_pol, s):
+        n_pol = self.params['n_pol']
+        return [np.polyval(path_pol[j*(n_pol+1):(j+1)*(n_pol+1)], s) for j in range(self.params['np'])]
+    
+    def compute_u(self, x, p, path_pol, rg, rho, epsilon):
+        # Compute MPC solution
+        
+        # e_max = self.e_max(rho, epsilon)  # parameter for tracking error constraint
+        # solution = self.mpc_solver.run(x.tolist(), self.u_prev, path_pol, self.params, e_max, rg.tolist(), self.verbosity)  # call to Rust solver
+        # # Extract first control signal and store it for later
+        # self.u_prev = solution['u'][:self.robot.nu]
+        
+        p = np.array(p)
+        e_max = self.e_max(rho, epsilon)
+        s_kappa = 0.9 * e_max / self.robot.vmax
+        p_ref = self.ref(path_pol, s_kappa)
+        
+        err = p_ref - p
+        dir = np.array([np.cos(x[2]), np.sin(x[2])])
+        vel = 0.65 * self.robot.vmax * max(0.1, (dir @ (err / np.linalg.norm(err))))
+        wel = 0.85 * ((np.arctan2(err[1], err[0]) - x[2] + np.pi) % (2*np.pi) - np.pi)
+        
+        alpha = 1
+        self.u_prev = [alpha*vel, alpha*wel]
+
+        return np.array(self.u_prev)
+
+
+if __name__ == "__main__":
+    
+    from starworlds.obstacles import StarshapedPolygon
+    
+    # environment
+    obstacles = [
+        StarshapedPolygon([[2, 2], [8, 2], [8, 3], [2, 3]]),
+        StarshapedPolygon([[2, 3], [3, 3], [3, 4.25], [2, 4.25]]),
+        StarshapedPolygon([[2, 5], [8, 5], [8, 6], [2, 6]]),
+        StarshapedPolygon([[2, 8], [8, 8], [8, 9], [2, 9]]),
+    ]
+    pg = np.array([0.5, 5.5])  # goal position
+    p0 = np.array([9, 4])  # initial position
+    theta0 = np.arctan2(pg[1]-p0[1], pg[0]-p0[0])  # initial heading (simply start heading towards goal)
+    
+    # robot
+    robot_type = "Unicycle"
+    with open(r'robot_params.yaml') as f:
+        params = yaml.safe_load(f)
+    robot_params = params[robot_type]
+    robot = Unicycle(width=robot_params['width'], 
+                     vel_min=[robot_params['lin_vel_min'], -robot_params['ang_vel_max']],
+                     vel_max=[robot_params['lin_vel_max'], robot_params['ang_vel_max']], 
+                     name=robot_type)
+    x0 = np.append(p0, [theta0])  # initial robot state
+    
+    # MPC
+    with open(r'./tunnel_mpc_params.yaml') as f:
+        params = yaml.safe_load(f)
+    mpc_params = params["tunnel_mpc"]
+    mpc_params['dp_max'] = robot.vmax * mpc_params['dt']
+    
+    # components
+    verbosity = 1
+    scene_updater = SceneUpdater(mpc_params, verbosity)
+    path_gen = PathGenerator(mpc_params, verbosity) 
+    controller = MpcController(mpc_params, robot, verbosity)
+    
+    
+    # plotting
+    fig = plt.figure()
+    handle_goal = plt.plot(*pg, c="g")[0]
+    handle_init = plt.plot(*x0[:2], c="b")[0]
+    handle_curr = plt.plot(*x0[:2], c="r", marker=(3, 0, np.rad2deg(x0[2]-np.pi/2)), markersize=10)[0]
+    handle_curr_dir = plt.plot(0, 0, marker=(2, 0, np.rad2deg(0)), markersize=5, color='w')[0]
+    handle_path = plt.plot([], [], c="k")[0]
+    coll = plt_col.PolyCollection([
+        np.array([[2, 2], [8, 2], [8, 3], [2, 3]]),
+        np.array([[2, 3], [3, 3], [3, 4.25], [2, 4.25]]),
+        np.array([[2, 5], [8, 5], [8, 6], [2, 6]]),
+        np.array([[2, 8], [8, 8], [8, 9], [2, 9]])
+    ])
+    plt.gca().add_collection(coll)
+    handle_title = plt.text(5, 9.5, "", bbox={'facecolor':'w', 'alpha':0.5, 'pad':5}, ha="center")
+    plt.gca().set_aspect("equal")
+    plt.xlim([0, 10])
+    plt.ylim([0, 10])
+    plt.draw()
+    
+    
+    # run the controller
+    T_max = 30
+    dt = controller.params['dt']
+    t = 0.
+    x = x0
+    u_prev = np.zeros(robot.nu)
+    convergence_threshold = 0.05
+    converged = False
+    try:
+        while t < T_max:
+            p = robot.h(x)
+            
+            if np.linalg.norm(p - pg) < convergence_threshold:
+                break
+            
+            # Udpate the scene
+            r0, rg, rho, obstacles_star = scene_updater.update(p, pg, obstacles)
+
+            # Check for convergence
+            if controller.check_convergence(p, pg):
+                u = np.zeros(robot.nu)
+            else:
+                # Update target path
+                path_pol, epsilon = path_gen.update(p, r0, rg, rho, obstacles_star)
+                # Calculate next control input
+                u = controller.compute_u(x, p, path_pol, rg, rho, epsilon)
+            
+            # update robot position
+            x, _ = robot.move(x, u, dt)
+            u_prev = u
+            t += dt
+            
+            # plot
+            handle_curr.set_data([x[0]], [x[1]])
+            handle_curr.set_marker((3, 0, np.rad2deg(x[2]-np.pi/2)))
+            handle_curr_dir.set_data([x[0]], [x[1]])
+            handle_curr_dir.set_marker((2, 0, np.rad2deg(x[2]-np.pi/2)))
+            handle_path.set_data([path_gen.target_path[::2], path_gen.target_path[1::2]])
+            handle_title.set_text(f"{t:5.3f}")
+            fig.canvas.draw()
+            plt.pause(0.005)
+        
+    except Exception as ex:
+        raise ex
+        pass
+    
+    plt.show()
+    
diff --git a/python/smc/path_generation/maps/premade_maps.py b/python/smc/path_generation/maps/premade_maps.py
new file mode 100644
index 0000000000000000000000000000000000000000..7037857efa21ad64937c6343838febd99021d2c8
--- /dev/null
+++ b/python/smc/path_generation/maps/premade_maps.py
@@ -0,0 +1,21 @@
+from smc.path_generation.starworlds.obstacles import StarshapedPolygon
+
+
+def createSampleStaticMap():
+    """
+    createMap
+    ---------
+    return obstacles that define the 2D map
+    """
+    # [lower_left, lower_right, top_right, top_left]
+    map_as_list = [
+        [[2, 2], [8, 2], [8, 3], [2, 3]],
+        [[2, 3], [3, 3], [3, 4.25], [2, 4.25]],
+        [[2, 5], [8, 5], [8, 6], [2, 6]],
+        [[2, 8], [8, 8], [8, 9], [2, 9]],
+    ]
+
+    obstacles = []
+    for map_element in map_as_list:
+        obstacles.append(StarshapedPolygon(map_element))
+    return obstacles, map_as_list
diff --git a/python/smc/path_generation/path_generator.py b/python/smc/path_generation/path_generator.py
index 3f6bea641f44fc51f0e53b42a80b03483a24d882..04cbaf0887ac5a576e634b83bebdae85c2fd2767 100644
--- a/python/smc/path_generation/path_generator.py
+++ b/python/smc/path_generation/path_generator.py
@@ -1,201 +1,10 @@
-from typing import List
-from abc import ABC, abstractmethod
+from smc.path_generation.starworlds.obstacles import StarshapedObstacle
+from smc.path_generation.starworlds.utils.misc import tic, toc
 
 import numpy as np
-from starworlds.obstacles import StarshapedObstacle
-from starworlds.starshaped_hull import cluster_and_starify, ObstacleCluster
-from starworlds.utils.misc import tic, toc
-import shapely
-import yaml
-
-import matplotlib.pyplot as plt
-import matplotlib.collections as plt_col
-
-
-
-### mobile_robot.py
-
-class MobileRobot(ABC):
-
-    def __init__(self, nu, nx, width, name, u_min=None, u_max=None, x_min=None, x_max=None):
-        """
-        nx : int            number of state variables
-        nu : int            number of input variables
-        baseline : float    distance between the wheels
-        name : str          the name of the robot
-        u_min : np.ndarray  minimum input value
-        u_max : np.ndarray  maximum input value
-        x_min : np.ndarray  minimum state value
-        x_max : np.ndarray  maximum state value
-        """
-        self.nx = nx
-        self.nu = nu
-        self.width = width
-        self.name = name
-        def valid_u_bound(bound): return bound is not None and len(bound) == self.nu
-        def valid_q_bound(bound): return bound is not None and len(bound) == self.nx
-        self.u_min = u_min if valid_u_bound(u_min) else [-np.inf] * self.nu
-        self.u_max = u_max if valid_u_bound(u_max) else [np.inf] * self.nu
-        self.x_min = x_min if valid_q_bound(x_min) else [-np.inf] * self.nx
-        self.x_max = x_max if valid_q_bound(x_max) else [np.inf] * self.nx
-
-    @abstractmethod
-    def f(self, x, u):
-        """ Forward dynamics ? """
-        pass
-
-    @abstractmethod
-    def h(self, q):
-        """ Forward kinematics """
-        pass
-
-    @abstractmethod
-    def vel_min(self):
-        pass
-
-    @abstractmethod
-    def vel_max(self):
-        pass
-
-    def move(self, x, u, dt):
-        u_sat = np.clip(u, self.u_min, self.u_max)
-        x_next = x + np.array(self.f(x, u_sat)) * dt
-        x_next = np.clip(x_next, self.x_min, self.x_max)
-        return x_next, u_sat
-
-
-class Unicycle(MobileRobot):
-
-    def __init__(self, width, vel_min=None, vel_max=None, name='robot'):
-        self.vmax = vel_max[0]
-        super().__init__(nu=2, nx=3, width=width, name=name, u_min=vel_min, u_max=vel_max)
-
-    def f(self, x, u):
-        return [u[0] * np.cos(x[2]),  # vx
-                u[0] * np.sin(x[2]),  # vy
-                u[1]]                 # wz
-
-    def h(self, x):
-        return x[:2]  # x, y
-
-    def vel_min(self):
-        return self.u_min
-
-    def vel_max(self):
-        return self.u_max
-
-    def init_plot(self, ax=None, color='b', alpha=0.7, markersize=10):
-        handles, ax = super(Unicycle, self).init_plot(ax=ax, color=color, alpha=alpha)
-        handles += ax.plot(0, 0, marker=(3, 0, np.rad2deg(0)), markersize=markersize, color=color)
-        handles += ax.plot(0, 0, marker=(2, 0, np.rad2deg(0)), markersize=0.5*markersize, color='w')
-        return handles, ax
-
-    def update_plot(self, x, handles):
-        super(Unicycle, self).update_plot(x, handles)
-        handles[1].set_data([x[0]], [x[1]])
-        handles[1].set_marker((3, 0, np.rad2deg(x[2]-np.pi/2)))
-        handles[1].set_markersize(handles[1].get_markersize())
-        handles[2].set_data([x[0]], [x[1]])
-        handles[2].set_marker((2, 0, np.rad2deg(x[2]-np.pi/2)))
-        handles[2].set_markersize(handles[2].get_markersize())
-
-
-
-### tunnel_mpc_controller.py
-
-class SceneUpdater():
-    
-    def __init__(self, params: dict, verbosity=0):
-        self.params = params
-        self.verbosity = verbosity
-        self.reset()
-
-    def reset(self):
-        self.obstacle_clusters : List[ObstacleCluster] = None
-        self.free_star = None
-    
-    # workspace_modification.py
-
-    # TODO: Check why computational time varies so much for same static scene
-    @staticmethod
-    def workspace_modification(obstacles, p, pg, rho0, max_compute_time, hull_epsilon, gamma=0.5, make_convex=0, obstacle_clusters_prev=None, free_star_prev=None, verbosity=0):
-
-        # Clearance variable initialization
-        rho = rho0 / gamma  # First rho should be rho0
-        t_init = tic()
-
-        while True:
-            if toc(t_init) > max_compute_time:
-                if verbosity > 0:
-                    print("[Workspace modification]: Max compute time in rho iteration.")
-                break
-
-            # Reduce rho
-            rho *= gamma
-
-            # Pad obstacles with rho
-            obstacles_rho = [o.dilated_obstacle(padding=rho, id="duplicate") for o in obstacles]
-
-            # TODO: Fix boundaries
-            free_rho = shapely.geometry.box(-20, -20, 20, 20)
-            for o in obstacles_rho:
-                free_rho = free_rho.difference(o.polygon())
-
-            # TODO: Check buffering fix
-            # Find P0
-            Bp = shapely.geometry.Point(p).buffer(0.95 * rho)
-            initial_reference_set = Bp.intersection(free_rho.buffer(-0.1 * rho))
-
-            if not initial_reference_set.is_empty:
-                break
+from typing import List
 
-        # Initial and goal reference position selection
-        r0_sh, _ = shapely.ops.nearest_points(initial_reference_set, shapely.geometry.Point(p))
-        r0 = np.array(r0_sh.coords[0])
-        rg_sh, _ = shapely.ops.nearest_points(free_rho, shapely.geometry.Point(pg))
-        rg = np.array(rg_sh.coords[0])
-
-
-        # TODO: Check more thoroughly
-        if free_star_prev is not None:
-            free_star_prev = free_star_prev.buffer(-1e-4)
-        if free_star_prev is not None and free_star_prev.contains(r0_sh) and free_star_prev.contains(rg_sh) and free_rho.contains(free_star_prev):# not any([free_star_prev.covers(o.polygon()) for o in obstacles_rho]):
-            if verbosity > 1:
-                print("[Workspace modification]: Reuse workspace from previous time step.")
-            obstacle_clusters = obstacle_clusters_prev
-            exit_flag = 10
-        else:
-            # Apply cluster and starify
-            obstacle_clusters, obstacle_timing, exit_flag, n_iter = \
-                cluster_and_starify(obstacles_rho, r0, rg, hull_epsilon, max_compute_time=max_compute_time-toc(t_init),
-                                    previous_clusters=obstacle_clusters_prev,
-                                    make_convex=make_convex, verbose=verbosity)
-
-        free_star = shapely.geometry.box(-20, -20, 20, 20)
-        for o in obstacle_clusters:
-            free_star = free_star.difference(o.polygon())
-
-        compute_time = toc(t_init)
-        return obstacle_clusters, r0, rg, rho, free_star, compute_time, exit_flag
-
-    def update(self, p: np.ndarray, pg: np.ndarray, obstacles) -> tuple[np.ndarray, np.ndarray, float, list[StarshapedObstacle]]:
-        # Update obstacles
-        if not self.params['use_prev_workspace']:
-            self.free_star = None
-        self.obstacle_clusters, r0, rg, rho, self.free_star, _, _ = SceneUpdater.workspace_modification(
-            obstacles, p, pg, self.params['rho0'], self.params['max_obs_compute_time'],
-            self.params['hull_epsilon'], self.params['gamma'],
-            make_convex=self.params['make_convex'], obstacle_clusters_prev=self.obstacle_clusters,
-            free_star_prev=self.free_star, verbosity=self.verbosity)
-        obstacles_star : List[StarshapedObstacle] = [o.cluster_obstacle for o in self.obstacle_clusters]
-        # Make sure all polygon representations are computed
-        [o._compute_polygon_representation() for o in obstacles_star]
-        
-        return r0, rg, rho, obstacles_star
-
-
-class PathGenerator():
-    
+class PathGenerator:
     def __init__(self, params: dict, verbosity=0):
         self.params = params
         self.verbosity = verbosity
@@ -203,12 +12,23 @@ class PathGenerator():
 
     def reset(self):
         self.target_path = []
-    
+
     ### soads.py
 
     # TODO: Check if can make more computationally efficient
     @staticmethod
-    def soads_f(r, rg, obstacles: List[StarshapedObstacle], adapt_obstacle_velocity=False, unit_magnitude=False, crep=1., reactivity=1., tail_effect=False, convergence_tolerance=1e-4, d=False):
+    def soads_f(
+        r,
+        rg,
+        obstacles: List[StarshapedObstacle],
+        adapt_obstacle_velocity=False,
+        unit_magnitude=False,
+        crep=1.0,
+        reactivity=1.0,
+        tail_effect=False,
+        convergence_tolerance=1e-4,
+        d=False,
+    ):
         goal_vector = rg - r
         goal_dist = np.linalg.norm(goal_vector)
         if goal_dist < convergence_tolerance:
@@ -234,8 +54,8 @@ class PathGenerator():
             for i, obs in enumerate(obstacles):
                 xd_o[:, i] = obs.vel_intertial_frame(r)
 
-        kappa = 0.
-        f_mag = 0.
+        kappa = 0.0
+        f_mag = 0.0
         for i in range(No):
             # Compute basis matrix
             E = np.zeros((2, 2))
@@ -243,7 +63,11 @@ class PathGenerator():
             E[:, 1] = [-normal[i][1], normal[i][0]]
             # Compute eigenvalues
             D = np.zeros((2, 2))
-            D[0, 0] = 1 - crep / (gamma[i] ** (1 / reactivity)) if tail_effect or normal[i].dot(fa) < 0. else 1
+            D[0, 0] = (
+                1 - crep / (gamma[i] ** (1 / reactivity))
+                if tail_effect or normal[i].dot(fa) < 0.0
+                else 1
+            )
             D[1, 1] = 1 + 1 / gamma[i] ** (1 / reactivity)
             # Compute modulation
             M = E.dot(D).dot(np.linalg.inv(E))
@@ -258,10 +82,14 @@ class PathGenerator():
             kappa_i = np.arccos(np.clip(nu_i_hat[0], -1, 1)) * np.sign(nu_i_hat[1])
             kappa += w[i] * kappa_i
         kappa_norm = abs(kappa)
-        f_o = Rf.dot([np.cos(kappa_norm), np.sin(kappa_norm) / kappa_norm * kappa]) if kappa_norm > 0. else fa
+        f_o = (
+            Rf.dot([np.cos(kappa_norm), np.sin(kappa_norm) / kappa_norm * kappa])
+            if kappa_norm > 0.0
+            else fa
+        )
 
         if unit_magnitude:
-            f_mag = 1.
+            f_mag = 1.0
         return f_mag * f_o
 
     @staticmethod
@@ -300,12 +128,38 @@ class PathGenerator():
     @staticmethod
     def pol2pos(path_pol, s):
         n_pol = len(path_pol) // 2 - 1
-        return [sum([path_pol[j * (n_pol + 1) + i] * s ** (n_pol - i) for i in range(n_pol + 1)]) for j in range(2)]
+        return [
+            sum(
+                [
+                    path_pol[j * (n_pol + 1) + i] * s ** (n_pol - i)
+                    for i in range(n_pol + 1)
+                ]
+            )
+            for j in range(2)
+        ]
 
     @staticmethod
-    def path_generator(r0, rg, obstacles, dp_max, N, dt, max_compute_time, n_pol, ds_decay_rate=0.5,
-                       ds_increase_rate=2., max_nr_steps=1000, convergence_tolerance=1e-5, P_prev=None, s_prev=None,
-                       reactivity=1., crep=1., tail_effect=False, reference_step_size=0.5, verbosity=0):
+    def path_generator(
+        r0,
+        rg,
+        obstacles,
+        dp_max,
+        N,
+        dt,
+        max_compute_time,
+        n_pol,
+        ds_decay_rate=0.5,
+        ds_increase_rate=2.0,
+        max_nr_steps=1000,
+        convergence_tolerance=1e-5,
+        P_prev=None,
+        s_prev=None,
+        reactivity=1.0,
+        crep=1.0,
+        tail_effect=False,
+        reference_step_size=0.5,
+        verbosity=0,
+    ):
         """
         r0 : np.ndarray                       initial reference position
         rg : np.ndarray                       goal reference position
@@ -327,7 +181,7 @@ class PathGenerator():
         reference_step_size : float           ???
         verbosity : int                       you guessed it...
         """
-        
+
         t0 = tic()
 
         # Initialize
@@ -347,33 +201,52 @@ class PathGenerator():
             # Check exit conditions
             if dist_to_goal < convergence_tolerance:
                 if verbosity > 1:
-                    print(f"[Path Generator]: Path converged. {int(100 * (s[i - 1] / N))}% of path completed.")
+                    print(
+                        f"[Path Generator]: Path converged. {int(100 * (s[i - 1] / N))}% of path completed."
+                    )
                 break
             if s[i - 1] >= N:
                 if verbosity > 1:
-                    print(f"[Path Generator]: Completed path length. {int(100 * (s[i - 1] / N))}% of path completed.")
+                    print(
+                        f"[Path Generator]: Completed path length. {int(100 * (s[i - 1] / N))}% of path completed."
+                    )
                 break
             if toc(t0) > max_compute_time:
                 if verbosity > 1:
-                    print(f"[Path Generator]: Max compute time in path integrator. {int(100 * (s[i - 1] / N))}% of path completed.")
+                    print(
+                        f"[Path Generator]: Max compute time in path integrator. {int(100 * (s[i - 1] / N))}% of path completed."
+                    )
                 break
             if i >= max_nr_steps:
                 if verbosity > 1:
-                    print(f"[Path Generator]: Max steps taken in path integrator. {int(100 * (s[i - 1] / N))}% of path completed.")
+                    print(
+                        f"[Path Generator]: Max steps taken in path integrator. {int(100 * (s[i - 1] / N))}% of path completed."
+                    )
                 break
 
             # Movement using SOADS dynamics
-            dr = min(dp_max, dist_to_goal) * PathGenerator.soads_f(r[i - 1, :], rg, obstacles, adapt_obstacle_velocity=False,
-                                                                   unit_magnitude=True, crep=crep,
-                                                                   reactivity=reactivity, tail_effect=tail_effect,
-                                                                   convergence_tolerance=convergence_tolerance)
+            dr = min(dp_max, dist_to_goal) * PathGenerator.soads_f(
+                r[i - 1, :],
+                rg,
+                obstacles,
+                adapt_obstacle_velocity=False,
+                unit_magnitude=True,
+                crep=crep,
+                reactivity=reactivity,
+                tail_effect=tail_effect,
+                convergence_tolerance=convergence_tolerance,
+            )
 
             r[i, :] = r[i - 1, :] + dr * ds
 
             ri_in_obstacle = False
             while any([o.interior_point(r[i, :]) for o in obstacles]):
                 if verbosity > 1:
-                    print("[Path Generator]: Path inside obstacle. Reducing integration step from {:5f} to {:5f}.".format(ds, ds*ds_decay_rate))
+                    print(
+                        "[Path Generator]: Path inside obstacle. Reducing integration step from {:5f} to {:5f}.".format(
+                            ds, ds * ds_decay_rate
+                        )
+                    )
                 ds *= ds_decay_rate
                 r[i, :] = r[i - 1, :] + dr * ds
                 # Additional compute time check
@@ -397,25 +270,40 @@ class PathGenerator():
         s_vec = np.arange(0, s[-1] + reference_step_size, reference_step_size)
         xs, ys = np.interp(s_vec, s, r[:, 0]), np.interp(s_vec, s, r[:, 1])
         # Append not finished path with fixed final position
-        s_vec = np.append(s_vec, np.arange(s[-1] + reference_step_size, N + reference_step_size, reference_step_size))
-        xs = np.append(xs, xs[-1] * np.ones(len(s_vec)-len(xs)))
-        ys = np.append(ys, ys[-1] * np.ones(len(s_vec)-len(ys)))
+        s_vec = np.append(
+            s_vec,
+            np.arange(
+                s[-1] + reference_step_size,
+                N + reference_step_size,
+                reference_step_size,
+            ),
+        )
+        xs = np.append(xs, xs[-1] * np.ones(len(s_vec) - len(xs)))
+        ys = np.append(ys, ys[-1] * np.ones(len(s_vec) - len(ys)))
 
         reference_path = [el for p in zip(xs, ys) for el in p]  # [x0 y0 x1 y1 ...]
 
         # TODO: Fix when close to goal
         # TODO: Adjust for short arc length, skip higher order terms..
-        path_pol = np.polyfit(s_vec, reference_path[::2], n_pol).tolist() + \
-                np.polyfit(s_vec, reference_path[1::2], n_pol).tolist()  # [px0 px1 ... pxn py0 py1 ... pyn]
+        path_pol = (
+            np.polyfit(s_vec, reference_path[::2], n_pol).tolist()
+            + np.polyfit(s_vec, reference_path[1::2], n_pol).tolist()
+        )  # [px0 px1 ... pxn py0 py1 ... pyn]
         # Force init position to be correct
         path_pol[n_pol] = reference_path[0]
         path_pol[-1] = reference_path[1]
 
         # Compute polyfit approximation error
-        epsilon = [np.linalg.norm(np.array(reference_path[2 * i:2 * (i + 1)]) - np.array(PathGenerator.pol2pos(path_pol, s_vec[i]))) for i in range(N + 1)]
+        epsilon = [
+            np.linalg.norm(
+                np.array(reference_path[2 * i : 2 * (i + 1)])
+                - np.array(PathGenerator.pol2pos(path_pol, s_vec[i]))
+            )
+            for i in range(N + 1)
+        ]
 
         compute_time = toc(t0)
-        
+
         """
         path_pol : np.ndarray   the polynomial approximation of `reference_path`
         epsilon : [float]       approximation error between the polynomial fit and the actual path
@@ -423,207 +311,72 @@ class PathGenerator():
         compute_time : float    overall timing of this function
         """
         return path_pol, epsilon, reference_path, compute_time
-        
-    def prepare_prev(self, p: np.ndarray, rho: float, obstacles_star: List[StarshapedObstacle]):
+
+    def prepare_prev(
+        self, p: np.ndarray, rho: float, obstacles_star: List[StarshapedObstacle]
+    ):
         P_prev = np.array([self.target_path[::2], self.target_path[1::2]]).T
         # Shift path to start at point closest to robot position
-        P_prev = P_prev[np.argmin(np.linalg.norm(p - P_prev, axis=1)):, :]
+        P_prev = P_prev[np.argmin(np.linalg.norm(p - P_prev, axis=1)) :, :]
         # P_prev[0, :] = self.r0
         if np.linalg.norm(p - P_prev[0, :]) > rho:
             if self.verbosity > 0:
-                print("[Path Generator]: No reuse of previous path. Path not within distance rho from robot.")
+                print(
+                    "[Path Generator]: No reuse of previous path. Path not within distance rho from robot."
+                )
             P_prev = None
         else:
             for r in P_prev:
                 if any([o.interior_point(r) for o in obstacles_star]):
                     if self.verbosity > 0:
-                        print("[Path Generator]: No reuse of previous path. Path not collision-free.")
+                        print(
+                            "[Path Generator]: No reuse of previous path. Path not collision-free."
+                        )
                     P_prev = None
 
         if P_prev is not None:
             # Cut off stand still padding in previous path
             P_prev_stepsize = np.linalg.norm(np.diff(P_prev, axis=0), axis=1)
-            s_prev = np.hstack((0, np.cumsum(P_prev_stepsize) / self.params['dp_max']))
+            s_prev = np.hstack((0, np.cumsum(P_prev_stepsize) / self.params["dp_max"]))
             P_prev_mask = [True] + (P_prev_stepsize > 1e-8).tolist()
             P_prev = P_prev[P_prev_mask, :]
             s_prev = s_prev[P_prev_mask]
         else:
             s_prev = None
-        
+
         return P_prev, s_prev
-    
-    def update(self, p: np.ndarray, r0: np.ndarray, rg: np.ndarray, rho: float, obstacles_star: List[StarshapedObstacle]) -> tuple[List[float], float]:
+
+    def update(
+        self,
+        p: np.ndarray,
+        r0: np.ndarray,
+        rg: np.ndarray,
+        rho: float,
+        obstacles_star: List[StarshapedObstacle],
+    ) -> tuple[List[float], float]:
         # Buffer previous target path
-        if self.params['buffer'] and self.target_path:
+        if self.params["buffer"] and self.target_path:
             P_prev, s_prev = self.prepare_prev(p, rho, obstacles_star)
         else:
             P_prev, s_prev = None, None
         # Generate the new path
         path_pol, epsilon, self.target_path, _ = PathGenerator.path_generator(
-            r0, rg, obstacles_star, self.params['dp_max'], self.params['N'],
-            self.params['dt'], self.params['max_compute_time'], self.params['n_pol'],
-            ds_decay_rate=0.5, ds_increase_rate=2., max_nr_steps=1000, P_prev=P_prev, s_prev=s_prev,
-            reactivity=self.params['reactivity'], crep=self.params['crep'],
-            convergence_tolerance=self.params['convergence_tolerance'], verbosity=self.verbosity)
+            r0,
+            rg,
+            obstacles_star,
+            self.params["dp_max"],
+            self.params["N"],
+            self.params["dt"],
+            self.params["max_compute_time"],
+            self.params["n_pol"],
+            ds_decay_rate=0.5,
+            ds_increase_rate=2.0,
+            max_nr_steps=1000,
+            P_prev=P_prev,
+            s_prev=s_prev,
+            reactivity=self.params["reactivity"],
+            crep=self.params["crep"],
+            convergence_tolerance=self.params["convergence_tolerance"],
+            verbosity=self.verbosity,
+        )
         return path_pol, epsilon
-
-
-class MpcController():
-    
-    def __init__(self, params: dict, robot, verbosity=0):
-        self.params = params
-        self.robot = robot
-        # self.mpc_solver = TunnelMpc(params, robot)
-        self.verbosity = verbosity
-        self.reset()
-
-    def reset(self):
-        # self.mpc_solver.reset()
-        self.u_prev = [0] * self.robot.nu
-    
-    def check_convergence(self, p: np.ndarray, pg: np.ndarray):
-        return np.linalg.norm(p - pg) < self.params['convergence_margin']
-
-    def e_max(self, rho, epsilon):
-        if rho > 0:
-            e_max = rho - max(epsilon)
-        else:
-            e_max = 1.e6
-        return e_max
-    
-    def ref(self, path_pol, s):
-        n_pol = self.params['n_pol']
-        return [np.polyval(path_pol[j*(n_pol+1):(j+1)*(n_pol+1)], s) for j in range(self.params['np'])]
-    
-    def compute_u(self, x, p, path_pol, rg, rho, epsilon):
-        # Compute MPC solution
-        
-        # e_max = self.e_max(rho, epsilon)  # parameter for tracking error constraint
-        # solution = self.mpc_solver.run(x.tolist(), self.u_prev, path_pol, self.params, e_max, rg.tolist(), self.verbosity)  # call to Rust solver
-        # # Extract first control signal and store it for later
-        # self.u_prev = solution['u'][:self.robot.nu]
-        
-        p = np.array(p)
-        e_max = self.e_max(rho, epsilon)
-        s_kappa = 0.9 * e_max / self.robot.vmax
-        p_ref = self.ref(path_pol, s_kappa)
-        
-        err = p_ref - p
-        dir = np.array([np.cos(x[2]), np.sin(x[2])])
-        vel = 0.65 * self.robot.vmax * max(0.1, (dir @ (err / np.linalg.norm(err))))
-        wel = 0.85 * ((np.arctan2(err[1], err[0]) - x[2] + np.pi) % (2*np.pi) - np.pi)
-        
-        alpha = 1
-        self.u_prev = [alpha*vel, alpha*wel]
-
-        return np.array(self.u_prev)
-
-
-if __name__ == "__main__":
-    
-    from starworlds.obstacles import StarshapedPolygon
-    
-    # environment
-    obstacles = [
-        StarshapedPolygon([[2, 2], [8, 2], [8, 3], [2, 3]]),
-        StarshapedPolygon([[2, 3], [3, 3], [3, 4.25], [2, 4.25]]),
-        StarshapedPolygon([[2, 5], [8, 5], [8, 6], [2, 6]]),
-        StarshapedPolygon([[2, 8], [8, 8], [8, 9], [2, 9]]),
-    ]
-    pg = np.array([0.5, 5.5])  # goal position
-    p0 = np.array([9, 4])  # initial position
-    theta0 = np.arctan2(pg[1]-p0[1], pg[0]-p0[0])  # initial heading (simply start heading towards goal)
-    
-    # robot
-    robot_type = "Unicycle"
-    with open(r'robot_params.yaml') as f:
-        params = yaml.safe_load(f)
-    robot_params = params[robot_type]
-    robot = Unicycle(width=robot_params['width'], 
-                     vel_min=[robot_params['lin_vel_min'], -robot_params['ang_vel_max']],
-                     vel_max=[robot_params['lin_vel_max'], robot_params['ang_vel_max']], 
-                     name=robot_type)
-    x0 = np.append(p0, [theta0])  # initial robot state
-    
-    # MPC
-    with open(r'./tunnel_mpc_params.yaml') as f:
-        params = yaml.safe_load(f)
-    mpc_params = params["tunnel_mpc"]
-    mpc_params['dp_max'] = robot.vmax * mpc_params['dt']
-    
-    # components
-    verbosity = 1
-    scene_updater = SceneUpdater(mpc_params, verbosity)
-    path_gen = PathGenerator(mpc_params, verbosity) 
-    controller = MpcController(mpc_params, robot, verbosity)
-    
-    
-    # plotting
-    fig = plt.figure()
-    handle_goal = plt.plot(*pg, c="g")[0]
-    handle_init = plt.plot(*x0[:2], c="b")[0]
-    handle_curr = plt.plot(*x0[:2], c="r", marker=(3, 0, np.rad2deg(x0[2]-np.pi/2)), markersize=10)[0]
-    handle_curr_dir = plt.plot(0, 0, marker=(2, 0, np.rad2deg(0)), markersize=5, color='w')[0]
-    handle_path = plt.plot([], [], c="k")[0]
-    coll = plt_col.PolyCollection([
-        np.array([[2, 2], [8, 2], [8, 3], [2, 3]]),
-        np.array([[2, 3], [3, 3], [3, 4.25], [2, 4.25]]),
-        np.array([[2, 5], [8, 5], [8, 6], [2, 6]]),
-        np.array([[2, 8], [8, 8], [8, 9], [2, 9]])
-    ])
-    plt.gca().add_collection(coll)
-    handle_title = plt.text(5, 9.5, "", bbox={'facecolor':'w', 'alpha':0.5, 'pad':5}, ha="center")
-    plt.gca().set_aspect("equal")
-    plt.xlim([0, 10])
-    plt.ylim([0, 10])
-    plt.draw()
-    
-    
-    # run the controller
-    T_max = 30
-    dt = controller.params['dt']
-    t = 0.
-    x = x0
-    u_prev = np.zeros(robot.nu)
-    convergence_threshold = 0.05
-    converged = False
-    try:
-        while t < T_max:
-            p = robot.h(x)
-            
-            if np.linalg.norm(p - pg) < convergence_threshold:
-                break
-            
-            # Udpate the scene
-            r0, rg, rho, obstacles_star = scene_updater.update(p, pg, obstacles)
-
-            # Check for convergence
-            if controller.check_convergence(p, pg):
-                u = np.zeros(robot.nu)
-            else:
-                # Update target path
-                path_pol, epsilon = path_gen.update(p, r0, rg, rho, obstacles_star)
-                # Calculate next control input
-                u = controller.compute_u(x, p, path_pol, rg, rho, epsilon)
-            
-            # update robot position
-            x, _ = robot.move(x, u, dt)
-            u_prev = u
-            t += dt
-            
-            # plot
-            handle_curr.set_data([x[0]], [x[1]])
-            handle_curr.set_marker((3, 0, np.rad2deg(x[2]-np.pi/2)))
-            handle_curr_dir.set_data([x[0]], [x[1]])
-            handle_curr_dir.set_marker((2, 0, np.rad2deg(x[2]-np.pi/2)))
-            handle_path.set_data([path_gen.target_path[::2], path_gen.target_path[1::2]])
-            handle_title.set_text(f"{t:5.3f}")
-            fig.canvas.draw()
-            plt.pause(0.005)
-        
-    except Exception as ex:
-        raise ex
-        pass
-    
-    plt.show()
-    
diff --git a/python/smc/path_generation/path_math/path2d_to_6d.py b/python/smc/path_generation/path_math/path2d_to_6d.py
new file mode 100644
index 0000000000000000000000000000000000000000..a90b9c5fa66a3aff4b3c007cf13bc09722095c68
--- /dev/null
+++ b/python/smc/path_generation/path_math/path2d_to_6d.py
@@ -0,0 +1,131 @@
+import pinocchio as pin
+import numpy as np
+
+
+def path2D_to_SE3_fixed(path2D: np.ndarray, path_height: float):
+    """
+    path2D_SE3
+    ----------
+    we have a 2D path of (N,2) shape as reference
+    the OCP accepts SE3 (it could just rotations or translation too),
+    so this function constructs it from the 2D path.
+    """
+    #########################
+    #  path2D into pathSE2  #
+    #########################
+    # construct theta
+    # since it's a pairwise operation it can't be done on the last point
+    x_i = path2D[:, 0][:-1]  # no last element
+    y_i = path2D[:, 1][:-1]  # no last element
+    x_i_plus_1 = path2D[:, 0][1:]  # no first element
+    y_i_plus_1 = path2D[:, 1][1:]  # no first element
+    x_diff = x_i_plus_1 - x_i
+    y_diff = y_i_plus_1 - y_i
+    # elementwise arctan2
+    thetas = np.arctan2(x_diff, y_diff)
+
+    ######################################
+    #  construct SE3 from SE2 reference  #
+    ######################################
+    # the plan is parallel to the ground because it's a mobile
+    # manipulation task
+    pathSE3 = []
+    for i in range(len(path2D) - 1):
+        # first set the x axis to be in the theta direction
+        # TODO: make sure this one makes sense
+        rotation = np.array(
+            [
+                [-np.cos(thetas[i]), np.sin(thetas[i]), 0.0],
+                [-np.sin(thetas[i]), -np.cos(thetas[i]), 0.0],
+                [0.0, 0.0, -1.0],
+            ]
+        )
+        # rotation = pin.rpy.rpyToMatrix(0.0, 0.0, thetas[i])
+        # rotation = pin.rpy.rpyToMatrix(np.pi/2, np.pi/2,0.0) @ rotation
+        translation = np.array([path2D[i][0], path2D[i][1], path_height])
+        pathSE3.append(pin.SE3(rotation, translation))
+    pathSE3.append(pin.SE3(rotation, translation))
+    return pathSE3
+
+
+# NOTE: this is a complete hack, but it does not need to be
+def path2D_to_SE3_with_transition_from_current_pose(
+    path2D: np.ndarray, path_height: float, T_w_current: pin.SE3
+):
+    """
+    path2D_SE3
+    ----------
+    we have a 2D path of (N,2) shape as reference
+    the OCP accepts SE3 (it could just rotations or translation too),
+    so this function constructs it from the 2D path.
+    """
+    #########################
+    #  path2D into pathSE2  #
+    #########################
+    # construct theta
+    # since it's a pairwise operation it can't be done on the last point
+    x_i = path2D[:, 0][:-1]  # no last element
+    y_i = path2D[:, 1][:-1]  # no last element
+    x_i_plus_1 = path2D[:, 0][1:]  # no first element
+    y_i_plus_1 = path2D[:, 1][1:]  # no first element
+    x_diff = x_i_plus_1 - x_i
+    y_diff = y_i_plus_1 - y_i
+    # elementwise arctan2
+    thetas = np.arctan2(x_diff, y_diff)
+
+    # there is a height difference, we can't teleport in height
+    height_current = T_w_current.translation[2]
+    height_difference = path_height - height_current
+    height_difference_step = height_difference / len(path2D)
+
+    ######################################
+    #  construct SE3 from SE2 reference  #
+    ######################################
+    # the plan is parallel to the ground because it's a mobile
+    # manipulation task
+    pathSE3 = []
+    for i in range(len(path2D) - 1):
+        # first set the x axis to be in the theta direction
+        # TODO: make sure this one makes sense
+        # should be: z pointing down (our arbitrary choice)
+        # x follows the path tangent
+        # y just completes the frame (in this case orthogonal to path tangent parallel to the floor).
+        # this is good for cart pulling, but could be anything else for anything else:
+        # you can slap any orientation you want on a 2D path.
+
+        # NOTE: for mpc to follow this reference, the path needs to be followable.
+        # this means we need to interpolate between the current thing and the reference
+        rotation = np.array(
+            [
+                [-np.cos(thetas[i]), np.sin(thetas[i]), 0.0],
+                [-np.sin(thetas[i]), -np.cos(thetas[i]), 0.0],
+                [0.0, 0.0, -1.0],
+            ]
+        )
+        # rotation = pin.rpy.rpyToMatrix(0.0, 0.0, thetas[i])
+        # rotation = pin.rpy.rpyToMatrix(np.pi/2, np.pi/2,0.0) @ rotation
+        translation = np.array(
+            [path2D[i][0], path2D[i][1], height_current + i * height_difference_step]
+        )
+        pathSE3.append(pin.SE3(rotation, translation))
+    pathSE3.append(pin.SE3(rotation, translation))
+    return pathSE3
+
+
+# stupid function for stupid data re-assembly
+# def path2D_to_SE2(path2D : list):
+#    path2D = np.array(path2D)
+#    # create (N,2) path for list [x0,y0,x1,y1,...]
+#    # of course it shouldn't be like that to begin with but
+#    # i have no time for that
+#    path2D = path2D.reshape((-1, 2))
+#    # since it's a pairwise operation it can't be done on the last point
+#    x_i = path2D[:,0][:-1] # no last element
+#    y_i = path2D[:,1][:-1] # no last element
+#    x_i_plus_1 = path2D[:,0][1:] # no first element
+#    y_i_plus_1 = path2D[:,1][1:] # no first element
+#    # elementwise arctan2
+#    thetas = np.arctan2(x_i_plus_1 - x_i, y_i_plus_1 - y_i)
+#    thetas = thetas.reshape((-1, 1))
+#    path_SE2 = np.hstack((path2D, thetas))
+#    return path_SE2
diff --git a/python/smc/path_generation/path_math/path_to_trajectory.py b/python/smc/path_generation/path_math/path_to_trajectory.py
new file mode 100644
index 0000000000000000000000000000000000000000..743f4c4c1b9c5e2886a59d4feb6172224574ca31
--- /dev/null
+++ b/python/smc/path_generation/path_math/path_to_trajectory.py
@@ -0,0 +1,91 @@
+import numpy as np
+
+
+def path2D_timed(args, path2D_untimed, max_base_v):
+    """
+    path2D_timed
+    ---------------------
+    we have a 2D path of (N,2) shape as reference.
+    it times it as this is what the current ocp formulation needs:
+        there should be a timing associated with the path,
+        because defining the cost function as the fit of the rollout to the path
+        is complicated to do software-wise.
+        as it is now, we're pre-selecting points of the path, and associating those
+        with rollout states at a set time step between the states in the rollout.
+        this isn't a problem if we have an idea of how fast the robot can go,
+        which gives us a heuristic of how to select the points (if you went at maximum
+        speed, this is how far you'd go in this time, so this is your point).
+        thankfully this does not need to be exact because we just care about the distance
+        between the current point and the point on the path, so if it's further out
+        that just means the error is larger, and that doesn't necessarily correspond
+        to a different action.
+    NOTE: we are constructing a possibly bullshit
+    trajectory here, it's a man-made heuristic,
+    and we should leave that to the MPC,
+    but that requires too much coding and there is no time rn.
+    the idea is to use compute the tangent of the path,
+    and use that to make a 2D frenet frame.
+    this is the put to some height, making it SE3.
+    i.e. roll and pitch are fixed to be 0,
+    but you could make them some other constant
+    """
+
+    ####################################################
+    #  getting a timed 2D trajectory from a heuristic  #
+    ####################################################
+    # the strategy is somewhat reasonable at least:
+    # assume we're moving at 90% max velocity in the base,
+    # and use that.
+    perc_of_max_v = 0.9
+    base_v = perc_of_max_v * max_base_v
+
+    # 1) the length of the path divided by 0.9 * max_vel
+    #    gives us the total time of the trajectory,
+    #    so we first compute that
+    # easiest possible way to get approximate path length
+    # (yes it should be from the polynomial approximation but that takes time to write)
+    x_i = path2D_untimed[:, 0][:-1]  # no last element
+    y_i = path2D_untimed[:, 1][:-1]  # no last element
+    x_i_plus_1 = path2D_untimed[:, 0][1:]  # no first element
+    y_i_plus_1 = path2D_untimed[:, 1][1:]  # no first element
+    x_diff = x_i_plus_1 - x_i
+    x_diff = x_diff.reshape((-1, 1))
+    y_diff = y_i_plus_1 - y_i
+    y_diff = y_diff.reshape((-1, 1))
+    path_length = np.sum(np.linalg.norm(np.hstack((x_diff, y_diff)), axis=1))
+    total_time = path_length / base_v
+    # 2) we find the correspondence between s and time
+    # TODO: read from where it should be, but seba checked that it's 5 for some reason
+    # TODO THIS IS N IN PATH PLANNING, MAKE THIS A SHARED ARGUMENT
+    max_s = 5
+    t_to_s = max_s / total_time
+    # 3) construct the ocp-timed 2D path
+    # TODO MAKE REFERENCE_STEP_SIZE A SHARED ARGUMENT
+    # TODO: we should know max s a priori
+    reference_step_size = 0.5
+    s_vec = np.arange(0, len(path2D_untimed)) / reference_step_size
+
+    path2D = []
+    # time is i * args.ocp_dt
+    for i in range(args.n_knots + 1):
+        # what it should be but gets stuck if we're not yet on path
+        # s = (i * args.ocp_dt) * t_to_s
+        # full path
+        # NOTE: this should be wrong, and ocp_dt correct,
+        # but it works better for some reason xd
+        s = i * (max_s / args.n_knots)
+        path2D.append(
+            np.array(
+                [
+                    np.interp(s, s_vec, path2D_untimed[:, 0]),
+                    np.interp(s, s_vec, path2D_untimed[:, 1]),
+                ]
+            )
+        )
+    path2D = np.array(path2D)
+    return path2D
+
+
+# TODO: todo
+def path2D_to_timed_SE3():
+    pass
diff --git a/python/smc/path_generation/planner.py b/python/smc/path_generation/planner.py
index 02bf2f184f33543e2ddd80a7f839d39c05f984cf..0fb591bc3edc1b8cd03ed55e7d7d83c20f9597b3 100644
--- a/python/smc/path_generation/planner.py
+++ b/python/smc/path_generation/planner.py
@@ -1,24 +1,13 @@
-from typing import List
-from abc import ABC, abstractmethod
-
-import numpy as np
-from smc.path_generation.starworlds.obstacles import StarshapedObstacle
-from smc.path_generation.starworlds.starshaped_hull import (
-    cluster_and_starify,
-    ObstacleCluster,
-)
-from smc.path_generation.starworlds.utils.misc import tic, toc
+from smc.path_generation.maps.premade_maps import createSampleStaticMap
 from smc.path_generation.star_navigation.robot.unicycle import Unicycle
-from smc.path_generation.starworlds.obstacles import StarshapedPolygon
-import shapely
+from smc.path_generation.scene_updater import SceneUpdater
+from smc.path_generation.path_generator import PathGenerator
+
+from importlib.resources import files
+from multiprocessing import Lock, shared_memory
 import yaml
-import pinocchio as pin
 import pickle
-from importlib.resources import files
-
-import matplotlib.pyplot as plt
-import matplotlib.collections as plt_col
-from multiprocessing import Queue, Lock, shared_memory
+import numpy as np
 
 
 def getPlanningArgs(parser):
@@ -57,592 +46,6 @@ def getPlanningArgs(parser):
     return parser
 
 
-class SceneUpdater:
-    def __init__(self, params: dict, verbosity=0):
-        self.params = params
-        self.verbosity = verbosity
-        self.reset()
-
-    def reset(self):
-        self.obstacle_clusters: List[ObstacleCluster] = None
-        self.free_star = None
-
-    # TODO: Check why computational time varies so much for same static scene
-    @staticmethod
-    def workspace_modification(
-        obstacles,
-        p,
-        pg,
-        rho0,
-        max_compute_time,
-        hull_epsilon,
-        gamma=0.5,
-        make_convex=0,
-        obstacle_clusters_prev=None,
-        free_star_prev=None,
-        verbosity=0,
-    ):
-
-        # Clearance variable initialization
-        rho = rho0 / gamma  # First rho should be rho0
-        t_init = tic()
-
-        while True:
-            if toc(t_init) > max_compute_time:
-                if verbosity > 0:
-                    print(
-                        "[Workspace modification]: Max compute time in rho iteration."
-                    )
-                break
-
-            # Reduce rho
-            rho *= gamma
-
-            # Pad obstacles with rho
-            obstacles_rho = [
-                o.dilated_obstacle(padding=rho, id="duplicate") for o in obstacles
-            ]
-
-            # TODO: Fix boundaries
-            free_rho = shapely.geometry.box(-20, -20, 20, 20)
-            for o in obstacles_rho:
-                free_rho = free_rho.difference(o.polygon())
-
-            # TODO: Check buffering fix
-            # Find P0
-            Bp = shapely.geometry.Point(p).buffer(0.95 * rho)
-            initial_reference_set = Bp.intersection(free_rho.buffer(-0.1 * rho))
-
-            if not initial_reference_set.is_empty:
-                break
-
-        # Initial and goal reference position selection
-        r0_sh, _ = shapely.ops.nearest_points(
-            initial_reference_set, shapely.geometry.Point(p)
-        )
-        r0 = np.array(r0_sh.coords[0])
-        rg_sh, _ = shapely.ops.nearest_points(free_rho, shapely.geometry.Point(pg))
-        rg = np.array(rg_sh.coords[0])
-
-        # TODO: Check more thoroughly
-        if free_star_prev is not None:
-            free_star_prev = free_star_prev.buffer(-1e-4)
-        if (
-            free_star_prev is not None
-            and free_star_prev.contains(r0_sh)
-            and free_star_prev.contains(rg_sh)
-            and free_rho.contains(free_star_prev)
-        ):  # not any([free_star_prev.covers(o.polygon()) for o in obstacles_rho]):
-            if verbosity > 1:
-                print(
-                    "[Workspace modification]: Reuse workspace from previous time step."
-                )
-            obstacle_clusters = obstacle_clusters_prev
-            exit_flag = 10
-        else:
-            # Apply cluster and starify
-            obstacle_clusters, obstacle_timing, exit_flag, n_iter = cluster_and_starify(
-                obstacles_rho,
-                r0,
-                rg,
-                hull_epsilon,
-                max_compute_time=max_compute_time - toc(t_init),
-                previous_clusters=obstacle_clusters_prev,
-                make_convex=make_convex,
-                verbose=verbosity,
-            )
-
-        free_star = shapely.geometry.box(-20, -20, 20, 20)
-        for o in obstacle_clusters:
-            free_star = free_star.difference(o.polygon())
-
-        compute_time = toc(t_init)
-        return obstacle_clusters, r0, rg, rho, free_star, compute_time, exit_flag
-
-    def update(
-        self, p: np.ndarray, pg: np.ndarray, obstacles
-    ) -> tuple[np.ndarray, np.ndarray, float, list[StarshapedObstacle]]:
-        # Update obstacles
-        if not self.params["use_prev_workspace"]:
-            self.free_star = None
-        self.obstacle_clusters, r0, rg, rho, self.free_star, _, _ = (
-            SceneUpdater.workspace_modification(
-                obstacles,
-                p,
-                pg,
-                self.params["rho0"],
-                self.params["max_obs_compute_time"],
-                self.params["hull_epsilon"],
-                self.params["gamma"],
-                make_convex=self.params["make_convex"],
-                obstacle_clusters_prev=self.obstacle_clusters,
-                free_star_prev=self.free_star,
-                verbosity=self.verbosity,
-            )
-        )
-        obstacles_star: List[StarshapedObstacle] = [
-            o.cluster_obstacle for o in self.obstacle_clusters
-        ]
-        # Make sure all polygon representations are computed
-        [o._compute_polygon_representation() for o in obstacles_star]
-
-        return r0, rg, rho, obstacles_star
-
-
-class PathGenerator:
-    def __init__(self, params: dict, verbosity=0):
-        self.params = params
-        self.verbosity = verbosity
-        self.reset()
-
-    def reset(self):
-        self.target_path = []
-
-    ### soads.py
-
-    # TODO: Check if can make more computationally efficient
-    @staticmethod
-    def soads_f(
-        r,
-        rg,
-        obstacles: List[StarshapedObstacle],
-        adapt_obstacle_velocity=False,
-        unit_magnitude=False,
-        crep=1.0,
-        reactivity=1.0,
-        tail_effect=False,
-        convergence_tolerance=1e-4,
-        d=False,
-    ):
-        goal_vector = rg - r
-        goal_dist = np.linalg.norm(goal_vector)
-        if goal_dist < convergence_tolerance:
-            return 0 * r
-
-        No = len(obstacles)
-        fa = goal_vector / goal_dist  # Attractor dynamics
-        if No == 0:
-            return fa
-
-        ef = [-fa[1], fa[0]]
-        Rf = np.vstack((fa, ef)).T
-
-        mu = [obs.reference_direction(r) for obs in obstacles]
-        normal = [obs.normal(r) for obs in obstacles]
-        gamma = [obs.distance_function(r) for obs in obstacles]
-        # Compute weights
-        w = PathGenerator.compute_weights(gamma, weightPow=1)
-
-        # Compute obstacle velocities
-        xd_o = np.zeros((2, No))
-        if adapt_obstacle_velocity:
-            for i, obs in enumerate(obstacles):
-                xd_o[:, i] = obs.vel_intertial_frame(r)
-
-        kappa = 0.0
-        f_mag = 0.0
-        for i in range(No):
-            # Compute basis matrix
-            E = np.zeros((2, 2))
-            E[:, 0] = mu[i]
-            E[:, 1] = [-normal[i][1], normal[i][0]]
-            # Compute eigenvalues
-            D = np.zeros((2, 2))
-            D[0, 0] = (
-                1 - crep / (gamma[i] ** (1 / reactivity))
-                if tail_effect or normal[i].dot(fa) < 0.0
-                else 1
-            )
-            D[1, 1] = 1 + 1 / gamma[i] ** (1 / reactivity)
-            # Compute modulation
-            M = E.dot(D).dot(np.linalg.inv(E))
-            # f_i = M.dot(fa)
-            f_i = M.dot(fa - xd_o[:, i]) + xd_o[:, i]
-            # Compute contribution to velocity magnitude
-            f_i_abs = np.linalg.norm(f_i)
-            f_mag += w[i] * f_i_abs
-            # Compute contribution to velocity direction
-            nu_i = f_i / f_i_abs
-            nu_i_hat = Rf.T.dot(nu_i)
-            kappa_i = np.arccos(np.clip(nu_i_hat[0], -1, 1)) * np.sign(nu_i_hat[1])
-            kappa += w[i] * kappa_i
-        kappa_norm = abs(kappa)
-        f_o = (
-            Rf.dot([np.cos(kappa_norm), np.sin(kappa_norm) / kappa_norm * kappa])
-            if kappa_norm > 0.0
-            else fa
-        )
-
-        if unit_magnitude:
-            f_mag = 1.0
-        return f_mag * f_o
-
-    @staticmethod
-    def compute_weights(
-        distMeas,
-        N=0,
-        distMeas_lowerLimit=1,
-        weightType="inverseGamma",
-        weightPow=2,
-    ):
-        """Compute weights based on a distance measure (with no upper limit)"""
-        distMeas = np.array(distMeas)
-        n_points = distMeas.shape[0]
-
-        critical_points = distMeas <= distMeas_lowerLimit
-
-        if np.sum(critical_points):  # at least one
-            if np.sum(critical_points) == 1:
-                w = critical_points * 1.0
-                return w
-            else:
-                # TODO: continuous weighting function
-                # warnings.warn("Implement continuity of weighting function.")
-                w = critical_points * 1.0 / np.sum(critical_points)
-                return w
-
-        distMeas = distMeas - distMeas_lowerLimit
-        w = (1 / distMeas) ** weightPow
-        if np.sum(w) == 0:
-            return w
-        w = w / np.sum(w)  # Normalization
-        return w
-
-    ### path_generator.py
-
-    @staticmethod
-    def pol2pos(path_pol, s):
-        n_pol = len(path_pol) // 2 - 1
-        return [
-            sum(
-                [
-                    path_pol[j * (n_pol + 1) + i] * s ** (n_pol - i)
-                    for i in range(n_pol + 1)
-                ]
-            )
-            for j in range(2)
-        ]
-
-    @staticmethod
-    def path_generator(
-        r0,
-        rg,
-        obstacles,
-        dp_max,
-        N,
-        dt,
-        max_compute_time,
-        n_pol,
-        ds_decay_rate=0.5,
-        ds_increase_rate=2.0,
-        max_nr_steps=1000,
-        convergence_tolerance=1e-5,
-        P_prev=None,
-        s_prev=None,
-        reactivity=1.0,
-        crep=1.0,
-        tail_effect=False,
-        reference_step_size=0.5,
-        verbosity=0,
-    ):
-        """
-        r0 : np.ndarray                       initial reference position
-        rg : np.ndarray                       goal reference position
-        obstacles : list[StarshapedObstacle]  obstacles in the scene
-        dp_max : float                        maximum position increment (i.e. vmax * dt)
-        N : int                               ???
-        dt : float                            time step
-        max_compute_time : float              timeout for computation
-        n_pol : int                           degree of the polynomial that fits the reference  ???
-        ds_decay_rate : float                 ???
-        ds_increase_rate : float              ???
-        max_nr_steps : int                    computation steps threshold
-        convergence_tolerance : float         ???
-        P_prev : np.ndarray                   previous path  ???
-        s_prev : np.ndarray                   previous path time  ???
-        reactivity : float                    ???
-        crep : float                          ???
-        tail_effect : bool                    ???
-        reference_step_size : float           ???
-        verbosity : int                       you guessed it...
-        """
-
-        t0 = tic()
-
-        # Initialize
-        ds = 1
-        s = np.zeros(max_nr_steps)
-        r = np.zeros((max_nr_steps, r0.size))
-        if P_prev is not None:
-            i = P_prev.shape[0]
-            r[:i, :] = P_prev
-            s[:i] = s_prev
-        else:
-            i = 1
-            r[0, :] = r0
-
-        while True:
-            dist_to_goal = np.linalg.norm(r[i - 1, :] - rg)
-            # Check exit conditions
-            if dist_to_goal < convergence_tolerance:
-                if verbosity > 1:
-                    print(
-                        f"[Path Generator]: Path converged. {int(100 * (s[i - 1] / N))}% of path completed."
-                    )
-                break
-            if s[i - 1] >= N:
-                if verbosity > 1:
-                    print(
-                        f"[Path Generator]: Completed path length. {int(100 * (s[i - 1] / N))}% of path completed."
-                    )
-                break
-            if toc(t0) > max_compute_time:
-                if verbosity > 1:
-                    print(
-                        f"[Path Generator]: Max compute time in path integrator. {int(100 * (s[i - 1] / N))}% of path completed."
-                    )
-                break
-            if i >= max_nr_steps:
-                if verbosity > 1:
-                    print(
-                        f"[Path Generator]: Max steps taken in path integrator. {int(100 * (s[i - 1] / N))}% of path completed."
-                    )
-                break
-
-            # Movement using SOADS dynamics
-            dr = min(dp_max, dist_to_goal) * PathGenerator.soads_f(
-                r[i - 1, :],
-                rg,
-                obstacles,
-                adapt_obstacle_velocity=False,
-                unit_magnitude=True,
-                crep=crep,
-                reactivity=reactivity,
-                tail_effect=tail_effect,
-                convergence_tolerance=convergence_tolerance,
-            )
-
-            r[i, :] = r[i - 1, :] + dr * ds
-
-            ri_in_obstacle = False
-            while any([o.interior_point(r[i, :]) for o in obstacles]):
-                if verbosity > 1:
-                    print(
-                        "[Path Generator]: Path inside obstacle. Reducing integration step from {:5f} to {:5f}.".format(
-                            ds, ds * ds_decay_rate
-                        )
-                    )
-                ds *= ds_decay_rate
-                r[i, :] = r[i - 1, :] + dr * ds
-                # Additional compute time check
-                if toc(t0) > max_compute_time:
-                    ri_in_obstacle = True
-                    break
-            if ri_in_obstacle:
-                continue
-
-            # Update travelled distance
-            s[i] = s[i - 1] + ds
-            # Try to increase step rate again
-            ds = min(ds_increase_rate * ds, 1)
-            # Increase iteration counter
-            i += 1
-
-        r = r[:i, :]
-        s = s[:i]
-
-        # Evenly spaced path
-        s_vec = np.arange(0, s[-1] + reference_step_size, reference_step_size)
-        xs, ys = np.interp(s_vec, s, r[:, 0]), np.interp(s_vec, s, r[:, 1])
-        # Append not finished path with fixed final position
-        s_vec = np.append(
-            s_vec,
-            np.arange(
-                s[-1] + reference_step_size,
-                N + reference_step_size,
-                reference_step_size,
-            ),
-        )
-        xs = np.append(xs, xs[-1] * np.ones(len(s_vec) - len(xs)))
-        ys = np.append(ys, ys[-1] * np.ones(len(s_vec) - len(ys)))
-
-        reference_path = [el for p in zip(xs, ys) for el in p]  # [x0 y0 x1 y1 ...]
-
-        # TODO: Fix when close to goal
-        # TODO: Adjust for short arc length, skip higher order terms..
-        path_pol = (
-            np.polyfit(s_vec, reference_path[::2], n_pol).tolist()
-            + np.polyfit(s_vec, reference_path[1::2], n_pol).tolist()
-        )  # [px0 px1 ... pxn py0 py1 ... pyn]
-        # Force init position to be correct
-        path_pol[n_pol] = reference_path[0]
-        path_pol[-1] = reference_path[1]
-
-        # Compute polyfit approximation error
-        epsilon = [
-            np.linalg.norm(
-                np.array(reference_path[2 * i : 2 * (i + 1)])
-                - np.array(PathGenerator.pol2pos(path_pol, s_vec[i]))
-            )
-            for i in range(N + 1)
-        ]
-
-        compute_time = toc(t0)
-
-        """
-        path_pol : np.ndarray   the polynomial approximation of `reference_path`
-        epsilon : [float]       approximation error between the polynomial fit and the actual path
-        reference_path : list   the actual path (used for P_prev later on) in [x1, y1, x2, y2, ...] format
-        compute_time : float    overall timing of this function
-        """
-        return path_pol, epsilon, reference_path, compute_time
-
-    def prepare_prev(
-        self, p: np.ndarray, rho: float, obstacles_star: List[StarshapedObstacle]
-    ):
-        P_prev = np.array([self.target_path[::2], self.target_path[1::2]]).T
-        # Shift path to start at point closest to robot position
-        P_prev = P_prev[np.argmin(np.linalg.norm(p - P_prev, axis=1)) :, :]
-        # P_prev[0, :] = self.r0
-        if np.linalg.norm(p - P_prev[0, :]) > rho:
-            if self.verbosity > 0:
-                print(
-                    "[Path Generator]: No reuse of previous path. Path not within distance rho from robot."
-                )
-            P_prev = None
-        else:
-            for r in P_prev:
-                if any([o.interior_point(r) for o in obstacles_star]):
-                    if self.verbosity > 0:
-                        print(
-                            "[Path Generator]: No reuse of previous path. Path not collision-free."
-                        )
-                    P_prev = None
-
-        if P_prev is not None:
-            # Cut off stand still padding in previous path
-            P_prev_stepsize = np.linalg.norm(np.diff(P_prev, axis=0), axis=1)
-            s_prev = np.hstack((0, np.cumsum(P_prev_stepsize) / self.params["dp_max"]))
-            P_prev_mask = [True] + (P_prev_stepsize > 1e-8).tolist()
-            P_prev = P_prev[P_prev_mask, :]
-            s_prev = s_prev[P_prev_mask]
-        else:
-            s_prev = None
-
-        return P_prev, s_prev
-
-    def update(
-        self,
-        p: np.ndarray,
-        r0: np.ndarray,
-        rg: np.ndarray,
-        rho: float,
-        obstacles_star: List[StarshapedObstacle],
-    ) -> tuple[List[float], float]:
-        # Buffer previous target path
-        if self.params["buffer"] and self.target_path:
-            P_prev, s_prev = self.prepare_prev(p, rho, obstacles_star)
-        else:
-            P_prev, s_prev = None, None
-        # Generate the new path
-        path_pol, epsilon, self.target_path, _ = PathGenerator.path_generator(
-            r0,
-            rg,
-            obstacles_star,
-            self.params["dp_max"],
-            self.params["N"],
-            self.params["dt"],
-            self.params["max_compute_time"],
-            self.params["n_pol"],
-            ds_decay_rate=0.5,
-            ds_increase_rate=2.0,
-            max_nr_steps=1000,
-            P_prev=P_prev,
-            s_prev=s_prev,
-            reactivity=self.params["reactivity"],
-            crep=self.params["crep"],
-            convergence_tolerance=self.params["convergence_tolerance"],
-            verbosity=self.verbosity,
-        )
-        return path_pol, epsilon
-
-
-def createMap():
-    """
-    createMap
-    ---------
-    return obstacles that define the 2D map
-    """
-    # [lower_left, lower_right, top_right, top_left]
-    map_as_list = [
-        [[2, 2], [8, 2], [8, 3], [2, 3]],
-        [[2, 3], [3, 3], [3, 4.25], [2, 4.25]],
-        [[2, 5], [8, 5], [8, 6], [2, 6]],
-        [[2, 8], [8, 8], [8, 9], [2, 9]],
-    ]
-
-    obstacles = []
-    for map_element in map_as_list:
-        obstacles.append(StarshapedPolygon(map_element))
-    return obstacles, map_as_list
-
-
-def pathVisualizer(x0, goal, map_as_list, positions):
-    # plotting
-    fig = plt.figure()
-    handle_goal = plt.plot(*pg, c="g")[0]
-    handle_init = plt.plot(*x0[:2], c="b")[0]
-    handle_curr = plt.plot(
-        *x0[:2], c="r", marker=(3, 0, np.rad2deg(x0[2] - np.pi / 2)), markersize=10
-    )[0]
-    handle_curr_dir = plt.plot(
-        0, 0, marker=(2, 0, np.rad2deg(0)), markersize=5, color="w"
-    )[0]
-    handle_path = plt.plot([], [], c="k")[0]
-    coll = []
-    for map_element in map_as_list:
-        coll.append(plt_col.PolyCollection(np.array(map_element)))
-    plt.gca().add_collection(coll)
-    handle_title = plt.text(
-        5, 9.5, "", bbox={"facecolor": "w", "alpha": 0.5, "pad": 5}, ha="center"
-    )
-    plt.gca().set_aspect("equal")
-    plt.xlim([0, 10])
-    plt.ylim([0, 10])
-    plt.draw()
-
-    # do the updating plotting
-    for x in positions:
-        handle_curr.set_data([x[0]], [x[1]])
-        handle_curr.set_marker((3, 0, np.rad2deg(x[2] - np.pi / 2)))
-        handle_curr_dir.set_data([x[0]], [x[1]])
-        handle_curr_dir.set_marker((2, 0, np.rad2deg(x[2] - np.pi / 2)))
-        handle_path.set_data([path_gen.target_path[::2], path_gen.target_path[1::2]])
-        handle_title.set_text(f"{t:5.3f}")
-        fig.canvas.draw()
-        plt.pause(0.005)
-    plt.show()
-
-
-# stupid function for stupid data re-assembly
-# def path2D_to_SE2(path2D : list):
-#    path2D = np.array(path2D)
-#    # create (N,2) path for list [x0,y0,x1,y1,...]
-#    # of course it shouldn't be like that to begin with but
-#    # i have no time for that
-#    path2D = path2D.reshape((-1, 2))
-#    # since it's a pairwise operation it can't be done on the last point
-#    x_i = path2D[:,0][:-1] # no last element
-#    y_i = path2D[:,1][:-1] # no last element
-#    x_i_plus_1 = path2D[:,0][1:] # no first element
-#    y_i_plus_1 = path2D[:,1][1:] # no first element
-#    # elementwise arctan2
-#    thetas = np.arctan2(x_i_plus_1 - x_i, y_i_plus_1 - y_i)
-#    thetas = thetas.reshape((-1, 1))
-#    path_SE2 = np.hstack((path2D, thetas))
-#    return path_SE2
-
-
 def pathPointFromPathParam(n_pol, path_dim, path_pol, s):
     return [
         np.polyval(path_pol[j * (n_pol + 1) : (j + 1) * (n_pol + 1)], s)
@@ -650,141 +53,6 @@ def pathPointFromPathParam(n_pol, path_dim, path_pol, s):
     ]
 
 
-def path2D_timed(args, path2D_untimed, max_base_v):
-    """
-    path2D_timed
-    ---------------------
-    we have a 2D path of (N,2) shape as reference.
-    it times it as this is what the current ocp formulation needs:
-        there should be a timing associated with the path,
-        because defining the cost function as the fit of the rollout to the path
-        is complicated to do software-wise.
-        as it is now, we're pre-selecting points of the path, and associating those
-        with rollout states at a set time step between the states in the rollout.
-        this isn't a problem if we have an idea of how fast the robot can go,
-        which gives us a heuristic of how to select the points (if you went at maximum
-        speed, this is how far you'd go in this time, so this is your point).
-        thankfully this does not need to be exact because we just care about the distance
-        between the current point and the point on the path, so if it's further out
-        that just means the error is larger, and that doesn't necessarily correspond
-        to a different action.
-    NOTE: we are constructing a possibly bullshit
-    trajectory here, it's a man-made heuristic,
-    and we should leave that to the MPC,
-    but that requires too much coding and there is no time rn.
-    the idea is to use compute the tangent of the path,
-    and use that to make a 2D frenet frame.
-    this is the put to some height, making it SE3.
-    i.e. roll and pitch are fixed to be 0,
-    but you could make them some other constant
-    """
-
-    ####################################################
-    #  getting a timed 2D trajectory from a heuristic  #
-    ####################################################
-    # the strategy is somewhat reasonable at least:
-    # assume we're moving at 90% max velocity in the base,
-    # and use that.
-    perc_of_max_v = 0.9
-    base_v = perc_of_max_v * max_base_v
-
-    # 1) the length of the path divided by 0.9 * max_vel
-    #    gives us the total time of the trajectory,
-    #    so we first compute that
-    # easiest possible way to get approximate path length
-    # (yes it should be from the polynomial approximation but that takes time to write)
-    x_i = path2D_untimed[:, 0][:-1]  # no last element
-    y_i = path2D_untimed[:, 1][:-1]  # no last element
-    x_i_plus_1 = path2D_untimed[:, 0][1:]  # no first element
-    y_i_plus_1 = path2D_untimed[:, 1][1:]  # no first element
-    x_diff = x_i_plus_1 - x_i
-    x_diff = x_diff.reshape((-1, 1))
-    y_diff = y_i_plus_1 - y_i
-    y_diff = y_diff.reshape((-1, 1))
-    path_length = np.sum(np.linalg.norm(np.hstack((x_diff, y_diff)), axis=1))
-    total_time = path_length / base_v
-    # 2) we find the correspondence between s and time
-    # TODO: read from where it should be, but seba checked that it's 5 for some reason
-    # TODO THIS IS N IN PATH PLANNING, MAKE THIS A SHARED ARGUMENT
-    max_s = 5
-    t_to_s = max_s / total_time
-    # 3) construct the ocp-timed 2D path
-    # TODO MAKE REFERENCE_STEP_SIZE A SHARED ARGUMENT
-    # TODO: we should know max s a priori
-    reference_step_size = 0.5
-    s_vec = np.arange(0, len(path2D_untimed)) / reference_step_size
-
-    path2D = []
-    # time is i * args.ocp_dt
-    for i in range(args.n_knots + 1):
-        # what it should be but gets stuck if we're not yet on path
-        # s = (i * args.ocp_dt) * t_to_s
-        # full path
-        # NOTE: this should be wrong, and ocp_dt correct,
-        # but it works better for some reason xd
-        s = i * (max_s / args.n_knots)
-        path2D.append(
-            np.array(
-                [
-                    np.interp(s, s_vec, path2D_untimed[:, 0]),
-                    np.interp(s, s_vec, path2D_untimed[:, 1]),
-                ]
-            )
-        )
-    path2D = np.array(path2D)
-    return path2D
-
-
-def path2D_to_SE3(path2D, path_height):
-    """
-    path2D_SE3
-    ----------
-    we have a 2D path of (N,2) shape as reference
-    the OCP accepts SE3 (it could just rotations or translation too),
-    so this function constructs it from the 2D path.
-    """
-    #########################
-    #  path2D into pathSE2  #
-    #########################
-    # construct theta
-    # since it's a pairwise operation it can't be done on the last point
-    x_i = path2D[:, 0][:-1]  # no last element
-    y_i = path2D[:, 1][:-1]  # no last element
-    x_i_plus_1 = path2D[:, 0][1:]  # no first element
-    y_i_plus_1 = path2D[:, 1][1:]  # no first element
-    x_diff = x_i_plus_1 - x_i
-    y_diff = y_i_plus_1 - y_i
-    # elementwise arctan2
-    thetas = np.arctan2(x_diff, y_diff)
-
-    ######################################
-    #  construct SE3 from SE2 reference  #
-    ######################################
-    # the plan is parallel to the ground because it's a mobile
-    # manipulation task
-    pathSE3 = []
-    for i in range(len(path2D) - 1):
-        # first set the x axis to be in the theta direction
-        # TODO: make sure this one makes sense
-        rotation = np.array(
-            [
-                [-np.cos(thetas[i]), np.sin(thetas[i]), 0.0],
-                [-np.sin(thetas[i]), -np.cos(thetas[i]), 0.0],
-                [0.0, 0.0, -1.0],
-            ]
-        )
-        # rotation = pin.rpy.rpyToMatrix(0.0, 0.0, thetas[i])
-        # rotation = pin.rpy.rpyToMatrix(np.pi/2, np.pi/2,0.0) @ rotation
-        translation = np.array([path2D[i][0], path2D[i][1], path_height])
-        pathSE3.append(pin.SE3(rotation, translation))
-    pathSE3.append(pin.SE3(rotation, translation))
-    return pathSE3
-
-
-def path2D_to_timed_SE3(todo):
-    pass
-
-
 def starPlanner(goal, args, init_cmd, shm_name, lock: Lock, shm_data):
     """
     starPlanner
@@ -804,7 +72,8 @@ def starPlanner(goal, args, init_cmd, shm_name, lock: Lock, shm_data):
     p_shared = np.ndarray((2,), dtype=np.float64, buffer=shm.buf)
     p = np.zeros(2)
     # environment
-    obstacles, _ = createMap()
+    # TODO: DIRTY HACK YOU CAN'T JUST HAVE THIS HERE !!!!!!!!!!!!!!!!
+    obstacles, _ = createSampleStaticMap()
 
     robot_type = "Unicycle"
     with open(args.planning_robot_params_file) as f:
@@ -854,9 +123,6 @@ def starPlanner(goal, args, init_cmd, shm_name, lock: Lock, shm_data):
             r0, rg, rho, obstacles_star = scene_updater.update(p, goal, obstacles)
             # compute the path
             path_pol, epsilon = path_gen.update(p, r0, rg, rho, obstacles_star)
-            # TODO: this is stupid, just used shared memory bro
-            # if data_queue.qsize() < 1:
-            # data_queue.put((path_pol, path_gen.target_path))
             data_pickled = pickle.dumps((path_pol, path_gen.target_path))
             lock.acquire()
             shm_data.buf[: len(data_pickled)] = data_pickled
diff --git a/python/smc/path_generation/scene_updater.py b/python/smc/path_generation/scene_updater.py
new file mode 100644
index 0000000000000000000000000000000000000000..a6db75f635f17738b3e092e6bdcaea6dd76a9ab2
--- /dev/null
+++ b/python/smc/path_generation/scene_updater.py
@@ -0,0 +1,142 @@
+from smc.path_generation.starworlds.utils.misc import tic, toc
+from smc.path_generation.starworlds.obstacles import StarshapedObstacle
+from smc.path_generation.starworlds.starshaped_hull import (
+    cluster_and_starify,
+    ObstacleCluster,
+)
+
+import numpy as np
+import shapely
+from typing import List
+
+
+class SceneUpdater:
+    def __init__(self, params: dict, verbosity=0):
+        self.params = params
+        self.verbosity = verbosity
+        self.reset()
+
+    def reset(self):
+        self.obstacle_clusters: List[ObstacleCluster] = None
+        self.free_star = None
+
+    # TODO: Check why computational time varies so much for same static scene
+    @staticmethod
+    def workspace_modification(
+        obstacles,
+        p,
+        pg,
+        rho0,
+        max_compute_time,
+        hull_epsilon,
+        gamma=0.5,
+        make_convex=0,
+        obstacle_clusters_prev=None,
+        free_star_prev=None,
+        verbosity=0,
+    ):
+
+        # Clearance variable initialization
+        rho = rho0 / gamma  # First rho should be rho0
+        t_init = tic()
+
+        while True:
+            if toc(t_init) > max_compute_time:
+                if verbosity > 0:
+                    print(
+                        "[Workspace modification]: Max compute time in rho iteration."
+                    )
+                break
+
+            # Reduce rho
+            rho *= gamma
+
+            # Pad obstacles with rho
+            obstacles_rho = [
+                o.dilated_obstacle(padding=rho, id="duplicate") for o in obstacles
+            ]
+
+            # TODO: Fix boundaries
+            free_rho = shapely.geometry.box(-20, -20, 20, 20)
+            for o in obstacles_rho:
+                free_rho = free_rho.difference(o.polygon())
+
+            # TODO: Check buffering fix
+            # Find P0
+            Bp = shapely.geometry.Point(p).buffer(0.95 * rho)
+            initial_reference_set = Bp.intersection(free_rho.buffer(-0.1 * rho))
+
+            if not initial_reference_set.is_empty:
+                break
+
+        # Initial and goal reference position selection
+        r0_sh, _ = shapely.ops.nearest_points(
+            initial_reference_set, shapely.geometry.Point(p)
+        )
+        r0 = np.array(r0_sh.coords[0])
+        rg_sh, _ = shapely.ops.nearest_points(free_rho, shapely.geometry.Point(pg))
+        rg = np.array(rg_sh.coords[0])
+
+        # TODO: Check more thoroughly
+        if free_star_prev is not None:
+            free_star_prev = free_star_prev.buffer(-1e-4)
+        if (
+            free_star_prev is not None
+            and free_star_prev.contains(r0_sh)
+            and free_star_prev.contains(rg_sh)
+            and free_rho.contains(free_star_prev)
+        ):  # not any([free_star_prev.covers(o.polygon()) for o in obstacles_rho]):
+            if verbosity > 1:
+                print(
+                    "[Workspace modification]: Reuse workspace from previous time step."
+                )
+            obstacle_clusters = obstacle_clusters_prev
+            exit_flag = 10
+        else:
+            # Apply cluster and starify
+            obstacle_clusters, obstacle_timing, exit_flag, n_iter = cluster_and_starify(
+                obstacles_rho,
+                r0,
+                rg,
+                hull_epsilon,
+                max_compute_time=max_compute_time - toc(t_init),
+                previous_clusters=obstacle_clusters_prev,
+                make_convex=make_convex,
+                verbose=verbosity,
+            )
+
+        free_star = shapely.geometry.box(-20, -20, 20, 20)
+        for o in obstacle_clusters:
+            free_star = free_star.difference(o.polygon())
+
+        compute_time = toc(t_init)
+        return obstacle_clusters, r0, rg, rho, free_star, compute_time, exit_flag
+
+    def update(
+        self, p: np.ndarray, pg: np.ndarray, obstacles
+    ) -> tuple[np.ndarray, np.ndarray, float, list[StarshapedObstacle]]:
+        # Update obstacles
+        if not self.params["use_prev_workspace"]:
+            self.free_star = None
+        self.obstacle_clusters, r0, rg, rho, self.free_star, _, _ = (
+            SceneUpdater.workspace_modification(
+                obstacles,
+                p,
+                pg,
+                self.params["rho0"],
+                self.params["max_obs_compute_time"],
+                self.params["hull_epsilon"],
+                self.params["gamma"],
+                make_convex=self.params["make_convex"],
+                obstacle_clusters_prev=self.obstacle_clusters,
+                free_star_prev=self.free_star,
+                verbosity=self.verbosity,
+            )
+        )
+        obstacles_star: List[StarshapedObstacle] = [
+            o.cluster_obstacle for o in self.obstacle_clusters
+        ]
+        # Make sure all polygon representations are computed
+        [o._compute_polygon_representation() for o in obstacles_star]
+
+        return r0, rg, rho, obstacles_star
diff --git a/python/smc/robots/implementations/heron.py b/python/smc/robots/implementations/heron.py
index 025c50f20b7de7faaea4fa0b0c97418a7ed34732..9054445a1eb0e19eef3aee37177ba8ad3f2ade0e 100644
--- a/python/smc/robots/implementations/heron.py
+++ b/python/smc/robots/implementations/heron.py
@@ -1,12 +1,17 @@
-import time
-from smc.robots.robotmanager_abstract import AbstractRobotManager
+from smc.robots.abstract_simulated_robot import AbstractSimulatedRobotManager
+from smc.robots.interfaces.force_torque_sensor_interface import (
+    ForceTorqueOnSingleArmWrist,
+)
+from smc.robots.interfaces.mobile_base_interface import MobileBaseInterface
+from smc.robots.implementations.ur5e import get_model
 
+import time
+import numpy as np
+import pinocchio as pin
+import hppfcl as fcl
 
-class RobotManagerHeron(AbstractRobotManager):
-    @property
-    def args(self):
-        return self._args
 
+class RobotManagerHeron(ForceTorqueOnSingleArmWrist, MobileBaseInterface):
     @property
     def model(self):
         return self._model
@@ -24,17 +29,66 @@ class RobotManagerHeron(AbstractRobotManager):
         return self._collision_model
 
     def __init__(self, args):
-        self._args = args
+        if args.debug_prints:
+            print("RobotManagerHeron init")
         self._model, self._collision_model, self._visual_model, self._data = (
             heron_approximation()
         )
-        self.ee_frame_id = self.model.getFrameId("tool0")
+        self._ee_frame_id = self.model.getFrameId("tool0")
+        self._base_frame_id = self.model.getFrameId("mobile_base")
+        # TODO: CHANGE THIS TO REAL VALUES
+        self._MAX_ACCELERATION = 1.7  # const
+        self._MAX_QD = 3.14  # const
+        super().__init__(args)
+
+
+class SimulatedHeronRobotManager(AbstractSimulatedRobotManager, RobotManagerHeron):
+    def __init__(self, args):
+        if args.debug_prints:
+            print("SimulatedRobotManagerHeron init")
+        super().__init__(args)
+
+    # NOTE: overriding wrench stuff here
+    # there can be a debated whether there should be a simulated forcetorquesensorinterface,
+    # but it's annoying as hell and there is no immediate benefit in solving this problem
+    def _updateWrench(self):
+        self._wrench_base = np.random.random(6)
+        # NOTE: create a robot_math module, make this mapping a function called
+        # mapse3ToDifferent frame or something like that
+        mapping = np.zeros((6, 6))
+        mapping[0:3, 0:3] = self._T_w_e.rotation
+        mapping[3:6, 3:6] = self._T_w_e.rotation
+        self._wrench = mapping.T @ self._wrench_base
+
+    def zeroFtSensor(self) -> None:
+        self._wrench_bias = np.zeros(6)
 
 
 class RealHeronRobotManager(RobotManagerHeron):
     def __init__(self, args):
+        pass
+
+
+"""
+TODO: finish
+        self._speed_slider = 1.0  # const
+        self._rtde_control: RTDEControlInterface
+        self._rtde_receive: RTDEReceiveInterface
+        self._rtde_io: RTDEIOInterface
         super().__init__(args)
 
+
+    def connectToGripper(self):
+        if (self.args.gripper == "none") or not self.args.real:
+            self.gripper = None
+            return
+        if self.args.gripper == "robotiq":
+            self.gripper = RobotiqGripper()
+            self.gripper.connect(self.args.robot_ip, 63352)
+            self.gripper.activate()
+        if self.args.gripper == "onrobot":
+            self.gripper = TwoFG()
+
     # TODO: here assert you need to have ros2 installed to run on real heron
     # and then set all this bullshit here instead of elsewhere
     def set_publisher_vel_base(self, publisher_vel_base):
@@ -81,6 +135,22 @@ class RealHeronRobotManager(RobotManagerHeron):
         # NOTE: only works for the arm
         self._rtde_control.endFreedriveMode()
 
+    def _updateWrench(self):
+        if not self.args.real:
+            self._wrench_base = np.random.random(6)
+        else:
+            # NOTE: UR5e's ft-sensors gives readings in robot's base frame
+            self._wrench_base = (
+                np.array(self._rtde_receive.getActualTCPForce()) - self._wrench_bias
+            )
+        # NOTE: we define the default wrench to be given in the end-effector frame
+        mapping = np.zeros((6, 6))
+        mapping[0:3, 0:3] = self._T_w_e.rotation
+        mapping[3:6, 3:6] = self._T_w_e.rotation
+        self._wrench = mapping.T @ self._wrench_base
+
+"""
+
 
 def heron_approximation():
     # arm + gripper
diff --git a/python/smc/robots/interfaces/mobile_base_interface.py b/python/smc/robots/interfaces/mobile_base_interface.py
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..8c2e9044a0c1ce8cd67dc79b4373fb70d1c514bf 100644
--- a/python/smc/robots/interfaces/mobile_base_interface.py
+++ b/python/smc/robots/interfaces/mobile_base_interface.py
@@ -0,0 +1,78 @@
+import numpy as np
+import pinocchio as pin
+from smc.robots.robotmanager_abstract import AbstractRobotManager
+
+
+class MobileBaseInterface(AbstractRobotManager):
+    """
+    MobileBaseInterface
+    -------------------
+    This interface assumes that the first joint in the kinematic chain will be a planarJoint,
+    modelling the mobile base of the robot.
+    This does not exactly work for underactuated bases like differential drive,
+    as some control inputs shouldn't even exist for this to be modelled properly.
+    As it currently stands, the underactuation is enforced at the control level
+    instead of the modelling level.
+    One day this might be a "fully actuated base" class,
+    implementing an abstract mobile base interface.
+    """
+
+    def __init__(self, args):
+        if args.debug_prints:
+            print("MobileBase init")
+        self._base_frame_id: int
+        self._T_w_b: pin.SE3
+        super().__init__(args)
+
+    @property
+    def base_position2D(self):
+        return self._q[:2]
+
+    @property
+    def base_position3D(self):
+        return np.array(list(self._q[:2]) + [0.0])
+
+    @property
+    def base_SE2_pose(self):
+        # NOTE: idk if this is the best way to calculate theta
+        # _q[:4] = [x, y, cos(theta), sin(theta)]
+        theta = np.arccos(self._q[2])
+        return np.array(list(self._q[:2]) + [theta])
+
+    @property
+    def base_frame_id(self):
+        return self._base_frame_id
+
+    @property
+    def T_w_b(self):
+        return self._T_w_b.copy()
+
+    def computeT_w_b(self, q) -> pin.SE3:
+        assert type(q) is np.ndarray
+        pin.forwardKinematics(
+            self.model,
+            self.data,
+            q,
+        )
+        # alternative if you want all frames
+        # pin.updateFramePlacements(self.model, self.data)
+        pin.updateFramePlacement(self.model, self.data, self._base_frame_id)
+        return self.data.oMf[self._base_frame_id].copy()
+
+    # TODO: make use of this for a standalone robot like the omnibot
+    # just driving around with a full-body robot without using hands.
+    # not prio right now and I don't want to deal with
+    # how this interacts with other interfaces
+    # def forwardKinematics(self):
+    #    pin.forwardKinematics(
+    #        self.model,
+    #        self.data,
+    #        self._q,
+    #    )
+    #    pin.updateFramePlacement(self.model, self.data, self._ee_frame_id)
+    #    self._T_w_e = self.data.oMf[self._ee_frame_id].copy()
+
+    # def _step(self):
+    #    self._updateQ()
+    #    self._updateV()
+    #    self.forwardKinematics()
diff --git a/python/smc/robots/robotmanager_abstract.py b/python/smc/robots/robotmanager_abstract.py
index 5f59cde7484002fac9d7e3b0d35fad2b723b779f..0e6cee64fd793b776d2d509c94c7b95a7616c856 100644
--- a/python/smc/robots/robotmanager_abstract.py
+++ b/python/smc/robots/robotmanager_abstract.py
@@ -96,8 +96,9 @@ class AbstractRobotManager(abc.ABC):
             self._log_manager = Logger(args)
 
         # since there is only one robot and one visualizer, this is robotmanager's job
+        # TODO: this should probably be transferred to a multiprocess manager,
+        # or in whatever way be detangled from robots
         self.visualizer_manager: ProcessManager
-        # TODO: this should be transferred to an multiprocess manager
         if self.args.visualizer:
             side_function = partial(
                 manipulatorVisualizer,
@@ -286,6 +287,10 @@ class AbstractRobotManager(abc.ABC):
         else:
             print("not implemented yet, so nothing is going to happen!")
 
+    ########################################################################################
+    # visualizer management. ideally transferred elsewhere
+    ###################################################################################
+
     def killManipulatorVisualizer(self):
         """
         killManipulatorVisualizer
@@ -314,6 +319,25 @@ class AbstractRobotManager(abc.ABC):
             if self.args.debug_prints:
                 print("you didn't select viz")
 
+    def sendRectangular2DMapToVisualizer(self, map_as_list):
+        for obstacle in map_as_list:
+            length = obstacle[1][0] - obstacle[0][0]
+            width = obstacle[3][1] - obstacle[0][1]
+            height = 0.4  # doesn't matter because plan because planning is 2D
+            pose = pin.SE3(
+                np.eye(3),
+                np.array(
+                    [
+                        obstacle[0][0] + (obstacle[1][0] - obstacle[0][0]) / 2,
+                        obstacle[0][1] + (obstacle[3][1] - obstacle[0][1]) / 2,
+                        0.0,
+                    ]
+                ),
+            )
+            dims = [length, width, height]
+            command = {"obstacle_box": [pose, dims]}
+            self.visualizer_manager.sendCommand(command)
+
 
 class AbstractRealRobotManager(AbstractRobotManager, abc.ABC):
     """
diff --git a/python/smc/robots/utils.py b/python/smc/robots/utils.py
index dbe9508f7ccdad465f03d8fad107102385744ce2..d18574145dd440bc8e8908e81c82d854697e37b2 100644
--- a/python/smc/robots/utils.py
+++ b/python/smc/robots/utils.py
@@ -248,10 +248,15 @@ def getRobotFromArgs(args: argparse.Namespace) -> AbstractRobotManager:
             return RealUR5eRobotManager(args)
         else:
             return SimulatedUR5eRobotManager(args)
+    if args.robot == "heron":
+        if args.real:
+            pass
+            # TODO: finish it
+            # return RealHeronRobotManager(args)
+        else:
+            return SimulatedHeronRobotManager(args)
 
 
-#    if args.robot == "heron":
-#        return RealUR5eRobotManager(args)
 #    if args.robot == "mir":
 #        return RealUR5eRobotManager(args)
 #    if args.robot == "yumi":
diff --git a/python/smc/visualization/meshcat_viewer_wrapper/visualizer.py b/python/smc/visualization/meshcat_viewer_wrapper/visualizer.py
index bdd34e3d75b5b149898fc2439ffb31bc8530a29e..45b02cc8a1eb6fac460e9c67b4575c52facd7648 100644
--- a/python/smc/visualization/meshcat_viewer_wrapper/visualizer.py
+++ b/python/smc/visualization/meshcat_viewer_wrapper/visualizer.py
@@ -79,7 +79,7 @@ class MeshcatVisualizer(PMV):
     def addBox(self, name, dims, color):
         material = materialFromColor(color)
         self.viewer[name].set_object(meshcat.geometry.Box(dims), material)
-    
+
     def addBoxObstacle(self, pose, dims):
         color = [0.5, 0.5, 0.5, 0.8]
         obstacle_name = f"world/obstacle_{self.n_obstacles}"
@@ -96,18 +96,17 @@ class MeshcatVisualizer(PMV):
         self.applyConfiguration(obstacle_name, pose)
         self.n_obstacles += 1
 
-
     def addEllipsoid(self, name, dims, color):
         material = materialFromColor(color)
         self.viewer[name].set_object(meshcat.geometry.Ellipsoid(dims), material)
 
-    def addPoint(self, point : pin.SE3, radius=5e-3, color=[1, 0, 0, 0.8]):
+    def addPoint(self, point: pin.SE3, radius=5e-3, color=[1, 0, 0, 0.8]):
         point_name = f"world/point_{self.n_points}"
         self.addSphere(point_name, radius, color)
         self.applyConfiguration(point_name, point)
         self.n_points += 1
-    
-    def addPath(self, name, path : list[pin.SE3], radius=5e-3, color=[1, 0, 0, 0.8]):
+
+    def addPath(self, name, path: list[pin.SE3], radius=5e-3, color=[1, 0, 0, 0.8]):
         # who cares about the name
         name = "path"
         if type(path) == np.ndarray:
@@ -120,22 +119,25 @@ class MeshcatVisualizer(PMV):
             self.applyConfiguration(f"world/path_{name}_point_{i}", point)
         self.n_path_points = max(i, self.n_path_points)
 
-    def addFramePath(self, name, path : list[pin.SE3], radius=5e-3, color=[1, 0, 0, 0.8]):
+    def addFramePath(
+        self, name, path: list[pin.SE3], radius=5e-3, color=[1, 0, 0, 0.8]
+    ):
         # who cares about the name
         name = "frame_path"
         for i, point in enumerate(path):
             if i < self.n_frame_path_points:
-                meshcat_shapes.frame(self.viewer[f"world/frame_path_{name}_point_{i}"], opacity=0.3)
+                meshcat_shapes.frame(
+                    self.viewer[f"world/frame_path_{name}_point_{i}"], opacity=0.3
+                )
             self.applyConfiguration(f"world/frame_path_{name}_point_{i}", point)
         self.n_frame_path_points = max(i, self.n_frame_path_points)
-        
 
     def applyConfiguration(self, name, placement):
         if isinstance(placement, list) or isinstance(placement, tuple):
             placement = np.array(placement)
         if isinstance(placement, pin.SE3):
-            #R, p = placement.rotation, placement.translation
-            #T = np.r_[np.c_[R, p], [[0, 0, 0, 1]]]
+            # R, p = placement.rotation, placement.translation
+            # T = np.r_[np.c_[R, p], [[0, 0, 0, 1]]]
             T = placement.homogeneous
         elif isinstance(placement, np.ndarray):
             if placement.shape == (7,):  # XYZ-quat
diff --git a/python/smc/visualization/path_visualizer.py b/python/smc/visualization/path_visualizer.py
new file mode 100644
index 0000000000000000000000000000000000000000..86669c3bfd02253912d5c8a4c8835deeb0e21699
--- /dev/null
+++ b/python/smc/visualization/path_visualizer.py
@@ -0,0 +1,40 @@
+import numpy as np
+import matplotlib.pyplot as plt
+import matplotlib.collections as plt_col
+
+
+def pathVisualizer(x0, goal, map_as_list, positions, path_gen):
+    # plotting
+    fig = plt.figure()
+    handle_goal = plt.plot(*pg, c="g")[0]
+    handle_init = plt.plot(*x0[:2], c="b")[0]
+    handle_curr = plt.plot(
+        *x0[:2], c="r", marker=(3, 0, np.rad2deg(x0[2] - np.pi / 2)), markersize=10
+    )[0]
+    handle_curr_dir = plt.plot(
+        0, 0, marker=(2, 0, np.rad2deg(0)), markersize=5, color="w"
+    )[0]
+    handle_path = plt.plot([], [], c="k")[0]
+    coll = []
+    for map_element in map_as_list:
+        coll.append(plt_col.PolyCollection(np.array(map_element)))
+    plt.gca().add_collection(coll)
+    handle_title = plt.text(
+        5, 9.5, "", bbox={"facecolor": "w", "alpha": 0.5, "pad": 5}, ha="center"
+    )
+    plt.gca().set_aspect("equal")
+    plt.xlim([0, 10])
+    plt.ylim([0, 10])
+    plt.draw()
+
+    # do the updating plotting
+    for x in positions:
+        handle_curr.set_data([x[0]], [x[1]])
+        handle_curr.set_marker((3, 0, np.rad2deg(x[2] - np.pi / 2)))
+        handle_curr_dir.set_data([x[0]], [x[1]])
+        handle_curr_dir.set_marker((2, 0, np.rad2deg(x[2] - np.pi / 2)))
+        handle_path.set_data([path_gen.target_path[::2], path_gen.target_path[1::2]])
+        handle_title.set_text(f"{t:5.3f}")
+        fig.canvas.draw()
+        plt.pause(0.005)
+    plt.show()