From 19ba625c3ddb602cb0d66d0a407878e2fbaf282f Mon Sep 17 00:00:00 2001 From: Mitchell Cohen Date: Fri, 15 Aug 2025 15:38:02 -0400 Subject: [PATCH] Add yaw-only alignment to Umeyama alignment options --- doc/alignment_demo.py | 4 + evo/core/geometry.py | 42 +- evo/core/trajectory.py | 10 +- evo/main_ape.py | 11 +- evo/main_ape_parser.py | 4 + evo/main_rpe.py | 13 +- evo/main_rpe_parser.py | 4 + evo/main_traj.py | 2 +- evo/main_traj_parser.py | 4 + test/data/V101_gt.txt | 2896 +++++++++++++++++++++++++++++++++++ test/data/V101_openvins.txt | 2776 +++++++++++++++++++++++++++++++++ test/demos/ape_demo.sh | 5 +- test/demos/rpe_demo.sh | 5 +- test/demos/traj_demo.sh | 3 + test/test_trajectory.py | 11 +- 15 files changed, 5769 insertions(+), 21 deletions(-) create mode 100644 test/data/V101_gt.txt create mode 100644 test/data/V101_openvins.txt diff --git a/doc/alignment_demo.py b/doc/alignment_demo.py index 74fce045..5416520d 100755 --- a/doc/alignment_demo.py +++ b/doc/alignment_demo.py @@ -53,6 +53,10 @@ traj_est_aligned_only_scaled = copy.deepcopy(traj_est) traj_est_aligned_only_scaled.align(traj_ref, correct_only_scale=True) +logger.info("\nUmeyama alignment with yaw-only rotation") +traj_est_aligned_only_yaw = copy.deepcopy(traj_est) +traj_est_aligned_only_yaw.align(traj_ref, yaw_only=True) + fig = plt.figure(figsize=(8, 8)) plot_mode = plot.PlotMode.xz diff --git a/evo/core/geometry.py b/evo/core/geometry.py index ec9097e2..88098000 100644 --- a/evo/core/geometry.py +++ b/evo/core/geometry.py @@ -31,9 +31,8 @@ class GeometryException(EvoException): UmeyamaResult = typing.Tuple[np.ndarray, np.ndarray, float] - def umeyama_alignment(x: np.ndarray, y: np.ndarray, - with_scale: bool = False) -> UmeyamaResult: + with_scale: bool = False, yaw_only: bool = False) -> UmeyamaResult: """ Computes the least squares solution parameters of an Sim(m) matrix that minimizes the distance between a set of registered points. @@ -76,8 +75,15 @@ def umeyama_alignment(x: np.ndarray, y: np.ndarray, # Ensure a RHS coordinate system (Kabsch algorithm). s[m - 1, m - 1] = -1 - # rotation, eq. 40 - r = u.dot(s).dot(v) + if yaw_only: + # See equations (15)-(17) in A Tutorial on Quantitative Trajectory Evaluation + # for Visual(-Inertial) Odometry, by Zhang and Scaramuzza + rot_C = (x - mean_x[:, np.newaxis]).dot((y - mean_y[:, np.newaxis]).T) + theta = get_best_yaw(rot_C) + r = rot_z(theta) + else: + # rotation, eq. 40 + r = u.dot(s).dot(v) # scale & translation, eq. 42 and 41 c = 1 / sigma_x * np.trace(np.diag(d).dot(s)) if with_scale else 1.0 @@ -101,3 +107,31 @@ def accumulated_distances(x: np.ndarray) -> np.ndarray: """ return np.concatenate( (np.array([0]), np.cumsum(np.linalg.norm(x[:-1] - x[1:], axis=1)))) + +def get_best_yaw(C: np.ndarray) -> float: + """Maximizes trace(Rz(theta) * C) + :param C: 3x3 rotation matrix + :return: yaw angle in radians + """ + if C.shape != (3, 3): + raise GeometryException("C must be a 3x3 matrix") + + A = C[0, 1] - C[1, 0] + B = C[0, 0] + C[1, 1] + theta = np.pi / 2.0 - np.arctan2(B, A) + return theta + +def rot_z(theta: float) -> np.ndarray: + """ + Creates a rotation about the z-axis by an angle theta. + :param theta: rotation angle in radians + :return: 3x3 rotation matrix + """ + cos_theta = np.cos(theta) + sin_theta = np.sin(theta) + + return np.array([ + [cos_theta, -sin_theta, 0], + [sin_theta, cos_theta, 0], + [0, 0, 1] + ]) diff --git a/evo/core/trajectory.py b/evo/core/trajectory.py index afa3cb2b..ed9f33b6 100644 --- a/evo/core/trajectory.py +++ b/evo/core/trajectory.py @@ -231,7 +231,7 @@ def project(self, plane: Plane) -> None: def align(self, traj_ref: 'PosePath3D', correct_scale: bool = False, correct_only_scale: bool = False, - n: int = -1) -> geometry.UmeyamaResult: + n: int = -1, yaw_only: bool = False) -> geometry.UmeyamaResult: """ align to a reference trajectory using Umeyama alignment :param traj_ref: reference trajectory @@ -246,14 +246,18 @@ def align(self, traj_ref: 'PosePath3D', correct_scale: bool = False, else: logger.debug("Aligning using Umeyama's method..." + (" (with scale correction)" if with_scale else "")) + + if yaw_only: + logger.debug("Computing yaw only alignment...") + if n == -1: r_a, t_a, s = geometry.umeyama_alignment(self.positions_xyz.T, traj_ref.positions_xyz.T, - with_scale) + with_scale, yaw_only) else: r_a, t_a, s = geometry.umeyama_alignment( self.positions_xyz[:n, :].T, traj_ref.positions_xyz[:n, :].T, - with_scale) + with_scale, yaw_only) if not correct_only_scale: logger.debug("Rotation of alignment:\n{}" diff --git a/evo/main_ape.py b/evo/main_ape.py index 0582915c..40447a16 100755 --- a/evo/main_ape.py +++ b/evo/main_ape.py @@ -41,7 +41,7 @@ def ape(traj_ref: PosePath3D, traj_est: PosePath3D, pose_relation: metrics.PoseRelation, align: bool = False, - correct_scale: bool = False, n_to_align: int = -1, + correct_scale: bool = False, yaw_only: bool = False, n_to_align: int = -1, align_origin: bool = False, ref_name: str = "reference", est_name: str = "estimate", change_unit: typing.Optional[metrics.Unit] = None, @@ -53,7 +53,8 @@ def ape(traj_ref: PosePath3D, traj_est: PosePath3D, if align or correct_scale: logger.debug(SEP) alignment_transformation = lie_algebra.sim3( - *traj_est.align(traj_ref, correct_scale, only_scale, n=n_to_align)) + *traj_est.align(traj_ref, correct_scale, only_scale, + n=n_to_align, yaw_only=yaw_only)) if align_origin: logger.debug(SEP) alignment_transformation = traj_est.align_origin(traj_ref) @@ -76,10 +77,12 @@ def ape(traj_ref: PosePath3D, traj_est: PosePath3D, ape_metric.change_unit(change_unit) title = str(ape_metric) - if align and not correct_scale: + if align and not correct_scale and not yaw_only: title += "\n(with SE(3) Umeyama alignment)" elif align and correct_scale: title += "\n(with Sim(3) Umeyama alignment)" + elif align and yaw_only: + title += "\n(with position-yaw alignment)" elif only_scale: title += "\n(scale corrected)" elif not align_origin: @@ -155,7 +158,7 @@ def run(args: argparse.Namespace) -> None: result = ape(traj_ref=traj_ref, traj_est=traj_est, pose_relation=pose_relation, align=args.align, correct_scale=args.correct_scale, n_to_align=args.n_to_align, - align_origin=args.align_origin, ref_name=ref_name, + yaw_only=args.yaw_only, align_origin=args.align_origin, ref_name=ref_name, est_name=est_name, change_unit=change_unit, project_to_plane=plane) diff --git a/evo/main_ape_parser.py b/evo/main_ape_parser.py index e43f8e86..0d0d9826 100644 --- a/evo/main_ape_parser.py +++ b/evo/main_ape_parser.py @@ -25,6 +25,10 @@ def parser() -> argparse.ArgumentParser: "--n_to_align", help="the number of poses to use for Umeyama alignment, " "counted from the start (default: all)", default=-1, type=int) + algo_opts.add_argument( + "--yaw_only", help="align yaw (z-axis) only", + action="store_true" + ) algo_opts.add_argument( "--change_unit", default=None, choices=[u.value for u in (units.ANGLE_UNITS + units.LENGTH_UNITS)], diff --git a/evo/main_rpe.py b/evo/main_rpe.py index 8d804127..fb609b24 100755 --- a/evo/main_rpe.py +++ b/evo/main_rpe.py @@ -43,8 +43,8 @@ def rpe(traj_ref: PosePath3D, traj_est: PosePath3D, pose_relation: metrics.PoseRelation, delta: float, delta_unit: metrics.Unit, rel_delta_tol: float = 0.1, all_pairs: bool = False, pairs_from_reference: bool = False, - align: bool = False, correct_scale: bool = False, n_to_align: int = -1, - align_origin: bool = False, ref_name: str = "reference", + align: bool = False, correct_scale: bool = False, yaw_only: bool = False, + n_to_align: int = -1, align_origin: bool = False, ref_name: str = "reference", est_name: str = "estimate", support_loop: bool = False, change_unit: typing.Optional[metrics.Unit] = None, project_to_plane: typing.Optional[Plane] = None) -> Result: @@ -55,7 +55,8 @@ def rpe(traj_ref: PosePath3D, traj_est: PosePath3D, if align or correct_scale: logger.debug(SEP) alignment_transformation = lie_algebra.sim3( - *traj_est.align(traj_ref, correct_scale, only_scale, n=n_to_align)) + *traj_est.align(traj_ref, correct_scale, only_scale, + n=n_to_align, yaw_only=yaw_only)) if align_origin: logger.debug(SEP) alignment_transformation = traj_est.align_origin(traj_ref) @@ -178,9 +179,9 @@ def run(args: argparse.Namespace) -> None: all_pairs=args.all_pairs, pairs_from_reference=args.pairs_from_reference, align=args.align, correct_scale=args.correct_scale, - n_to_align=args.n_to_align, align_origin=args.align_origin, - ref_name=ref_name, est_name=est_name, change_unit=change_unit, - project_to_plane=plane) + n_to_align=args.n_to_align, align_origin=args.align_origin, + yaw_only=args.yaw_only, ref_name=ref_name, est_name=est_name, + change_unit=change_unit, project_to_plane=plane) if args.rerun and isinstance(traj_ref, PoseTrajectory3D) and isinstance( traj_est, PoseTrajectory3D): diff --git a/evo/main_rpe_parser.py b/evo/main_rpe_parser.py index 29f59484..3dc2913f 100644 --- a/evo/main_rpe_parser.py +++ b/evo/main_rpe_parser.py @@ -25,6 +25,10 @@ def parser() -> argparse.ArgumentParser: "--n_to_align", help="the number of poses to use for Umeyama alignment, " "counted from the start (default: all)", default=-1, type=int) + algo_opts.add_argument( + "--yaw_only", help="align yaw (z-axis) only", + action="store_true" + ) algo_opts.add_argument("-d", "--delta", type=float, default=1, help="delta between relative poses") algo_opts.add_argument("-t", "--delta_tol", type=float, default=0.1, diff --git a/evo/main_traj.py b/evo/main_traj.py index 54236569..1c102db0 100755 --- a/evo/main_traj.py +++ b/evo/main_traj.py @@ -262,7 +262,7 @@ def run(args): trajectories[name].align( ref_traj_tmp, correct_scale=args.correct_scale, correct_only_scale=args.correct_scale and not args.align, - n=args.n_to_align) + n=args.n_to_align, yaw_only=args.yaw_only) if args.align_origin: logger.debug(SEP) logger.debug("Aligning {}'s origin to reference.".format(name)) diff --git a/evo/main_traj_parser.py b/evo/main_traj_parser.py index 94beb089..3b685826 100644 --- a/evo/main_traj_parser.py +++ b/evo/main_traj_parser.py @@ -24,6 +24,10 @@ def parser() -> argparse.ArgumentParser: "--sync", help="associate trajectories via matching timestamps - requires --ref", action="store_true") + algo_opts.add_argument( + "--yaw_only", help="align yaw (z-axis) only", + action="store_true" + ) algo_opts.add_argument( "--transform_left", help="path to a file with a transformation" " to apply to the trajectories (left multiplicative)") diff --git a/test/data/V101_gt.txt b/test/data/V101_gt.txt new file mode 100644 index 00000000..52e82eac --- /dev/null +++ b/test/data/V101_gt.txt @@ -0,0 +1,2896 @@ +# timestamp(s) tx ty tz qx qy qz qw +1403715273.26214 0.878895 2.183400 0.948427 -0.824237 -0.106942 -0.551702 0.069433 +1403715273.31214 0.878973 2.183480 0.948329 -0.824253 -0.106951 -0.551676 0.069437 +1403715273.36214 0.879043 2.183530 0.948278 -0.824264 -0.106935 -0.551665 0.069420 +1403715273.41214 0.879078 2.183540 0.948260 -0.824287 -0.106929 -0.551634 0.069404 +1403715273.46214 0.879090 2.183560 0.948267 -0.824305 -0.106940 -0.551608 0.069377 +1403715273.51214 0.879066 2.183580 0.948250 -0.824320 -0.106940 -0.551588 0.069360 +1403715273.56214 0.878981 2.183570 0.948229 -0.824341 -0.106838 -0.551587 0.069272 +1403715273.61214 0.878882 2.183600 0.948193 -0.824370 -0.106705 -0.551586 0.069144 +1403715273.66214 0.878816 2.183630 0.948148 -0.824397 -0.106914 -0.551514 0.069073 +1403715273.71214 0.878778 2.183620 0.948081 -0.824455 -0.106748 -0.551473 0.068970 +1403715273.76214 0.878755 2.183730 0.948102 -0.824439 -0.106914 -0.551461 0.068990 +1403715273.81214 0.878783 2.183770 0.948127 -0.824438 -0.106959 -0.551440 0.069112 +1403715273.86214 0.878855 2.183760 0.948173 -0.824430 -0.107143 -0.551414 0.069121 +1403715273.91214 0.879001 2.183660 0.948175 -0.824501 -0.106936 -0.551346 0.069140 +1403715273.96214 0.879235 2.183480 0.948209 -0.824517 -0.106925 -0.551356 0.068886 +1403715274.01214 0.879594 2.183140 0.948225 -0.824620 -0.106392 -0.551404 0.068091 +1403715274.06214 0.879899 2.183190 0.948264 -0.824556 -0.106693 -0.551355 0.068785 +1403715274.11214 0.880156 2.183210 0.948386 -0.824468 -0.106756 -0.551462 0.068882 +1403715274.16214 0.880422 2.183310 0.948470 -0.824522 -0.106948 -0.551310 0.069157 +1403715274.21214 0.880622 2.183450 0.948550 -0.824501 -0.107280 -0.551222 0.069599 +1403715274.26214 0.880763 2.183400 0.948595 -0.824670 -0.107290 -0.551011 0.069248 +1403715274.31214 0.880801 2.183390 0.948616 -0.824812 -0.107279 -0.550812 0.069152 +1403715274.36214 0.880673 2.183300 0.948655 -0.824780 -0.107231 -0.550890 0.068994 +1403715274.41214 0.880484 2.183230 0.948675 -0.824852 -0.107307 -0.550780 0.068892 +1403715274.46214 0.880238 2.183230 0.948684 -0.824844 -0.107155 -0.550823 0.068883 +1403715274.51214 0.879978 2.183280 0.948691 -0.824775 -0.107516 -0.550864 0.068812 +1403715274.56214 0.879691 2.183390 0.948679 -0.824820 -0.107449 -0.550788 0.068988 +1403715274.61214 0.879448 2.183470 0.948678 -0.824755 -0.107583 -0.550860 0.068972 +1403715274.66214 0.879291 2.183520 0.948663 -0.824716 -0.107711 -0.550924 0.068731 +1403715274.71214 0.879124 2.183580 0.948689 -0.824621 -0.107608 -0.551070 0.068866 +1403715274.76214 0.879105 2.183610 0.948644 -0.824635 -0.107640 -0.551066 0.068677 +1403715274.81214 0.879204 2.183590 0.948625 -0.824646 -0.107605 -0.551062 0.068632 +1403715274.86214 0.879301 2.183490 0.948635 -0.824631 -0.107608 -0.551092 0.068569 +1403715274.91214 0.879452 2.183470 0.948602 -0.824660 -0.107636 -0.551049 0.068530 +1403715274.96214 0.879634 2.183430 0.948563 -0.824696 -0.107642 -0.550986 0.068590 +1403715275.01214 0.879761 2.183410 0.948570 -0.824699 -0.107639 -0.550984 0.068570 +1403715275.06214 0.879844 2.183450 0.948551 -0.824683 -0.107676 -0.551000 0.068582 +1403715275.11214 0.880022 2.183480 0.948529 -0.824691 -0.107687 -0.550982 0.068608 +1403715275.16214 0.880211 2.183480 0.948549 -0.824704 -0.107754 -0.550961 0.068512 +1403715275.21214 0.880363 2.183480 0.948623 -0.824678 -0.107756 -0.551001 0.068500 +1403715275.26214 0.880514 2.183520 0.948644 -0.824706 -0.107712 -0.550965 0.068528 +1403715275.31214 0.880602 2.183580 0.948643 -0.824698 -0.107715 -0.550978 0.068514 +1403715275.36214 0.880602 2.183640 0.948613 -0.824699 -0.107756 -0.550972 0.068490 +1403715275.41214 0.880533 2.183680 0.948566 -0.824695 -0.107748 -0.550977 0.068505 +1403715275.46214 0.880403 2.183700 0.948546 -0.824669 -0.107740 -0.551017 0.068510 +1403715275.51214 0.880272 2.183740 0.948545 -0.824673 -0.107694 -0.551018 0.068520 +1403715275.56214 0.880127 2.183720 0.948530 -0.824665 -0.107639 -0.551040 0.068537 +1403715275.61214 0.879953 2.183670 0.948519 -0.824703 -0.107618 -0.550989 0.068520 +1403715275.66214 0.879771 2.183650 0.948525 -0.824713 -0.107580 -0.550974 0.068571 +1403715275.71214 0.879630 2.183660 0.948505 -0.824720 -0.107613 -0.550950 0.068638 +1403715275.76214 0.879521 2.183660 0.948495 -0.824738 -0.107591 -0.550921 0.068686 +1403715275.81214 0.879465 2.183620 0.948493 -0.824744 -0.107551 -0.550917 0.068706 +1403715275.86214 0.879455 2.183570 0.948547 -0.824636 -0.107532 -0.551081 0.068722 +1403715275.91214 0.879440 2.183530 0.948648 -0.824584 -0.107481 -0.551172 0.068686 +1403715275.96214 0.879331 2.183490 0.948868 -0.824258 -0.107456 -0.551657 0.068755 +1403715276.01214 0.879322 2.183490 0.948983 -0.824228 -0.107328 -0.551719 0.068815 +1403715276.06214 0.879321 2.183530 0.948978 -0.824387 -0.107413 -0.551475 0.068725 +1403715276.11214 0.879365 2.183580 0.948769 -0.824576 -0.107434 -0.551186 0.068748 +1403715276.16214 0.879246 2.183610 0.948565 -0.824521 -0.107280 -0.551281 0.068892 +1403715276.21214 0.879188 2.183630 0.948455 -0.824579 -0.107366 -0.551186 0.068812 +1403715276.26214 0.879241 2.183650 0.948346 -0.824604 -0.107274 -0.551162 0.068865 +1403715276.31214 0.879366 2.183630 0.948218 -0.824657 -0.107281 -0.551083 0.068836 +1403715276.36214 0.879484 2.183630 0.948219 -0.824702 -0.107265 -0.551020 0.068831 +1403715276.41214 0.879573 2.183660 0.948273 -0.824752 -0.107259 -0.550947 0.068828 +1403715276.46214 0.879626 2.183700 0.948351 -0.824713 -0.107252 -0.551010 0.068793 +1403715276.51214 0.879568 2.183730 0.948648 -0.824485 -0.107205 -0.551333 0.069017 +1403715276.56214 0.879577 2.183680 0.948919 -0.824567 -0.107134 -0.551237 0.068918 +1403715276.61214 0.879660 2.183660 0.948844 -0.824705 -0.107133 -0.551036 0.068866 +1403715276.66214 0.879667 2.183650 0.948740 -0.824726 -0.107094 -0.551008 0.068903 +1403715276.71214 0.879518 2.183630 0.948820 -0.824646 -0.107154 -0.551116 0.068904 +1403715276.76214 0.879328 2.183510 0.948941 -0.824531 -0.107075 -0.551282 0.069082 +1403715276.81214 0.879281 2.183370 0.948948 -0.824657 -0.107004 -0.551105 0.069091 +1403715276.86214 0.879216 2.183240 0.949062 -0.824697 -0.106927 -0.551059 0.069109 +1403715276.91214 0.879073 2.183360 0.949153 -0.824556 -0.106853 -0.551266 0.069256 +1403715276.96214 0.878981 2.183570 0.949207 -0.824403 -0.106837 -0.551494 0.069278 +1403715277.01214 0.878911 2.183670 0.949372 -0.824359 -0.106720 -0.551563 0.069428 +1403715277.06214 0.879109 2.183530 0.949416 -0.824547 -0.106696 -0.551289 0.069421 +1403715277.11214 0.879334 2.183440 0.949403 -0.824481 -0.106699 -0.551382 0.069459 +1403715277.16214 0.879752 2.183490 0.949425 -0.824520 -0.106761 -0.551308 0.069482 +1403715277.21214 0.879743 2.183460 0.949532 -0.824593 -0.106557 -0.551213 0.069687 +1403715277.26214 0.879566 2.183350 0.949532 -0.824659 -0.106603 -0.551136 0.069437 +1403715277.31214 0.879356 2.183270 0.949418 -0.824784 -0.106416 -0.550976 0.069519 +1403715277.36214 0.879035 2.183250 0.949463 -0.824803 -0.106588 -0.550943 0.069293 +1403715277.41214 0.878681 2.183180 0.949478 -0.824733 -0.106463 -0.551050 0.069465 +1403715277.46214 0.878430 2.183050 0.949348 -0.824685 -0.106356 -0.551123 0.069623 +1403715277.51214 0.878741 2.183140 0.949447 -0.824780 -0.106326 -0.550988 0.069610 +1403715277.56214 0.878939 2.183140 0.949754 -0.824607 -0.106468 -0.551226 0.069551 +1403715277.61214 0.879067 2.183160 0.949640 -0.824723 -0.106397 -0.551043 0.069736 +1403715277.66214 0.879232 2.183260 0.949653 -0.824686 -0.106201 -0.551111 0.069937 +1403715277.71214 0.879176 2.183270 0.949980 -0.824695 -0.106236 -0.551088 0.069961 +1403715277.76214 0.879042 2.183410 0.950216 -0.824658 -0.106151 -0.551145 0.070072 +1403715277.81214 0.878842 2.183470 0.950161 -0.824650 -0.106358 -0.551155 0.069775 +1403715277.86214 0.878711 2.183310 0.950018 -0.824968 -0.105910 -0.550718 0.070153 +1403715277.91214 0.878593 2.183230 0.950267 -0.824844 -0.106280 -0.550889 0.069699 +1403715277.96214 0.878576 2.183140 0.950548 -0.824707 -0.106074 -0.551086 0.070073 +1403715278.01214 0.878809 2.183000 0.950657 -0.824926 -0.106011 -0.550759 0.070161 +1403715278.06214 0.878984 2.183040 0.950666 -0.824827 -0.106178 -0.550900 0.069971 +1403715278.11214 0.879067 2.183190 0.950876 -0.824649 -0.106057 -0.551192 0.069947 +1403715278.16214 0.879257 2.183390 0.951116 -0.824871 -0.105941 -0.550842 0.070265 +1403715278.21214 0.879601 2.183470 0.951245 -0.824795 -0.105997 -0.550940 0.070298 +1403715278.26214 0.879519 2.183410 0.951212 -0.824547 -0.106031 -0.551361 0.069859 +1403715278.31214 0.879482 2.183320 0.951715 -0.824381 -0.105209 -0.551798 0.069611 +1403715278.36214 0.879606 2.183060 0.952654 -0.824008 -0.104479 -0.552596 0.068791 +1403715278.41214 0.880214 2.182940 0.953597 -0.823822 -0.104227 -0.553030 0.067914 +1403715278.46214 0.881821 2.183340 0.954399 -0.823102 -0.103013 -0.554274 0.068349 +1403715278.51214 0.884562 2.184330 0.955440 -0.821961 -0.101847 -0.556161 0.068499 +1403715278.56214 0.888383 2.186110 0.958044 -0.819253 -0.100174 -0.560319 0.069521 +1403715278.61214 0.893209 2.188480 0.962522 -0.816582 -0.098548 -0.564341 0.070722 +1403715278.66214 0.899090 2.191560 0.969273 -0.815233 -0.098768 -0.566343 0.069969 +1403715278.71214 0.905808 2.195440 0.978907 -0.814039 -0.096960 -0.568125 0.071926 +1403715278.76214 0.913299 2.199710 0.991778 -0.811870 -0.095467 -0.571216 0.073922 +1403715278.81214 0.921233 2.204210 1.007130 -0.810195 -0.094708 -0.573535 0.075319 +1403715278.86214 0.929498 2.208740 1.025030 -0.808186 -0.093852 -0.576267 0.077096 +1403715278.91214 0.937427 2.212920 1.044030 -0.807707 -0.093730 -0.576908 0.077466 +1403715278.96214 0.944931 2.216870 1.062690 -0.807063 -0.093805 -0.577821 0.077286 +1403715279.01214 0.952027 2.220300 1.077790 -0.806734 -0.094343 -0.578307 0.076428 +1403715279.06214 0.958607 2.223560 1.087850 -0.806892 -0.094545 -0.578105 0.076030 +1403715279.11214 0.964914 2.226590 1.092620 -0.806781 -0.094659 -0.578284 0.075705 +1403715279.16214 0.970614 2.229400 1.092370 -0.806977 -0.095395 -0.577982 0.074999 +1403715279.21214 0.975736 2.231810 1.088800 -0.807431 -0.095967 -0.577353 0.074221 +1403715279.26214 0.980750 2.234250 1.084310 -0.807776 -0.096464 -0.576807 0.074074 +1403715279.31214 0.985195 2.236510 1.079820 -0.808503 -0.096582 -0.575769 0.074063 +1403715279.36214 0.989119 2.238580 1.076280 -0.809320 -0.096185 -0.574631 0.074489 +1403715279.41214 0.992671 2.240530 1.073930 -0.809541 -0.095719 -0.574265 0.075500 +1403715279.46214 0.995814 2.241990 1.072490 -0.810321 -0.095751 -0.573119 0.075806 +1403715279.51214 0.998639 2.243280 1.072460 -0.810596 -0.095668 -0.572677 0.076304 +1403715279.56214 1.001300 2.244520 1.073620 -0.810459 -0.096170 -0.572849 0.075836 +1403715279.61214 1.003560 2.245580 1.075750 -0.810890 -0.096236 -0.572250 0.075665 +1403715279.66214 1.005540 2.246320 1.078740 -0.811107 -0.096484 -0.571895 0.075709 +1403715279.71214 1.007540 2.246950 1.082570 -0.810996 -0.096416 -0.572051 0.075808 +1403715279.76214 1.009280 2.247500 1.087340 -0.811124 -0.096378 -0.571858 0.075950 +1403715279.81214 1.010600 2.247700 1.092780 -0.811342 -0.095995 -0.571567 0.076286 +1403715279.86214 1.011500 2.247520 1.098910 -0.811610 -0.096122 -0.571158 0.076341 +1403715279.91214 1.012220 2.247200 1.105700 -0.812092 -0.096163 -0.570488 0.076172 +1403715279.96214 1.012860 2.246730 1.112710 -0.813589 -0.096545 -0.568363 0.075594 +1403715280.01214 1.013410 2.246100 1.119220 -0.816981 -0.096794 -0.563508 0.075042 +1403715280.06214 1.014210 2.245360 1.125410 -0.821203 -0.097387 -0.557342 0.074245 +1403715280.11214 1.015700 2.244390 1.131950 -0.824783 -0.099675 -0.552070 0.070829 +1403715280.16214 1.018140 2.243550 1.139150 -0.826671 -0.101890 -0.549173 0.068137 +1403715280.21214 1.021600 2.242930 1.147060 -0.827041 -0.105071 -0.548514 0.063999 +1403715280.26214 1.026080 2.242950 1.155650 -0.826278 -0.107727 -0.549556 0.060401 +1403715280.31214 1.031400 2.244040 1.164470 -0.825046 -0.109815 -0.551266 0.057840 +1403715280.36214 1.037460 2.246130 1.173550 -0.823389 -0.111088 -0.553701 0.055720 +1403715280.41214 1.044240 2.249120 1.182620 -0.821711 -0.111195 -0.556398 0.053371 +1403715280.46214 1.051680 2.253040 1.191330 -0.821303 -0.107935 -0.557615 0.053632 +1403715280.51214 1.059620 2.257750 1.199800 -0.820926 -0.101271 -0.559293 0.054920 +1403715280.56214 1.067770 2.263130 1.208150 -0.820749 -0.093656 -0.560852 0.055167 +1403715280.61214 1.076210 2.268600 1.216320 -0.820494 -0.084641 -0.562747 0.054228 +1403715280.66214 1.085100 2.273990 1.224260 -0.820507 -0.075319 -0.564397 0.050508 +1403715280.71214 1.094080 2.279380 1.231720 -0.820589 -0.064913 -0.565937 0.046210 +1403715280.76214 1.103230 2.284720 1.238500 -0.821083 -0.054264 -0.566768 0.040639 +1403715280.81214 1.112380 2.289880 1.244500 -0.821916 -0.043314 -0.566906 0.034570 +1403715280.86214 1.121730 2.295000 1.250550 -0.821923 -0.032490 -0.567985 0.027911 +1403715280.91214 1.131020 2.300220 1.256130 -0.822048 -0.022708 -0.568561 0.021428 +1403715280.96214 1.140320 2.305670 1.261560 -0.821931 -0.014407 -0.569185 0.015836 +1403715281.01214 1.149270 2.311150 1.266620 -0.821858 -0.006809 -0.569541 0.011284 +1403715281.06214 1.158070 2.316830 1.271470 -0.822082 -0.000831 -0.569333 0.006401 +1403715281.11214 1.167080 2.322630 1.276130 -0.821971 0.004494 -0.569505 0.002661 +1403715281.16214 1.176250 2.328670 1.280590 0.821621 -0.008656 0.569968 0.000698 +1403715281.21214 1.185680 2.334690 1.284800 0.821572 -0.012601 0.569953 0.003791 +1403715281.26214 1.195200 2.340480 1.288630 0.821724 -0.017310 0.569585 0.006563 +1403715281.31214 1.204470 2.345920 1.291860 0.822226 -0.022447 0.568629 0.010095 +1403715281.36214 1.213570 2.351080 1.294290 0.822716 -0.028216 0.567580 0.013993 +1403715281.41214 1.222860 2.356100 1.296180 0.823186 -0.034400 0.566425 0.018543 +1403715281.46214 1.232350 2.360740 1.297690 0.823023 -0.041429 0.565976 0.024230 +1403715281.51214 1.241930 2.365110 1.298930 0.822770 -0.049508 0.565391 0.030502 +1403715281.56214 1.251580 2.369100 1.299500 0.822505 -0.058393 0.564483 0.037872 +1403715281.61214 1.261320 2.372890 1.299410 0.821802 -0.068454 0.563811 0.045529 +1403715281.66214 1.271180 2.376590 1.298620 0.820880 -0.079747 0.562986 0.053315 +1403715281.71214 1.281180 2.380210 1.297410 0.819903 -0.091362 0.561754 0.061998 +1403715281.76214 1.291420 2.383700 1.296050 0.818809 -0.103740 0.560200 0.070472 +1403715281.81214 1.301840 2.387260 1.294230 0.817565 -0.116347 0.558380 0.079142 +1403715281.86214 1.312480 2.390950 1.291960 0.815545 -0.129156 0.557192 0.087989 +1403715281.91214 1.323370 2.394610 1.289130 0.813731 -0.141568 0.555289 0.097237 +1403715281.96214 1.334590 2.398330 1.285730 0.811573 -0.154136 0.553555 0.105676 +1403715282.01214 1.346110 2.402110 1.281920 0.809285 -0.166657 0.551670 0.113772 +1403715282.06214 1.358090 2.405760 1.277440 0.806799 -0.178777 0.549819 0.121711 +1403715282.11214 1.370400 2.409400 1.272660 0.804253 -0.189438 0.547882 0.130828 +1403715282.16214 1.382940 2.413020 1.267520 0.801654 -0.200799 0.545817 0.138254 +1403715282.21214 1.395800 2.416690 1.262380 0.798722 -0.211140 0.544038 0.146582 +1403715282.26214 1.409000 2.420320 1.256940 0.796034 -0.222015 0.541485 0.154381 +1403715282.31214 1.422760 2.423890 1.251450 0.793207 -0.232681 0.538934 0.161963 +1403715282.36214 1.436820 2.427460 1.245850 0.790148 -0.243186 0.536372 0.169799 +1403715282.41214 1.451250 2.430780 1.240140 0.787716 -0.252610 0.532694 0.178690 +1403715282.46214 1.466250 2.434280 1.234110 0.784362 -0.263501 0.529982 0.185638 +1403715282.51214 1.482160 2.437530 1.227980 0.780638 -0.273413 0.527650 0.193481 +1403715282.56214 1.498610 2.440790 1.221540 0.776898 -0.283441 0.525098 0.200905 +1403715282.61214 1.515630 2.444210 1.215270 0.772384 -0.292644 0.523720 0.208569 +1403715282.66214 1.533130 2.447710 1.208790 0.767593 -0.302195 0.522619 0.215289 +1403715282.71214 1.550940 2.451410 1.201960 0.762563 -0.312150 0.521503 0.221574 +1403715282.76214 1.569020 2.455360 1.194680 0.757482 -0.322227 0.520556 0.226744 +1403715282.81214 1.587310 2.459020 1.186890 0.752881 -0.332443 0.518605 0.231733 +1403715282.86214 1.605800 2.462560 1.179150 0.748079 -0.341461 0.516694 0.238349 +1403715282.91214 1.624340 2.466240 1.171430 0.742969 -0.350053 0.514977 0.245477 +1403715282.96214 1.643160 2.469900 1.163460 0.738081 -0.359293 0.512626 0.251715 +1403715283.01214 1.662140 2.473650 1.155760 0.732700 -0.368536 0.510708 0.257896 +1403715283.06214 1.681210 2.477450 1.148080 0.726965 -0.378062 0.509021 0.263609 +1403715283.11214 1.700190 2.481450 1.140450 0.721343 -0.387710 0.507120 0.268653 +1403715283.16214 1.718760 2.485470 1.133120 0.715289 -0.397389 0.505783 0.273179 +1403715283.21214 1.736610 2.489670 1.126030 0.709162 -0.406777 0.504290 0.278053 +1403715283.26214 1.753780 2.493890 1.119270 0.703499 -0.415391 0.502189 0.283454 +1403715283.31214 1.770320 2.498110 1.112530 0.697834 -0.424300 0.500029 0.288043 +1403715283.36214 1.785790 2.502300 1.106400 0.692255 -0.431909 0.497830 0.293943 +1403715283.41214 1.800140 2.506500 1.100050 0.688050 -0.440085 0.493786 0.298476 +1403715283.46214 1.813490 2.510650 1.093710 0.684305 -0.448105 0.489258 0.302582 +1403715283.51214 1.825950 2.514710 1.087820 0.681288 -0.455122 0.483732 0.307757 +1403715283.56214 1.837620 2.518720 1.082370 0.678519 -0.461661 0.478010 0.313030 +1403715283.61214 1.848920 2.522670 1.077180 0.676218 -0.467866 0.472310 0.317417 +1403715283.66214 1.860340 2.526280 1.072180 0.674363 -0.472703 0.467634 0.321100 +1403715283.71214 1.871900 2.529420 1.067260 0.672383 -0.476465 0.464337 0.324459 +1403715283.76214 1.883730 2.532300 1.062350 0.670445 -0.479598 0.462281 0.326781 +1403715283.81214 1.895880 2.534910 1.057730 0.667877 -0.482080 0.462036 0.328727 +1403715283.86214 1.908160 2.537200 1.052980 0.666036 -0.483298 0.461553 0.331342 +1403715283.91214 1.920440 2.539200 1.048180 0.663951 -0.484507 0.462433 0.332532 +1403715283.96214 1.932650 2.540930 1.043150 0.662605 -0.485363 0.462679 0.333626 +1403715284.01214 1.945020 2.542460 1.037220 0.662872 -0.486840 0.461357 0.332773 +1403715284.06214 1.957500 2.543650 1.031260 0.663741 -0.487847 0.459810 0.331705 +1403715284.11214 1.969910 2.544560 1.025410 0.664459 -0.489168 0.458843 0.329653 +1403715284.16214 1.982020 2.545300 1.019710 0.665053 -0.490284 0.458624 0.327094 +1403715284.21214 1.993830 2.545450 1.014110 0.664873 -0.492084 0.459767 0.323127 +1403715284.26214 2.005100 2.544860 1.008970 0.664581 -0.493544 0.461265 0.319343 +1403715284.31214 2.015920 2.543350 1.004150 0.664075 -0.494971 0.463286 0.315236 +1403715284.36214 2.025980 2.540820 0.999868 0.663613 -0.495287 0.465353 0.312659 +1403715284.41214 2.035110 2.537170 0.996294 0.664641 -0.492911 0.465536 0.313953 +1403715284.46214 2.043540 2.532530 0.992908 0.666149 -0.489935 0.465232 0.315861 +1403715284.51214 2.051400 2.526950 0.989856 0.668221 -0.485930 0.464311 0.319012 +1403715284.56214 2.059100 2.520440 0.986975 0.669662 -0.482103 0.464370 0.321700 +1403715284.61214 2.066630 2.513530 0.984230 0.670922 -0.478213 0.464758 0.324308 +1403715284.66214 2.074050 2.506420 0.981302 0.672548 -0.474749 0.464471 0.326435 +1403715284.71214 2.081510 2.499010 0.978571 0.673575 -0.472128 0.464844 0.327584 +1403715284.76214 2.088820 2.491530 0.976021 0.674088 -0.470116 0.464978 0.329229 +1403715284.81214 2.095810 2.484110 0.973492 0.673398 -0.469522 0.464923 0.331559 +1403715284.86214 2.102510 2.476920 0.971373 0.670968 -0.470344 0.465499 0.334498 +1403715284.91214 2.109050 2.469940 0.969425 0.666729 -0.473610 0.466753 0.336612 +1403715284.96214 2.115160 2.463220 0.967938 0.660790 -0.477825 0.468012 0.340595 +1403715285.01214 2.120920 2.457060 0.966668 0.652685 -0.483937 0.470379 0.344312 +1403715285.06214 2.126330 2.451320 0.965984 0.644731 -0.490525 0.471135 0.348912 +1403715285.11214 2.130980 2.446160 0.965915 0.637684 -0.497387 0.468902 0.355102 +1403715285.16214 2.135000 2.442470 0.966476 0.631691 -0.505304 0.464839 0.359944 +1403715285.21214 2.138430 2.439970 0.966961 0.626104 -0.514593 0.459834 0.362961 +1403715285.26214 2.141620 2.438190 0.968517 0.621343 -0.523408 0.455118 0.364479 +1403715285.31214 2.144460 2.437550 0.972014 0.617574 -0.532357 0.450558 0.363588 +1403715285.36214 2.146830 2.437190 0.978759 0.614753 -0.540440 0.445893 0.362191 +1403715285.41214 2.148780 2.436650 0.989369 0.613349 -0.547078 0.441069 0.360509 +1403715285.46214 2.150070 2.435850 1.003950 0.612259 -0.551878 0.437294 0.359643 +1403715285.51214 2.150440 2.434910 1.021210 0.611082 -0.555905 0.434677 0.358615 +1403715285.56214 2.149970 2.433170 1.040810 0.609211 -0.559304 0.433734 0.357653 +1403715285.61214 2.148720 2.430880 1.061080 0.607376 -0.561907 0.433459 0.357028 +1403715285.66214 2.146370 2.427970 1.081190 0.606483 -0.563546 0.432535 0.357083 +1403715285.71214 2.142840 2.424100 1.100750 0.605357 -0.565302 0.432149 0.356685 +1403715285.76214 2.138040 2.419530 1.120330 0.604537 -0.565134 0.431709 0.358868 +1403715285.81214 2.132040 2.414250 1.139290 0.603996 -0.565028 0.431154 0.360609 +1403715285.86214 2.125040 2.408350 1.157220 0.605133 -0.563676 0.428680 0.363755 +1403715285.91214 2.117260 2.401660 1.174920 0.606997 -0.561409 0.425634 0.367709 +1403715285.96214 2.108960 2.394460 1.191860 0.609468 -0.559840 0.421793 0.370429 +1403715286.01214 2.100560 2.386610 1.208140 0.611678 -0.557868 0.418555 0.373422 +1403715286.06214 2.092320 2.378170 1.223440 0.613351 -0.556339 0.415751 0.376083 +1403715286.11214 2.084440 2.369250 1.237680 0.613906 -0.556182 0.414574 0.376708 +1403715286.16214 2.076920 2.359720 1.251230 0.613360 -0.557336 0.414857 0.375579 +1403715286.21214 2.069500 2.349620 1.264000 0.612411 -0.559339 0.415528 0.373402 +1403715286.26214 2.062160 2.338780 1.276290 0.611958 -0.560504 0.415976 0.371895 +1403715286.31214 2.054810 2.327020 1.288460 0.612266 -0.560168 0.415499 0.372427 +1403715286.36214 2.047520 2.314690 1.300170 0.612400 -0.559355 0.415362 0.373582 +1403715286.41214 2.040510 2.301660 1.310960 0.612804 -0.558738 0.414815 0.374449 +1403715286.46214 2.033670 2.287910 1.321070 0.613128 -0.557606 0.414325 0.376144 +1403715286.51214 2.026990 2.273560 1.330880 0.613403 -0.556856 0.413510 0.377701 +1403715286.56214 2.020670 2.258650 1.340420 0.612918 -0.556072 0.413627 0.379511 +1403715286.61214 2.014450 2.243310 1.349630 0.611000 -0.556535 0.414352 0.381131 +1403715286.66214 2.008290 2.227630 1.359000 0.607287 -0.557569 0.415244 0.384566 +1403715286.71214 2.002220 2.211800 1.367910 0.601985 -0.558756 0.416804 0.389461 +1403715286.76214 1.996220 2.196020 1.375920 0.596903 -0.561229 0.416358 0.394176 +1403715286.81214 1.990300 2.180710 1.382710 0.593574 -0.565147 0.412973 0.397154 +1403715286.86214 1.984740 2.165810 1.388310 0.591394 -0.570098 0.408486 0.397971 +1403715286.91214 1.979650 2.150820 1.393870 0.590523 -0.574406 0.403122 0.398539 +1403715286.96214 1.975100 2.135660 1.399580 0.589509 -0.578110 0.398534 0.399298 +1403715287.01214 1.971210 2.120040 1.405590 0.588402 -0.580908 0.394563 0.400811 +1403715287.06214 1.968000 2.104310 1.411820 0.586577 -0.583600 0.392159 0.401934 +1403715287.11214 1.965660 2.088040 1.418260 0.585254 -0.584750 0.389920 0.404361 +1403715287.16214 1.964180 2.071100 1.424880 0.582802 -0.585302 0.389835 0.407177 +1403715287.21214 1.963520 2.053670 1.431840 0.579854 -0.584765 0.391188 0.410842 +1403715287.26214 1.963620 2.036190 1.438660 0.577312 -0.584473 0.392161 0.413898 +1403715287.31214 1.964450 2.018530 1.445540 0.574583 -0.584253 0.394258 0.416010 +1403715287.36214 1.965840 2.000970 1.452050 0.572675 -0.584474 0.395416 0.417228 +1403715287.41214 1.967980 1.983700 1.458370 0.570851 -0.585522 0.397310 0.416459 +1403715287.46214 1.970440 1.966810 1.464750 0.568190 -0.587884 0.399801 0.414380 +1403715287.51214 1.972870 1.950360 1.471290 0.565185 -0.590918 0.401452 0.412575 +1403715287.56214 1.974950 1.934620 1.477910 0.560985 -0.595091 0.402195 0.411585 +1403715287.61214 1.976410 1.919490 1.484700 0.555832 -0.600906 0.401897 0.410415 +1403715287.66214 1.976930 1.904760 1.491950 0.549828 -0.607152 0.400742 0.410440 +1403715287.71214 1.976250 1.890400 1.499700 0.543407 -0.613442 0.398381 0.411934 +1403715287.76214 1.974440 1.876400 1.508030 0.536678 -0.619359 0.395096 0.415055 +1403715287.81214 1.971360 1.862850 1.516910 0.529809 -0.624473 0.390502 0.420527 +1403715287.86214 1.967160 1.849800 1.526290 0.522218 -0.629733 0.385601 0.426658 +1403715287.91214 1.961760 1.836850 1.536140 0.514098 -0.634836 0.379620 0.434252 +1403715287.96214 1.955610 1.824730 1.546150 0.505533 -0.640226 0.372968 0.442088 +1403715288.01214 1.948980 1.813320 1.555960 0.496269 -0.646196 0.366203 0.449492 +1403715288.06214 1.942250 1.802750 1.565890 0.486472 -0.652126 0.360263 0.456385 +1403715288.11214 1.935550 1.792730 1.575370 0.477511 -0.658032 0.355017 0.461454 +1403715288.16214 1.928770 1.783470 1.583380 0.470179 -0.663098 0.349895 0.465626 +1403715288.21214 1.922030 1.775040 1.588530 0.464372 -0.667578 0.344970 0.468715 +1403715288.26214 1.915350 1.767400 1.590620 0.459480 -0.671746 0.340639 0.470745 +1403715288.31214 1.908560 1.760230 1.589600 0.456114 -0.674239 0.336323 0.473549 +1403715288.36214 1.902030 1.753610 1.585020 0.453139 -0.676813 0.333365 0.474822 +1403715288.41214 1.895700 1.747160 1.577970 0.450348 -0.679106 0.331915 0.475220 +1403715288.46214 1.889380 1.741260 1.571490 0.448017 -0.680787 0.331364 0.475402 +1403715288.51214 1.882860 1.736180 1.567360 0.446400 -0.681519 0.331013 0.476120 +1403715288.56214 1.876440 1.731900 1.565920 0.445329 -0.682754 0.331046 0.475329 +1403715288.61214 1.869800 1.728320 1.567940 0.444093 -0.683418 0.332198 0.474726 +1403715288.66214 1.862620 1.724700 1.573450 0.443725 -0.684260 0.332499 0.473646 +1403715288.71214 1.855200 1.721640 1.581660 0.444011 -0.683916 0.332590 0.473811 +1403715288.76214 1.847520 1.718980 1.590390 0.446128 -0.683202 0.330414 0.474375 +1403715288.81214 1.839540 1.716960 1.598060 0.447644 -0.682697 0.329002 0.474655 +1403715288.86214 1.831270 1.715480 1.602510 0.449175 -0.682223 0.326391 0.475692 +1403715288.91214 1.822580 1.714420 1.603880 0.449991 -0.682053 0.322795 0.477614 +1403715288.96214 1.813520 1.713470 1.601950 0.449381 -0.682707 0.319347 0.479569 +1403715289.01214 1.804450 1.713160 1.596420 0.447577 -0.684887 0.316003 0.480362 +1403715289.06214 1.795380 1.713030 1.587440 0.444691 -0.687619 0.312714 0.481290 +1403715289.11214 1.786440 1.712970 1.575370 0.441442 -0.690456 0.308574 0.482888 +1403715289.16214 1.777820 1.712680 1.561690 0.438673 -0.692815 0.304150 0.484836 +1403715289.21214 1.769440 1.711900 1.547720 0.435980 -0.694634 0.300163 0.487142 +1403715289.26214 1.761620 1.710970 1.533600 0.432836 -0.697181 0.296768 0.488385 +1403715289.31214 1.753970 1.709940 1.519170 0.429465 -0.699701 0.292255 0.490474 +1403715289.36214 1.746790 1.709080 1.504420 0.425013 -0.702471 0.287767 0.493040 +1403715289.41214 1.740020 1.707730 1.488690 0.419586 -0.706472 0.283263 0.494577 +1403715289.46214 1.733540 1.705940 1.471790 0.413386 -0.710954 0.278805 0.495908 +1403715289.51214 1.727430 1.703710 1.454090 0.407027 -0.715784 0.273686 0.497069 +1403715289.56214 1.721590 1.700870 1.435800 0.399940 -0.720353 0.269014 0.498770 +1403715289.61214 1.716120 1.697220 1.416910 0.393309 -0.725036 0.264348 0.499751 +1403715289.66214 1.711040 1.692830 1.397330 0.388117 -0.729483 0.259604 0.499825 +1403715289.71214 1.706230 1.687430 1.377440 0.383021 -0.733266 0.256891 0.499623 +1403715289.76214 1.701790 1.681150 1.358920 0.379803 -0.735117 0.254184 0.500742 +1403715289.81214 1.697680 1.673970 1.342750 0.377313 -0.736542 0.252967 0.501147 +1403715289.86214 1.693800 1.665840 1.329230 0.375353 -0.737049 0.253083 0.501814 +1403715289.91214 1.690080 1.656590 1.318480 0.373650 -0.737397 0.254863 0.501674 +1403715289.96214 1.686660 1.646750 1.310310 0.374033 -0.737631 0.255517 0.500710 +1403715290.01214 1.683210 1.636010 1.304730 0.374846 -0.737588 0.256604 0.499608 +1403715290.06214 1.679940 1.624600 1.302360 0.376463 -0.736422 0.258075 0.499355 +1403715290.11214 1.677210 1.612650 1.302930 0.378548 -0.733971 0.259832 0.500476 +1403715290.16214 1.674430 1.599780 1.305920 0.381527 -0.732118 0.261387 0.500117 +1403715290.21214 1.671610 1.586260 1.311710 0.385450 -0.731263 0.261377 0.498363 +1403715290.26214 1.669110 1.572250 1.319510 0.388688 -0.731297 0.262091 0.495413 +1403715290.31214 1.666610 1.556840 1.327260 0.391390 -0.731291 0.263227 0.492685 +1403715290.36214 1.664080 1.540350 1.334090 0.393905 -0.731752 0.264158 0.489487 +1403715290.41214 1.661720 1.523030 1.339970 0.394859 -0.733219 0.266196 0.485403 +1403715290.46214 1.659540 1.505080 1.345230 0.395944 -0.734480 0.267441 0.481916 +1403715290.51214 1.656900 1.486190 1.350560 0.396043 -0.733955 0.269701 0.481375 +1403715290.56214 1.653430 1.466110 1.355380 0.396221 -0.732586 0.270979 0.482595 +1403715290.61214 1.649730 1.445270 1.359980 0.394720 -0.731178 0.273794 0.484367 +1403715290.66214 1.646000 1.423980 1.363400 0.393372 -0.731122 0.275530 0.484564 +1403715290.71214 1.641620 1.402050 1.366640 0.392500 -0.729234 0.276153 0.487752 +1403715290.76214 1.637010 1.379750 1.369720 0.391514 -0.727252 0.276574 0.491252 +1403715290.81214 1.632390 1.357210 1.372640 0.389703 -0.726207 0.278038 0.493406 +1403715290.86214 1.627890 1.334460 1.375070 0.387805 -0.726619 0.279537 0.493448 +1403715290.91214 1.623460 1.311600 1.376710 0.386487 -0.727533 0.279650 0.493071 +1403715290.96214 1.619460 1.288880 1.377930 0.383283 -0.728362 0.281477 0.493308 +1403715291.01214 1.615390 1.266140 1.379070 0.378693 -0.729433 0.284408 0.493590 +1403715291.06214 1.611180 1.243450 1.380100 0.373533 -0.730927 0.288054 0.493196 +1403715291.11214 1.606300 1.221160 1.380620 0.368222 -0.733166 0.290794 0.492260 +1403715291.16214 1.600810 1.199410 1.381100 0.362858 -0.735012 0.293551 0.491854 +1403715291.21214 1.594600 1.178660 1.381380 0.357794 -0.736815 0.294929 0.492040 +1403715291.26214 1.587390 1.158990 1.380610 0.353210 -0.738585 0.294957 0.492682 +1403715291.31214 1.579240 1.140690 1.378650 0.349335 -0.740442 0.293629 0.493450 +1403715291.36214 1.569930 1.123410 1.376180 0.345563 -0.741948 0.291917 0.494858 +1403715291.41214 1.559810 1.107240 1.372580 0.342107 -0.744178 0.289470 0.495348 +1403715291.46214 1.548950 1.092200 1.368470 0.338943 -0.746449 0.286241 0.495982 +1403715291.51214 1.537010 1.078290 1.363630 0.336975 -0.749369 0.281204 0.495800 +1403715291.56214 1.524330 1.065530 1.358360 0.333699 -0.752524 0.277344 0.495412 +1403715291.61214 1.510550 1.053600 1.353080 0.329921 -0.755637 0.274285 0.494907 +1403715291.66214 1.495520 1.042160 1.347660 0.326006 -0.758339 0.271906 0.494680 +1403715291.71214 1.479100 1.031380 1.342070 0.322402 -0.761025 0.269589 0.494186 +1403715291.76214 1.461340 1.020930 1.337150 0.321455 -0.762116 0.264709 0.495757 +1403715291.81214 1.442520 1.010870 1.332280 0.321367 -0.762434 0.259468 0.498090 +1403715291.86214 1.422490 1.001110 1.327190 0.324191 -0.761505 0.251213 0.501898 +1403715291.91214 1.401570 0.991321 1.321460 0.326936 -0.760559 0.243618 0.505285 +1403715291.96214 1.380180 0.981320 1.314980 0.327771 -0.760663 0.239366 0.506618 +1403715292.01214 1.358580 0.971110 1.308290 0.328941 -0.760763 0.235423 0.507556 +1403715292.06214 1.336900 0.960151 1.301870 0.329667 -0.760714 0.233289 0.508143 +1403715292.11214 1.315100 0.948094 1.295400 0.331167 -0.760267 0.233452 0.507763 +1403715292.16214 1.293560 0.935385 1.288240 0.334182 -0.759366 0.234576 0.506617 +1403715292.21214 1.272040 0.921707 1.281350 0.339092 -0.757265 0.236532 0.505588 +1403715292.26214 1.250510 0.906947 1.274820 0.345287 -0.754810 0.239386 0.503720 +1403715292.31214 1.229120 0.891372 1.268160 0.353224 -0.751732 0.242853 0.501152 +1403715292.36214 1.207590 0.874755 1.261750 0.362882 -0.747451 0.245863 0.499184 +1403715292.41214 1.186590 0.857007 1.255680 0.371931 -0.742871 0.251188 0.496704 +1403715292.46214 1.165600 0.837884 1.249700 0.382980 -0.738326 0.255581 0.492827 +1403715292.51214 1.144950 0.817616 1.244420 0.392546 -0.732150 0.263078 0.490566 +1403715292.56214 1.124790 0.796479 1.239660 0.402310 -0.724063 0.272040 0.489769 +1403715292.61214 1.105010 0.774553 1.235510 0.412996 -0.714404 0.280771 0.490131 +1403715292.66214 1.085770 0.752000 1.232750 0.423567 -0.702132 0.290580 0.493117 +1403715292.71214 1.067660 0.729413 1.229960 0.435024 -0.691440 0.299113 0.493149 +1403715292.76214 1.050610 0.706653 1.228400 0.446559 -0.680177 0.307495 0.493347 +1403715292.81214 1.035190 0.684298 1.228450 0.458013 -0.670017 0.315655 0.491592 +1403715292.86214 1.021610 0.662360 1.230700 0.469719 -0.661734 0.322726 0.487155 +1403715292.91214 1.009810 0.640657 1.235380 0.481329 -0.655514 0.329378 0.479723 +1403715292.96214 0.999419 0.619186 1.243130 0.490944 -0.650563 0.337762 0.470805 +1403715293.01214 0.990183 0.598204 1.253960 0.498780 -0.645168 0.347306 0.462986 +1403715293.06214 0.981996 0.577588 1.267640 0.506475 -0.639474 0.356698 0.455327 +1403715293.11214 0.974486 0.557127 1.282880 0.513173 -0.633545 0.366360 0.448391 +1403715293.16214 0.967296 0.537006 1.298320 0.520404 -0.628018 0.374243 0.441265 +1403715293.21214 0.960379 0.517325 1.313950 0.528228 -0.621867 0.381006 0.434846 +1403715293.26214 0.953572 0.497809 1.329870 0.534653 -0.615223 0.388801 0.429511 +1403715293.31214 0.946855 0.478554 1.345800 0.541644 -0.607350 0.395401 0.425918 +1403715293.36214 0.940173 0.459938 1.361640 0.547875 -0.599258 0.402291 0.422947 +1403715293.41214 0.933495 0.442039 1.377520 0.552620 -0.590983 0.410726 0.420302 +1403715293.46214 0.926489 0.425223 1.393140 0.557842 -0.583208 0.417460 0.417621 +1403715293.51214 0.919337 0.409692 1.408340 0.564278 -0.577149 0.421841 0.412966 +1403715293.56214 0.912128 0.395202 1.423600 0.570662 -0.571881 0.425729 0.407494 +1403715293.61214 0.904683 0.381571 1.438910 0.577474 -0.567269 0.428279 0.401631 +1403715293.66214 0.897050 0.368640 1.454330 0.584630 -0.563204 0.429652 0.395484 +1403715293.71214 0.889142 0.356378 1.470180 0.591298 -0.558367 0.431612 0.390262 +1403715293.76214 0.880888 0.344660 1.486010 0.597940 -0.553805 0.433325 0.384703 +1403715293.81214 0.872591 0.333438 1.501730 0.604357 -0.548543 0.435321 0.379933 +1403715293.86214 0.864334 0.322514 1.517200 0.610180 -0.543648 0.438151 0.374367 +1403715293.91214 0.856113 0.311583 1.532460 0.616401 -0.538188 0.440579 0.369180 +1403715293.96214 0.847784 0.300587 1.547310 0.622228 -0.531754 0.443912 0.364710 +1403715294.01214 0.839367 0.289803 1.559900 0.627917 -0.524771 0.447842 0.360240 +1403715294.06214 0.830978 0.279067 1.569120 0.633711 -0.517519 0.451866 0.355529 +1403715294.11214 0.822493 0.268564 1.575370 0.638434 -0.509868 0.457437 0.350982 +1403715294.16214 0.813814 0.258284 1.578650 0.642583 -0.501885 0.463675 0.346705 +1403715294.21214 0.805048 0.248378 1.578780 0.646651 -0.493812 0.469910 0.342312 +1403715294.26214 0.796191 0.239272 1.575500 0.650849 -0.486154 0.475931 0.336957 +1403715294.31214 0.786949 0.230696 1.568710 0.655298 -0.478387 0.481306 0.331775 +1403715294.36214 0.777180 0.222734 1.558310 0.660344 -0.470710 0.485767 0.326202 +1403715294.41214 0.767151 0.215072 1.545650 0.665231 -0.462386 0.490436 0.321154 +1403715294.46214 0.756572 0.208107 1.531930 0.670683 -0.453711 0.494053 0.316610 +1403715294.51214 0.745613 0.201900 1.517940 0.676389 -0.444876 0.497287 0.311911 +1403715294.56214 0.734345 0.196655 1.503320 0.683277 -0.437208 0.498869 0.305141 +1403715294.61214 0.722713 0.192135 1.488690 0.691227 -0.429519 0.498876 0.298063 +1403715294.66214 0.710714 0.187907 1.474350 0.699662 -0.420795 0.497945 0.292328 +1403715294.71214 0.698798 0.183857 1.460030 0.708095 -0.412020 0.496822 0.286373 +1403715294.76214 0.687008 0.179857 1.445860 0.715537 -0.403150 0.496685 0.280681 +1403715294.81214 0.675635 0.175849 1.431870 0.722012 -0.394705 0.497613 0.274387 +1403715294.86214 0.664699 0.171686 1.417890 0.727842 -0.385826 0.499082 0.268891 +1403715294.91214 0.654708 0.167294 1.404440 0.732901 -0.376521 0.501297 0.264177 +1403715294.96214 0.645437 0.162847 1.391920 0.736386 -0.366625 0.505546 0.260279 +1403715295.01214 0.637016 0.158514 1.379670 0.739072 -0.357525 0.510564 0.255485 +1403715295.06214 0.629303 0.154509 1.367390 0.741978 -0.348954 0.514999 0.249952 +1403715295.11214 0.622229 0.150633 1.355800 0.743435 -0.341023 0.521423 0.243159 +1403715295.16214 0.615311 0.147240 1.345040 0.744477 -0.333427 0.527912 0.236408 +1403715295.21214 0.608430 0.144482 1.335500 0.745823 -0.325543 0.533796 0.229849 +1403715295.26214 0.601201 0.142461 1.328250 0.748101 -0.318118 0.538157 0.222558 +1403715295.31214 0.593867 0.140838 1.324670 0.751275 -0.309460 0.541519 0.215819 +1403715295.36214 0.586347 0.139970 1.323940 0.756530 -0.300258 0.542482 0.207898 +1403715295.41214 0.578465 0.139469 1.326010 0.761494 -0.290129 0.543731 0.200773 +1403715295.46214 0.570714 0.139194 1.331070 0.766385 -0.279420 0.545117 0.193459 +1403715295.51214 0.562857 0.139040 1.336410 0.770964 -0.268453 0.546499 0.186781 +1403715295.56214 0.554665 0.138668 1.339250 0.774969 -0.257154 0.547707 0.182517 +1403715295.61214 0.546279 0.138418 1.338500 0.778101 -0.247791 0.549043 0.178073 +1403715295.66214 0.537746 0.138246 1.334330 0.779849 -0.239635 0.551155 0.175038 +1403715295.71214 0.529287 0.138420 1.327120 0.780881 -0.233060 0.553505 0.171871 +1403715295.76214 0.521087 0.139263 1.318050 0.782101 -0.226409 0.555670 0.168190 +1403715295.81214 0.512826 0.140932 1.307690 0.782677 -0.220753 0.558773 0.162655 +1403715295.86214 0.504504 0.143222 1.297200 0.782459 -0.215240 0.562769 0.157230 +1403715295.91214 0.495593 0.146180 1.285920 0.783280 -0.209857 0.565383 0.150913 +1403715295.96214 0.486144 0.149438 1.274190 0.783003 -0.205159 0.569220 0.144241 +1403715296.01214 0.475592 0.152999 1.260950 0.782902 -0.201152 0.572299 0.138114 +1403715296.06214 0.463927 0.156599 1.246670 0.783668 -0.199060 0.573703 0.130785 +1403715296.11214 0.451348 0.160149 1.231510 0.785790 -0.198254 0.572744 0.123262 +1403715296.16214 0.437931 0.163501 1.215680 0.789713 -0.196254 0.569416 0.116634 +1403715296.21214 0.423823 0.166190 1.199450 0.793974 -0.193030 0.565632 0.111378 +1403715296.26214 0.409224 0.167976 1.182890 0.798464 -0.189384 0.561575 0.105937 +1403715296.31214 0.394466 0.168772 1.166920 0.804389 -0.185334 0.555373 0.100849 +1403715296.36214 0.379571 0.168456 1.153380 0.810127 -0.180145 0.549394 0.096999 +1403715296.41214 0.365381 0.166903 1.142870 0.814102 -0.174665 0.546103 0.092209 +1403715296.46214 0.352161 0.163782 1.135220 0.816261 -0.169622 0.545377 0.086664 +1403715296.51214 0.339438 0.159097 1.129700 0.817948 -0.165767 0.544857 0.081321 +1403715296.56214 0.327507 0.152640 1.126930 0.818852 -0.160795 0.545421 0.078377 +1403715296.61214 0.315978 0.144551 1.127030 0.819336 -0.154882 0.546405 0.078366 +1403715296.66214 0.305236 0.135175 1.128620 0.818075 -0.148849 0.549763 0.079736 +1403715296.71214 0.295260 0.124596 1.130030 0.816894 -0.143981 0.552686 0.080573 +1403715296.76214 0.286152 0.113007 1.131650 0.815849 -0.140613 0.555114 0.080412 +1403715296.81214 0.277694 0.100789 1.132820 0.815112 -0.135912 0.557148 0.081899 +1403715296.86214 0.269894 0.088074 1.134340 0.814035 -0.130470 0.559669 0.084235 +1403715296.91214 0.262848 0.075580 1.135540 0.813298 -0.123904 0.562028 0.085548 +1403715296.96214 0.256375 0.063416 1.136430 0.812482 -0.116691 0.564761 0.085450 +1403715297.01214 0.250149 0.051931 1.136400 0.813459 -0.110545 0.565294 0.080663 +1403715297.06214 0.243432 0.041287 1.135340 0.816408 -0.105847 0.563190 0.071355 +1403715297.11214 0.236998 0.030870 1.134190 0.818865 -0.100175 0.561779 0.061884 +1403715297.16214 0.231552 0.020170 1.130930 0.823957 -0.094235 0.556438 0.050907 +1403715297.21214 0.227080 0.009064 1.127070 0.829053 -0.086442 0.550970 0.040392 +1403715297.26214 0.223836 -0.002598 1.123110 0.832642 -0.077742 0.547537 0.029427 +1403715297.31214 0.222168 -0.015453 1.118780 0.834900 -0.067762 0.545874 0.019267 +1403715297.36214 0.221646 -0.029413 1.113410 0.836573 -0.056911 0.544795 0.010301 +1403715297.41214 0.222351 -0.044808 1.108190 0.836823 -0.044448 0.545649 0.004279 +1403715297.46214 0.224718 -0.061643 1.103130 -0.836897 0.032953 -0.546366 0.001450 +1403715297.51214 0.228854 -0.079560 1.098690 -0.836297 0.021085 -0.547838 0.006026 +1403715297.56214 0.234319 -0.098338 1.093780 -0.836261 0.011612 -0.548078 0.011995 +1403715297.61214 0.241178 -0.117735 1.088210 -0.837445 0.003632 -0.546170 0.019237 +1403715297.66214 0.249749 -0.137754 1.082590 -0.838778 -0.002999 -0.543798 0.026934 +1403715297.71214 0.259767 -0.158409 1.077300 -0.839363 -0.008467 -0.542349 0.035450 +1403715297.76214 0.271951 -0.179753 1.072290 -0.839259 -0.013939 -0.541790 0.043739 +1403715297.81214 0.286324 -0.201942 1.068870 -0.836042 -0.020290 -0.545946 0.050645 +1403715297.86214 0.302532 -0.225086 1.066740 -0.831431 -0.027117 -0.551991 0.057380 +1403715297.91214 0.320406 -0.249074 1.065510 -0.826052 -0.034731 -0.558962 0.063193 +1403715297.96214 0.339402 -0.273879 1.065020 -0.818523 -0.041731 -0.568570 0.070752 +1403715298.01214 0.358291 -0.299537 1.064570 -0.810461 -0.050999 -0.578473 0.076952 +1403715298.06214 0.376368 -0.325929 1.064030 -0.803845 -0.062382 -0.585883 0.081749 +1403715298.11214 0.393707 -0.353238 1.063680 -0.798125 -0.076542 -0.591807 0.083079 +1403715298.16214 0.410042 -0.381187 1.062470 -0.794872 -0.093302 -0.594015 0.081362 +1403715298.21214 0.424866 -0.409683 1.060810 -0.792912 -0.111163 -0.594018 0.077950 +1403715298.26214 0.438017 -0.437730 1.059210 -0.791385 -0.128289 -0.592909 0.075568 +1403715298.31214 0.449399 -0.465186 1.057860 -0.790374 -0.142398 -0.591135 0.074774 +1403715298.36214 0.458907 -0.491494 1.056250 -0.791055 -0.154025 -0.587308 0.074684 +1403715298.41214 0.466442 -0.516329 1.055710 -0.792366 -0.162863 -0.583102 0.074992 +1403715298.46214 0.472303 -0.539696 1.055890 -0.793538 -0.169933 -0.579485 0.074948 +1403715298.51214 0.477074 -0.561231 1.056600 -0.793912 -0.176304 -0.577248 0.073519 +1403715298.56214 0.481036 -0.580278 1.058140 -0.793811 -0.182359 -0.575943 0.069991 +1403715298.61214 0.483963 -0.596474 1.060300 -0.792968 -0.187555 -0.575938 0.065728 +1403715298.66214 0.485596 -0.609837 1.062790 -0.791854 -0.191997 -0.576452 0.061705 +1403715298.71214 0.485889 -0.619981 1.066010 -0.791038 -0.194877 -0.576966 0.058246 +1403715298.76214 0.484581 -0.626531 1.070070 -0.790314 -0.195744 -0.577856 0.056308 +1403715298.81214 0.481446 -0.629637 1.074550 -0.791261 -0.194148 -0.577003 0.057281 +1403715298.86214 0.476352 -0.629597 1.077900 -0.796884 -0.187558 -0.570552 0.065324 +1403715298.91214 0.470155 -0.626080 1.081420 -0.803096 -0.179362 -0.562875 0.077701 +1403715298.96214 0.463352 -0.620057 1.084690 -0.808810 -0.172517 -0.554762 0.091122 +1403715299.01214 0.456715 -0.611943 1.088270 -0.812925 -0.169691 -0.547810 0.101303 +1403715299.06214 0.450624 -0.602308 1.091960 -0.815448 -0.169224 -0.542372 0.110633 +1403715299.11214 0.445650 -0.591472 1.096110 -0.816374 -0.171514 -0.538661 0.118158 +1403715299.16214 0.442050 -0.579603 1.100590 -0.816422 -0.175084 -0.535919 0.124864 +1403715299.21214 0.439810 -0.566829 1.104950 -0.815880 -0.180125 -0.533596 0.131033 +1403715299.26214 0.439036 -0.553344 1.108970 -0.815291 -0.186154 -0.530908 0.137051 +1403715299.31214 0.439781 -0.539297 1.113140 -0.813628 -0.192794 -0.529345 0.143641 +1403715299.36214 0.442164 -0.524827 1.117170 -0.812070 -0.200260 -0.527150 0.150170 +1403715299.41214 0.446434 -0.509706 1.121610 -0.809747 -0.208143 -0.525578 0.157331 +1403715299.46214 0.452661 -0.494247 1.126410 -0.806771 -0.216889 -0.524447 0.164423 +1403715299.51214 0.460760 -0.478365 1.131570 -0.802692 -0.225978 -0.524348 0.172274 +1403715299.56214 0.470106 -0.462137 1.136460 -0.798338 -0.235852 -0.524003 0.180141 +1403715299.61214 0.480743 -0.445627 1.141090 -0.792956 -0.246102 -0.524768 0.187810 +1403715299.66214 0.492078 -0.428867 1.144780 -0.788388 -0.256617 -0.523603 0.196041 +1403715299.71214 0.504425 -0.412062 1.148180 -0.783165 -0.266717 -0.522892 0.205181 +1403715299.76214 0.517843 -0.395223 1.151070 -0.778621 -0.278518 -0.520417 0.212940 +1403715299.81214 0.532039 -0.378531 1.153620 -0.773137 -0.289594 -0.518592 0.222388 +1403715299.86214 0.546935 -0.362299 1.154910 -0.768117 -0.301226 -0.515492 0.231360 +1403715299.91214 0.562526 -0.346209 1.156390 -0.762002 -0.313552 -0.513502 0.239489 +1403715299.96214 0.578701 -0.330178 1.157700 -0.755730 -0.325534 -0.511435 0.247657 +1403715300.01214 0.595556 -0.314478 1.158600 -0.750381 -0.336636 -0.508706 0.254604 +1403715300.06214 0.613202 -0.298950 1.160170 -0.742882 -0.346344 -0.509876 0.261148 +1403715300.11214 0.631364 -0.284236 1.161450 -0.736106 -0.353943 -0.511243 0.267399 +1403715300.16214 0.649986 -0.270324 1.162490 -0.729395 -0.362095 -0.513804 0.269955 +1403715300.21214 0.668841 -0.257005 1.163450 -0.722862 -0.370576 -0.517208 0.269517 +1403715300.26214 0.687287 -0.244137 1.164630 -0.716542 -0.376353 -0.521255 0.270592 +1403715300.31214 0.704801 -0.231869 1.165710 -0.712642 -0.378575 -0.522851 0.274680 +1403715300.36214 0.721457 -0.220210 1.166910 -0.709832 -0.378917 -0.523877 0.279489 +1403715300.41214 0.737258 -0.209180 1.168510 -0.708492 -0.378123 -0.523515 0.284593 +1403715300.46214 0.752218 -0.199403 1.170050 -0.707933 -0.376630 -0.523026 0.288833 +1403715300.51214 0.766249 -0.190944 1.171800 -0.707535 -0.376247 -0.522873 0.290580 +1403715300.56214 0.779512 -0.183894 1.173270 -0.708349 -0.375051 -0.521763 0.292133 +1403715300.61214 0.792074 -0.178245 1.174590 -0.709683 -0.374240 -0.520428 0.292316 +1403715300.66214 0.804137 -0.173998 1.175750 -0.710907 -0.373242 -0.519559 0.292165 +1403715300.71214 0.815685 -0.171054 1.177110 -0.712540 -0.371658 -0.518371 0.292315 +1403715300.76214 0.826688 -0.169632 1.178740 -0.713424 -0.370029 -0.518558 0.291895 +1403715300.81214 0.837260 -0.169601 1.180210 -0.713450 -0.369222 -0.519928 0.290411 +1403715300.86214 0.847512 -0.170760 1.181680 -0.712915 -0.369303 -0.522187 0.287555 +1403715300.91214 0.857112 -0.173265 1.182690 -0.712317 -0.370091 -0.524526 0.283741 +1403715300.96214 0.865986 -0.176990 1.183560 -0.711733 -0.370902 -0.526757 0.279991 +1403715301.01214 0.873991 -0.181618 1.184150 -0.711283 -0.371330 -0.528677 0.276931 +1403715301.06214 0.880935 -0.186996 1.184480 -0.710399 -0.371454 -0.531249 0.274098 +1403715301.11214 0.886790 -0.193259 1.184900 -0.708746 -0.371307 -0.534890 0.271482 +1403715301.16214 0.891344 -0.200080 1.185110 -0.706741 -0.371702 -0.538709 0.268602 +1403715301.21214 0.894370 -0.207885 1.185060 -0.704588 -0.372136 -0.542715 0.265576 +1403715301.26214 0.895537 -0.216420 1.184520 -0.702919 -0.373144 -0.545586 0.262687 +1403715301.31214 0.894492 -0.225459 1.183450 -0.701305 -0.373921 -0.547956 0.260956 +1403715301.36214 0.890989 -0.235235 1.181700 -0.700599 -0.374171 -0.549069 0.260154 +1403715301.41214 0.885132 -0.245546 1.179020 -0.701215 -0.374135 -0.548248 0.260279 +1403715301.46214 0.877046 -0.256405 1.175550 -0.703519 -0.372433 -0.545031 0.263241 +1403715301.51214 0.867059 -0.268030 1.170910 -0.708142 -0.370853 -0.538720 0.266052 +1403715301.56214 0.855528 -0.280324 1.165250 -0.713726 -0.369972 -0.531240 0.267395 +1403715301.61214 0.842797 -0.293091 1.159270 -0.719321 -0.369184 -0.523938 0.267899 +1403715301.66214 0.829375 -0.306239 1.153040 -0.723903 -0.367764 -0.518146 0.268773 +1403715301.71214 0.815691 -0.319915 1.146570 -0.726754 -0.366925 -0.514983 0.268303 +1403715301.76214 0.801937 -0.334114 1.139700 -0.728169 -0.366833 -0.514084 0.266310 +1403715301.81214 0.788241 -0.348502 1.133210 -0.727217 -0.367904 -0.516365 0.263001 +1403715301.86214 0.774242 -0.362645 1.126750 -0.726023 -0.369040 -0.519063 0.259372 +1403715301.91214 0.759704 -0.376633 1.120390 -0.725541 -0.369657 -0.520840 0.256261 +1403715301.96214 0.744585 -0.390504 1.114410 -0.726351 -0.368880 -0.520688 0.255392 +1403715302.01214 0.728954 -0.404031 1.109540 -0.725994 -0.368888 -0.522219 0.253261 +1403715302.06214 0.712599 -0.417328 1.105040 -0.725968 -0.368913 -0.523281 0.251099 +1403715302.11214 0.695581 -0.430329 1.100680 -0.726835 -0.369173 -0.523006 0.248771 +1403715302.16214 0.677678 -0.443082 1.096610 -0.728585 -0.369814 -0.521592 0.245648 +1403715302.21214 0.659067 -0.455530 1.093090 -0.730323 -0.369888 -0.520421 0.242843 +1403715302.26214 0.639803 -0.467136 1.089810 -0.732579 -0.369894 -0.518646 0.239818 +1403715302.31214 0.620225 -0.477539 1.087540 -0.734014 -0.370096 -0.517984 0.236527 +1403715302.36214 0.600039 -0.486710 1.086180 -0.735036 -0.369419 -0.518205 0.233911 +1403715302.41214 0.579207 -0.494671 1.085510 -0.735450 -0.368525 -0.519191 0.231826 +1403715302.46214 0.557742 -0.501491 1.085340 -0.736570 -0.365581 -0.519329 0.232621 +1403715302.51214 0.535393 -0.507207 1.085690 -0.739041 -0.360704 -0.517511 0.236418 +1403715302.56214 0.512752 -0.511963 1.086330 -0.742016 -0.356495 -0.514863 0.239249 +1403715302.61214 0.489766 -0.516082 1.086930 -0.744441 -0.352496 -0.512633 0.242407 +1403715302.66214 0.466656 -0.519889 1.087440 -0.746471 -0.350258 -0.510928 0.243008 +1403715302.71214 0.443881 -0.523019 1.087700 -0.748817 -0.347261 -0.508500 0.245174 +1403715302.76214 0.421530 -0.525706 1.087140 -0.750961 -0.345579 -0.506147 0.245860 +1403715302.81214 0.399860 -0.527858 1.085210 -0.753816 -0.344442 -0.502507 0.246187 +1403715302.86214 0.379358 -0.529256 1.082550 -0.756205 -0.344854 -0.499283 0.244839 +1403715302.91214 0.359781 -0.529525 1.079410 -0.758015 -0.345937 -0.495590 0.245218 +1403715302.96214 0.341115 -0.528870 1.076570 -0.758640 -0.348811 -0.492085 0.246269 +1403715303.01214 0.323655 -0.527246 1.073650 -0.758123 -0.353744 -0.488813 0.247340 +1403715303.06214 0.307445 -0.524497 1.070570 -0.756805 -0.359381 -0.485360 0.250032 +1403715303.11214 0.292546 -0.520565 1.067180 -0.754251 -0.366994 -0.481938 0.253291 +1403715303.16214 0.278828 -0.515106 1.063750 -0.750092 -0.375960 -0.479340 0.257388 +1403715303.21214 0.266194 -0.508117 1.060760 -0.744119 -0.385577 -0.477818 0.263265 +1403715303.26214 0.254575 -0.499702 1.058840 -0.735670 -0.395508 -0.478520 0.270891 +1403715303.31214 0.243813 -0.490065 1.057240 -0.725884 -0.406534 -0.479936 0.278359 +1403715303.36214 0.233658 -0.479479 1.055700 -0.715591 -0.418357 -0.481131 0.285344 +1403715303.41214 0.224055 -0.468272 1.054380 -0.705559 -0.430044 -0.481649 0.291999 +1403715303.46214 0.214417 -0.456308 1.052900 -0.696372 -0.441720 -0.480546 0.298371 +1403715303.51214 0.204270 -0.443858 1.051190 -0.688251 -0.452654 -0.477553 0.305544 +1403715303.56214 0.193840 -0.430944 1.049900 -0.679218 -0.463912 -0.475758 0.311614 +1403715303.61214 0.182683 -0.417659 1.048480 -0.672157 -0.472945 -0.470647 0.320966 +1403715303.66214 0.171069 -0.403883 1.047460 -0.664438 -0.480764 -0.466119 0.331845 +1403715303.71214 0.158953 -0.389992 1.046280 -0.657326 -0.488705 -0.460483 0.342120 +1403715303.76214 0.146416 -0.376324 1.045210 -0.650054 -0.495948 -0.454938 0.352843 +1403715303.81214 0.133588 -0.362937 1.044070 -0.642144 -0.503729 -0.450294 0.362138 +1403715303.86214 0.120644 -0.350010 1.043110 -0.634533 -0.509934 -0.445640 0.372478 +1403715303.91214 0.107712 -0.337853 1.042100 -0.627843 -0.515488 -0.441535 0.380961 +1403715303.96214 0.095207 -0.326230 1.041110 -0.622101 -0.520353 -0.438303 0.387445 +1403715304.01214 0.083127 -0.315555 1.039720 -0.617648 -0.524528 -0.435056 0.392567 +1403715304.06214 0.071497 -0.305730 1.038040 -0.614047 -0.527833 -0.432533 0.396551 +1403715304.11214 0.060406 -0.297047 1.036130 -0.611696 -0.529453 -0.430054 0.400701 +1403715304.16214 0.049981 -0.289470 1.034310 -0.609493 -0.530562 -0.428704 0.404023 +1403715304.21214 0.040229 -0.283243 1.031810 -0.608635 -0.531948 -0.426858 0.405447 +1403715304.26214 0.031040 -0.278053 1.028710 -0.608813 -0.533122 -0.424774 0.405826 +1403715304.31214 0.022367 -0.273666 1.025340 -0.609524 -0.534301 -0.422751 0.405321 +1403715304.36214 0.014293 -0.270004 1.021440 -0.610642 -0.534869 -0.421323 0.404374 +1403715304.41214 0.006853 -0.267298 1.016980 -0.612043 -0.535314 -0.420180 0.402854 +1403715304.46214 0.000156 -0.265225 1.012250 -0.613257 -0.535297 -0.420294 0.400907 +1403715304.51214 -0.005818 -0.263710 1.006590 -0.612834 -0.535490 -0.423288 0.398135 +1403715304.56214 -0.011402 -0.262563 0.997802 -0.613078 -0.535519 -0.425632 0.395211 +1403715304.61214 -0.016702 -0.261671 0.986407 -0.613285 -0.535196 -0.428048 0.392711 +1403715304.66214 -0.021957 -0.261378 0.973551 -0.613640 -0.533586 -0.430215 0.391978 +1403715304.71214 -0.027195 -0.261688 0.959924 -0.614255 -0.532460 -0.432050 0.390525 +1403715304.76214 -0.032318 -0.262385 0.946178 -0.615178 -0.532239 -0.433503 0.387753 +1403715304.81214 -0.037572 -0.263898 0.934076 -0.616108 -0.531614 -0.434396 0.386132 +1403715304.86214 -0.042923 -0.265803 0.924828 -0.617333 -0.531393 -0.434734 0.384093 +1403715304.91214 -0.048320 -0.267619 0.918863 -0.618141 -0.531365 -0.435382 0.382094 +1403715304.96214 -0.053841 -0.269620 0.916407 -0.619390 -0.531290 -0.434845 0.380784 +1403715305.01214 -0.059666 -0.271948 0.917062 -0.619858 -0.531165 -0.434937 0.380092 +1403715305.06214 -0.065860 -0.274561 0.919925 -0.621092 -0.530880 -0.433630 0.379969 +1403715305.11214 -0.072320 -0.277296 0.924919 -0.621703 -0.530657 -0.432972 0.380031 +1403715305.16214 -0.079028 -0.280073 0.930497 -0.622419 -0.531026 -0.431878 0.379589 +1403715305.21214 -0.085566 -0.282807 0.935416 -0.623633 -0.531393 -0.429684 0.379571 +1403715305.26214 -0.091872 -0.285243 0.939835 -0.624392 -0.531562 -0.428147 0.379824 +1403715305.31214 -0.097933 -0.287788 0.943778 -0.624192 -0.532551 -0.427573 0.379415 +1403715305.36214 -0.104043 -0.290215 0.947125 -0.624783 -0.533187 -0.425497 0.379881 +1403715305.41214 -0.110026 -0.292430 0.950714 -0.624079 -0.534667 -0.425036 0.379475 +1403715305.46214 -0.115970 -0.294415 0.955554 -0.622715 -0.535752 -0.424724 0.380532 +1403715305.51214 -0.121664 -0.296517 0.963157 -0.621382 -0.536310 -0.424045 0.382676 +1403715305.56214 -0.127164 -0.298495 0.974008 -0.619703 -0.537816 -0.423454 0.383939 +1403715305.61214 -0.132415 -0.300503 0.987898 -0.618441 -0.539756 -0.422030 0.384818 +1403715305.66214 -0.137642 -0.302194 1.005580 -0.616531 -0.541088 -0.421498 0.386592 +1403715305.71214 -0.142761 -0.303711 1.025480 -0.616455 -0.541301 -0.418760 0.389380 +1403715305.76214 -0.147399 -0.305320 1.047000 -0.615212 -0.542321 -0.417870 0.390879 +1403715305.81214 -0.151421 -0.306974 1.068350 -0.614653 -0.543169 -0.416488 0.392054 +1403715305.86214 -0.154728 -0.308514 1.089160 -0.613861 -0.544620 -0.415953 0.391851 +1403715305.91214 -0.157582 -0.310138 1.109220 -0.613702 -0.545919 -0.415050 0.391248 +1403715305.96214 -0.159887 -0.311197 1.128840 -0.613323 -0.546742 -0.414854 0.390903 +1403715306.01214 -0.161892 -0.312018 1.147350 -0.613297 -0.547347 -0.414418 0.390559 +1403715306.06214 -0.163424 -0.312830 1.164640 -0.613445 -0.548448 -0.414043 0.389175 +1403715306.11214 -0.164678 -0.313478 1.180770 -0.614435 -0.549201 -0.412560 0.388125 +1403715306.16214 -0.165742 -0.313741 1.196160 -0.616335 -0.547792 -0.409724 0.390104 +1403715306.21214 -0.166167 -0.313521 1.211250 -0.618207 -0.544042 -0.408182 0.393987 +1403715306.26214 -0.165534 -0.313200 1.225790 -0.620227 -0.538859 -0.407664 0.398447 +1403715306.31214 -0.163704 -0.313030 1.239560 -0.622836 -0.531805 -0.407855 0.403625 +1403715306.36214 -0.160519 -0.313019 1.253290 -0.625586 -0.524330 -0.409211 0.407757 +1403715306.41214 -0.155461 -0.313465 1.267160 -0.627843 -0.515790 -0.412667 0.411679 +1403715306.46214 -0.148322 -0.314552 1.280910 -0.630700 -0.507872 -0.416925 0.412865 +1403715306.51214 -0.139058 -0.316894 1.294070 -0.633664 -0.500625 -0.422545 0.411462 +1403715306.56214 -0.127666 -0.320568 1.307000 -0.636761 -0.493491 -0.429251 0.408346 +1403715306.61214 -0.114173 -0.325610 1.320200 -0.639817 -0.485208 -0.437151 0.405101 +1403715306.66214 -0.098882 -0.332303 1.333580 -0.642682 -0.477101 -0.446211 0.400288 +1403715306.71214 -0.082144 -0.341116 1.346730 -0.645338 -0.470089 -0.456202 0.392981 +1403715306.76214 -0.064308 -0.352351 1.359300 -0.648175 -0.463660 -0.466613 0.383616 +1403715306.81214 -0.045871 -0.365995 1.372220 -0.650128 -0.455418 -0.478301 0.375707 +1403715306.86214 -0.027248 -0.381906 1.384880 -0.651952 -0.447043 -0.490259 0.367093 +1403715306.91214 -0.008817 -0.400141 1.396390 -0.654204 -0.439881 -0.501888 0.355853 +1403715306.96214 0.008945 -0.420296 1.407370 -0.657299 -0.434348 -0.512210 0.341967 +1403715307.01214 0.025663 -0.442332 1.417050 -0.660528 -0.429703 -0.522227 0.326095 +1403715307.06214 0.040642 -0.466575 1.423770 -0.664971 -0.424708 -0.530124 0.310492 +1403715307.11214 0.053545 -0.492554 1.426440 -0.671610 -0.419518 -0.534423 0.295528 +1403715307.16214 0.064223 -0.519578 1.424940 -0.679765 -0.414496 -0.536238 0.280289 +1403715307.21214 0.072436 -0.547233 1.420520 -0.687702 -0.408871 -0.537666 0.266094 +1403715307.26214 0.078070 -0.575039 1.413270 -0.695357 -0.403401 -0.538673 0.252146 +1403715307.31214 0.081158 -0.602604 1.403430 -0.703156 -0.396341 -0.539026 0.240702 +1403715307.36214 0.081641 -0.629449 1.391620 -0.712195 -0.387652 -0.537196 0.232218 +1403715307.41214 0.079651 -0.655056 1.378950 -0.722941 -0.376226 -0.532734 0.228047 +1403715307.46214 0.075625 -0.679583 1.366270 -0.732856 -0.364142 -0.528716 0.225347 +1403715307.51214 0.070204 -0.703164 1.353760 -0.741688 -0.352533 -0.525381 0.222696 +1403715307.56214 0.063937 -0.725539 1.341450 -0.749641 -0.340764 -0.522827 0.220385 +1403715307.61214 0.057372 -0.746596 1.329280 -0.756495 -0.329483 -0.521366 0.217561 +1403715307.66214 0.050927 -0.766824 1.317320 -0.762642 -0.318474 -0.520836 0.213733 +1403715307.71214 0.044748 -0.786405 1.304760 -0.768471 -0.308317 -0.520851 0.207623 +1403715307.76214 0.038950 -0.805608 1.291880 -0.773302 -0.298580 -0.522263 0.200238 +1403715307.81214 0.033860 -0.823986 1.278630 -0.777858 -0.288868 -0.524075 0.191932 +1403715307.86214 0.029188 -0.841531 1.265250 -0.781927 -0.279089 -0.526296 0.183607 +1403715307.91214 0.024990 -0.858053 1.251830 -0.785872 -0.269759 -0.528307 0.174717 +1403715307.96214 0.021326 -0.873506 1.238480 -0.789153 -0.260443 -0.530954 0.165815 +1403715308.01214 0.018248 -0.887871 1.225120 -0.792069 -0.250668 -0.533887 0.157344 +1403715308.06214 0.015696 -0.900998 1.211980 -0.794977 -0.240764 -0.536438 0.149256 +1403715308.11214 0.013614 -0.912843 1.199100 -0.797669 -0.230918 -0.538877 0.141464 +1403715308.16214 0.012047 -0.923361 1.186530 -0.800193 -0.222022 -0.540721 0.134232 +1403715308.21214 0.010969 -0.932530 1.174180 -0.801925 -0.214034 -0.542901 0.127920 +1403715308.26214 0.010205 -0.940479 1.161610 -0.804075 -0.205895 -0.544212 0.122081 +1403715308.31214 0.009703 -0.947214 1.149090 -0.805856 -0.198381 -0.545753 0.115736 +1403715308.36214 0.009491 -0.952470 1.136850 -0.807237 -0.190683 -0.547436 0.111009 +1403715308.41214 0.009419 -0.956340 1.124460 -0.809061 -0.183432 -0.547878 0.107714 +1403715308.46214 0.009713 -0.958804 1.112130 -0.810357 -0.176824 -0.548445 0.106130 +1403715308.51214 0.010504 -0.959836 1.100610 -0.811300 -0.170641 -0.548952 0.106423 +1403715308.56214 0.011938 -0.959505 1.091180 -0.812373 -0.165377 -0.548706 0.107800 +1403715308.61214 0.014183 -0.958447 1.084410 -0.813358 -0.161241 -0.548167 0.109373 +1403715308.66214 0.017449 -0.957008 1.080460 -0.813821 -0.158470 -0.548072 0.110449 +1403715308.71214 0.021731 -0.955165 1.079000 -0.814797 -0.156109 -0.547043 0.111715 +1403715308.76214 0.027151 -0.953035 1.080450 -0.815158 -0.154885 -0.546698 0.112470 +1403715308.81214 0.033637 -0.950702 1.084160 -0.815911 -0.154591 -0.545609 0.112703 +1403715308.86214 0.041208 -0.948271 1.089250 -0.816837 -0.153886 -0.544146 0.114028 +1403715308.91214 0.049697 -0.945856 1.094340 -0.817594 -0.153361 -0.542726 0.116058 +1403715308.96214 0.059522 -0.943292 1.099540 -0.817334 -0.153115 -0.542680 0.118401 +1403715309.01214 0.070575 -0.940592 1.104680 -0.816327 -0.153172 -0.543481 0.121555 +1403715309.06214 0.082785 -0.937969 1.109690 -0.814686 -0.152769 -0.545065 0.125911 +1403715309.11214 0.095740 -0.935778 1.114160 -0.813452 -0.152440 -0.545886 0.130640 +1403715309.16214 0.109485 -0.934098 1.118320 -0.811660 -0.152986 -0.547377 0.134841 +1403715309.21214 0.123860 -0.932946 1.122700 -0.808694 -0.152515 -0.550397 0.140767 +1403715309.26214 0.138925 -0.932616 1.127550 -0.803893 -0.151847 -0.555952 0.147020 +1403715309.31214 0.154232 -0.933632 1.132080 -0.799221 -0.152587 -0.561197 0.151725 +1403715309.36214 0.169613 -0.936093 1.135650 -0.796761 -0.156155 -0.563580 0.152198 +1403715309.41214 0.184906 -0.939914 1.138620 -0.795522 -0.161601 -0.564363 0.150082 +1403715309.46214 0.199977 -0.944947 1.141590 -0.795035 -0.167359 -0.564225 0.146834 +1403715309.51214 0.214815 -0.951010 1.144910 -0.794365 -0.172740 -0.564266 0.144047 +1403715309.56214 0.229418 -0.957468 1.148200 -0.794131 -0.177437 -0.563671 0.141937 +1403715309.61214 0.243653 -0.964069 1.152080 -0.793682 -0.181022 -0.563469 0.140725 +1403715309.66214 0.257308 -0.971121 1.155620 -0.793316 -0.184057 -0.563081 0.140402 +1403715309.71214 0.270401 -0.978273 1.158750 -0.793533 -0.185867 -0.561915 0.141456 +1403715309.76214 0.282613 -0.985675 1.162160 -0.793973 -0.187089 -0.560483 0.143051 +1403715309.81214 0.294108 -0.993363 1.165790 -0.794707 -0.187446 -0.558488 0.146274 +1403715309.86214 0.305263 -1.001370 1.169020 -0.796073 -0.185878 -0.555811 0.150970 +1403715309.91214 0.316411 -1.009490 1.171870 -0.797756 -0.183892 -0.552510 0.156532 +1403715309.96214 0.327512 -1.018700 1.174080 -0.797925 -0.181832 -0.551504 0.161541 +1403715310.01214 0.338970 -1.028690 1.175710 -0.796577 -0.180038 -0.552720 0.165990 +1403715310.06214 0.351221 -1.039360 1.177190 -0.793744 -0.177665 -0.556584 0.169173 +1403715310.11214 0.363910 -1.051670 1.178360 -0.790752 -0.174952 -0.561380 0.170163 +1403715310.16214 0.376466 -1.065720 1.179410 -0.787770 -0.172059 -0.566818 0.168913 +1403715310.21214 0.388987 -1.081600 1.180740 -0.785690 -0.169696 -0.571663 0.164609 +1403715310.26214 0.401075 -1.099370 1.182330 -0.784153 -0.168191 -0.576343 0.156983 +1403715310.31214 0.412115 -1.118830 1.184200 -0.783070 -0.166990 -0.580730 0.147201 +1403715310.36214 0.421653 -1.139410 1.186520 -0.783023 -0.163980 -0.583849 0.138227 +1403715310.41214 0.429460 -1.160840 1.188970 -0.784093 -0.159674 -0.585627 0.129399 +1403715310.46214 0.435724 -1.182790 1.191410 -0.786086 -0.154040 -0.586200 0.121285 +1403715310.51214 0.440547 -1.204980 1.193530 -0.789510 -0.148925 -0.584438 0.113701 +1403715310.56214 0.444125 -1.227030 1.195640 -0.793629 -0.144184 -0.581302 0.107010 +1403715310.61214 0.446414 -1.249040 1.198180 -0.798145 -0.140213 -0.577173 0.100879 +1403715310.66214 0.447960 -1.270600 1.200870 -0.802590 -0.136735 -0.572723 0.095612 +1403715310.71214 0.448768 -1.291670 1.203280 -0.806285 -0.133516 -0.568961 0.091436 +1403715310.76214 0.449183 -1.312060 1.205760 -0.809180 -0.130712 -0.565998 0.088246 +1403715310.81214 0.449698 -1.331630 1.208160 -0.811158 -0.128036 -0.564053 0.086456 +1403715310.86214 0.450062 -1.350570 1.210440 -0.812192 -0.125452 -0.563339 0.085180 +1403715310.91214 0.450724 -1.368770 1.212780 -0.812748 -0.123208 -0.563165 0.084298 +1403715310.96214 0.451513 -1.386430 1.215410 -0.813878 -0.120482 -0.562146 0.084134 +1403715311.01214 0.452188 -1.403730 1.217290 -0.815519 -0.117184 -0.560310 0.085143 +1403715311.06214 0.453260 -1.420500 1.218500 -0.817385 -0.112949 -0.558098 0.087474 +1403715311.11214 0.454978 -1.436970 1.219490 -0.818911 -0.109888 -0.556252 0.088847 +1403715311.16214 0.457535 -1.453270 1.220190 -0.820029 -0.106842 -0.554911 0.090614 +1403715311.21214 0.460804 -1.469650 1.220830 -0.820706 -0.103299 -0.554148 0.093224 +1403715311.26214 0.464852 -1.486180 1.220960 -0.821395 -0.101202 -0.553348 0.094200 +1403715311.31214 0.469829 -1.503010 1.221250 -0.822135 -0.098820 -0.552360 0.096053 +1403715311.36214 0.475862 -1.520320 1.221720 -0.823152 -0.097199 -0.550980 0.096924 +1403715311.41214 0.483369 -1.538040 1.223180 -0.823779 -0.097335 -0.550310 0.095254 +1403715311.46214 0.492064 -1.556290 1.225170 -0.824119 -0.099101 -0.550105 0.091602 +1403715311.51214 0.501850 -1.575240 1.227290 -0.824204 -0.101459 -0.550360 0.086588 +1403715311.56214 0.512536 -1.594220 1.229650 -0.823824 -0.103183 -0.551194 0.082786 +1403715311.61214 0.524276 -1.613080 1.232460 -0.823155 -0.104227 -0.552393 0.080094 +1403715311.66214 0.536820 -1.631620 1.235250 -0.822734 -0.104905 -0.553245 0.077615 +1403715311.71214 0.550045 -1.649830 1.237750 -0.822385 -0.103756 -0.553950 0.077831 +1403715311.76214 0.563974 -1.667690 1.240210 -0.822097 -0.102436 -0.554533 0.078463 +1403715311.81214 0.578922 -1.685440 1.242610 -0.821925 -0.100433 -0.555038 0.079279 +1403715311.86214 0.594717 -1.703260 1.245040 -0.821741 -0.097151 -0.555606 0.081270 +1403715311.91214 0.611257 -1.720790 1.247890 -0.821106 -0.095178 -0.556873 0.081352 +1403715311.96214 0.628475 -1.738370 1.250650 -0.821101 -0.094323 -0.557314 0.079353 +1403715312.01214 0.646807 -1.755790 1.253290 -0.821183 -0.094624 -0.557648 0.075724 +1403715312.06214 0.665907 -1.773070 1.255820 -0.821322 -0.095330 -0.557862 0.071636 +1403715312.11214 0.685602 -1.790170 1.258420 -0.820742 -0.095131 -0.559092 0.068913 +1403715312.16214 0.705431 -1.806860 1.261170 -0.820256 -0.095212 -0.560155 0.065892 +1403715312.21214 0.725672 -1.822880 1.264050 -0.820181 -0.094808 -0.560584 0.063719 +1403715312.26214 0.746207 -1.838390 1.267020 -0.820336 -0.093630 -0.560688 0.062534 +1403715312.31214 0.766876 -1.853360 1.269970 -0.820414 -0.091263 -0.560869 0.063386 +1403715312.36214 0.787745 -1.867870 1.272390 -0.820895 -0.088780 -0.560431 0.064549 +1403715312.41214 0.809019 -1.882160 1.274710 -0.820908 -0.086440 -0.560637 0.065759 +1403715312.46214 0.830784 -1.896240 1.276770 -0.820635 -0.084024 -0.561234 0.067191 +1403715312.51214 0.852693 -1.910150 1.278430 -0.819507 -0.082406 -0.562972 0.068409 +1403715312.56214 0.874982 -1.924100 1.279280 -0.818601 -0.082493 -0.564376 0.067580 +1403715312.61214 0.897310 -1.938180 1.279620 -0.816592 -0.083532 -0.567309 0.066027 +1403715312.66214 0.919646 -1.952260 1.279400 -0.813840 -0.085399 -0.571204 0.064015 +1403715312.71214 0.941640 -1.966130 1.278410 -0.811027 -0.086961 -0.575077 0.062921 +1403715312.76214 0.963071 -1.979800 1.276450 -0.808699 -0.089455 -0.578143 0.061279 +1403715312.81214 0.983975 -1.992980 1.273970 -0.806545 -0.092992 -0.580817 0.059068 +1403715312.86214 1.003880 -2.005340 1.272000 -0.803208 -0.096403 -0.584957 0.058217 +1403715312.91214 1.022520 -2.017030 1.271250 -0.800016 -0.099446 -0.588778 0.058532 +1403715312.96214 1.039630 -2.027890 1.273060 -0.797160 -0.102715 -0.592038 0.058961 +1403715313.01214 1.054530 -2.038180 1.277500 -0.795047 -0.105651 -0.594281 0.059736 +1403715313.06214 1.067750 -2.047510 1.284280 -0.793998 -0.108884 -0.595069 0.060035 +1403715313.11214 1.078800 -2.056020 1.293290 -0.794120 -0.112089 -0.594300 0.060151 +1403715313.16214 1.088320 -2.063560 1.304260 -0.794023 -0.114449 -0.593870 0.061220 +1403715313.21214 1.096350 -2.070010 1.315550 -0.794765 -0.115270 -0.592411 0.064117 +1403715313.26214 1.102470 -2.075690 1.326310 -0.796437 -0.115467 -0.589721 0.067705 +1403715313.31214 1.106570 -2.080910 1.335920 -0.798493 -0.115504 -0.586515 0.071188 +1403715313.36214 1.109680 -2.085520 1.345020 -0.800795 -0.115644 -0.583036 0.073642 +1403715313.41214 1.111810 -2.089750 1.353870 -0.803161 -0.116179 -0.579496 0.074952 +1403715313.46214 1.113180 -2.094070 1.362150 -0.805209 -0.115149 -0.576759 0.075687 +1403715313.51214 1.113620 -2.098630 1.370730 -0.806324 -0.113674 -0.575718 0.073957 +1403715313.56214 1.113500 -2.103140 1.379390 -0.807622 -0.111365 -0.574679 0.071330 +1403715313.61214 1.113020 -2.107150 1.388290 -0.808880 -0.109655 -0.573755 0.067032 +1403715313.66214 1.112100 -2.110650 1.397220 -0.809439 -0.108129 -0.573737 0.062792 +1403715313.71214 1.110510 -2.113560 1.406650 -0.809749 -0.106540 -0.573939 0.059580 +1403715313.76214 1.108530 -2.115780 1.416450 -0.810500 -0.104074 -0.573470 0.058225 +1403715313.81214 1.106120 -2.116890 1.426720 -0.810767 -0.101747 -0.573614 0.057191 +1403715313.86214 1.103390 -2.117210 1.436910 -0.811132 -0.099642 -0.573580 0.056050 +1403715313.91214 1.100510 -2.116620 1.447120 -0.811332 -0.096845 -0.573691 0.056918 +1403715313.96214 1.097140 -2.115330 1.456820 -0.811459 -0.093555 -0.573816 0.059303 +1403715314.01214 1.093510 -2.113780 1.464980 -0.812454 -0.090314 -0.572836 0.060183 +1403715314.06214 1.089530 -2.112490 1.472240 -0.813565 -0.087334 -0.571974 0.057715 +1403715314.11214 1.085260 -2.111450 1.478670 -0.814578 -0.083824 -0.571643 0.051574 +1403715314.16214 1.080800 -2.110480 1.484320 -0.815542 -0.078037 -0.571706 0.044208 +1403715314.21214 1.076120 -2.109400 1.489030 -0.817111 -0.071502 -0.570949 0.035141 +1403715314.26214 1.071420 -2.107780 1.493840 -0.817925 -0.063850 -0.571177 0.026059 +1403715314.31214 1.066470 -2.105440 1.497670 -0.819699 -0.055070 -0.569870 0.017596 +1403715314.36214 1.061570 -2.102040 1.501020 -0.820838 -0.046122 -0.569219 0.009404 +1403715314.41214 1.056590 -2.097300 1.503360 -0.821648 -0.036694 -0.568800 0.003771 +1403715314.46214 1.051770 -2.091210 1.505080 0.822956 0.028925 0.567366 0.001821 +1403715314.51214 1.047720 -2.083730 1.507140 0.823601 0.021496 0.566734 0.005703 +1403715314.56214 1.044420 -2.075160 1.508940 0.824647 0.013931 0.565428 0.007352 +1403715314.61214 1.041420 -2.065690 1.510320 0.824934 0.007187 0.565125 0.008151 +1403715314.66214 1.038590 -2.055480 1.511370 0.824669 0.002016 0.565534 0.009395 +1403715314.71214 1.036090 -2.044420 1.511840 0.824586 -0.001987 0.565632 0.010703 +1403715314.76214 1.033900 -2.032720 1.512180 0.824180 -0.004700 0.566168 0.012579 +1403715314.81214 1.032210 -2.020400 1.512840 0.822919 -0.006735 0.567948 0.013930 +1403715314.86214 1.030840 -2.007590 1.513520 0.822385 -0.007556 0.568650 0.016206 +1403715314.91214 1.029620 -1.994110 1.514010 0.821802 -0.008614 0.569447 0.017210 +1403715314.96214 1.028420 -1.979920 1.514550 0.821159 -0.009766 0.570363 0.016985 +1403715315.01214 1.027730 -1.964800 1.514810 0.820555 -0.010753 0.571246 0.015894 +1403715315.06214 1.027480 -1.948940 1.514840 0.819050 -0.012372 0.573421 0.013854 +1403715315.11214 1.027610 -1.932690 1.514080 0.818535 -0.012789 0.574167 0.012971 +1403715315.16214 1.027780 -1.916160 1.513150 0.818878 -0.013266 0.573691 0.011916 +1403715315.21214 1.027870 -1.899410 1.512270 0.819306 -0.013312 0.573096 0.011016 +1403715315.26214 1.027790 -1.882590 1.511750 0.819427 -0.013522 0.572919 0.010954 +1403715315.31214 1.027250 -1.866060 1.511050 0.819646 -0.015014 0.572547 0.012048 +1403715315.36214 1.026650 -1.849690 1.510990 0.819366 -0.017799 0.572812 0.014443 +1403715315.41214 1.025780 -1.833250 1.510960 0.819295 -0.022201 0.572700 0.016641 +1403715315.46214 1.024800 -1.816730 1.510790 0.819160 -0.027917 0.572562 0.019260 +1403715315.51214 1.023500 -1.800330 1.511010 0.818711 -0.034271 0.572753 0.022163 +1403715315.56214 1.022190 -1.784010 1.511520 0.818082 -0.040786 0.573109 0.024989 +1403715315.61214 1.019940 -1.767870 1.512110 0.817512 -0.047679 0.573241 0.028217 +1403715315.66214 1.017510 -1.752040 1.513180 0.816584 -0.054999 0.573710 0.031978 +1403715315.71214 1.014870 -1.736410 1.514000 0.815137 -0.065022 0.574657 0.033064 +1403715315.76214 1.011780 -1.721170 1.514840 0.813764 -0.076133 0.575210 0.033534 +1403715315.81214 1.008170 -1.706750 1.515320 0.812702 -0.087478 0.575033 0.034655 +1403715315.86214 1.004350 -1.693540 1.515780 0.811844 -0.097938 0.574338 0.038115 +1403715315.91214 1.000040 -1.681460 1.516100 0.811291 -0.107302 0.573048 0.043683 +1403715315.96214 0.995127 -1.670240 1.516350 0.810195 -0.115909 0.572325 0.050923 +1403715316.01214 0.989496 -1.660050 1.515480 0.809649 -0.124555 0.570553 0.058510 +1403715316.06214 0.983399 -1.650800 1.513940 0.808691 -0.132091 0.569187 0.067805 +1403715316.11214 0.977239 -1.642430 1.511460 0.808064 -0.139178 0.567077 0.078016 +1403715316.16214 0.970937 -1.635000 1.507670 0.807592 -0.146298 0.564379 0.088703 +1403715316.21214 0.964454 -1.628230 1.503020 0.807477 -0.153578 0.560805 0.099457 +1403715316.26214 0.957811 -1.622000 1.497720 0.808658 -0.160778 0.554849 0.111196 +1403715316.31214 0.951520 -1.616030 1.492120 0.810065 -0.169092 0.548026 0.121941 +1403715316.36214 0.945832 -1.609860 1.485160 0.812326 -0.176343 0.539927 0.132321 +1403715316.41214 0.941207 -1.603150 1.477920 0.814170 -0.182961 0.532630 0.141269 +1403715316.46214 0.938277 -1.595740 1.470680 0.814646 -0.189095 0.527719 0.148683 +1403715316.51214 0.937502 -1.587620 1.463070 0.813937 -0.195327 0.525242 0.153215 +1403715316.56214 0.938676 -1.579060 1.455370 0.811955 -0.200920 0.525072 0.157034 +1403715316.61214 0.941811 -1.570060 1.447320 0.809192 -0.206297 0.526604 0.159178 +1403715316.66214 0.946732 -1.560740 1.439110 0.805688 -0.210536 0.529653 0.161272 +1403715316.71214 0.953131 -1.551110 1.430190 0.802117 -0.215380 0.532624 0.162883 +1403715316.76214 0.960510 -1.541340 1.420630 0.798561 -0.220410 0.535117 0.165440 +1403715316.81214 0.968811 -1.531480 1.410410 0.795333 -0.225666 0.536725 0.168661 +1403715316.86214 0.977909 -1.521550 1.399750 0.791898 -0.231771 0.537881 0.172811 +1403715316.91214 0.987926 -1.511550 1.388760 0.788124 -0.239062 0.538827 0.177131 +1403715316.96214 0.998439 -1.501410 1.378160 0.783681 -0.246279 0.539849 0.183721 +1403715317.01214 1.008830 -1.490960 1.367740 0.778145 -0.255031 0.541639 0.189940 +1403715317.06214 1.019310 -1.479850 1.356780 0.773708 -0.265291 0.541172 0.195268 +1403715317.11214 1.029610 -1.468400 1.345890 0.770218 -0.276129 0.538528 0.201259 +1403715317.16214 1.039860 -1.456760 1.335400 0.767099 -0.287554 0.534615 0.207505 +1403715317.21214 1.050050 -1.444930 1.325290 0.763879 -0.299175 0.530172 0.214244 +1403715317.26214 1.060470 -1.433080 1.315890 0.760377 -0.309894 0.525665 0.222418 +1403715317.31214 1.071080 -1.421170 1.306830 0.756256 -0.321121 0.521415 0.230403 +1403715317.36214 1.081760 -1.408870 1.298210 0.751479 -0.333356 0.517531 0.237309 +1403715317.41214 1.092520 -1.396230 1.290050 0.745669 -0.346249 0.514665 0.243329 +1403715317.46214 1.103430 -1.383610 1.282250 0.740226 -0.358660 0.511113 0.249384 +1403715317.51214 1.114380 -1.371010 1.274920 0.734578 -0.370424 0.507706 0.255764 +1403715317.56214 1.125330 -1.358680 1.267940 0.728588 -0.381257 0.504593 0.263039 +1403715317.61214 1.136430 -1.346550 1.261160 0.722466 -0.391987 0.501612 0.269768 +1403715317.66214 1.147530 -1.334580 1.254630 0.715843 -0.403043 0.499229 0.275492 +1403715317.71214 1.158390 -1.322830 1.248350 0.709434 -0.413661 0.496362 0.281447 +1403715317.76214 1.168930 -1.311250 1.242190 0.702669 -0.424891 0.493910 0.285966 +1403715317.81214 1.179090 -1.299880 1.236100 0.694790 -0.437585 0.492962 0.287705 +1403715317.86214 1.188540 -1.289020 1.230060 0.687153 -0.450471 0.491174 0.289214 +1403715317.91214 1.197090 -1.278680 1.224430 0.680312 -0.461144 0.488673 0.292781 +1403715317.96214 1.204370 -1.268940 1.218970 0.674176 -0.470676 0.485256 0.297453 +1403715318.01214 1.210440 -1.259660 1.213400 0.668382 -0.479514 0.481591 0.302330 +1403715318.06214 1.215540 -1.250910 1.207900 0.662509 -0.487048 0.479569 0.306398 +1403715318.11214 1.219510 -1.243000 1.202430 0.657471 -0.493842 0.477843 0.309058 +1403715318.16214 1.222160 -1.235940 1.197220 0.653470 -0.498906 0.475935 0.312339 +1403715318.21214 1.223540 -1.229800 1.191780 0.650998 -0.502746 0.473150 0.315559 +1403715318.26214 1.223650 -1.224270 1.186270 0.648586 -0.505997 0.471319 0.318059 +1403715318.31214 1.222120 -1.219600 1.180530 0.646965 -0.508761 0.468560 0.321014 +1403715318.36214 1.219070 -1.215750 1.175030 0.645113 -0.511376 0.465891 0.324453 +1403715318.41214 1.214620 -1.212400 1.169610 0.644106 -0.513493 0.461826 0.328891 +1403715318.46214 1.208680 -1.209510 1.164040 0.643773 -0.515048 0.455936 0.335268 +1403715318.51214 1.201870 -1.207050 1.158260 0.643815 -0.516588 0.449100 0.341977 +1403715318.56214 1.194540 -1.205080 1.152190 0.643559 -0.519697 0.441777 0.347247 +1403715318.61214 1.187030 -1.203790 1.145730 0.643633 -0.524459 0.433233 0.350698 +1403715318.66214 1.179560 -1.203280 1.138980 0.643319 -0.530650 0.424362 0.352801 +1403715318.71214 1.172370 -1.203730 1.131750 0.642935 -0.538108 0.415060 0.353271 +1403715318.76214 1.165630 -1.205750 1.124750 0.640091 -0.546022 0.408566 0.353860 +1403715318.81214 1.159090 -1.209850 1.117930 0.637301 -0.552969 0.401236 0.356487 +1403715318.86214 1.153110 -1.216210 1.111720 0.632581 -0.559150 0.396730 0.360275 +1403715318.91214 1.147690 -1.224770 1.105850 0.627671 -0.563944 0.393300 0.365119 +1403715318.96214 1.142930 -1.235820 1.100440 0.622687 -0.567743 0.390819 0.370391 +1403715319.01214 1.138560 -1.248810 1.095230 0.616748 -0.571793 0.389021 0.375949 +1403715319.06214 1.134540 -1.263610 1.090330 0.610668 -0.575377 0.386790 0.382649 +1403715319.11214 1.131010 -1.279580 1.085820 0.604456 -0.578079 0.384569 0.390595 +1403715319.16214 1.128010 -1.296860 1.081800 0.598172 -0.580729 0.381935 0.398835 +1403715319.21214 1.125740 -1.315430 1.078170 0.591404 -0.584326 0.379161 0.406252 +1403715319.26214 1.124280 -1.335070 1.074680 0.584930 -0.588837 0.375322 0.412626 +1403715319.31214 1.123710 -1.355700 1.071640 0.578642 -0.593161 0.370995 0.419161 +1403715319.36214 1.124030 -1.377030 1.068680 0.572150 -0.597862 0.366273 0.425499 +1403715319.41214 1.125710 -1.399190 1.065810 0.565120 -0.602692 0.362527 0.431250 +1403715319.46214 1.128510 -1.421780 1.062770 0.557187 -0.608357 0.360259 0.435497 +1403715319.51214 1.131970 -1.444540 1.059550 0.548868 -0.614460 0.357812 0.439491 +1403715319.56214 1.136360 -1.467880 1.056400 0.541389 -0.620210 0.354217 0.443584 +1403715319.61214 1.141930 -1.491590 1.054440 0.533946 -0.625681 0.351755 0.446870 +1403715319.66214 1.148890 -1.515590 1.054590 0.528907 -0.629649 0.348178 0.450079 +1403715319.71214 1.157030 -1.539790 1.057460 0.524416 -0.633156 0.346471 0.451730 +1403715319.76214 1.166240 -1.564560 1.063240 0.522141 -0.635619 0.344151 0.452679 +1403715319.81214 1.176360 -1.589950 1.072260 0.520100 -0.637430 0.343565 0.452926 +1403715319.86214 1.187060 -1.615830 1.084140 0.518433 -0.638888 0.342774 0.453383 +1403715319.91214 1.198340 -1.642290 1.098430 0.516533 -0.641006 0.341930 0.453198 +1403715319.96214 1.210160 -1.668830 1.113910 0.514869 -0.642297 0.340775 0.454133 +1403715320.01214 1.222500 -1.695980 1.129110 0.512278 -0.644004 0.339358 0.455703 +1403715320.06214 1.235350 -1.723700 1.143710 0.509057 -0.646342 0.337232 0.457579 +1403715320.11214 1.248630 -1.751740 1.157650 0.505071 -0.648279 0.334228 0.461443 +1403715320.16214 1.262510 -1.779820 1.170630 0.499987 -0.651481 0.330293 0.465288 +1403715320.21214 1.277000 -1.807940 1.183380 0.492731 -0.654995 0.326759 0.470560 +1403715320.26214 1.292290 -1.835980 1.195920 0.483454 -0.658208 0.323543 0.477864 +1403715320.31214 1.308440 -1.863710 1.207860 0.471304 -0.662436 0.322078 0.485094 +1403715320.36214 1.325430 -1.890880 1.218950 0.457390 -0.668699 0.320502 0.490829 +1403715320.41214 1.342990 -1.917310 1.229710 0.443165 -0.676649 0.317446 0.494954 +1403715320.46214 1.361120 -1.942650 1.240660 0.428740 -0.684998 0.312949 0.499022 +1403715320.51214 1.379710 -1.966220 1.251140 0.414583 -0.694169 0.307388 0.501760 +1403715320.56214 1.398590 -1.988890 1.261250 0.400100 -0.703079 0.301983 0.504386 +1403715320.61214 1.417720 -2.010450 1.271840 0.385386 -0.711830 0.297160 0.506430 +1403715320.66214 1.436760 -2.030560 1.282310 0.370025 -0.720174 0.293094 0.508455 +1403715320.71214 1.455560 -2.049050 1.292090 0.355306 -0.727824 0.289852 0.509917 +1403715320.76214 1.474180 -2.066170 1.301220 0.340818 -0.734559 0.288905 0.510686 +1403715320.81214 1.492480 -2.081530 1.309830 0.327992 -0.740090 0.288732 0.511196 +1403715320.86214 1.510040 -2.094860 1.317350 0.317563 -0.745825 0.288026 0.509842 +1403715320.91214 1.526330 -2.105980 1.324280 0.309835 -0.751279 0.286073 0.507685 +1403715320.96214 1.540830 -2.114990 1.331060 0.304625 -0.755439 0.282677 0.506566 +1403715321.01214 1.553550 -2.121890 1.337510 0.301751 -0.758691 0.277848 0.506097 +1403715321.06214 1.564330 -2.126880 1.343680 0.300183 -0.760798 0.272897 0.506560 +1403715321.11214 1.573300 -2.130380 1.349680 0.299338 -0.762215 0.268353 0.507358 +1403715321.16214 1.580370 -2.132480 1.355160 0.298937 -0.763222 0.264449 0.508129 +1403715321.21214 1.585700 -2.133210 1.360020 0.299360 -0.764213 0.260586 0.508386 +1403715321.26214 1.589760 -2.132540 1.364610 0.299557 -0.764958 0.258029 0.508455 +1403715321.31214 1.592270 -2.130610 1.368900 0.299387 -0.765702 0.257267 0.507821 +1403715321.36214 1.593210 -2.127390 1.372980 0.299177 -0.766238 0.257186 0.507176 +1403715321.41214 1.592600 -2.122790 1.377050 0.298562 -0.766091 0.258176 0.507257 +1403715321.46214 1.590340 -2.116990 1.381070 0.298443 -0.765324 0.259146 0.507990 +1403715321.51214 1.586540 -2.110060 1.384880 0.299826 -0.764741 0.259189 0.508032 +1403715321.56214 1.581260 -2.102120 1.388510 0.301648 -0.764505 0.259485 0.507157 +1403715321.61214 1.574430 -2.093020 1.392220 0.305017 -0.763450 0.258380 0.507295 +1403715321.66214 1.565950 -2.082900 1.396340 0.306949 -0.762029 0.257256 0.508836 +1403715321.71214 1.555840 -2.071930 1.401080 0.306038 -0.759660 0.257882 0.512596 +1403715321.76214 1.544490 -2.059760 1.405900 0.304170 -0.758282 0.257927 0.515715 +1403715321.81214 1.532170 -2.046150 1.410690 0.299200 -0.757382 0.260551 0.518618 +1403715321.86214 1.518870 -2.031100 1.416030 0.292867 -0.755670 0.264679 0.522625 +1403715321.91214 1.504410 -2.014120 1.421160 0.287603 -0.754328 0.266618 0.526487 +1403715321.96214 1.488940 -1.994460 1.425590 0.283114 -0.755103 0.265738 0.528250 +1403715322.01214 1.472710 -1.972240 1.429510 0.279825 -0.758036 0.261845 0.527746 +1403715322.06214 1.455540 -1.948000 1.433510 0.276475 -0.762448 0.258337 0.524878 +1403715322.11214 1.437200 -1.921720 1.438190 0.275266 -0.766186 0.252253 0.523026 +1403715322.16214 1.417800 -1.893760 1.443050 0.277672 -0.768341 0.242583 0.523168 +1403715322.21214 1.397060 -1.864650 1.448220 0.280589 -0.769292 0.232313 0.524872 +1403715322.26214 1.375300 -1.834460 1.453160 0.281599 -0.770631 0.222325 0.526690 +1403715322.31214 1.353020 -1.803720 1.457720 0.281358 -0.772983 0.212741 0.527330 +1403715322.36214 1.330010 -1.772830 1.461080 0.279356 -0.775737 0.203494 0.527998 +1403715322.41214 1.306270 -1.742030 1.461490 0.275782 -0.778804 0.194009 0.528932 +1403715322.46214 1.282380 -1.711510 1.458730 0.271063 -0.782377 0.185488 0.529155 +1403715322.51214 1.258540 -1.681740 1.452840 0.266043 -0.785675 0.178265 0.529299 +1403715322.56214 1.234680 -1.653060 1.443890 0.261265 -0.789029 0.173066 0.528415 +1403715322.61214 1.210720 -1.625600 1.433340 0.257793 -0.791429 0.168017 0.528160 +1403715322.66214 1.186310 -1.599860 1.422050 0.254783 -0.793618 0.164400 0.527474 +1403715322.71214 1.161330 -1.575800 1.410650 0.252211 -0.794809 0.161906 0.527689 +1403715322.76214 1.135410 -1.553530 1.399370 0.250012 -0.794992 0.160371 0.528927 +1403715322.81214 1.108640 -1.532760 1.388760 0.248777 -0.795410 0.158641 0.529401 +1403715322.86214 1.081130 -1.513840 1.380320 0.248470 -0.795764 0.156889 0.529536 +1403715322.91214 1.053170 -1.496510 1.375110 0.248644 -0.794991 0.155093 0.531141 +1403715322.96214 1.024850 -1.480910 1.372760 0.248589 -0.794281 0.153917 0.532570 +1403715323.01214 0.996305 -1.467180 1.373320 0.249013 -0.793689 0.153030 0.533508 +1403715323.06214 0.967458 -1.455270 1.376480 0.249433 -0.793391 0.152808 0.533820 +1403715323.11214 0.937972 -1.445220 1.381160 0.249988 -0.793020 0.152194 0.534286 +1403715323.16214 0.908015 -1.437130 1.384320 0.250991 -0.792745 0.151478 0.534428 +1403715323.21214 0.877794 -1.430710 1.384970 0.252534 -0.791885 0.150351 0.535293 +1403715323.26214 0.847387 -1.425750 1.382480 0.253414 -0.790838 0.149735 0.536596 +1403715323.31214 0.816855 -1.422520 1.376980 0.254216 -0.790376 0.149419 0.536986 +1403715323.36214 0.786219 -1.421080 1.370230 0.253844 -0.790078 0.150416 0.537322 +1403715323.41214 0.755422 -1.421920 1.365320 0.253880 -0.789842 0.150463 0.537638 +1403715323.46214 0.724434 -1.424990 1.362240 0.253842 -0.790316 0.150541 0.536938 +1403715323.51214 0.693160 -1.430530 1.361870 0.253781 -0.790379 0.150543 0.536873 +1403715323.56214 0.661981 -1.437960 1.364190 0.253549 -0.790808 0.150412 0.536387 +1403715323.61214 0.630748 -1.447350 1.371000 0.251741 -0.787417 0.152859 0.541512 +1403715323.66214 0.599221 -1.458530 1.379950 0.248842 -0.781967 0.156658 0.549603 +1403715323.71214 0.568290 -1.470720 1.389390 0.246122 -0.775881 0.159540 0.558552 +1403715323.76214 0.538529 -1.483610 1.398640 0.243491 -0.768972 0.162628 0.568284 +1403715323.81214 0.510665 -1.496910 1.407090 0.241064 -0.762975 0.165788 0.576430 +1403715323.86214 0.484837 -1.510300 1.415150 0.238788 -0.757699 0.168427 0.583528 +1403715323.91214 0.461290 -1.523670 1.423360 0.237005 -0.752135 0.170766 0.590728 +1403715323.96214 0.440889 -1.536980 1.432150 0.234722 -0.745102 0.174598 0.599370 +1403715324.01214 0.423815 -1.549520 1.440840 0.232518 -0.739831 0.178365 0.605616 +1403715324.06214 0.410344 -1.561060 1.448450 0.231320 -0.737775 0.181087 0.607772 +1403715324.11214 0.400550 -1.571270 1.454660 0.230732 -0.739688 0.183217 0.605026 +1403715324.16214 0.394286 -1.580290 1.460440 0.230649 -0.743482 0.184659 0.599948 +1403715324.21214 0.391006 -1.588560 1.465960 0.230117 -0.747319 0.186560 0.594774 +1403715324.26214 0.390557 -1.596020 1.471840 0.229154 -0.750839 0.189304 0.589825 +1403715324.31214 0.392476 -1.602460 1.477500 0.227476 -0.754281 0.193407 0.584729 +1403715324.36214 0.396483 -1.607630 1.483820 0.224346 -0.758945 0.198963 0.578000 +1403715324.41214 0.402299 -1.611160 1.489580 0.222791 -0.765725 0.202806 0.568243 +1403715324.46214 0.409419 -1.612830 1.495380 0.222359 -0.773353 0.204435 0.557393 +1403715324.51214 0.416620 -1.613180 1.501220 0.222334 -0.779714 0.204898 0.548298 +1403715324.56214 0.423126 -1.612500 1.507720 0.222958 -0.784843 0.203944 0.541034 +1403715324.61214 0.428518 -1.611040 1.515170 0.223533 -0.787891 0.202569 0.536867 +1403715324.66214 0.432698 -1.608670 1.522740 0.224647 -0.789230 0.200508 0.535206 +1403715324.71214 0.435800 -1.605220 1.530600 0.225604 -0.789461 0.198532 0.535200 +1403715324.76214 0.437843 -1.600910 1.538110 0.227383 -0.788864 0.195588 0.536410 +1403715324.81214 0.439135 -1.596130 1.545430 0.231002 -0.787175 0.190361 0.539219 +1403715324.86214 0.439879 -1.591110 1.552150 0.235135 -0.784469 0.184681 0.543335 +1403715324.91214 0.440279 -1.586300 1.558570 0.238506 -0.780814 0.180523 0.548503 +1403715324.96214 0.440802 -1.581750 1.564370 0.240061 -0.777144 0.179179 0.553455 +1403715325.01214 0.441671 -1.577370 1.569540 0.240944 -0.773726 0.179149 0.557853 +1403715325.06214 0.443259 -1.573080 1.574160 0.241060 -0.771127 0.179939 0.561137 +1403715325.11214 0.445867 -1.568610 1.578180 0.240518 -0.768689 0.182200 0.563978 +1403715325.16214 0.449349 -1.563920 1.581280 0.240690 -0.767305 0.183374 0.565407 +1403715325.21214 0.453812 -1.558870 1.584200 0.240774 -0.766102 0.184642 0.566589 +1403715325.26214 0.459443 -1.553610 1.585890 0.240832 -0.766153 0.186104 0.566017 +1403715325.31214 0.466297 -1.548100 1.587230 0.241144 -0.766991 0.187306 0.564350 +1403715325.36214 0.474141 -1.541890 1.588290 0.241739 -0.768879 0.187750 0.561371 +1403715325.41214 0.482720 -1.535250 1.588910 0.241815 -0.771660 0.189234 0.557007 +1403715325.46214 0.491895 -1.528160 1.589030 0.241751 -0.775129 0.190273 0.551840 +1403715325.51214 0.500934 -1.521010 1.588630 0.241511 -0.778300 0.191343 0.547091 +1403715325.56214 0.509916 -1.513930 1.588310 0.240050 -0.780715 0.193584 0.543494 +1403715325.61214 0.518151 -1.506850 1.588820 0.236487 -0.782659 0.198443 0.540499 +1403715325.66214 0.525442 -1.499080 1.588620 0.232737 -0.784360 0.203379 0.537819 +1403715325.71214 0.531755 -1.490430 1.588320 0.230050 -0.785981 0.206761 0.535314 +1403715325.76214 0.536638 -1.480660 1.588110 0.228241 -0.787758 0.208660 0.532733 +1403715325.81214 0.540379 -1.469510 1.588180 0.228043 -0.789156 0.208289 0.530890 +1403715325.86214 0.542861 -1.457480 1.587960 0.228397 -0.790096 0.207069 0.529816 +1403715325.91214 0.544180 -1.444400 1.587340 0.228939 -0.790926 0.205383 0.529000 +1403715325.96214 0.544172 -1.430560 1.586470 0.230013 -0.791684 0.203196 0.528245 +1403715326.01214 0.542466 -1.416020 1.585320 0.231101 -0.791627 0.200281 0.528967 +1403715326.06214 0.539152 -1.400890 1.583920 0.232651 -0.790804 0.196483 0.530940 +1403715326.11214 0.534610 -1.385320 1.581680 0.234939 -0.789575 0.191399 0.533611 +1403715326.16214 0.529180 -1.369650 1.579220 0.237281 -0.787887 0.186285 0.536869 +1403715326.21214 0.523174 -1.353900 1.575700 0.239057 -0.786456 0.181967 0.539654 +1403715326.26214 0.516730 -1.338440 1.571550 0.240533 -0.784466 0.178155 0.543155 +1403715326.31214 0.510454 -1.323040 1.567160 0.240709 -0.781975 0.176277 0.547267 +1403715326.36214 0.504251 -1.308030 1.562910 0.240119 -0.778214 0.175345 0.553155 +1403715326.41214 0.498256 -1.293710 1.558790 0.238524 -0.774224 0.175897 0.559235 +1403715326.46214 0.492388 -1.280090 1.554680 0.236772 -0.771178 0.176758 0.563896 +1403715326.51214 0.487514 -1.266310 1.550650 0.235328 -0.768014 0.177339 0.568617 +1403715326.56214 0.484434 -1.251950 1.545660 0.234063 -0.765813 0.177531 0.572039 +1403715326.61214 0.482787 -1.237170 1.540400 0.233571 -0.763869 0.176849 0.575041 +1403715326.66214 0.482585 -1.221880 1.535460 0.232559 -0.763354 0.176614 0.576207 +1403715326.71214 0.483471 -1.206070 1.530410 0.231745 -0.763826 0.175854 0.576141 +1403715326.76214 0.485550 -1.190090 1.524610 0.230287 -0.766443 0.176153 0.573152 +1403715326.81214 0.488839 -1.173650 1.518690 0.228628 -0.770252 0.176998 0.568430 +1403715326.86214 0.493368 -1.156970 1.512630 0.226506 -0.774285 0.177947 0.563483 +1403715326.91214 0.498722 -1.139870 1.506590 0.225566 -0.778290 0.177775 0.558373 +1403715326.96214 0.504784 -1.122330 1.500980 0.223469 -0.781389 0.178655 0.554595 +1403715327.01214 0.510894 -1.104570 1.495630 0.220914 -0.784070 0.180535 0.551216 +1403715327.06214 0.516880 -1.086400 1.490960 0.218402 -0.786109 0.182606 0.548624 +1403715327.11214 0.522305 -1.067700 1.486420 0.216303 -0.788186 0.184055 0.545985 +1403715327.16214 0.527177 -1.048360 1.481890 0.215065 -0.790192 0.184779 0.543323 +1403715327.21214 0.531331 -1.028370 1.477170 0.213693 -0.792179 0.185598 0.540686 +1403715327.26214 0.534624 -1.007480 1.473100 0.212290 -0.794073 0.186152 0.538264 +1403715327.31214 0.536732 -0.986113 1.469890 0.210654 -0.795588 0.187034 0.536361 +1403715327.36214 0.537452 -0.964125 1.466850 0.209182 -0.797053 0.187627 0.534551 +1403715327.41214 0.536917 -0.941296 1.463520 0.207445 -0.798285 0.188296 0.533154 +1403715327.46214 0.535015 -0.917927 1.460280 0.207887 -0.798790 0.188129 0.532283 +1403715327.51214 0.531772 -0.893680 1.457220 0.208832 -0.798763 0.189114 0.531604 +1403715327.56214 0.526902 -0.868402 1.454270 0.212915 -0.797817 0.188042 0.531785 +1403715327.61214 0.520413 -0.842765 1.451290 0.218634 -0.796292 0.186527 0.532283 +1403715327.66214 0.512913 -0.816989 1.448090 0.225168 -0.794572 0.186111 0.532276 +1403715327.71214 0.504398 -0.791134 1.444860 0.232952 -0.792319 0.186372 0.532193 +1403715327.76214 0.495151 -0.765608 1.441580 0.240883 -0.789861 0.188847 0.531444 +1403715327.81214 0.485083 -0.740216 1.437750 0.249750 -0.787447 0.191742 0.529893 +1403715327.86214 0.474355 -0.715256 1.433520 0.258830 -0.784608 0.196265 0.528089 +1403715327.91214 0.463039 -0.690999 1.429070 0.268319 -0.780791 0.200984 0.527234 +1403715327.96214 0.450919 -0.667258 1.424330 0.277874 -0.776383 0.205550 0.527033 +1403715328.01214 0.438188 -0.643691 1.419780 0.286394 -0.771729 0.209012 0.527946 +1403715328.06214 0.424933 -0.620221 1.415200 0.292909 -0.767793 0.212356 0.528775 +1403715328.11214 0.411098 -0.597185 1.411150 0.298073 -0.763462 0.214956 0.531105 +1403715328.16214 0.397157 -0.574574 1.407900 0.301973 -0.759464 0.216621 0.533949 +1403715328.21214 0.383432 -0.552391 1.405380 0.304839 -0.755336 0.217293 0.537889 +1403715328.26214 0.370468 -0.530338 1.403270 0.306287 -0.751810 0.217999 0.541707 +1403715328.31214 0.358314 -0.508209 1.401380 0.307057 -0.748890 0.217459 0.545519 +1403715328.36214 0.347189 -0.486251 1.399560 0.306968 -0.747056 0.215968 0.548667 +1403715328.41214 0.337496 -0.464280 1.398110 0.306175 -0.745823 0.214281 0.551442 +1403715328.46214 0.329423 -0.442345 1.396720 0.305174 -0.745637 0.212195 0.553052 +1403715328.51214 0.322881 -0.420676 1.395340 0.303750 -0.746303 0.210339 0.553647 +1403715328.56214 0.317922 -0.399209 1.393520 0.302835 -0.748686 0.208026 0.551802 +1403715328.61214 0.314473 -0.378362 1.391360 0.303792 -0.751508 0.205735 0.548287 +1403715328.66214 0.312445 -0.358435 1.389280 0.305916 -0.754351 0.204170 0.543769 +1403715328.71214 0.311835 -0.339621 1.387560 0.308471 -0.755597 0.204874 0.540320 +1403715328.76214 0.312575 -0.322273 1.385450 0.312140 -0.756923 0.207745 0.535236 +1403715328.81214 0.314529 -0.306373 1.383430 0.317456 -0.756296 0.212461 0.531129 +1403715328.86214 0.317387 -0.291919 1.381580 0.323888 -0.753979 0.219205 0.527789 +1403715328.91214 0.320784 -0.278809 1.379640 0.332007 -0.750623 0.227021 0.524212 +1403715328.96214 0.325105 -0.266771 1.377630 0.341988 -0.745903 0.235618 0.520727 +1403715329.01214 0.330060 -0.255754 1.375620 0.353029 -0.740160 0.245344 0.517049 +1403715329.06214 0.335760 -0.245346 1.373070 0.365022 -0.734318 0.255173 0.512272 +1403715329.11214 0.341871 -0.235732 1.370380 0.376888 -0.728020 0.266500 0.506872 +1403715329.16214 0.348085 -0.226926 1.367200 0.389698 -0.721565 0.276905 0.500803 +1403715329.21214 0.354305 -0.218569 1.363320 0.402559 -0.715139 0.286071 0.494657 +1403715329.26214 0.360465 -0.210518 1.358930 0.414902 -0.709232 0.293921 0.488319 +1403715329.31214 0.366252 -0.202829 1.354660 0.425054 -0.703832 0.301114 0.482991 +1403715329.36214 0.371788 -0.195416 1.349910 0.433330 -0.699397 0.307158 0.478249 +1403715329.41214 0.377075 -0.188149 1.344060 0.439786 -0.695305 0.312697 0.474722 +1403715329.46214 0.381936 -0.181040 1.336990 0.445395 -0.692527 0.316440 0.471058 +1403715329.51214 0.386436 -0.174470 1.330200 0.449978 -0.689875 0.319002 0.468861 +1403715329.56214 0.390668 -0.168420 1.323060 0.453451 -0.688612 0.321273 0.465811 +1403715329.61214 0.394559 -0.162532 1.316800 0.456642 -0.687314 0.321908 0.464169 +1403715329.66214 0.397814 -0.157323 1.311490 0.458127 -0.686014 0.323007 0.463866 +1403715329.71214 0.400780 -0.152702 1.305930 0.458794 -0.684572 0.323855 0.464745 +1403715329.76214 0.403924 -0.148281 1.299490 0.458387 -0.683496 0.325201 0.465789 +1403715329.81214 0.406865 -0.144262 1.292230 0.457885 -0.682750 0.326181 0.466691 +1403715329.86214 0.409752 -0.140600 1.284420 0.457116 -0.682754 0.326814 0.466995 +1403715329.91214 0.412244 -0.137531 1.276150 0.456305 -0.682577 0.327064 0.467870 +1403715329.96214 0.414491 -0.134996 1.267630 0.455595 -0.682831 0.327544 0.467857 +1403715330.01214 0.416856 -0.132509 1.258350 0.455517 -0.682453 0.329159 0.467351 +1403715330.06214 0.419327 -0.130293 1.248270 0.456047 -0.681426 0.331517 0.466664 +1403715330.11214 0.421538 -0.127816 1.236830 0.457548 -0.680835 0.332495 0.465361 +1403715330.16214 0.423263 -0.125405 1.224930 0.460223 -0.679641 0.331756 0.464995 +1403715330.21214 0.424662 -0.123358 1.213470 0.462959 -0.678985 0.330287 0.464284 +1403715330.26214 0.425917 -0.121994 1.202350 0.465419 -0.679164 0.328291 0.462976 +1403715330.31214 0.427047 -0.120932 1.191950 0.467367 -0.679107 0.326409 0.462428 +1403715330.36214 0.428170 -0.120336 1.181900 0.468484 -0.679401 0.325074 0.461805 +1403715330.41214 0.429309 -0.120465 1.172820 0.468457 -0.679458 0.325463 0.461474 +1403715330.46214 0.430467 -0.120771 1.166210 0.467521 -0.678962 0.327086 0.462006 +1403715330.51214 0.431349 -0.121466 1.162070 0.466359 -0.679205 0.328817 0.461594 +1403715330.56214 0.431857 -0.122936 1.161120 0.466471 -0.678800 0.328884 0.462029 +1403715330.61214 0.432076 -0.124979 1.163770 0.464851 -0.678145 0.331014 0.463100 +1403715330.66214 0.432279 -0.126874 1.170060 0.461753 -0.677084 0.334953 0.464916 +1403715330.71214 0.432569 -0.128317 1.178870 0.458556 -0.676635 0.339427 0.465490 +1403715330.76214 0.432864 -0.129565 1.188720 0.455907 -0.676818 0.345078 0.463668 +1403715330.81214 0.433272 -0.130562 1.198700 0.455024 -0.676474 0.351402 0.460275 +1403715330.86214 0.433673 -0.131046 1.208590 0.457667 -0.674831 0.355825 0.456654 +1403715330.91214 0.433935 -0.131270 1.217670 0.461718 -0.672448 0.361457 0.451641 +1403715330.96214 0.433635 -0.131377 1.226580 0.467111 -0.668531 0.367708 0.446838 +1403715331.01214 0.432677 -0.130776 1.235410 0.473836 -0.663905 0.374158 0.441265 +1403715331.06214 0.430875 -0.129268 1.244400 0.481206 -0.659060 0.381128 0.434536 +1403715331.11214 0.427874 -0.126916 1.254340 0.489852 -0.653249 0.387151 0.428280 +1403715331.16214 0.423382 -0.124119 1.265300 0.500864 -0.646717 0.390165 0.422687 +1403715331.21214 0.417122 -0.121031 1.277570 0.510750 -0.639962 0.392936 0.418550 +1403715331.26214 0.409266 -0.117594 1.291120 0.519991 -0.633279 0.394389 0.415962 +1403715331.31214 0.400075 -0.113766 1.305900 0.529024 -0.626886 0.393804 0.414809 +1403715331.36214 0.389937 -0.109901 1.322420 0.537100 -0.620636 0.392524 0.415042 +1403715331.41214 0.378921 -0.105933 1.340310 0.543027 -0.615823 0.392098 0.414900 +1403715331.46214 0.367348 -0.102008 1.358840 0.546477 -0.612372 0.393150 0.414484 +1403715331.51214 0.355455 -0.098294 1.377550 0.549665 -0.609601 0.393574 0.413950 +1403715331.56214 0.343299 -0.094695 1.396200 0.551568 -0.607289 0.394977 0.413480 +1403715331.61214 0.330905 -0.091096 1.413910 0.552807 -0.606448 0.396250 0.411839 +1403715331.66214 0.318148 -0.087556 1.431490 0.553828 -0.604743 0.396806 0.412438 +1403715331.71214 0.305076 -0.084070 1.448680 0.555234 -0.602413 0.395607 0.415102 +1403715331.76214 0.291926 -0.080783 1.465110 0.556820 -0.600872 0.393365 0.417334 +1403715331.81214 0.278683 -0.077512 1.480470 0.557080 -0.600122 0.392099 0.419253 +1403715331.86214 0.265713 -0.074454 1.495170 0.556160 -0.600335 0.392011 0.420252 +1403715331.91214 0.252947 -0.071434 1.508560 0.555352 -0.601162 0.391113 0.420975 +1403715331.96214 0.240496 -0.068442 1.519560 0.554433 -0.603975 0.390463 0.418756 +1403715332.01214 0.228435 -0.065598 1.527760 0.552062 -0.607050 0.391195 0.416754 +1403715332.06214 0.216226 -0.062987 1.532880 0.550718 -0.610256 0.389491 0.415444 +1403715332.11214 0.203941 -0.060706 1.535200 0.549512 -0.613210 0.387435 0.414615 +1403715332.16214 0.191660 -0.058897 1.535490 0.546710 -0.617701 0.387411 0.411663 +1403715332.21214 0.179402 -0.058288 1.535360 0.542913 -0.621962 0.389948 0.407859 +1403715332.26214 0.167159 -0.058513 1.536050 0.539116 -0.624469 0.394286 0.404885 +1403715332.31214 0.154497 -0.059179 1.537450 0.536388 -0.625556 0.398400 0.402795 +1403715332.36214 0.141187 -0.060316 1.539090 0.536338 -0.626045 0.400674 0.399838 +1403715332.41214 0.126906 -0.062005 1.541040 0.538245 -0.625367 0.401325 0.397678 +1403715332.46214 0.111339 -0.064504 1.543460 0.541151 -0.624530 0.400352 0.396025 +1403715332.51214 0.094690 -0.067889 1.545920 0.543947 -0.624281 0.399656 0.393280 +1403715332.56214 0.077030 -0.072447 1.547980 0.546885 -0.623452 0.398059 0.392141 +1403715332.61214 0.058291 -0.078337 1.550490 0.548016 -0.622086 0.398565 0.392216 +1403715332.66214 0.038546 -0.085339 1.553620 0.548466 -0.620349 0.399941 0.392937 +1403715332.71214 0.017513 -0.093170 1.557160 0.549226 -0.618051 0.401223 0.394187 +1403715332.76214 -0.004493 -0.101877 1.560690 0.551067 -0.616175 0.401346 0.394429 +1403715332.81214 -0.027220 -0.111779 1.564280 0.553687 -0.613284 0.401293 0.395320 +1403715332.86214 -0.050585 -0.123058 1.567650 0.557008 -0.610044 0.401175 0.395786 +1403715332.91214 -0.074086 -0.135368 1.572040 0.557818 -0.603866 0.405848 0.399339 +1403715332.96214 -0.097905 -0.148433 1.577270 0.557349 -0.595436 0.413317 0.404953 +1403715333.01214 -0.121797 -0.161299 1.582980 0.556830 -0.586464 0.421680 0.410104 +1403715333.06214 -0.146188 -0.173385 1.588020 0.556582 -0.578585 0.429224 0.413790 +1403715333.11214 -0.171060 -0.183947 1.591970 0.556874 -0.572285 0.434592 0.416546 +1403715333.16214 -0.196096 -0.193250 1.594870 0.557915 -0.567359 0.437846 0.418480 +1403715333.21214 -0.221394 -0.200781 1.596330 0.559260 -0.564173 0.439449 0.419311 +1403715333.26214 -0.246732 -0.206449 1.596380 0.561451 -0.562985 0.439207 0.418231 +1403715333.31214 -0.272044 -0.210663 1.595340 0.564015 -0.563118 0.437899 0.415968 +1403715333.36214 -0.297281 -0.213485 1.593520 0.566750 -0.563657 0.435436 0.414102 +1403715333.41214 -0.322176 -0.214797 1.591000 0.569277 -0.564749 0.432886 0.411815 +1403715333.46214 -0.346783 -0.214592 1.588030 0.571038 -0.565796 0.430994 0.409920 +1403715333.51214 -0.371153 -0.213064 1.585170 0.571368 -0.566288 0.430648 0.409145 +1403715333.56214 -0.395372 -0.210693 1.582250 0.570779 -0.566423 0.431518 0.408862 +1403715333.61214 -0.419428 -0.207432 1.578940 0.570392 -0.565698 0.432146 0.409742 +1403715333.66214 -0.443321 -0.203085 1.574610 0.571447 -0.566786 0.431022 0.407948 +1403715333.71214 -0.467127 -0.197604 1.569610 0.573561 -0.568946 0.428450 0.404672 +1403715333.76214 -0.490935 -0.191314 1.564160 0.576589 -0.572332 0.424391 0.399842 +1403715333.81214 -0.514605 -0.184490 1.558840 0.579782 -0.574985 0.421078 0.394890 +1403715333.86214 -0.538058 -0.177562 1.554150 0.583400 -0.575900 0.419335 0.390054 +1403715333.91214 -0.561437 -0.170947 1.550280 0.586986 -0.575482 0.418943 0.385687 +1403715333.96214 -0.584542 -0.165053 1.547650 0.590921 -0.572965 0.419396 0.382924 +1403715334.01214 -0.607391 -0.159807 1.545950 0.594236 -0.569906 0.421900 0.379594 +1403715334.06214 -0.629970 -0.155545 1.544830 0.597770 -0.566838 0.424613 0.375592 +1403715334.11214 -0.652712 -0.151830 1.544470 0.600943 -0.563789 0.427210 0.372157 +1403715334.16214 -0.675823 -0.148744 1.544620 0.604530 -0.560763 0.428855 0.369014 +1403715334.21214 -0.699337 -0.146291 1.545080 0.607321 -0.558580 0.430495 0.365818 +1403715334.26214 -0.723019 -0.144531 1.545740 0.609825 -0.556819 0.431574 0.363056 +1403715334.31214 -0.747077 -0.143490 1.546580 0.611593 -0.554770 0.432947 0.361583 +1403715334.36214 -0.771478 -0.143127 1.547270 0.613372 -0.553137 0.433618 0.360263 +1403715334.41214 -0.796178 -0.143778 1.547990 0.614527 -0.551653 0.434324 0.359719 +1403715334.46214 -0.820854 -0.145283 1.548930 0.615334 -0.550533 0.435192 0.359005 +1403715334.51214 -0.845699 -0.147456 1.549910 0.615826 -0.549515 0.435825 0.358955 +1403715334.56214 -0.870807 -0.150269 1.551060 0.616081 -0.547967 0.436740 0.359771 +1403715334.61214 -0.895929 -0.153540 1.551790 0.617260 -0.546378 0.436488 0.360472 +1403715334.66214 -0.921178 -0.157216 1.552210 0.618645 -0.544874 0.435413 0.361673 +1403715334.71214 -0.946384 -0.161365 1.552450 0.618933 -0.543939 0.435406 0.362593 +1403715334.76214 -0.971388 -0.166131 1.552490 0.619171 -0.543169 0.435220 0.363564 +1403715334.81214 -0.996055 -0.171457 1.552530 0.619536 -0.542796 0.434499 0.364360 +1403715334.86214 -1.020530 -0.177260 1.552410 0.619613 -0.542250 0.434119 0.365494 +1403715334.91214 -1.044920 -0.183525 1.552140 0.619643 -0.542018 0.433765 0.366206 +1403715334.96214 -1.069060 -0.190245 1.551490 0.620018 -0.542203 0.432599 0.366676 +1403715335.01214 -1.092800 -0.197181 1.550860 0.620014 -0.541935 0.432623 0.367051 +1403715335.06214 -1.115960 -0.204482 1.550000 0.620844 -0.541497 0.432328 0.366643 +1403715335.11214 -1.138610 -0.212306 1.549280 0.621554 -0.540925 0.432160 0.366481 +1403715335.16214 -1.160960 -0.220599 1.548530 0.622300 -0.540093 0.431824 0.366838 +1403715335.21214 -1.182670 -0.229334 1.547680 0.622697 -0.539993 0.431631 0.366539 +1403715335.26214 -1.203800 -0.238340 1.546750 0.623922 -0.538917 0.431382 0.366332 +1403715335.31214 -1.224230 -0.247680 1.545820 0.625378 -0.537307 0.431964 0.365528 +1403715335.36214 -1.243970 -0.257522 1.545030 0.627269 -0.534973 0.433256 0.364179 +1403715335.41214 -1.263090 -0.267703 1.544230 0.629629 -0.531908 0.434956 0.362565 +1403715335.46214 -1.281580 -0.278199 1.543140 0.632083 -0.529032 0.436699 0.360404 +1403715335.51214 -1.299750 -0.289262 1.542000 0.633624 -0.527392 0.439126 0.357136 +1403715335.56214 -1.317780 -0.300718 1.541130 0.634289 -0.526110 0.442232 0.354001 +1403715335.61214 -1.335440 -0.312431 1.540090 0.635429 -0.524594 0.444773 0.351009 +1403715335.66214 -1.352660 -0.324453 1.539050 0.637136 -0.522298 0.447626 0.347697 +1403715335.71214 -1.369470 -0.337054 1.537910 0.640630 -0.518638 0.449030 0.344934 +1403715335.76214 -1.385940 -0.350190 1.536770 0.643909 -0.514254 0.451444 0.342233 +1403715335.81214 -1.402330 -0.363689 1.535200 0.647084 -0.510088 0.453426 0.339848 +1403715335.86214 -1.418700 -0.377646 1.533540 0.649780 -0.506227 0.455441 0.337777 +1403715335.91214 -1.435010 -0.391890 1.531730 0.652464 -0.502571 0.456963 0.336002 +1403715335.96214 -1.451260 -0.406462 1.530290 0.653581 -0.498928 0.460330 0.334664 +1403715336.01214 -1.467530 -0.421241 1.528900 0.655279 -0.494611 0.462470 0.334799 +1403715336.06214 -1.483640 -0.436130 1.527780 0.655520 -0.491041 0.465738 0.335053 +1403715336.11214 -1.499630 -0.451014 1.526620 0.655050 -0.487989 0.469354 0.335385 +1403715336.16214 -1.515550 -0.465791 1.525320 0.654743 -0.484610 0.472143 0.336967 +1403715336.21214 -1.531180 -0.480318 1.523930 0.653817 -0.482304 0.475375 0.337529 +1403715336.26214 -1.546820 -0.493993 1.521860 0.653970 -0.481445 0.476938 0.336250 +1403715336.31214 -1.562640 -0.507214 1.519550 0.655726 -0.481208 0.475881 0.334664 +1403715336.36214 -1.578570 -0.520118 1.517000 0.658301 -0.481518 0.473902 0.331959 +1403715336.41214 -1.594460 -0.532710 1.514910 0.660613 -0.481593 0.471731 0.330346 +1403715336.46214 -1.610170 -0.545255 1.513520 0.663098 -0.480809 0.469214 0.330093 +1403715336.51214 -1.625380 -0.557760 1.512260 0.664236 -0.481030 0.468223 0.328889 +1403715336.56214 -1.640360 -0.570449 1.511560 0.664549 -0.481005 0.467934 0.328704 +1403715336.61214 -1.654950 -0.583217 1.511020 0.664377 -0.481087 0.468306 0.328403 +1403715336.66214 -1.669270 -0.596154 1.510470 0.664453 -0.481244 0.467954 0.328519 +1403715336.71214 -1.683290 -0.609077 1.510010 0.664350 -0.481394 0.467678 0.328901 +1403715336.76214 -1.697090 -0.622331 1.509950 0.664136 -0.481680 0.467491 0.329179 +1403715336.81214 -1.710550 -0.635890 1.510450 0.664220 -0.481322 0.467057 0.330150 +1403715336.86214 -1.723620 -0.649572 1.511550 0.663970 -0.481029 0.467078 0.331049 +1403715336.91214 -1.736120 -0.663479 1.513310 0.663757 -0.480930 0.467266 0.331354 +1403715336.96214 -1.748210 -0.677448 1.516080 0.663599 -0.480243 0.467236 0.332707 +1403715337.01214 -1.759680 -0.691326 1.519450 0.663813 -0.479652 0.467264 0.333092 +1403715337.06214 -1.770330 -0.704820 1.523660 0.665060 -0.478224 0.467051 0.332956 +1403715337.11214 -1.780160 -0.717852 1.528040 0.667186 -0.477000 0.466957 0.330582 +1403715337.16214 -1.788980 -0.730630 1.532750 0.670789 -0.473960 0.466453 0.328367 +1403715337.21214 -1.796860 -0.743507 1.537420 0.674225 -0.471079 0.467226 0.324352 +1403715337.26214 -1.803730 -0.756751 1.542080 0.677581 -0.468151 0.469215 0.318678 +1403715337.31214 -1.809820 -0.770319 1.546690 0.681401 -0.464745 0.471461 0.312137 +1403715337.36214 -1.815610 -0.784479 1.550970 0.684754 -0.461903 0.473784 0.305430 +1403715337.41214 -1.821360 -0.799375 1.555100 0.687430 -0.459515 0.476292 0.299051 +1403715337.46214 -1.827190 -0.815086 1.559270 0.688683 -0.456991 0.480125 0.293861 +1403715337.51214 -1.833200 -0.831485 1.563110 0.688767 -0.456029 0.484681 0.287615 +1403715337.56214 -1.839640 -0.848815 1.566720 0.688599 -0.454080 0.488810 0.284091 +1403715337.61214 -1.846450 -0.867190 1.570430 0.689868 -0.450724 0.490503 0.283437 +1403715337.66214 -1.853690 -0.886321 1.574150 0.690773 -0.446953 0.492057 0.284509 +1403715337.71214 -1.861200 -0.905978 1.577130 0.692030 -0.443869 0.492510 0.285498 +1403715337.76214 -1.868900 -0.926164 1.580200 0.692944 -0.441731 0.492777 0.286134 +1403715337.81214 -1.876760 -0.946892 1.583250 0.693209 -0.440228 0.493151 0.287163 +1403715337.86214 -1.884770 -0.967996 1.586350 0.693082 -0.439279 0.493248 0.288752 +1403715337.91214 -1.892560 -0.989483 1.589580 0.693325 -0.438373 0.492364 0.291045 +1403715337.96214 -1.900250 -1.011250 1.592960 0.693218 -0.438106 0.491467 0.293212 +1403715338.01214 -1.907920 -1.032810 1.596420 0.692089 -0.438922 0.491500 0.294598 +1403715338.06214 -1.915730 -1.054310 1.599800 0.690531 -0.440600 0.491761 0.295312 +1403715338.11214 -1.923570 -1.075580 1.603300 0.688763 -0.442444 0.492279 0.295823 +1403715338.16214 -1.931350 -1.096780 1.606450 0.687974 -0.443126 0.492727 0.295892 +1403715338.21214 -1.938980 -1.117830 1.608990 0.687463 -0.443537 0.493511 0.295155 +1403715338.26214 -1.946230 -1.138700 1.611280 0.687186 -0.443413 0.494980 0.293522 +1403715338.31214 -1.953360 -1.159560 1.613380 0.687724 -0.442934 0.496207 0.290901 +1403715338.36214 -1.960380 -1.180280 1.615760 0.688660 -0.442064 0.497995 0.286929 +1403715338.41214 -1.967500 -1.201150 1.618620 0.690284 -0.439132 0.500412 0.283300 +1403715338.46214 -1.975160 -1.222150 1.621710 0.692657 -0.435333 0.502686 0.279318 +1403715338.51214 -1.982990 -1.243390 1.624840 0.695908 -0.430742 0.504741 0.274610 +1403715338.56214 -1.991080 -1.265100 1.628650 0.699674 -0.423945 0.507002 0.271431 +1403715338.61214 -1.999530 -1.286940 1.633150 0.703946 -0.416185 0.509187 0.268289 +1403715338.66214 -2.008190 -1.309070 1.637960 0.708436 -0.407628 0.511725 0.264755 +1403715338.71214 -2.017310 -1.331250 1.642900 0.713105 -0.398916 0.514009 0.261041 +1403715338.76214 -2.026840 -1.353220 1.647650 0.717642 -0.391195 0.516034 0.256253 +1403715338.81214 -2.036990 -1.374970 1.652000 0.722378 -0.383900 0.516535 0.252947 +1403715338.86214 -2.047300 -1.396830 1.656240 0.725715 -0.378159 0.517723 0.249590 +1403715338.91214 -2.057900 -1.418870 1.659810 0.728919 -0.373700 0.518051 0.246268 +1403715338.96214 -2.069060 -1.440750 1.662670 0.732444 -0.369043 0.517306 0.244394 +1403715339.01214 -2.080380 -1.462580 1.664700 0.735492 -0.365877 0.516345 0.242021 +1403715339.06214 -2.091790 -1.484590 1.666090 0.738270 -0.363365 0.515128 0.239931 +1403715339.11214 -2.103230 -1.506990 1.666830 0.740813 -0.360282 0.513754 0.239687 +1403715339.16214 -2.114180 -1.529650 1.667020 0.742867 -0.356917 0.512789 0.240431 +1403715339.21214 -2.124720 -1.552560 1.666620 0.744759 -0.353815 0.511483 0.241937 +1403715339.26214 -2.134600 -1.575430 1.665760 0.745424 -0.352001 0.511632 0.242221 +1403715339.31214 -2.143810 -1.598520 1.664930 0.744461 -0.351597 0.513818 0.241139 +1403715339.36214 -2.152390 -1.621900 1.663830 0.742983 -0.351459 0.516331 0.240533 +1403715339.41214 -2.160710 -1.645090 1.662170 0.741532 -0.352230 0.518427 0.239368 +1403715339.46214 -2.169020 -1.668160 1.660010 0.740353 -0.353169 0.519717 0.238838 +1403715339.51214 -2.177210 -1.691390 1.657570 0.738747 -0.353972 0.521233 0.239317 +1403715339.56214 -2.185420 -1.714270 1.654300 0.737819 -0.355862 0.521624 0.238527 +1403715339.61214 -2.193490 -1.737060 1.649890 0.738552 -0.357861 0.519358 0.238209 +1403715339.66214 -2.201640 -1.759550 1.645180 0.739315 -0.358637 0.516693 0.240460 +1403715339.71214 -2.209430 -1.782090 1.640210 0.740762 -0.357998 0.513088 0.244641 +1403715339.76214 -2.216700 -1.804680 1.635220 0.741239 -0.356296 0.510595 0.250819 +1403715339.81214 -2.223130 -1.826720 1.629610 0.741932 -0.354212 0.507704 0.257503 +1403715339.86214 -2.228470 -1.848140 1.623810 0.742292 -0.351820 0.505697 0.263620 +1403715339.91214 -2.232280 -1.868560 1.617920 0.743129 -0.348338 0.504490 0.268161 +1403715339.96214 -2.234130 -1.887990 1.611670 0.745125 -0.343945 0.503154 0.270790 +1403715340.01214 -2.234080 -1.906110 1.606320 0.747717 -0.337983 0.502217 0.272882 +1403715340.06214 -2.231440 -1.922640 1.601530 0.750561 -0.332176 0.502575 0.271543 +1403715340.11214 -2.226660 -1.937220 1.597930 0.753405 -0.326523 0.504254 0.267381 +1403715340.16214 -2.220020 -1.949840 1.596200 0.755757 -0.320210 0.507569 0.262052 +1403715340.21214 -2.211450 -1.960410 1.595610 0.758181 -0.314644 0.511993 0.253029 +1403715340.26214 -2.201030 -1.969440 1.596610 0.760391 -0.308706 0.517329 0.242646 +1403715340.31214 -2.188680 -1.977250 1.599620 0.763231 -0.301262 0.522649 0.231427 +1403715340.36214 -2.174920 -1.984050 1.604540 0.766140 -0.293585 0.528444 0.218136 +1403715340.41214 -2.160540 -1.989900 1.611100 0.769881 -0.284118 0.533020 0.206034 +1403715340.46214 -2.145610 -1.994880 1.618710 0.774109 -0.274890 0.535863 0.195041 +1403715340.51214 -2.130140 -1.999450 1.626350 0.777904 -0.266762 0.537896 0.185393 +1403715340.56214 -2.114410 -2.003870 1.633100 0.781569 -0.261077 0.538859 0.174983 +1403715340.61214 -2.098770 -2.008320 1.639410 0.784091 -0.255440 0.540394 0.167112 +1403715340.66214 -2.082980 -2.013310 1.644920 0.786211 -0.250924 0.541454 0.160428 +1403715340.71214 -2.067030 -2.018800 1.649910 0.787952 -0.247373 0.542022 0.155404 +1403715340.76214 -2.050810 -2.024760 1.654320 0.789642 -0.245007 0.541772 0.151396 +1403715340.81214 -2.034360 -2.031420 1.658710 0.790833 -0.243291 0.541616 0.148471 +1403715340.86214 -2.018070 -2.038750 1.662920 0.790853 -0.244672 0.542206 0.143874 +1403715340.91214 -2.001540 -2.046840 1.666780 0.790422 -0.246987 0.542960 0.139371 +1403715340.96214 -1.984960 -2.055750 1.670390 0.790213 -0.248934 0.542999 0.136924 +1403715341.01214 -1.968370 -2.065870 1.673970 0.789938 -0.251622 0.542718 0.134690 +1403715341.06214 -1.951800 -2.077510 1.678010 0.789044 -0.253220 0.543102 0.135387 +1403715341.11214 -1.935340 -2.090600 1.682170 0.788031 -0.253093 0.543625 0.139366 +1403715341.16214 -1.918840 -2.104810 1.686710 0.787154 -0.251441 0.543987 0.145752 +1403715341.21214 -1.902210 -2.119860 1.691620 0.783611 -0.252577 0.547624 0.149219 +1403715341.26214 -1.885610 -2.135850 1.696660 0.780617 -0.254327 0.550252 0.152242 +1403715341.31214 -1.869300 -2.152440 1.701720 0.777919 -0.255267 0.552370 0.156741 +1403715341.36214 -1.854060 -2.168950 1.707110 0.775267 -0.255553 0.554392 0.162181 +1403715341.41214 -1.839110 -2.185190 1.712460 0.772852 -0.256845 0.555944 0.166304 +1403715341.46214 -1.824800 -2.200970 1.717440 0.772256 -0.257234 0.555093 0.171239 +1403715341.51214 -1.810990 -2.216550 1.722660 0.772030 -0.258825 0.553732 0.174242 +1403715341.56214 -1.797680 -2.231800 1.727920 0.772367 -0.258358 0.551768 0.179591 +1403715341.61214 -1.784590 -2.246620 1.733040 0.771495 -0.256969 0.551843 0.185018 +1403715341.66214 -1.771830 -2.260770 1.737980 0.770287 -0.255305 0.552279 0.190958 +1403715341.71214 -1.759150 -2.273880 1.742790 0.769351 -0.252821 0.552457 0.197409 +1403715341.76214 -1.746330 -2.285880 1.746700 0.770063 -0.251568 0.550534 0.201567 +1403715341.81214 -1.733720 -2.296030 1.749760 0.771044 -0.250543 0.548481 0.204667 +1403715341.86214 -1.720460 -2.304530 1.752610 0.772133 -0.248707 0.546435 0.208241 +1403715341.91214 -1.706390 -2.310820 1.754840 0.772886 -0.251010 0.545734 0.204489 +1403715341.96214 -1.691910 -2.315550 1.757100 0.773276 -0.254242 0.545831 0.198681 +1403715342.01214 -1.677710 -2.318960 1.759080 0.774005 -0.258067 0.545429 0.191897 +1403715342.06214 -1.663410 -2.321550 1.761030 0.775622 -0.261017 0.543865 0.185720 +1403715342.11214 -1.649470 -2.323170 1.763070 0.777775 -0.262917 0.541573 0.180662 +1403715342.16214 -1.635920 -2.324110 1.764890 0.779507 -0.266404 0.539698 0.173563 +1403715342.21214 -1.622080 -2.325140 1.766740 0.781019 -0.267789 0.538294 0.168930 +1403715342.26214 -1.607800 -2.326960 1.768540 0.781867 -0.268587 0.537868 0.165053 +1403715342.31214 -1.592940 -2.329840 1.769570 0.782366 -0.268277 0.538309 0.161725 +1403715342.36214 -1.577890 -2.333110 1.770030 0.784006 -0.265576 0.538022 0.159173 +1403715342.41214 -1.562510 -2.336710 1.770260 0.786173 -0.260268 0.537981 0.157381 +1403715342.46214 -1.546410 -2.340890 1.769910 0.789440 -0.254957 0.537013 0.152964 +1403715342.51214 -1.529560 -2.345840 1.769650 0.792998 -0.247084 0.536270 0.150058 +1403715342.56214 -1.511960 -2.351590 1.769490 0.796540 -0.237144 0.535823 0.148931 +1403715342.61214 -1.493530 -2.358160 1.770050 0.799563 -0.224993 0.536277 0.149946 +1403715342.66214 -1.473940 -2.364900 1.770950 0.801424 -0.211381 0.538408 0.152167 +1403715342.71214 -1.452900 -2.371250 1.771540 0.803030 -0.198882 0.540767 0.152185 +1403715342.76214 -1.431080 -2.376890 1.771490 0.804605 -0.189641 0.542667 0.148861 +1403715342.81214 -1.408630 -2.381540 1.771230 0.805607 -0.184621 0.544924 0.141319 +1403715342.86214 -1.385560 -2.385490 1.771700 0.805486 -0.180343 0.548171 0.134822 +1403715342.91214 -1.361880 -2.388890 1.771730 0.805626 -0.177907 0.550368 0.128106 +1403715342.96214 -1.337630 -2.392130 1.771810 0.804610 -0.175610 0.553723 0.123107 +1403715343.01214 -1.312930 -2.395400 1.771440 0.803503 -0.173735 0.556744 0.119306 +1403715343.06214 -1.287920 -2.398690 1.770440 0.802649 -0.172789 0.559105 0.115324 +1403715343.11214 -1.262730 -2.401920 1.768890 0.802524 -0.170421 0.560225 0.114278 +1403715343.16214 -1.237550 -2.405120 1.766630 0.802885 -0.169093 0.560535 0.112174 +1403715343.21214 -1.212250 -2.408340 1.764360 0.802341 -0.167736 0.562039 0.110566 +1403715343.26214 -1.187060 -2.411610 1.761020 0.803612 -0.166732 0.560773 0.109281 +1403715343.31214 -1.162170 -2.414920 1.757220 0.804890 -0.166304 0.559296 0.108092 +1403715343.36214 -1.137400 -2.418330 1.752980 0.806628 -0.166401 0.556957 0.107057 +1403715343.41214 -1.112650 -2.421760 1.748670 0.808793 -0.165438 0.553921 0.107958 +1403715343.46214 -1.088030 -2.425270 1.744460 0.809958 -0.164717 0.552150 0.109392 +1403715343.51214 -1.062880 -2.428900 1.740170 0.810435 -0.165465 0.551215 0.109448 +1403715343.56214 -1.037240 -2.432460 1.736010 0.810841 -0.165552 0.550316 0.110822 +1403715343.61214 -1.010860 -2.435880 1.732150 0.810826 -0.166170 0.549972 0.111708 +1403715343.66214 -0.983876 -2.439240 1.728510 0.810543 -0.166064 0.549993 0.113798 +1403715343.71214 -0.956201 -2.442750 1.725620 0.809923 -0.165675 0.550498 0.116310 +1403715343.76214 -0.927824 -2.446150 1.723610 0.808651 -0.164405 0.551871 0.120382 +1403715343.81214 -0.898870 -2.449170 1.722190 0.806289 -0.163879 0.554852 0.123209 +1403715343.86214 -0.869330 -2.451580 1.720550 0.805383 -0.164121 0.555796 0.124547 +1403715343.91214 -0.839639 -2.453150 1.719330 0.804264 -0.164305 0.557300 0.124818 +1403715343.96214 -0.809334 -2.453850 1.718660 0.803273 -0.163964 0.559237 0.122973 +1403715344.01214 -0.778679 -2.453700 1.718120 0.803213 -0.162137 0.560269 0.121073 +1403715344.06214 -0.747957 -2.452560 1.717640 0.802520 -0.158789 0.562876 0.117972 +1403715344.11214 -0.717173 -2.450580 1.717440 0.802311 -0.154141 0.565308 0.113864 +1403715344.16214 -0.686208 -2.447740 1.716700 0.802525 -0.148200 0.567556 0.108953 +1403715344.21214 -0.655485 -2.444290 1.715660 0.803284 -0.139805 0.569129 0.106221 +1403715344.26214 -0.625034 -2.440150 1.714720 0.803173 -0.130743 0.571585 0.105404 +1403715344.31214 -0.595325 -2.434970 1.713750 0.802673 -0.121113 0.574246 0.106248 +1403715344.36214 -0.566317 -2.428630 1.712550 0.801589 -0.112665 0.577361 0.106844 +1403715344.41214 -0.537674 -2.421020 1.711280 0.799921 -0.104447 0.581041 0.107743 +1403715344.46214 -0.509768 -2.411880 1.709430 0.798862 -0.098120 0.583649 0.107449 +1403715344.51214 -0.483039 -2.400970 1.707390 0.797911 -0.091662 0.585809 0.108459 +1403715344.56214 -0.457269 -2.388040 1.704660 0.797709 -0.087253 0.586972 0.107289 +1403715344.61214 -0.432457 -2.373090 1.700980 0.799151 -0.084453 0.585855 0.104879 +1403715344.66214 -0.408649 -2.356050 1.696490 0.802348 -0.081185 0.582045 0.104261 +1403715344.71214 -0.385592 -2.336840 1.691600 0.805547 -0.079219 0.578146 0.102785 +1403715344.76214 -0.362908 -2.315320 1.686540 0.808735 -0.077772 0.574143 0.101282 +1403715344.81214 -0.340529 -2.291740 1.681820 0.810625 -0.076484 0.571877 0.099966 +1403715344.86214 -0.318466 -2.266320 1.677200 0.811887 -0.075562 0.570371 0.099031 +1403715344.91214 -0.296452 -2.238910 1.672570 0.812847 -0.075049 0.569300 0.097700 +1403715344.96214 -0.274379 -2.209540 1.667950 0.812447 -0.075808 0.570205 0.095128 +1403715345.01214 -0.252140 -2.178250 1.663820 0.810580 -0.079155 0.573344 0.089285 +1403715345.06214 -0.229861 -2.145380 1.660110 0.808338 -0.082088 0.576822 0.084424 +1403715345.11214 -0.208090 -2.111390 1.656800 0.806043 -0.084617 0.580233 0.080400 +1403715345.16214 -0.187000 -2.076460 1.653070 0.805011 -0.086803 0.581759 0.077326 +1403715345.21214 -0.166675 -2.041120 1.649240 0.805032 -0.088910 0.581763 0.074628 +1403715345.26214 -0.147212 -2.005330 1.645420 0.805821 -0.089353 0.580660 0.074180 +1403715345.31214 -0.128848 -1.969300 1.641390 0.806081 -0.090779 0.580276 0.072615 +1403715345.36214 -0.111287 -1.932670 1.637330 0.806593 -0.091299 0.579552 0.072052 +1403715345.41214 -0.094331 -1.895530 1.633260 0.807162 -0.091820 0.578757 0.071415 +1403715345.46214 -0.078033 -1.857880 1.629170 0.807497 -0.092467 0.578339 0.070153 +1403715345.51214 -0.062492 -1.819840 1.625050 0.807717 -0.091795 0.578042 0.070955 +1403715345.56214 -0.047571 -1.781350 1.621170 0.807350 -0.091913 0.578624 0.070230 +1403715345.61214 -0.033223 -1.742510 1.617080 0.807219 -0.092269 0.578878 0.069160 +1403715345.66214 -0.019639 -1.703340 1.612800 0.807057 -0.092318 0.579185 0.068414 +1403715345.71214 -0.006941 -1.664040 1.608290 0.807013 -0.092668 0.579311 0.067389 +1403715345.76214 0.005095 -1.624620 1.603520 0.806860 -0.093115 0.579556 0.066497 +1403715345.81214 0.016593 -1.585340 1.598580 0.807031 -0.093430 0.579357 0.065708 +1403715345.86214 0.027338 -1.546050 1.593290 0.808049 -0.093950 0.577972 0.064640 +1403715345.91214 0.037329 -1.506980 1.587350 0.811703 -0.094314 0.572806 0.064307 +1403715345.96214 0.047348 -1.467780 1.581290 0.816724 -0.094763 0.565617 0.063713 +1403715346.01214 0.057283 -1.428690 1.576180 0.820686 -0.095719 0.559803 0.062721 +1403715346.06214 0.067596 -1.390000 1.571510 0.824573 -0.097339 0.553973 0.060977 +1403715346.11214 0.078848 -1.352000 1.567960 0.826886 -0.098332 0.550380 0.060603 +1403715346.16214 0.091114 -1.314440 1.565410 0.827806 -0.098922 0.548913 0.060379 +1403715346.21214 0.104622 -1.277530 1.564240 0.826345 -0.099517 0.550998 0.060427 +1403715346.26214 0.119263 -1.241190 1.563570 0.824010 -0.099850 0.554356 0.061043 +1403715346.31214 0.134372 -1.205320 1.562830 0.821712 -0.101065 0.557503 0.061370 +1403715346.36214 0.150141 -1.169690 1.562390 0.819597 -0.101618 0.560425 0.062107 +1403715346.41214 0.166288 -1.134580 1.562460 0.817016 -0.102832 0.563900 0.062666 +1403715346.46214 0.182435 -1.100120 1.562940 0.814463 -0.104079 0.567253 0.063572 +1403715346.51214 0.198503 -1.066050 1.563680 0.812040 -0.106082 0.570355 0.063514 +1403715346.56214 0.214365 -1.032470 1.564260 0.810484 -0.108486 0.572135 0.063317 +1403715346.61214 0.229723 -0.999579 1.564980 0.808673 -0.111866 0.574120 0.062610 +1403715346.66214 0.244282 -0.967431 1.565750 0.807684 -0.114853 0.574872 0.063077 +1403715346.71214 0.257985 -0.935930 1.567010 0.806064 -0.117575 0.576500 0.063912 +1403715346.76214 0.270795 -0.904995 1.568120 0.805172 -0.120349 0.577115 0.064440 +1403715346.81214 0.282729 -0.874804 1.569110 0.805002 -0.123048 0.576681 0.065347 +1403715346.86214 0.294041 -0.845368 1.569980 0.805750 -0.124689 0.575033 0.067497 +1403715346.91214 0.304726 -0.816504 1.570460 0.806735 -0.128288 0.572946 0.066732 +1403715346.96214 0.314908 -0.788512 1.570810 0.808288 -0.132008 0.570017 0.065773 +1403715347.01214 0.324823 -0.761561 1.571470 0.809806 -0.135180 0.567206 0.064948 +1403715347.06214 0.334192 -0.735920 1.572540 0.811514 -0.137564 0.564208 0.064728 +1403715347.11214 0.343556 -0.711375 1.574680 0.812651 -0.136190 0.562629 0.067081 +1403715347.16214 0.352805 -0.687461 1.576680 0.813973 -0.132638 0.561307 0.069207 +1403715347.21214 0.362502 -0.664387 1.579610 0.814822 -0.126605 0.561226 0.071147 +1403715347.26214 0.372789 -0.641714 1.582810 0.815122 -0.119553 0.562335 0.071149 +1403715347.31214 0.383922 -0.619378 1.586840 0.815279 -0.110761 0.564014 0.070288 +1403715347.36214 0.394700 -0.597269 1.590690 0.815198 -0.100576 0.566235 0.068670 +1403715347.41214 0.405741 -0.575061 1.594940 0.814942 -0.088439 0.568735 0.067738 +1403715347.46214 0.416688 -0.552123 1.599140 0.815291 -0.076900 0.570255 0.064777 +1403715347.51214 0.427585 -0.528691 1.603680 0.815409 -0.065732 0.571707 0.062754 +1403715347.56214 0.438637 -0.504796 1.608480 0.814972 -0.056054 0.573554 0.060939 +1403715347.61214 0.449401 -0.480051 1.613450 0.814478 -0.047862 0.575210 0.058897 +1403715347.66214 0.460027 -0.454427 1.618310 0.813593 -0.042106 0.577257 0.055390 +1403715347.71214 0.470069 -0.428180 1.622840 0.812890 -0.039948 0.578983 0.048914 +1403715347.76214 0.479757 -0.401133 1.627000 0.812877 -0.039410 0.579628 0.041343 +1403715347.81214 0.489301 -0.373365 1.631180 0.812916 -0.037620 0.580139 0.034504 +1403715347.86214 0.498396 -0.345164 1.634560 0.813111 -0.035911 0.580431 0.025721 +1403715347.91214 0.506726 -0.316743 1.637880 0.813272 -0.032999 0.580712 0.016537 +1403715347.96214 0.514329 -0.288624 1.641170 0.813427 -0.030792 0.580832 0.004722 +1403715348.01214 0.521467 -0.260986 1.644620 -0.813286 0.027465 -0.581161 0.007941 +1403715348.06214 0.528237 -0.234261 1.647480 -0.813935 0.021643 -0.580229 0.019358 +1403715348.11214 0.534534 -0.208567 1.651210 -0.813808 0.012972 -0.580247 0.029362 +1403715348.16214 0.540237 -0.184256 1.654240 -0.814802 0.002622 -0.578430 0.038864 +1403715348.21214 0.545461 -0.161487 1.657380 -0.815208 -0.009059 -0.577097 0.048083 +1403715348.26214 0.550598 -0.140373 1.660140 -0.816574 -0.022326 -0.574110 0.055733 +1403715348.31214 0.555630 -0.121193 1.662610 -0.817343 -0.035504 -0.571661 0.062400 +1403715348.36214 0.560757 -0.103626 1.663510 -0.818421 -0.046944 -0.568505 0.069181 +1403715348.41214 0.566206 -0.087794 1.662970 -0.819255 -0.057351 -0.565779 0.073664 +1403715348.46214 0.571753 -0.073771 1.659700 -0.820530 -0.065134 -0.562471 0.078197 +1403715348.51214 0.577678 -0.061279 1.653290 -0.821155 -0.071944 -0.560317 0.081081 +1403715348.56214 0.584422 -0.049865 1.643850 -0.821355 -0.076604 -0.558961 0.084086 +1403715348.61214 0.592347 -0.039613 1.632100 -0.820217 -0.079600 -0.559660 0.087681 +1403715348.66214 0.600442 -0.030584 1.617680 -0.818546 -0.080134 -0.561186 0.092909 +1403715348.71214 0.609078 -0.023249 1.601220 -0.817184 -0.080524 -0.562370 0.097293 +1403715348.76214 0.618757 -0.017429 1.583800 -0.816695 -0.080929 -0.562284 0.101474 +1403715348.81214 0.628827 -0.013006 1.566500 -0.815823 -0.082908 -0.562622 0.104957 +1403715348.86214 0.639287 -0.010104 1.549760 -0.814390 -0.086091 -0.563520 0.108638 +1403715348.91214 0.649823 -0.009257 1.533490 -0.813432 -0.089333 -0.563777 0.111820 +1403715348.96214 0.660484 -0.010340 1.517930 -0.813104 -0.092807 -0.563192 0.114291 +1403715349.01214 0.671734 -0.013266 1.503290 -0.811827 -0.097146 -0.564155 0.115015 +1403715349.06214 0.683551 -0.017836 1.488970 -0.810664 -0.101566 -0.565037 0.115068 +1403715349.11214 0.695626 -0.023831 1.475370 -0.809001 -0.107603 -0.566513 0.114023 +1403715349.16214 0.707452 -0.031295 1.462150 -0.807234 -0.112649 -0.567945 0.114554 +1403715349.21214 0.719467 -0.040043 1.449520 -0.804981 -0.117511 -0.570088 0.114875 +1403715349.26214 0.731313 -0.049907 1.437260 -0.802884 -0.121327 -0.571975 0.116199 +1403715349.31214 0.742891 -0.061119 1.425760 -0.800434 -0.123520 -0.574428 0.118662 +1403715349.36214 0.754216 -0.073606 1.414170 -0.798814 -0.126798 -0.575926 0.118861 +1403715349.41214 0.764877 -0.087344 1.402530 -0.796785 -0.129912 -0.578259 0.117784 +1403715349.46214 0.774842 -0.102266 1.390450 -0.795871 -0.132355 -0.579326 0.115989 +1403715349.51214 0.784052 -0.117776 1.378440 -0.795008 -0.134839 -0.580445 0.113419 +1403715349.56214 0.792334 -0.133709 1.365510 -0.795662 -0.137936 -0.579197 0.111474 +1403715349.61214 0.799490 -0.149860 1.352440 -0.796134 -0.141740 -0.577709 0.111055 +1403715349.66214 0.805548 -0.166149 1.339500 -0.796543 -0.145654 -0.575871 0.112588 +1403715349.71214 0.810486 -0.182323 1.326610 -0.797308 -0.150123 -0.573007 0.115871 +1403715349.76214 0.814753 -0.198445 1.314770 -0.797379 -0.155375 -0.570577 0.120366 +1403715349.81214 0.818221 -0.214545 1.303690 -0.797677 -0.160408 -0.567287 0.127147 +1403715349.86214 0.821156 -0.230582 1.293290 -0.796980 -0.166421 -0.564922 0.134131 +1403715349.91214 0.823911 -0.246645 1.283510 -0.795589 -0.174172 -0.563090 0.140117 +1403715349.96214 0.826119 -0.262840 1.274120 -0.794197 -0.182396 -0.560810 0.146542 +1403715350.01214 0.828032 -0.279752 1.264870 -0.792732 -0.191295 -0.558662 0.151257 +1403715350.06214 0.829793 -0.297356 1.255930 -0.791088 -0.199365 -0.557195 0.154812 +1403715350.11214 0.831160 -0.315569 1.246060 -0.791829 -0.207479 -0.552841 0.155965 +1403715350.16214 0.832551 -0.334180 1.235930 -0.793013 -0.213359 -0.548342 0.157887 +1403715350.21214 0.834569 -0.353031 1.226120 -0.794211 -0.219231 -0.544384 0.157523 +1403715350.26214 0.836923 -0.372137 1.215990 -0.796673 -0.225492 -0.539016 0.154684 +1403715350.31214 0.839927 -0.390805 1.205910 -0.798536 -0.230999 -0.534907 0.151177 +1403715350.36214 0.843518 -0.408835 1.195690 -0.800470 -0.235053 -0.531158 0.147882 +1403715350.41214 0.847879 -0.425738 1.185770 -0.801693 -0.239083 -0.528783 0.143235 +1403715350.46214 0.852949 -0.441008 1.175900 -0.802521 -0.242181 -0.527268 0.138914 +1403715350.51214 0.858720 -0.454281 1.166240 -0.802674 -0.244472 -0.527020 0.134896 +1403715350.56214 0.865270 -0.465467 1.156660 -0.803135 -0.245464 -0.526555 0.132139 +1403715350.61214 0.872616 -0.474146 1.147360 -0.803383 -0.244488 -0.526796 0.131483 +1403715350.66214 0.880613 -0.480420 1.138480 -0.803719 -0.242613 -0.526957 0.132255 +1403715350.71214 0.889224 -0.484380 1.129870 -0.804022 -0.239797 -0.527193 0.134590 +1403715350.76214 0.898669 -0.486313 1.121650 -0.804410 -0.237091 -0.527189 0.137055 +1403715350.81214 0.909049 -0.486299 1.114170 -0.803946 -0.235240 -0.528163 0.139203 +1403715350.86214 0.920330 -0.484764 1.107520 -0.802407 -0.235377 -0.530510 0.138925 +1403715350.91214 0.932175 -0.481599 1.101490 -0.800781 -0.237009 -0.532707 0.137112 +1403715350.96214 0.944443 -0.476750 1.096090 -0.798860 -0.238386 -0.535346 0.135642 +1403715351.01214 0.956904 -0.470171 1.091010 -0.797788 -0.239593 -0.536622 0.134783 +1403715351.06214 0.969314 -0.461551 1.086480 -0.797253 -0.240673 -0.536997 0.134529 +1403715351.11214 0.981737 -0.450857 1.082970 -0.796652 -0.241229 -0.537696 0.134301 +1403715351.16214 0.994097 -0.438131 1.079870 -0.796888 -0.240639 -0.537167 0.136069 +1403715351.21214 1.006590 -0.423717 1.076990 -0.797340 -0.240187 -0.536216 0.137959 +1403715351.26214 1.019300 -0.407641 1.074640 -0.797532 -0.240001 -0.535686 0.139224 +1403715351.31214 1.032340 -0.389579 1.073600 -0.795476 -0.238485 -0.538549 0.142502 +1403715351.36214 1.045440 -0.370195 1.072850 -0.793468 -0.237841 -0.541410 0.143931 +1403715351.41214 1.058360 -0.349601 1.072490 -0.791279 -0.236659 -0.544605 0.145860 +1403715351.46214 1.071140 -0.327988 1.072490 -0.789464 -0.236520 -0.547291 0.145867 +1403715351.51214 1.083480 -0.305342 1.072700 -0.788161 -0.236211 -0.549336 0.145730 +1403715351.56214 1.095390 -0.281628 1.074060 -0.785004 -0.235478 -0.554038 0.146156 +1403715351.61214 1.106480 -0.257038 1.076420 -0.780329 -0.234650 -0.560845 0.146555 +1403715351.66214 1.116310 -0.231538 1.078370 -0.777855 -0.234947 -0.564047 0.146945 +1403715351.71214 1.124870 -0.204943 1.080360 -0.777028 -0.236882 -0.564310 0.147205 +1403715351.76214 1.131950 -0.177340 1.082570 -0.777359 -0.239702 -0.562295 0.148593 +1403715351.81214 1.137580 -0.148633 1.085120 -0.777440 -0.242207 -0.559828 0.153350 +1403715351.86214 1.142030 -0.118981 1.088000 -0.777761 -0.245255 -0.556280 0.159658 +1403715351.91214 1.145430 -0.088703 1.090770 -0.777479 -0.249209 -0.552896 0.166518 +1403715351.96214 1.148280 -0.057790 1.093790 -0.777406 -0.252942 -0.548608 0.175185 +1403715352.01214 1.150490 -0.026611 1.097780 -0.776663 -0.257831 -0.544609 0.183624 +1403715352.06214 1.152220 0.004446 1.102420 -0.775818 -0.263285 -0.540424 0.191648 +1403715352.11214 1.154080 0.035287 1.108410 -0.774487 -0.269369 -0.537325 0.197212 +1403715352.16214 1.155790 0.065810 1.114500 -0.773163 -0.273706 -0.534626 0.203661 +1403715352.21214 1.157500 0.095830 1.120620 -0.771856 -0.276863 -0.532543 0.209723 +1403715352.26214 1.159510 0.125231 1.126500 -0.771295 -0.280208 -0.530201 0.213247 +1403715352.31214 1.162050 0.154291 1.131800 -0.771402 -0.283345 -0.527343 0.215788 +1403715352.36214 1.165140 0.182795 1.136820 -0.771042 -0.285646 -0.525707 0.218022 +1403715352.41214 1.168620 0.210683 1.140990 -0.771308 -0.284866 -0.523589 0.223135 +1403715352.46214 1.172450 0.237836 1.144520 -0.772163 -0.281426 -0.520701 0.231157 +1403715352.51214 1.177370 0.264202 1.147970 -0.772006 -0.278387 -0.519458 0.238057 +1403715352.56214 1.183440 0.289382 1.151090 -0.771004 -0.278363 -0.519828 0.240511 +1403715352.61214 1.190810 0.313278 1.154010 -0.768957 -0.281384 -0.522347 0.238081 +1403715352.66214 1.198960 0.335970 1.156140 -0.767286 -0.284493 -0.524388 0.235273 +1403715352.71214 1.207990 0.357805 1.158380 -0.764939 -0.286454 -0.527649 0.233234 +1403715352.76214 1.217350 0.378719 1.160440 -0.762011 -0.289186 -0.531840 0.229906 +1403715352.81214 1.226690 0.398637 1.162260 -0.759010 -0.290644 -0.536014 0.228296 +1403715352.86214 1.235840 0.417706 1.163650 -0.756753 -0.292370 -0.539051 0.226425 +1403715352.91214 1.244580 0.435893 1.164960 -0.755513 -0.294271 -0.540830 0.223849 +1403715352.96214 1.252500 0.453203 1.166260 -0.754818 -0.293860 -0.541619 0.224820 +1403715353.01214 1.259790 0.469837 1.167670 -0.754740 -0.292367 -0.541445 0.227435 +1403715353.06214 1.266660 0.485560 1.169500 -0.754678 -0.292473 -0.541276 0.227906 +1403715353.11214 1.273050 0.500436 1.172150 -0.754850 -0.293816 -0.540604 0.227203 +1403715353.16214 1.279020 0.514361 1.176570 -0.755346 -0.295388 -0.539339 0.226520 +1403715353.21214 1.284430 0.527438 1.183670 -0.755374 -0.296834 -0.538696 0.226068 +1403715353.26214 1.289240 0.539700 1.193810 -0.755188 -0.298191 -0.538060 0.226417 +1403715353.31214 1.293470 0.551120 1.206720 -0.755424 -0.299454 -0.536834 0.226875 +1403715353.36214 1.297230 0.561879 1.220740 -0.755699 -0.301231 -0.535345 0.227122 +1403715353.41214 1.300750 0.572202 1.233440 -0.755417 -0.304110 -0.534476 0.226270 +1403715353.46214 1.304050 0.582493 1.243360 -0.754687 -0.306471 -0.534228 0.226104 +1403715353.51214 1.307140 0.592489 1.249660 -0.754541 -0.308479 -0.533318 0.226010 +1403715353.56214 1.309910 0.601921 1.252140 -0.754222 -0.310537 -0.532810 0.225454 +1403715353.61214 1.312230 0.611094 1.250860 -0.753941 -0.312003 -0.532066 0.226128 +1403715353.66214 1.314310 0.619915 1.246930 -0.752998 -0.314184 -0.532331 0.225625 +1403715353.71214 1.315990 0.628449 1.241300 -0.752196 -0.316023 -0.532515 0.225296 +1403715353.76214 1.317150 0.636820 1.234780 -0.751334 -0.317764 -0.532647 0.225411 +1403715353.81214 1.317760 0.645418 1.227690 -0.750099 -0.319671 -0.533338 0.225195 +1403715353.86214 1.317830 0.654079 1.219950 -0.749536 -0.320733 -0.533267 0.225727 +1403715353.91214 1.317380 0.662781 1.211970 -0.748524 -0.321709 -0.533720 0.226622 +1403715353.96214 1.316240 0.671356 1.203200 -0.748511 -0.322684 -0.532928 0.227142 +1403715354.01214 1.314660 0.679869 1.193720 -0.748649 -0.323381 -0.531941 0.228008 +1403715354.06214 1.312590 0.688571 1.183460 -0.750471 -0.322780 -0.528660 0.230489 +1403715354.11214 1.310060 0.697190 1.173400 -0.752724 -0.319715 -0.524652 0.236493 +1403715354.16214 1.307520 0.705360 1.163310 -0.754889 -0.316502 -0.520792 0.242372 +1403715354.21214 1.305250 0.712835 1.153130 -0.756790 -0.314241 -0.517283 0.246858 +1403715354.26214 1.303870 0.719539 1.143480 -0.758173 -0.313808 -0.514745 0.248469 +1403715354.31214 1.303270 0.725487 1.134550 -0.758296 -0.314964 -0.514179 0.247801 +1403715354.36214 1.303520 0.730640 1.125540 -0.758439 -0.317632 -0.513837 0.244646 +1403715354.41214 1.304680 0.735368 1.116770 -0.758199 -0.321065 -0.514133 0.240246 +1403715354.46214 1.306730 0.740027 1.108190 -0.757801 -0.324285 -0.514518 0.236322 +1403715354.51214 1.309360 0.744675 1.099750 -0.757152 -0.326784 -0.515270 0.233302 +1403715354.56214 1.312310 0.749460 1.091660 -0.756792 -0.327800 -0.515707 0.232079 +1403715354.61214 1.315420 0.754478 1.085830 -0.756262 -0.327588 -0.516503 0.232332 +1403715354.66214 1.319000 0.759824 1.082370 -0.756207 -0.327408 -0.516767 0.232179 +1403715354.71214 1.323310 0.765585 1.082050 -0.756239 -0.326801 -0.516938 0.232547 +1403715354.76214 1.328210 0.771440 1.085360 -0.756304 -0.326242 -0.517175 0.232596 +1403715354.81214 1.333360 0.777529 1.091790 -0.756945 -0.325562 -0.516357 0.233279 +1403715354.86214 1.338770 0.783583 1.101200 -0.756698 -0.325618 -0.516895 0.232808 +1403715354.91214 1.344420 0.789937 1.113320 -0.756916 -0.323632 -0.516260 0.236254 +1403715354.96214 1.350330 0.796364 1.127240 -0.756773 -0.322144 -0.515966 0.239370 +1403715355.01214 1.356580 0.802541 1.142550 -0.755951 -0.320980 -0.516455 0.242455 +1403715355.06214 1.363420 0.808415 1.157350 -0.755334 -0.321528 -0.516733 0.243057 +1403715355.11214 1.370600 0.814021 1.171440 -0.754717 -0.323806 -0.516509 0.242425 +1403715355.16214 1.377920 0.819611 1.184870 -0.753335 -0.327385 -0.515896 0.243222 +1403715355.21214 1.385390 0.825150 1.197540 -0.752221 -0.331914 -0.513509 0.245570 +1403715355.26214 1.393150 0.830571 1.209760 -0.749592 -0.338123 -0.512083 0.248106 +1403715355.31214 1.401110 0.836125 1.221060 -0.746629 -0.346370 -0.509801 0.250353 +1403715355.36214 1.409130 0.841874 1.231850 -0.743104 -0.355043 -0.507277 0.253794 +1403715355.41214 1.417120 0.847860 1.242770 -0.738567 -0.363370 -0.505213 0.259307 +1403715355.46214 1.425250 0.853930 1.253270 -0.733919 -0.371538 -0.502303 0.266484 +1403715355.51214 1.433580 0.860070 1.263930 -0.728306 -0.379760 -0.500284 0.273987 +1403715355.56214 1.441890 0.865913 1.274180 -0.722826 -0.388469 -0.497660 0.280980 +1403715355.61214 1.450130 0.871688 1.283740 -0.717650 -0.397261 -0.494171 0.288021 +1403715355.66214 1.458810 0.877165 1.292500 -0.712279 -0.406468 -0.491634 0.292811 +1403715355.71214 1.467700 0.882292 1.300800 -0.707550 -0.414376 -0.489281 0.297101 +1403715355.76214 1.476810 0.886919 1.308520 -0.703564 -0.421277 -0.487259 0.300172 +1403715355.81214 1.485920 0.891108 1.315720 -0.700733 -0.427146 -0.485226 0.301785 +1403715355.86214 1.494980 0.895333 1.322680 -0.698883 -0.431757 -0.483047 0.303008 +1403715355.91214 1.504250 0.899886 1.329810 -0.697119 -0.435465 -0.481711 0.303890 +1403715355.96214 1.513800 0.904549 1.336630 -0.695782 -0.438988 -0.480916 0.303146 +1403715356.01214 1.523070 0.909269 1.343440 -0.694433 -0.441560 -0.481259 0.301957 +1403715356.06214 1.532210 0.914305 1.350220 -0.693421 -0.444420 -0.481993 0.298899 +1403715356.11214 1.540900 0.919674 1.356980 -0.692734 -0.446910 -0.483435 0.294418 +1403715356.16214 1.548930 0.925625 1.363550 -0.692510 -0.448386 -0.485109 0.289912 +1403715356.21214 1.556010 0.932082 1.370210 -0.692470 -0.448167 -0.487513 0.286291 +1403715356.26214 1.562300 0.939472 1.376350 -0.693112 -0.447022 -0.489373 0.283341 +1403715356.31214 1.567480 0.947495 1.381780 -0.694761 -0.445714 -0.490131 0.280033 +1403715356.36214 1.571590 0.956733 1.386300 -0.697943 -0.443709 -0.488936 0.277379 +1403715356.41214 1.574550 0.967144 1.390040 -0.701479 -0.441498 -0.487035 0.275325 +1403715356.46214 1.576520 0.978618 1.392980 -0.705361 -0.437945 -0.484790 0.275044 +1403715356.51214 1.577600 0.991148 1.395010 -0.710022 -0.432152 -0.481320 0.278287 +1403715356.56214 1.578240 1.004810 1.396550 -0.712927 -0.427771 -0.479102 0.281440 +1403715356.61214 1.578520 1.019720 1.397620 -0.714667 -0.424982 -0.476921 0.284934 +1403715356.66214 1.578640 1.035800 1.398420 -0.714821 -0.423609 -0.475377 0.289143 +1403715356.71214 1.578970 1.053160 1.399000 -0.714023 -0.424598 -0.473474 0.292762 +1403715356.76214 1.579520 1.071550 1.399400 -0.712222 -0.426715 -0.471565 0.297119 +1403715356.81214 1.580340 1.090410 1.399420 -0.709214 -0.430071 -0.469703 0.302381 +1403715356.86214 1.581570 1.109630 1.399000 -0.706089 -0.436054 -0.466296 0.306370 +1403715356.91214 1.583300 1.129720 1.398790 -0.702573 -0.441829 -0.462069 0.312522 +1403715356.96214 1.586010 1.150520 1.400400 -0.697749 -0.448066 -0.457977 0.320376 +1403715357.01214 1.589510 1.171820 1.403760 -0.690933 -0.456019 -0.455482 0.327406 +1403715357.06214 1.593750 1.193170 1.408350 -0.684295 -0.464528 -0.451445 0.334891 +1403715357.11214 1.598480 1.214560 1.414170 -0.676588 -0.473025 -0.448681 0.342289 +1403715357.16214 1.603710 1.235850 1.420300 -0.669036 -0.482166 -0.445573 0.348384 +1403715357.21214 1.609830 1.257170 1.427150 -0.661961 -0.490900 -0.442680 0.353356 +1403715357.26214 1.617010 1.278560 1.434640 -0.654691 -0.498493 -0.442017 0.357080 +1403715357.31214 1.625350 1.300150 1.442530 -0.648544 -0.505247 -0.442115 0.358679 +1403715357.36214 1.634480 1.322080 1.451340 -0.643459 -0.510951 -0.442514 0.359265 +1403715357.41214 1.643580 1.343750 1.459970 -0.640029 -0.514878 -0.442072 0.360327 +1403715357.46214 1.652620 1.365140 1.468240 -0.636713 -0.518617 -0.442694 0.360076 +1403715357.51214 1.661440 1.386380 1.475540 -0.635177 -0.522073 -0.441668 0.359054 +1403715357.56214 1.670010 1.407720 1.481610 -0.634167 -0.524974 -0.440614 0.357902 +1403715357.61214 1.678210 1.429240 1.487220 -0.633158 -0.527787 -0.439844 0.356494 +1403715357.66214 1.686030 1.451210 1.492380 -0.631556 -0.529808 -0.440501 0.355527 +1403715357.71214 1.693450 1.473480 1.498140 -0.628748 -0.530744 -0.443200 0.355753 +1403715357.76214 1.700260 1.495830 1.503080 -0.626717 -0.532313 -0.445129 0.354583 +1403715357.81214 1.706110 1.518340 1.507480 -0.623875 -0.534430 -0.448219 0.352511 +1403715357.86214 1.710790 1.541030 1.510530 -0.621558 -0.537006 -0.450879 0.349284 +1403715357.91214 1.714130 1.564140 1.512510 -0.620418 -0.538786 -0.452145 0.346923 +1403715357.96214 1.716130 1.587810 1.513710 -0.620674 -0.540127 -0.451805 0.344817 +1403715358.01214 1.716720 1.612010 1.514110 -0.621142 -0.541364 -0.451007 0.343074 +1403715358.06214 1.715780 1.636740 1.513950 -0.621798 -0.542367 -0.450193 0.341368 +1403715358.11214 1.713140 1.662120 1.513300 -0.623412 -0.541725 -0.448199 0.342066 +1403715358.16214 1.709010 1.688370 1.512380 -0.625390 -0.539731 -0.446038 0.344424 +1403715358.21214 1.703490 1.715650 1.510780 -0.628972 -0.537415 -0.441780 0.347001 +1403715358.26214 1.696770 1.743740 1.509550 -0.631231 -0.535364 -0.438980 0.349613 +1403715358.31214 1.689520 1.772700 1.507890 -0.633119 -0.534776 -0.436434 0.350286 +1403715358.36214 1.681910 1.803110 1.506230 -0.633255 -0.536036 -0.435129 0.349737 +1403715358.41214 1.673590 1.834460 1.504870 -0.630695 -0.539213 -0.435972 0.348429 +1403715358.46214 1.664260 1.866570 1.503230 -0.626797 -0.542577 -0.436897 0.349080 +1403715358.51214 1.653780 1.900040 1.501660 -0.621154 -0.545990 -0.438941 0.351274 +1403715358.56214 1.642390 1.934280 1.499720 -0.615660 -0.549236 -0.440319 0.354149 +1403715358.61214 1.629850 1.968880 1.497140 -0.610603 -0.551942 -0.440945 0.357897 +1403715358.66214 1.615950 2.003950 1.494650 -0.606338 -0.552953 -0.440330 0.364289 +1403715358.71214 1.600830 2.039150 1.492280 -0.603552 -0.551505 -0.437269 0.374651 +1403715358.76214 1.584940 2.074270 1.489940 -0.601064 -0.550580 -0.433677 0.384068 +1403715358.81214 1.568730 2.108990 1.487430 -0.598403 -0.550231 -0.430811 0.391870 +1403715358.86214 1.552330 2.143070 1.484580 -0.596004 -0.550253 -0.427790 0.398744 +1403715358.91214 1.536200 2.176330 1.481460 -0.592951 -0.550375 -0.426630 0.404331 +1403715358.96214 1.520040 2.208540 1.477610 -0.590508 -0.551548 -0.425116 0.407887 +1403715359.01214 1.504100 2.239850 1.473110 -0.589651 -0.552917 -0.421824 0.410681 +1403715359.06214 1.488580 2.270290 1.467930 -0.589119 -0.555226 -0.418802 0.411423 +1403715359.11214 1.473570 2.299400 1.463140 -0.588026 -0.556739 -0.417501 0.412262 +1403715359.16214 1.458920 2.327490 1.458370 -0.586342 -0.557611 -0.417568 0.413414 +1403715359.21214 1.444560 2.354730 1.453430 -0.584754 -0.557563 -0.418296 0.414987 +1403715359.26214 1.430730 2.380660 1.448660 -0.583167 -0.557893 -0.419760 0.415300 +1403715359.31214 1.417410 2.405200 1.444040 -0.581977 -0.558873 -0.421436 0.413951 +1403715359.36214 1.404130 2.428260 1.439240 -0.581277 -0.560161 -0.422763 0.411836 +1403715359.41214 1.390880 2.450060 1.435000 -0.580003 -0.561748 -0.425646 0.408487 +1403715359.46214 1.377310 2.470920 1.431180 -0.578594 -0.563246 -0.428845 0.405061 +1403715359.51214 1.363040 2.490700 1.428570 -0.577437 -0.564218 -0.431650 0.402371 +1403715359.56214 1.348040 2.509420 1.426900 -0.576701 -0.564066 -0.434120 0.400981 +1403715359.61214 1.331980 2.526990 1.425860 -0.576654 -0.563169 -0.435154 0.401188 +1403715359.66214 1.314860 2.543400 1.425100 -0.577782 -0.562167 -0.434537 0.401639 +1403715359.71214 1.296910 2.558670 1.424960 -0.579601 -0.560991 -0.432953 0.402371 +1403715359.76214 1.278170 2.572880 1.425260 -0.581724 -0.560149 -0.430801 0.402791 +1403715359.81214 1.258820 2.585810 1.426290 -0.583259 -0.558692 -0.429499 0.403984 +1403715359.86214 1.239050 2.597710 1.427700 -0.584721 -0.558570 -0.427871 0.403767 +1403715359.91214 1.218930 2.608460 1.429200 -0.587294 -0.558436 -0.424545 0.403729 +1403715359.96214 1.198650 2.618340 1.430930 -0.590362 -0.557326 -0.420317 0.405209 +1403715360.01214 1.178460 2.627520 1.433080 -0.591862 -0.557903 -0.418071 0.404549 +1403715360.06214 1.158400 2.636190 1.435060 -0.592681 -0.558848 -0.416728 0.403430 +1403715360.11214 1.138380 2.644550 1.437010 -0.592921 -0.559858 -0.415962 0.402467 +1403715360.16214 1.118430 2.652830 1.439070 -0.592691 -0.560937 -0.415763 0.401507 +1403715360.21214 1.098700 2.660830 1.441120 -0.592535 -0.561725 -0.415571 0.400835 +1403715360.26214 1.079370 2.668330 1.443310 -0.592998 -0.561682 -0.415432 0.400352 +1403715360.31214 1.060410 2.675510 1.445350 -0.594803 -0.559945 -0.415118 0.400435 +1403715360.36214 1.042040 2.682470 1.447300 -0.598917 -0.555726 -0.413398 0.401956 +1403715360.41214 1.024330 2.689010 1.449440 -0.604553 -0.549480 -0.411153 0.404402 +1403715360.46214 1.007610 2.695020 1.451830 -0.611131 -0.542317 -0.409336 0.406025 +1403715360.51214 0.992243 2.700850 1.454150 -0.618157 -0.534351 -0.408475 0.406817 +1403715360.56214 0.978504 2.706390 1.456060 -0.624894 -0.526369 -0.409359 0.406040 +1403715360.61214 0.966587 2.711610 1.458410 -0.631262 -0.519038 -0.412289 0.402648 +1403715360.66214 0.956678 2.716510 1.461690 -0.636672 -0.511961 -0.417688 0.397594 +1403715360.71214 0.948844 2.720380 1.465540 -0.642207 -0.504942 -0.423565 0.391404 +1403715360.76214 0.943018 2.723690 1.470000 -0.647057 -0.499366 -0.431187 0.382137 +1403715360.81214 0.938759 2.726530 1.474110 -0.652381 -0.493291 -0.438874 0.372092 +1403715360.86214 0.935479 2.729060 1.478630 -0.657641 -0.486900 -0.446790 0.361685 +1403715360.91214 0.933180 2.731170 1.483150 -0.662708 -0.479663 -0.455014 0.351716 +1403715360.96214 0.931466 2.733210 1.487720 -0.668797 -0.471804 -0.461746 0.341911 +1403715361.01214 0.930179 2.735090 1.492640 -0.675083 -0.463164 -0.467871 0.332924 +1403715361.06214 0.929047 2.736730 1.497490 -0.681607 -0.454105 -0.473474 0.324074 +1403715361.11214 0.927747 2.738300 1.502160 -0.688625 -0.444412 -0.478097 0.315781 +1403715361.16214 0.926266 2.739900 1.506830 -0.695545 -0.434616 -0.482379 0.307630 +1403715361.21214 0.924996 2.741560 1.511630 -0.702196 -0.425089 -0.486859 0.298645 +1403715361.26214 0.923666 2.743520 1.516480 -0.708443 -0.415372 -0.491300 0.290169 +1403715361.31214 0.922138 2.745630 1.521120 -0.714383 -0.405975 -0.495717 0.281258 +1403715361.36214 0.920516 2.747930 1.525670 -0.719749 -0.396335 -0.500720 0.272321 +1403715361.41214 0.918603 2.750430 1.529320 -0.725226 -0.386521 -0.505059 0.263749 +1403715361.46214 0.916252 2.753500 1.532210 -0.730360 -0.376744 -0.508969 0.256102 +1403715361.51214 0.913404 2.757250 1.534560 -0.734481 -0.368121 -0.512672 0.249384 +1403715361.56214 0.910078 2.761740 1.536160 -0.738212 -0.361053 -0.515340 0.243122 +1403715361.61214 0.906097 2.766880 1.537280 -0.741181 -0.355880 -0.517757 0.236491 +1403715361.66214 0.901633 2.772910 1.537790 -0.743856 -0.351035 -0.519377 0.231731 +1403715361.71214 0.896805 2.779830 1.537380 -0.747383 -0.345624 -0.519709 0.227738 +1403715361.76214 0.891801 2.787470 1.536060 -0.751829 -0.339647 -0.518987 0.223709 +1403715361.81214 0.886808 2.795950 1.534010 -0.756550 -0.333296 -0.517932 0.219756 +1403715361.86214 0.882002 2.805220 1.531420 -0.761448 -0.326403 -0.517062 0.215189 +1403715361.91214 0.877635 2.815160 1.528460 -0.765746 -0.319250 -0.517670 0.209119 +1403715361.96214 0.873538 2.826040 1.525620 -0.769150 -0.310514 -0.519811 0.204414 +1403715362.01214 0.869920 2.837550 1.522450 -0.772517 -0.301142 -0.522374 0.199141 +1403715362.06214 0.866735 2.849850 1.518850 -0.775668 -0.292107 -0.525385 0.192312 +1403715362.11214 0.864070 2.862850 1.514770 -0.778906 -0.282090 -0.528578 0.185298 +1403715362.16214 0.861832 2.876530 1.509890 -0.782448 -0.272331 -0.531393 0.176725 +1403715362.21214 0.860203 2.890840 1.504890 -0.785746 -0.261707 -0.534728 0.167865 +1403715362.26214 0.858986 2.905890 1.499630 -0.788650 -0.250532 -0.538575 0.158753 +1403715362.31214 0.858113 2.921880 1.493820 -0.792071 -0.239335 -0.541415 0.149038 +1403715362.36214 0.857546 2.938870 1.488030 -0.795430 -0.227455 -0.544144 0.139509 +1403715362.41214 0.856842 2.956760 1.482230 -0.798611 -0.215134 -0.546793 0.130212 +1403715362.46214 0.855982 2.975730 1.476350 -0.801595 -0.202059 -0.549418 0.121480 +1403715362.51214 0.855114 2.995590 1.470390 -0.804265 -0.188923 -0.552115 0.112404 +1403715362.56214 0.854398 3.016490 1.464420 -0.807316 -0.176594 -0.553684 0.102423 +1403715362.61214 0.853949 3.038600 1.458810 -0.809923 -0.163628 -0.555360 0.093944 +1403715362.66214 0.853726 3.061860 1.453830 -0.812145 -0.150854 -0.557078 0.085602 +1403715362.71214 0.853834 3.086200 1.449320 -0.814207 -0.137477 -0.558595 0.078346 +1403715362.76214 0.854271 3.111600 1.445130 -0.816395 -0.122557 -0.559505 0.073709 +1403715362.81214 0.854789 3.137820 1.441650 -0.818469 -0.106333 -0.560116 0.071219 +1403715362.86214 0.855384 3.164420 1.438570 -0.819985 -0.087911 -0.560939 0.072412 +1403715362.91214 0.856394 3.190920 1.436570 -0.819454 -0.068157 -0.563971 0.076068 +1403715362.96214 0.858090 3.216490 1.435710 -0.817624 -0.050709 -0.568263 0.077434 +1403715363.01214 0.860325 3.240620 1.435360 -0.815933 -0.034627 -0.571736 0.078557 +1403715363.06214 0.862713 3.262830 1.435550 -0.815063 -0.020589 -0.573763 0.077741 +1403715363.11214 0.864994 3.282670 1.436370 -0.814728 -0.008666 -0.574910 0.074984 +1403715363.16214 0.866990 3.299840 1.437230 -0.815968 0.001405 -0.573777 0.070537 +1403715363.21214 0.868872 3.314150 1.438840 -0.816897 0.010651 -0.573003 0.065060 +1403715363.26214 0.870896 3.325660 1.441170 -0.817508 0.019070 -0.572601 0.058695 +1403715363.31214 0.872986 3.334610 1.444070 -0.818117 0.027451 -0.571973 0.052694 +1403715363.36214 0.874802 3.340880 1.447500 -0.818216 0.035705 -0.571938 0.046199 +1403715363.41214 0.876484 3.344790 1.451570 -0.817732 0.043512 -0.572586 0.039580 +1403715363.46214 0.878061 3.345960 1.455930 -0.817227 0.051331 -0.573123 0.032175 +1403715363.51214 0.879505 3.344610 1.460690 -0.816635 0.058918 -0.573625 0.024295 +1403715363.56214 0.880719 3.340970 1.465890 -0.816279 0.064753 -0.573854 0.013681 +1403715363.61214 0.882004 3.335200 1.471270 -0.815986 0.068883 -0.573953 0.000319 +1403715363.66214 0.883334 3.327730 1.476730 0.815549 -0.074279 0.573791 0.011231 +1403715363.71214 0.884671 3.318820 1.482460 0.814525 -0.080350 0.574084 0.022818 +1403715363.76214 0.885798 3.308960 1.488010 0.813158 -0.088290 0.574369 0.032841 +1403715363.81214 0.886619 3.298450 1.493440 0.811529 -0.097331 0.574571 0.042599 +1403715363.86214 0.887206 3.287370 1.498460 0.809915 -0.108115 0.574204 0.051365 +1403715363.91214 0.887445 3.275820 1.503650 0.807675 -0.118881 0.574271 0.061167 +1403715363.96214 0.887230 3.263550 1.509050 0.804525 -0.129991 0.574987 0.072328 +1403715364.01214 0.886468 3.250990 1.514030 0.801750 -0.142783 0.574544 0.081913 +1403715364.06214 0.885197 3.238210 1.519110 0.798586 -0.154978 0.574227 0.092226 +1403715364.11214 0.883199 3.225620 1.524420 0.795402 -0.166647 0.573954 0.100704 +1403715364.16214 0.880386 3.213370 1.529980 0.792314 -0.176713 0.573761 0.108674 +1403715364.21214 0.877147 3.201600 1.535140 0.790675 -0.185292 0.572064 0.115074 +1403715364.26214 0.873766 3.190200 1.540550 0.789443 -0.193412 0.570276 0.118985 +1403715364.31214 0.869655 3.178910 1.546230 0.788847 -0.200774 0.568166 0.120818 +1403715364.36214 0.864761 3.168000 1.552150 0.788964 -0.206921 0.565688 0.121312 +1403715364.41214 0.859515 3.157100 1.558760 0.788838 -0.212274 0.564060 0.120460 +1403715364.46214 0.854089 3.145670 1.565930 0.788358 -0.215639 0.563402 0.120706 +1403715364.51214 0.848337 3.133530 1.572900 0.788310 -0.218541 0.562688 0.119116 +1403715364.56214 0.841697 3.120810 1.580460 0.787929 -0.219951 0.562879 0.118136 +1403715364.61214 0.834548 3.107130 1.588430 0.787823 -0.220438 0.562859 0.118030 +1403715364.66214 0.826842 3.092330 1.596630 0.786886 -0.221272 0.563678 0.118811 +1403715364.71214 0.818293 3.076510 1.605750 0.785703 -0.220896 0.564546 0.123137 +1403715364.76214 0.808699 3.059910 1.614990 0.785491 -0.220003 0.563612 0.130169 +1403715364.81214 0.798569 3.042930 1.623670 0.786300 -0.219430 0.560761 0.138313 +1403715364.86214 0.788116 3.025930 1.632100 0.787230 -0.220155 0.557257 0.145823 +1403715364.91214 0.777585 3.009260 1.640390 0.787717 -0.222546 0.554021 0.151777 +1403715364.96214 0.767172 2.992910 1.648700 0.788206 -0.225304 0.550293 0.158574 +1403715365.01214 0.757124 2.976800 1.657020 0.787667 -0.230364 0.547788 0.162606 +1403715365.06214 0.747296 2.960760 1.665330 0.787353 -0.234950 0.544655 0.168004 +1403715365.11214 0.737832 2.945170 1.673950 0.785418 -0.240235 0.543557 0.173066 +1403715365.16214 0.728835 2.930250 1.682840 0.781831 -0.245950 0.544508 0.178214 +1403715365.21214 0.720392 2.916010 1.691670 0.778503 -0.251639 0.545017 0.183216 +1403715365.26214 0.712366 2.902630 1.700070 0.775739 -0.256340 0.545058 0.188231 +1403715365.31214 0.704638 2.890090 1.707960 0.773443 -0.260410 0.544826 0.192711 +1403715365.36214 0.697288 2.878580 1.715300 0.771303 -0.264879 0.544555 0.195935 +1403715365.41214 0.690104 2.867910 1.722300 0.768360 -0.270943 0.544870 0.198314 +1403715365.46214 0.682667 2.857980 1.728790 0.765955 -0.277079 0.543800 0.202044 +1403715365.51214 0.675189 2.848870 1.734930 0.762641 -0.284216 0.543398 0.205715 +1403715365.56214 0.667618 2.840520 1.740720 0.759619 -0.291736 0.541744 0.210674 +1403715365.61214 0.659756 2.832900 1.746290 0.755324 -0.301778 0.540999 0.213858 +1403715365.66214 0.651590 2.825790 1.751740 0.750191 -0.313277 0.540547 0.216518 +1403715365.71214 0.643120 2.818960 1.756870 0.744817 -0.325292 0.539675 0.219507 +1403715365.76214 0.634023 2.812100 1.761650 0.739433 -0.337466 0.538152 0.223045 +1403715365.81214 0.624132 2.805570 1.766230 0.734436 -0.348980 0.535867 0.227295 +1403715365.86214 0.613583 2.799380 1.770890 0.729709 -0.358741 0.533778 0.232185 +1403715365.91214 0.602349 2.793550 1.775180 0.725713 -0.367652 0.531157 0.236737 +1403715365.96214 0.590627 2.787770 1.779120 0.722124 -0.375848 0.528879 0.239922 +1403715366.01214 0.578317 2.782010 1.782570 0.717614 -0.383879 0.528803 0.240906 +1403715366.06214 0.565171 2.776180 1.785290 0.714173 -0.391080 0.528007 0.241293 +1403715366.11214 0.550984 2.770030 1.787710 0.710459 -0.397881 0.528290 0.240519 +1403715366.16214 0.535383 2.763660 1.790170 0.707770 -0.402096 0.528085 0.241881 +1403715366.21214 0.518076 2.757220 1.792010 0.705752 -0.405093 0.528000 0.242959 +1403715366.26214 0.499304 2.750440 1.793670 0.704155 -0.407000 0.527973 0.244459 +1403715366.31214 0.479267 2.743200 1.795510 0.703941 -0.407348 0.526855 0.246900 +1403715366.36214 0.458053 2.735450 1.797480 0.703834 -0.407195 0.526071 0.249117 +1403715366.41214 0.435474 2.727590 1.799070 0.705850 -0.406224 0.523092 0.251260 +1403715366.46214 0.411455 2.719640 1.800760 0.708349 -0.403703 0.519579 0.255545 +1403715366.51214 0.386956 2.711530 1.802540 0.711067 -0.400927 0.516122 0.259346 +1403715366.56214 0.362083 2.703510 1.803810 0.713464 -0.398899 0.513515 0.261058 +1403715366.61214 0.336877 2.695360 1.804650 0.716251 -0.397242 0.510411 0.262037 +1403715366.66214 0.311982 2.687070 1.805360 0.718615 -0.395604 0.508066 0.262602 +1403715366.71214 0.287462 2.678620 1.805890 0.721196 -0.394175 0.505776 0.262093 +1403715366.76214 0.263036 2.670000 1.806480 0.723416 -0.393446 0.503808 0.260858 +1403715366.81214 0.238709 2.661240 1.806840 0.726236 -0.392650 0.501016 0.259596 +1403715366.86214 0.214838 2.652010 1.807550 0.728569 -0.391871 0.499067 0.257985 +1403715366.91214 0.191647 2.642220 1.808790 0.730071 -0.391050 0.498197 0.256663 +1403715366.96214 0.169051 2.632050 1.810240 0.731151 -0.391380 0.497776 0.253887 +1403715367.01214 0.147073 2.621210 1.812210 0.731980 -0.391166 0.497822 0.251729 +1403715367.06214 0.125845 2.609610 1.814670 0.732312 -0.391168 0.498440 0.249530 +1403715367.11214 0.105235 2.597180 1.817540 0.732866 -0.390666 0.498835 0.247893 +1403715367.16214 0.085327 2.583920 1.820530 0.733718 -0.390377 0.498866 0.245756 +1403715367.21214 0.066009 2.569680 1.824070 0.734180 -0.389054 0.499485 0.245219 +1403715367.26214 0.047191 2.554620 1.827270 0.734193 -0.389365 0.500588 0.242420 +1403715367.31214 0.028481 2.538580 1.830160 0.735294 -0.389033 0.500070 0.240678 +1403715367.36214 0.010388 2.521170 1.833030 0.736277 -0.389275 0.499542 0.238368 +1403715367.41214 -0.007480 2.502620 1.835680 0.736979 -0.389091 0.499424 0.236741 +1403715367.46214 -0.024984 2.482880 1.838330 0.737543 -0.388470 0.499576 0.235678 +1403715367.51214 -0.042358 2.461910 1.841220 0.738648 -0.388124 0.498788 0.234454 +1403715367.56214 -0.059263 2.439520 1.844420 0.739450 -0.387231 0.498663 0.233668 +1403715367.61214 -0.075794 2.415810 1.847940 0.739570 -0.386302 0.499446 0.233156 +1403715367.66214 -0.091836 2.390940 1.851480 0.739664 -0.385746 0.500239 0.232074 +1403715367.71214 -0.107402 2.364670 1.855380 0.739725 -0.384173 0.501055 0.232730 +1403715367.76214 -0.122452 2.337180 1.859420 0.739823 -0.383174 0.501751 0.232563 +1403715367.81214 -0.137044 2.308530 1.863630 0.740026 -0.381570 0.502225 0.233532 +1403715367.86214 -0.151407 2.279010 1.868040 0.739913 -0.379412 0.503099 0.235512 +1403715367.91214 -0.165434 2.248410 1.872500 0.739209 -0.376736 0.504579 0.238830 +1403715367.96214 -0.178810 2.217070 1.877100 0.736939 -0.374938 0.508041 0.241322 +1403715368.01214 -0.191855 2.185190 1.881140 0.734716 -0.373977 0.511153 0.243015 +1403715368.06214 -0.204671 2.152900 1.884730 0.732192 -0.373811 0.514556 0.243704 +1403715368.11214 -0.217608 2.120500 1.887590 0.730383 -0.373756 0.516822 0.244422 +1403715368.16214 -0.230706 2.088090 1.889740 0.728655 -0.374239 0.518798 0.244653 +1403715368.21214 -0.244089 2.055890 1.891100 0.727389 -0.375216 0.520128 0.244101 +1403715368.26214 -0.257909 2.023900 1.891780 0.725879 -0.377258 0.521766 0.241942 +1403715368.31214 -0.272302 1.991820 1.892190 0.724590 -0.379496 0.523012 0.239603 +1403715368.36214 -0.287414 1.959570 1.892260 0.722442 -0.382426 0.525379 0.236229 +1403715368.41214 -0.303565 1.927080 1.892020 0.720701 -0.384680 0.527245 0.233717 +1403715368.46214 -0.320475 1.894100 1.891860 0.718312 -0.386179 0.529958 0.232462 +1403715368.51214 -0.338507 1.860670 1.891490 0.716710 -0.386953 0.531515 0.232563 +1403715368.56214 -0.358020 1.827100 1.890920 0.716272 -0.385938 0.531571 0.235456 +1403715368.61214 -0.378786 1.793380 1.890120 0.717140 -0.383573 0.529855 0.240490 +1403715368.66214 -0.400713 1.759740 1.889080 0.718683 -0.381138 0.527200 0.245538 +1403715368.71214 -0.423455 1.726530 1.887540 0.719756 -0.379958 0.525160 0.248576 +1403715368.76214 -0.446957 1.693350 1.886090 0.720755 -0.378714 0.523025 0.252056 +1403715368.81214 -0.470945 1.660660 1.884720 0.721391 -0.377742 0.521435 0.254971 +1403715368.86214 -0.495095 1.628590 1.883110 0.722011 -0.378103 0.519807 0.256007 +1403715368.91214 -0.519242 1.596910 1.881520 0.723101 -0.377609 0.518477 0.256356 +1403715368.96214 -0.543414 1.566170 1.879740 0.725126 -0.376457 0.517101 0.255106 +1403715369.01214 -0.567359 1.536100 1.877640 0.728023 -0.374734 0.515734 0.252141 +1403715369.06214 -0.591197 1.506310 1.875780 0.731726 -0.371924 0.514517 0.248035 +1403715369.11214 -0.614671 1.476790 1.874440 0.735753 -0.367530 0.514135 0.243423 +1403715369.16214 -0.637539 1.447270 1.873010 0.740212 -0.361533 0.514151 0.238809 +1403715369.21214 -0.659749 1.417560 1.871940 0.744802 -0.354591 0.514818 0.233446 +1403715369.26214 -0.681431 1.387810 1.871230 0.749498 -0.345750 0.516036 0.228947 +1403715369.31214 -0.702672 1.358390 1.870320 0.754601 -0.336834 0.517138 0.222907 +1403715369.36214 -0.723112 1.328780 1.870000 0.759155 -0.327069 0.519361 0.216735 +1403715369.41214 -0.742783 1.299140 1.869670 0.764236 -0.316702 0.521019 0.210196 +1403715369.46214 -0.761467 1.269450 1.869470 0.768978 -0.306352 0.523112 0.202917 +1403715369.51214 -0.779491 1.239740 1.869340 0.773532 -0.295618 0.525453 0.195341 +1403715369.56214 -0.796937 1.210080 1.869110 0.777850 -0.284751 0.527878 0.187648 +1403715369.61214 -0.813679 1.180540 1.868780 0.782033 -0.273445 0.530313 0.180057 +1403715369.66214 -0.829679 1.150850 1.868590 0.785968 -0.262680 0.532228 0.173166 +1403715369.71214 -0.845136 1.120570 1.868360 0.789094 -0.253043 0.534110 0.167408 +1403715369.76214 -0.859959 1.090060 1.867990 0.792102 -0.243880 0.535253 0.163096 +1403715369.81214 -0.873995 1.059300 1.867380 0.794658 -0.236634 0.535911 0.159131 +1403715369.86214 -0.887207 1.028400 1.866450 0.797001 -0.229673 0.535968 0.157409 +1403715369.91214 -0.899374 0.997473 1.864850 0.799727 -0.224209 0.534600 0.156105 +1403715369.96214 -0.910501 0.966549 1.862810 0.802622 -0.219890 0.532359 0.155051 +1403715370.01214 -0.920372 0.935725 1.860630 0.805070 -0.215690 0.530140 0.155857 +1403715370.06214 -0.928746 0.905205 1.858140 0.807003 -0.211547 0.528235 0.157991 +1403715370.11214 -0.935438 0.874938 1.855780 0.807634 -0.208467 0.527883 0.160026 +1403715370.16214 -0.940273 0.845137 1.853790 0.806417 -0.205433 0.530165 0.162525 +1403715370.21214 -0.943345 0.816246 1.851830 0.803418 -0.206626 0.534828 0.160575 +1403715370.26214 -0.945313 0.788148 1.850260 0.800103 -0.208946 0.539645 0.157990 +1403715370.31214 -0.946212 0.760704 1.848650 0.797354 -0.211440 0.543480 0.155400 +1403715370.36214 -0.946575 0.734071 1.847190 0.794676 -0.215102 0.546956 0.151857 +1403715370.41214 -0.946388 0.707901 1.845980 0.792203 -0.219253 0.549970 0.147904 +1403715370.46214 -0.946038 0.682192 1.844900 0.790509 -0.222847 0.551718 0.145059 +1403715370.51214 -0.945631 0.656514 1.844120 0.788896 -0.226039 0.553158 0.143407 +1403715370.56214 -0.945457 0.630812 1.843210 0.787960 -0.228607 0.553769 0.142116 +1403715370.61214 -0.945610 0.604969 1.842770 0.786839 -0.230164 0.554661 0.142337 +1403715370.66214 -0.946262 0.578880 1.842030 0.786518 -0.232063 0.554411 0.142004 +1403715370.71214 -0.947158 0.552441 1.841430 0.786246 -0.232850 0.554284 0.142712 +1403715370.76214 -0.948058 0.525789 1.841160 0.786373 -0.232189 0.553696 0.145350 +1403715370.81214 -0.949233 0.499100 1.841020 0.787081 -0.231210 0.552332 0.148239 +1403715370.86214 -0.950600 0.472451 1.840810 0.788144 -0.230533 0.550385 0.150860 +1403715370.91214 -0.951922 0.445970 1.840350 0.788906 -0.230516 0.548892 0.152337 +1403715370.96214 -0.953097 0.419685 1.839120 0.790706 -0.231273 0.545808 0.152939 +1403715371.01214 -0.953859 0.393344 1.837340 0.793584 -0.232501 0.541131 0.152789 +1403715371.06214 -0.954386 0.366886 1.835060 0.797675 -0.234170 0.534545 0.152124 +1403715371.11214 -0.953862 0.340314 1.832720 0.801625 -0.235321 0.528126 0.152001 +1403715371.16214 -0.952061 0.313563 1.830320 0.804906 -0.236461 0.522751 0.151470 +1403715371.21214 -0.948542 0.286213 1.827700 0.807662 -0.236916 0.518233 0.151619 +1403715371.26214 -0.943121 0.258099 1.825020 0.809145 -0.237171 0.515695 0.151965 +1403715371.31214 -0.935657 0.229173 1.822200 0.809706 -0.236828 0.514801 0.152540 +1403715371.36214 -0.926450 0.199700 1.819270 0.809786 -0.236679 0.514689 0.152724 +1403715371.41214 -0.915576 0.169724 1.816380 0.809002 -0.236091 0.516061 0.153160 +1403715371.46214 -0.903066 0.139231 1.813920 0.805941 -0.236339 0.520944 0.152381 +1403715371.51214 -0.889003 0.108261 1.811750 0.801366 -0.237706 0.527969 0.150189 +1403715371.56214 -0.873975 0.076955 1.809550 0.796708 -0.239306 0.535159 0.146951 +1403715371.61214 -0.858213 0.044999 1.807130 0.792576 -0.240563 0.541432 0.144240 +1403715371.66214 -0.842255 0.012421 1.804580 0.788783 -0.242295 0.547023 0.140994 +1403715371.71214 -0.826424 -0.020843 1.801620 0.785938 -0.244435 0.551181 0.136943 +1403715371.76214 -0.810884 -0.055031 1.798560 0.784262 -0.245523 0.553780 0.134088 +1403715371.81214 -0.795779 -0.090385 1.795420 0.783384 -0.245408 0.555261 0.133302 +1403715371.86214 -0.781521 -0.126297 1.791440 0.785312 -0.243099 0.553115 0.135099 +1403715371.91214 -0.768093 -0.162900 1.787470 0.787424 -0.239752 0.550695 0.138627 +1403715371.96214 -0.754850 -0.200122 1.783440 0.789464 -0.236170 0.548317 0.142542 +1403715372.01214 -0.741627 -0.237579 1.779420 0.791174 -0.233889 0.546265 0.144689 +1403715372.06214 -0.728148 -0.275338 1.775970 0.791111 -0.231852 0.546700 0.146652 +1403715372.11214 -0.714525 -0.313110 1.772830 0.790631 -0.230874 0.547651 0.147235 +1403715372.16214 -0.700594 -0.350938 1.770170 0.790154 -0.229851 0.548819 0.147048 +1403715372.21214 -0.686438 -0.388626 1.768560 0.789581 -0.228631 0.550789 0.144645 +1403715372.26214 -0.671786 -0.426291 1.768000 0.790070 -0.225462 0.551713 0.143420 +1403715372.31214 -0.657032 -0.463801 1.768260 0.790835 -0.221379 0.552876 0.141063 +1403715372.36214 -0.642203 -0.501071 1.769450 0.792091 -0.216244 0.553885 0.137996 +1403715372.41214 -0.627168 -0.538120 1.772050 0.793215 -0.209168 0.555650 0.135323 +1403715372.46214 -0.612208 -0.575043 1.775570 0.794317 -0.203392 0.557018 0.132000 +1403715372.51214 -0.597306 -0.611674 1.780080 0.795562 -0.197656 0.557888 0.129514 +1403715372.56214 -0.582342 -0.648189 1.786020 0.796034 -0.192291 0.559575 0.127395 +1403715372.61214 -0.567440 -0.684483 1.792450 0.796537 -0.187972 0.560840 0.125111 +1403715372.66214 -0.552525 -0.720643 1.798940 0.797118 -0.184028 0.561680 0.123498 +1403715372.71214 -0.537836 -0.756480 1.805210 0.797513 -0.181469 0.562440 0.121257 +1403715372.76214 -0.523408 -0.791901 1.810720 0.798229 -0.178906 0.562439 0.120357 +1403715372.81214 -0.509172 -0.827009 1.815920 0.798307 -0.177303 0.563126 0.118989 +1403715372.86214 -0.495033 -0.861936 1.820660 0.798678 -0.176462 0.563193 0.117423 +1403715372.91214 -0.480828 -0.896641 1.825040 0.798680 -0.176619 0.563609 0.115158 +1403715372.96214 -0.466720 -0.931141 1.829220 0.798349 -0.177423 0.564322 0.112693 +1403715373.01214 -0.452734 -0.965459 1.833210 0.798375 -0.178383 0.564425 0.110463 +1403715373.06214 -0.438838 -0.999697 1.836810 0.798105 -0.179405 0.564843 0.108600 +1403715373.11214 -0.425208 -1.033960 1.839950 0.797779 -0.180546 0.565202 0.107230 +1403715373.16214 -0.411897 -1.068340 1.842840 0.797577 -0.181440 0.565369 0.106337 +1403715373.21214 -0.398847 -1.102990 1.845490 0.797309 -0.182259 0.565530 0.106089 +1403715373.26214 -0.386308 -1.137650 1.848110 0.797497 -0.182525 0.565008 0.107003 +1403715373.31214 -0.373940 -1.172410 1.851270 0.797537 -0.181272 0.564723 0.110288 +1403715373.36214 -0.361808 -1.206990 1.854220 0.797419 -0.181277 0.564542 0.112047 +1403715373.41214 -0.349832 -1.241450 1.857090 0.797289 -0.181412 0.564420 0.113357 +1403715373.46214 -0.337914 -1.275550 1.859760 0.797117 -0.181110 0.564431 0.114981 +1403715373.51214 -0.326112 -1.309100 1.861770 0.797351 -0.180040 0.564301 0.115679 +1403715373.56214 -0.314170 -1.342300 1.863780 0.797804 -0.176548 0.564433 0.117283 +1403715373.61214 -0.302102 -1.374840 1.865390 0.799434 -0.170580 0.563472 0.119616 +1403715373.66214 -0.289992 -1.406400 1.866910 0.800862 -0.163479 0.563380 0.120406 +1403715373.71214 -0.277875 -1.436570 1.868290 0.802350 -0.154462 0.563749 0.120678 +1403715373.76214 -0.265445 -1.465160 1.869650 0.803930 -0.145580 0.564356 0.118347 +1403715373.81214 -0.252410 -1.492080 1.870460 0.805279 -0.136912 0.565651 0.113222 +1403715373.86214 -0.238755 -1.517460 1.871180 0.806911 -0.128240 0.566800 0.105766 +1403715373.91214 -0.224745 -1.541400 1.872190 0.808469 -0.119180 0.568103 0.097124 +1403715373.96214 -0.210642 -1.564030 1.873460 0.809765 -0.109850 0.569702 0.087478 +1403715374.01214 -0.196794 -1.585280 1.874320 0.811255 -0.099356 0.570845 0.078296 +1403715374.06214 -0.183117 -1.605090 1.874500 0.812550 -0.088657 0.572022 0.068509 +1403715374.11214 -0.169230 -1.623640 1.874530 0.813563 -0.077584 0.573293 0.058582 +1403715374.16214 -0.155539 -1.641120 1.874570 0.814798 -0.065386 0.573847 0.050279 +1403715374.21214 -0.141833 -1.657610 1.874620 0.815889 -0.053790 0.574256 0.040763 +1403715374.26214 -0.128628 -1.673380 1.874690 0.816677 -0.042044 0.574694 0.031591 +1403715374.31214 -0.115510 -1.688390 1.874520 0.818017 -0.030976 0.573943 0.021890 +1403715374.36214 -0.102866 -1.703210 1.874730 0.819223 -0.019672 0.572964 0.014103 +1403715374.41214 -0.090406 -1.717650 1.875100 0.820797 -0.009678 0.571091 0.007359 +1403715374.46214 -0.077716 -1.731630 1.875670 0.822373 -0.001188 0.568945 0.001720 +1403715374.51214 -0.064772 -1.745220 1.875860 -0.825135 -0.005788 -0.564901 0.002470 +1403715374.56214 -0.051423 -1.758440 1.876330 -0.827178 -0.011283 -0.561797 0.005800 +1403715374.61214 -0.037828 -1.771300 1.876870 -0.829372 -0.015845 -0.558417 0.007866 +1403715374.66214 -0.023285 -1.783440 1.877610 -0.830888 -0.018456 -0.556044 0.010000 +1403715374.71214 -0.007511 -1.794970 1.878510 -0.831963 -0.020751 -0.554334 0.010939 +1403715374.76214 0.009344 -1.806010 1.879610 -0.832686 -0.022291 -0.553188 0.010979 +1403715374.81214 0.027552 -1.816340 1.880860 -0.833030 -0.023309 -0.552637 0.010493 +1403715374.86214 0.047268 -1.825980 1.882010 -0.833162 -0.023333 -0.552445 0.010060 +1403715374.91214 0.068345 -1.834820 1.883330 -0.832670 -0.023804 -0.553196 0.008246 +1403715374.96214 0.090446 -1.842640 1.885010 -0.830351 -0.023679 -0.556695 0.006877 +1403715375.01214 0.113515 -1.849460 1.886280 -0.828211 -0.022953 -0.559918 0.005598 +1403715375.06214 0.137592 -1.855280 1.887600 -0.826074 -0.022770 -0.563094 0.003103 +1403715375.11214 0.162165 -1.859840 1.888270 -0.824752 -0.021614 -0.565080 0.001457 +1403715375.16214 0.187143 -1.863320 1.888650 -0.823421 -0.019879 -0.567082 0.000201 +1403715375.21214 0.212390 -1.865570 1.888710 0.822327 0.017716 0.568738 0.000936 +1403715375.26214 0.237578 -1.866550 1.888010 0.822106 0.014970 0.569136 0.001228 +1403715375.31214 0.262677 -1.866550 1.886940 0.821939 0.012559 0.569432 0.002405 +1403715375.36214 0.287546 -1.865740 1.885540 0.821519 0.008597 0.570115 0.001259 +1403715375.41214 0.312866 -1.864330 1.883760 0.822328 0.006959 0.568959 0.003776 +1403715375.46214 0.338500 -1.861910 1.882130 0.822058 0.003663 0.569382 0.003391 +1403715375.51214 0.364210 -1.858850 1.880140 0.822374 0.001214 0.568933 0.003836 +1403715375.56214 0.390272 -1.855070 1.877730 0.822654 -0.002196 0.568529 0.003127 +1403715375.61214 0.416156 -1.850810 1.874920 0.822699 -0.004901 0.568447 0.003175 +1403715375.66214 0.442124 -1.846310 1.871740 0.822332 -0.007210 0.568951 0.003531 +1403715375.71214 0.468369 -1.841450 1.868560 0.821546 -0.008524 0.570056 0.004950 +1403715375.76214 0.495063 -1.836000 1.865220 0.820824 -0.009837 0.571069 0.005517 +1403715375.81214 0.521782 -1.830250 1.861940 0.820178 -0.010815 0.571969 0.006521 +1403715375.86214 0.548674 -1.824100 1.859070 0.819218 -0.010628 0.573318 0.008637 +1403715375.91214 0.575631 -1.817480 1.855950 0.818830 -0.009607 0.573844 0.011342 +1403715375.96214 0.602263 -1.810220 1.853280 0.817709 -0.009232 0.575416 0.012742 +1403715376.01214 0.628576 -1.802450 1.850550 0.816996 -0.008217 0.576407 0.014306 +1403715376.06214 0.654516 -1.793970 1.847180 0.816468 -0.008878 0.577168 0.013387 +1403715376.11214 0.679932 -1.784900 1.843160 0.816083 -0.009805 0.577742 0.011231 +1403715376.16214 0.704798 -1.775480 1.838680 0.815582 -0.011077 0.578479 0.008088 +1403715376.21214 0.729387 -1.765780 1.833940 0.815031 -0.012749 0.579256 0.004892 +1403715376.26214 0.753401 -1.755750 1.828780 0.814579 -0.013997 0.579880 0.001976 +1403715376.31214 0.776979 -1.745630 1.824380 0.811072 -0.013624 0.584787 0.001345 +1403715376.36214 0.799886 -1.735570 1.820100 0.806154 -0.013506 0.591552 0.000576 +1403715376.41214 0.821714 -1.725450 1.815630 0.802376 -0.011292 0.596707 0.002540 +1403715376.46214 0.841869 -1.715290 1.810200 0.802343 -0.008423 0.596776 0.005719 +1403715376.51214 0.860561 -1.704840 1.803990 0.804460 -0.005679 0.593921 0.008283 +1403715376.56214 0.878113 -1.693900 1.797540 0.807366 -0.003276 0.589959 0.009838 +1403715376.61214 0.894474 -1.682330 1.790990 0.809736 -0.001248 0.586692 0.010876 +1403715376.66214 0.910007 -1.670160 1.784270 0.812383 0.000335 0.583022 0.010926 +1403715376.71214 0.924845 -1.657360 1.778200 0.813323 0.001430 0.581719 0.010312 +1403715376.76214 0.939020 -1.643850 1.772430 0.813495 0.003374 0.581463 0.010763 +1403715376.81214 0.952553 -1.629690 1.766990 0.812463 0.004899 0.582897 0.010544 +1403715376.86214 0.965342 -1.614840 1.762180 0.810466 0.005869 0.585685 0.009126 +1403715376.91214 0.977100 -1.599250 1.758160 0.806651 0.007009 0.590937 0.007696 +1403715376.96214 0.987674 -1.582850 1.754730 0.801879 0.009128 0.597369 0.007508 +1403715377.01214 0.996602 -1.565660 1.750520 0.798883 0.009451 0.601395 0.004442 +1403715377.06214 1.003860 -1.547800 1.745570 0.798819 0.011424 0.601452 0.003537 +1403715377.11214 1.009490 -1.529340 1.739850 0.801856 0.013393 0.597359 0.003294 +1403715377.16214 1.013590 -1.510440 1.734420 0.804775 0.016118 0.593348 0.004015 +1403715377.21214 1.016570 -1.490650 1.729080 0.807461 0.018373 0.589619 0.004405 +1403715377.26214 1.018650 -1.469920 1.724000 0.809284 0.020054 0.587063 0.003682 +1403715377.31214 1.019700 -1.448190 1.719440 0.810324 0.020670 0.585614 0.001757 +1403715377.36214 1.019780 -1.425720 1.715290 0.810348 0.021358 0.585560 0.000397 +1403715377.41214 1.019050 -1.402480 1.711300 -0.809276 -0.021420 -0.587033 0.002277 +1403715377.46214 1.017400 -1.378770 1.707360 -0.808273 -0.022147 -0.588383 0.003226 +1403715377.51214 1.014700 -1.354450 1.703260 -0.807703 -0.022686 -0.589135 0.004494 +1403715377.56214 1.011100 -1.329530 1.699020 -0.807606 -0.022636 -0.589257 0.006082 +1403715377.61214 1.006450 -1.304190 1.694620 -0.808020 -0.022934 -0.588671 0.006603 +1403715377.66214 1.000940 -1.278220 1.690120 -0.809367 -0.023305 -0.586799 0.007025 +1403715377.71214 0.994695 -1.251930 1.685510 -0.810709 -0.023189 -0.584944 0.007371 +1403715377.76214 0.987848 -1.225120 1.681210 -0.811178 -0.023314 -0.584288 0.007380 +1403715377.81214 0.980183 -1.197740 1.677290 -0.811813 -0.023205 -0.583407 0.007609 +1403715377.86214 0.971751 -1.169890 1.673430 -0.812374 -0.022989 -0.582631 0.007853 +1403715377.91214 0.962701 -1.141690 1.669130 -0.812594 -0.022980 -0.582323 0.007965 +1403715377.96214 0.953163 -1.113080 1.664580 -0.812531 -0.022806 -0.582409 0.008504 +1403715378.01214 0.943065 -1.083990 1.660040 -0.812633 -0.021490 -0.582285 0.010458 +1403715378.06214 0.932528 -1.054450 1.655560 -0.812278 -0.019801 -0.582777 0.013534 +1403715378.11214 0.921225 -1.024790 1.650770 -0.812132 -0.018299 -0.582957 0.016388 +1403715378.16214 0.909294 -0.995092 1.645920 -0.811740 -0.016780 -0.583449 0.019587 +1403715378.21214 0.896881 -0.965826 1.641170 -0.811211 -0.014784 -0.584116 0.022930 +1403715378.26214 0.883952 -0.937023 1.636070 -0.812363 -0.013177 -0.582425 0.025938 +1403715378.31214 0.870646 -0.908839 1.630720 -0.813751 -0.011114 -0.580364 0.029380 +1403715378.36214 0.857021 -0.881694 1.625100 -0.815866 -0.009372 -0.577271 0.032149 +1403715378.41214 0.843019 -0.855662 1.619640 -0.818571 -0.008693 -0.573373 0.033307 +1403715378.46214 0.829030 -0.830941 1.614660 -0.820506 -0.009136 -0.570656 0.032233 +1403715378.51214 0.815161 -0.807280 1.610210 -0.822311 -0.010883 -0.568160 0.029670 +1403715378.56214 0.801450 -0.784685 1.606620 -0.823379 -0.013298 -0.566740 0.025998 +1403715378.61214 0.788024 -0.762697 1.603750 -0.824218 -0.014440 -0.565575 0.024115 +1403715378.66214 0.774846 -0.741018 1.600960 -0.825410 -0.015747 -0.563882 0.022078 +1403715378.71214 0.762554 -0.719714 1.598650 -0.826652 -0.016797 -0.562085 0.020623 +1403715378.76214 0.750664 -0.699029 1.596840 -0.828171 -0.017264 -0.559857 0.019858 +1403715378.81214 0.739583 -0.678770 1.595350 -0.830190 -0.017384 -0.556861 0.019685 +1403715378.86214 0.729406 -0.658849 1.594600 -0.831784 -0.017140 -0.554473 0.020056 +1403715378.91214 0.720742 -0.639255 1.594490 -0.832931 -0.016926 -0.552735 0.020561 +1403715378.96214 0.713318 -0.619958 1.595230 -0.833576 -0.016521 -0.551760 0.020944 +1403715379.01214 0.707270 -0.600914 1.596900 -0.833649 -0.016188 -0.551644 0.021346 +1403715379.06214 0.702597 -0.582222 1.599190 -0.833385 -0.016690 -0.552073 0.020161 +1403715379.11214 0.699129 -0.563791 1.602140 -0.832464 -0.017819 -0.553470 0.018904 +1403715379.16214 0.696877 -0.545648 1.605810 -0.830517 -0.020090 -0.556422 0.015265 +1403715379.21214 0.695488 -0.527515 1.609390 -0.829345 -0.022267 -0.558167 0.011834 +1403715379.26214 0.694479 -0.509160 1.612990 -0.828334 -0.024413 -0.559637 0.008527 +1403715379.31214 0.694156 -0.490747 1.616750 -0.827655 -0.026072 -0.560603 0.005616 +1403715379.36214 0.694545 -0.471734 1.620590 -0.826833 -0.027888 -0.561748 0.003074 +1403715379.41214 0.695419 -0.452105 1.624320 -0.826599 -0.029143 -0.562036 0.000827 +1403715379.46214 0.696817 -0.431723 1.627720 0.827069 0.030242 0.561285 0.000949 +1403715379.51214 0.698787 -0.410591 1.631140 0.827501 0.031181 0.560592 0.002606 +1403715379.56214 0.701455 -0.388524 1.634340 0.828312 0.031023 0.559401 0.002620 +1403715379.61214 0.705107 -0.365533 1.637960 0.828995 0.031716 0.558345 0.003535 +1403715379.66214 0.709306 -0.341658 1.641410 0.830429 0.031835 0.556199 0.004165 +1403715379.71214 0.714505 -0.316705 1.645400 0.830126 0.032656 0.556596 0.005149 +1403715379.76214 0.720563 -0.290652 1.649620 0.829884 0.032901 0.556937 0.005624 +1403715379.81214 0.727510 -0.263428 1.654570 0.828301 0.033433 0.559252 0.006049 +1403715379.86214 0.735284 -0.235107 1.659680 0.826171 0.034412 0.562322 0.007177 +1403715379.91214 0.743658 -0.205555 1.664850 0.823620 0.035105 0.566001 0.007744 +1403715379.96214 0.752441 -0.174832 1.669720 0.821703 0.035364 0.568757 0.008324 +1403715380.01214 0.761365 -0.142659 1.674300 0.820385 0.036054 0.570590 0.009762 +1403715380.06214 0.770340 -0.109123 1.678660 0.818686 0.034983 0.573106 0.008823 +1403715380.11214 0.778885 -0.074337 1.682280 0.817549 0.031938 0.574949 0.005204 +1403715380.16214 0.786814 -0.038486 1.685580 -0.816468 -0.027886 -0.576717 0.000060 +1403715380.21214 0.794401 -0.002252 1.688850 -0.815758 -0.025482 -0.577822 0.003199 +1403715380.26214 0.801490 0.034385 1.691780 -0.815794 -0.022729 -0.577855 0.006850 +1403715380.31214 0.808106 0.071029 1.694470 -0.816289 -0.020539 -0.577203 0.009318 +1403715380.36214 0.814483 0.107373 1.696930 -0.817145 -0.018583 -0.576041 0.010313 +1403715380.41214 0.821041 0.143471 1.699440 -0.818341 -0.017877 -0.574368 0.009949 +1403715380.46214 0.827863 0.179333 1.702280 -0.818540 -0.018493 -0.574090 0.008429 +1403715380.51214 0.834331 0.214842 1.705020 -0.818383 -0.019401 -0.574302 0.007028 +1403715380.56214 0.840208 0.250260 1.707670 -0.818379 -0.020577 -0.574281 0.005857 +1403715380.61214 0.845559 0.285873 1.710630 -0.818540 -0.021653 -0.574017 0.005345 +1403715380.66214 0.850695 0.321763 1.713910 -0.818519 -0.022227 -0.574024 0.005338 +1403715380.71214 0.855556 0.357902 1.717360 -0.818169 -0.022600 -0.574505 0.005718 +1403715380.76214 0.860305 0.394390 1.721070 -0.817742 -0.023194 -0.575090 0.005564 +1403715380.81214 0.864724 0.431175 1.725200 -0.817251 -0.023556 -0.575771 0.005874 +1403715380.86214 0.868858 0.468003 1.729000 -0.816660 -0.024016 -0.576590 0.005834 +1403715380.91214 0.872465 0.504715 1.732030 -0.816451 -0.024615 -0.576865 0.005301 +1403715380.96214 0.875587 0.541805 1.735040 -0.816044 -0.025155 -0.577422 0.004897 +1403715381.01214 0.878186 0.579205 1.737950 -0.815992 -0.025928 -0.577469 0.003916 +1403715381.06214 0.880249 0.616709 1.740870 -0.815461 -0.025535 -0.578239 0.003440 +1403715381.11214 0.881733 0.654554 1.743250 -0.815639 -0.023956 -0.578046 0.004581 +1403715381.16214 0.882894 0.692453 1.745910 -0.815306 -0.021587 -0.578594 0.006254 +1403715381.21214 0.883533 0.730449 1.748280 -0.814896 -0.019444 -0.579232 0.007569 +1403715381.26214 0.883648 0.768267 1.750040 -0.814380 -0.017139 -0.580014 0.008698 +1403715381.31214 0.883125 0.805811 1.751510 -0.813894 -0.015390 -0.580736 0.009200 +1403715381.36214 0.882248 0.842769 1.752420 -0.813904 -0.012668 -0.580769 0.010316 +1403715381.41214 0.880968 0.879245 1.753330 -0.813302 -0.009934 -0.581649 0.011184 +1403715381.46214 0.879330 0.915101 1.754010 -0.812845 -0.007876 -0.582324 0.010911 +1403715381.51214 0.876995 0.950272 1.754590 -0.811128 -0.006052 -0.584744 0.010482 +1403715381.56214 0.873636 0.984865 1.754310 -0.810718 -0.006755 -0.585352 0.007328 +1403715381.61214 0.869523 1.018960 1.753380 -0.810899 -0.007028 -0.585123 0.004899 +1403715381.66214 0.864602 1.052690 1.751490 -0.812225 -0.008000 -0.583287 0.001794 +1403715381.71214 0.859177 1.086300 1.749200 0.814837 0.009190 0.579615 0.001269 +1403715381.76214 0.853639 1.119950 1.747190 0.817455 0.010514 0.575884 0.003664 +1403715381.81214 0.847856 1.153560 1.745330 0.820175 0.011734 0.571966 0.005535 +1403715381.86214 0.842131 1.187350 1.743000 0.823406 0.012368 0.567270 0.007385 +1403715381.91214 0.836939 1.221170 1.740600 0.826228 0.011730 0.563124 0.010046 +1403715381.96214 0.832096 1.255190 1.738310 0.828435 0.009624 0.559825 0.014110 +1403715382.01214 0.827858 1.289570 1.736340 0.829774 0.004817 0.557813 0.017211 +1403715382.06214 0.824755 1.324180 1.734530 0.830911 -0.001261 0.555998 0.021236 +1403715382.11214 0.822574 1.359350 1.732770 0.831299 -0.009199 0.555211 0.024449 +1403715382.16214 0.821010 1.394800 1.731340 0.831252 -0.018216 0.554901 0.027817 +1403715382.21214 0.820554 1.430370 1.730690 0.830816 -0.028292 0.554949 0.031248 +1403715382.26214 0.820967 1.466030 1.730340 0.830139 -0.038041 0.555075 0.036248 +1403715382.31214 0.822386 1.501570 1.730090 0.829222 -0.048563 0.555290 0.041064 +1403715382.36214 0.824761 1.537010 1.729810 0.828124 -0.058713 0.555472 0.047054 +1403715382.41214 0.828064 1.572170 1.729330 0.826386 -0.069165 0.556273 0.053507 +1403715382.46214 0.832309 1.607340 1.728610 0.825605 -0.078983 0.555543 0.059251 +1403715382.51214 0.837620 1.642710 1.727890 0.824403 -0.088098 0.555419 0.064094 +1403715382.56214 0.843953 1.678190 1.727160 0.823534 -0.096424 0.554818 0.068347 +1403715382.61214 0.851019 1.713220 1.726250 0.822519 -0.104856 0.554376 0.071660 +1403715382.66214 0.858914 1.747830 1.724920 0.821822 -0.112613 0.553241 0.076491 +1403715382.71214 0.867617 1.782030 1.723340 0.820635 -0.121154 0.552653 0.080347 +1403715382.76214 0.877377 1.815710 1.721430 0.820279 -0.128541 0.550647 0.086068 +1403715382.81214 0.888030 1.848900 1.719730 0.818840 -0.135748 0.550119 0.091889 +1403715382.86214 0.899341 1.881650 1.717770 0.817711 -0.143562 0.548910 0.097140 +1403715382.91214 0.911556 1.914010 1.715830 0.816401 -0.150901 0.547872 0.102737 +1403715382.96214 0.924837 1.945930 1.713720 0.815368 -0.158907 0.546312 0.107080 +1403715383.01214 0.939078 1.977330 1.711730 0.813977 -0.166991 0.545190 0.111013 +1403715383.06214 0.954076 2.008320 1.709280 0.813037 -0.174828 0.543681 0.113211 +1403715383.11214 0.969958 2.038810 1.706680 0.812090 -0.181793 0.542637 0.114046 +1403715383.16214 0.986581 2.068670 1.703910 0.811439 -0.186919 0.541675 0.114957 +1403715383.21214 1.004340 2.097890 1.700980 0.811353 -0.192115 0.540100 0.114410 +1403715383.26214 1.023590 2.126180 1.698290 0.811214 -0.194437 0.539189 0.115766 +1403715383.31214 1.043770 2.153550 1.695220 0.810852 -0.197346 0.538792 0.115223 +1403715383.36214 1.064800 2.179900 1.692210 0.810159 -0.199774 0.539167 0.114156 +1403715383.41214 1.086350 2.204950 1.688930 0.809445 -0.200693 0.539882 0.114228 +1403715383.46214 1.108500 2.228560 1.685500 0.808280 -0.201881 0.541214 0.114085 +1403715383.51214 1.131220 2.250750 1.682420 0.805957 -0.203781 0.543808 0.114801 +1403715383.56214 1.154430 2.271510 1.679240 0.803599 -0.205600 0.546071 0.117322 +1403715383.61214 1.177910 2.290850 1.675780 0.800566 -0.208084 0.548689 0.121390 +1403715383.66214 1.201180 2.308950 1.671580 0.798167 -0.212469 0.549540 0.125665 +1403715383.71214 1.224000 2.325690 1.667360 0.795734 -0.218001 0.549732 0.130682 +1403715383.76214 1.246570 2.341130 1.662940 0.792713 -0.224949 0.549885 0.136495 +1403715383.81214 1.268880 2.355550 1.658450 0.789567 -0.233297 0.549394 0.142559 +1403715383.86214 1.290950 2.369110 1.654130 0.786730 -0.242487 0.547667 0.149388 +1403715383.91214 1.312540 2.381750 1.649980 0.783162 -0.252918 0.546040 0.156621 +1403715383.96214 1.333690 2.393560 1.645700 0.779767 -0.263388 0.543309 0.165546 +1403715384.01214 1.354730 2.404730 1.641890 0.775497 -0.274866 0.541207 0.173632 +1403715384.06214 1.375030 2.415270 1.637990 0.771650 -0.286418 0.537969 0.181961 +1403715384.11214 1.394560 2.425480 1.634710 0.767109 -0.298209 0.535133 0.190390 +1403715384.16214 1.413620 2.435020 1.631750 0.762351 -0.309755 0.532409 0.198528 +1403715384.21214 1.432360 2.443880 1.629060 0.757815 -0.321494 0.529100 0.205939 +1403715384.26214 1.450770 2.452050 1.626850 0.752563 -0.333161 0.526550 0.213065 +1403715384.31214 1.468710 2.459750 1.625020 0.747146 -0.345066 0.523939 0.219523 +1403715384.36214 1.485930 2.466870 1.623540 0.741489 -0.356525 0.521353 0.226439 +1403715384.41214 1.502460 2.473450 1.622230 0.736062 -0.367317 0.518438 0.233479 +1403715384.46214 1.518150 2.479620 1.620780 0.730783 -0.378463 0.515091 0.239589 +1403715384.51214 1.532940 2.485190 1.619280 0.725788 -0.389796 0.511202 0.244874 +1403715384.56214 1.547030 2.489660 1.617640 0.721809 -0.400404 0.505776 0.250717 +1403715384.61214 1.560600 2.493010 1.616560 0.717181 -0.411311 0.501040 0.255800 +1403715384.66214 1.573180 2.495560 1.615550 0.712870 -0.421751 0.495626 0.261337 +1403715384.71214 1.584920 2.496750 1.614800 0.709007 -0.431054 0.489618 0.267908 +1403715384.76214 1.596060 2.496850 1.614810 0.703830 -0.440594 0.485564 0.273362 +1403715384.81214 1.606400 2.495790 1.614990 0.699059 -0.449626 0.480948 0.279000 +1403715384.86214 1.616290 2.493560 1.615440 0.694136 -0.458287 0.476849 0.284189 +1403715384.91214 1.625910 2.489960 1.616420 0.688820 -0.465996 0.474095 0.289152 +1403715384.96214 1.635050 2.485100 1.618000 0.683749 -0.471681 0.472944 0.293817 +1403715385.01214 1.643800 2.478930 1.619940 0.679981 -0.475353 0.471447 0.299003 +1403715385.06214 1.651800 2.471570 1.621960 0.677380 -0.477998 0.469136 0.304279 +1403715385.11214 1.659150 2.463080 1.624570 0.675148 -0.480097 0.466314 0.310216 +1403715385.16214 1.666120 2.453760 1.627490 0.672687 -0.482599 0.463272 0.316178 +1403715385.21214 1.672740 2.443870 1.630640 0.670172 -0.485284 0.460076 0.322023 +1403715385.26214 1.679400 2.433280 1.634030 0.668153 -0.487678 0.457102 0.326801 +1403715385.31214 1.686360 2.422040 1.637310 0.666531 -0.490270 0.454382 0.330014 +1403715385.36214 1.693700 2.409970 1.640710 0.664596 -0.492520 0.453241 0.332128 +1403715385.41214 1.701020 2.397320 1.644020 0.663731 -0.494488 0.451358 0.333494 +1403715385.46214 1.708290 2.384400 1.647740 0.661775 -0.496461 0.451937 0.333666 +1403715385.51214 1.715660 2.371010 1.651730 0.659298 -0.497950 0.454200 0.333279 +1403715385.56214 1.722930 2.357070 1.655830 0.656347 -0.500286 0.457372 0.331260 +1403715385.61214 1.730020 2.342680 1.660190 0.653304 -0.502727 0.461450 0.327907 +1403715385.66214 1.736560 2.327880 1.664280 0.651647 -0.505542 0.463703 0.323671 +1403715385.71214 1.742220 2.312570 1.668770 0.650191 -0.506985 0.466289 0.320614 +1403715385.76214 1.746730 2.296660 1.673420 0.649203 -0.507113 0.468475 0.319224 +1403715385.81214 1.749820 2.280130 1.678830 0.647579 -0.506871 0.471609 0.318288 +1403715385.86214 1.751260 2.262890 1.684920 0.646534 -0.505724 0.474002 0.318683 +1403715385.91214 1.751080 2.245060 1.691680 0.645551 -0.503395 0.476306 0.320920 +1403715385.96214 1.749370 2.226860 1.698670 0.645384 -0.499141 0.477470 0.326130 +1403715386.01214 1.746220 2.208760 1.705300 0.645940 -0.494681 0.477368 0.331922 +1403715386.06214 1.741870 2.191310 1.711560 0.646930 -0.491257 0.476426 0.336401 +1403715386.11214 1.736510 2.174590 1.717450 0.647869 -0.488678 0.475404 0.339780 +1403715386.16214 1.730240 2.158800 1.722810 0.649007 -0.487296 0.473708 0.341956 +1403715386.21214 1.723480 2.143790 1.727350 0.650394 -0.486618 0.471518 0.343310 +1403715386.26214 1.716340 2.129270 1.730770 0.651298 -0.487068 0.469772 0.343351 +1403715386.31214 1.708940 2.115520 1.733870 0.651207 -0.488235 0.469238 0.342595 +1403715386.36214 1.701130 2.102090 1.737080 0.650470 -0.488546 0.469779 0.342811 +1403715386.41214 1.692870 2.089450 1.740070 0.649028 -0.488531 0.471191 0.343627 +1403715386.46214 1.684310 2.077380 1.742530 0.647435 -0.488532 0.472759 0.344475 +1403715386.51214 1.675280 2.066030 1.744530 0.645577 -0.488547 0.474892 0.345007 +1403715386.56214 1.665730 2.055660 1.745850 0.643425 -0.489699 0.477537 0.343740 +1403715386.61214 1.655580 2.046390 1.746360 0.642155 -0.490588 0.479088 0.342687 +1403715386.66214 1.644600 2.038150 1.746360 0.639540 -0.492294 0.482529 0.340296 +1403715386.71214 1.632630 2.030890 1.745720 0.638062 -0.493859 0.484677 0.337740 +1403715386.76214 1.619620 2.024850 1.744530 0.637376 -0.496007 0.485670 0.334445 +1403715386.81214 1.605080 2.019690 1.741830 0.637903 -0.500169 0.485049 0.328083 +1403715386.86214 1.588920 2.014960 1.739070 0.638213 -0.504063 0.484972 0.321569 +1403715386.91214 1.570630 2.010610 1.736070 0.638492 -0.507765 0.484573 0.315739 +1403715386.96214 1.550440 2.006180 1.732800 0.638975 -0.510443 0.484025 0.311253 +1403715387.01214 1.528040 2.001340 1.729170 0.639619 -0.512331 0.483176 0.308132 +1403715387.06214 1.503350 1.996070 1.725130 0.640838 -0.512628 0.481678 0.307451 +1403715387.11214 1.476860 1.989950 1.720950 0.642710 -0.510940 0.479723 0.309403 +1403715387.16214 1.448510 1.983190 1.716640 0.645114 -0.508622 0.476908 0.312553 +1403715387.21214 1.418730 1.976030 1.712240 0.647783 -0.505100 0.474279 0.316718 +1403715387.26214 1.387660 1.968590 1.707440 0.649819 -0.502598 0.472337 0.319418 +1403715387.31214 1.355640 1.960790 1.702550 0.651300 -0.499898 0.471186 0.322326 +1403715387.36214 1.323050 1.952530 1.697300 0.652491 -0.497693 0.470540 0.324267 +1403715387.41214 1.289890 1.944140 1.691790 0.653861 -0.495675 0.469583 0.325981 +1403715387.46214 1.256290 1.935700 1.686230 0.655182 -0.494343 0.468735 0.326571 +1403715387.51214 1.222150 1.927040 1.680990 0.657582 -0.493728 0.466459 0.325937 +1403715387.56214 1.187680 1.918170 1.677060 0.659559 -0.493698 0.464618 0.324614 +1403715387.61214 1.152760 1.909190 1.674960 0.661411 -0.494830 0.462985 0.321440 +1403715387.66214 1.117700 1.899610 1.675710 0.663419 -0.495571 0.461125 0.318823 +1403715387.71214 1.082790 1.889090 1.679740 0.665632 -0.495281 0.459480 0.317031 +1403715387.76214 1.048000 1.877690 1.687050 0.667513 -0.495120 0.458461 0.314794 +1403715387.81214 1.013050 1.865150 1.697280 0.668964 -0.494535 0.458092 0.313168 +1403715387.86214 0.978292 1.851170 1.709140 0.670307 -0.494320 0.457739 0.311145 +1403715387.91214 0.943589 1.836150 1.720320 0.671274 -0.493852 0.457952 0.309485 +1403715387.96214 0.908739 1.820410 1.728750 0.672138 -0.493105 0.458166 0.308483 +1403715388.01214 0.873999 1.803450 1.733880 0.672369 -0.492507 0.459061 0.307605 +1403715388.06214 0.839174 1.785470 1.735980 0.673082 -0.491068 0.459425 0.307801 +1403715388.11214 0.804218 1.766910 1.734670 0.672975 -0.489882 0.460563 0.308224 +1403715388.16214 0.769384 1.747460 1.729860 0.672821 -0.488499 0.461904 0.308748 +1403715388.21214 0.734770 1.727070 1.722080 0.672274 -0.486482 0.463683 0.310453 +1403715388.26214 0.700352 1.705920 1.711920 0.671376 -0.484326 0.465891 0.312455 +1403715388.31214 0.665774 1.684020 1.700240 0.670884 -0.482211 0.467518 0.314345 +1403715388.36214 0.631221 1.661450 1.688110 0.670497 -0.480213 0.468653 0.316533 +1403715388.41214 0.596791 1.638470 1.675530 0.670247 -0.479133 0.469631 0.317250 +1403715388.46214 0.562351 1.615100 1.662910 0.670272 -0.477574 0.469911 0.319127 +1403715388.51214 0.528136 1.591570 1.649560 0.670392 -0.477283 0.469823 0.319440 +1403715388.56214 0.494286 1.567910 1.636490 0.669848 -0.477206 0.470895 0.319118 +1403715388.61214 0.460267 1.544220 1.623750 0.669429 -0.477209 0.471475 0.319136 +1403715388.66214 0.426377 1.520640 1.611240 0.669139 -0.476748 0.472128 0.319468 +1403715388.71214 0.392656 1.497030 1.599160 0.668725 -0.476210 0.473086 0.319721 +1403715388.76214 0.358942 1.473270 1.587640 0.668836 -0.475629 0.473148 0.320261 +1403715388.81214 0.325411 1.449550 1.576720 0.668766 -0.475400 0.473519 0.320198 +1403715388.86214 0.292076 1.425760 1.566570 0.669130 -0.474684 0.473678 0.320264 +1403715388.91214 0.258666 1.402070 1.558370 0.669617 -0.473093 0.473510 0.321843 +1403715388.96214 0.225501 1.378480 1.552430 0.669732 -0.472099 0.474138 0.322141 +1403715389.01214 0.192509 1.354580 1.549030 0.670148 -0.471062 0.474247 0.322633 +1403715389.06214 0.159999 1.330470 1.548850 0.670249 -0.469877 0.475016 0.323020 +1403715389.11214 0.127839 1.306430 1.551940 0.670933 -0.468727 0.474868 0.323487 +1403715389.16214 0.096103 1.282450 1.557630 0.671808 -0.467378 0.474525 0.324126 +1403715389.21214 0.064887 1.258520 1.563970 0.672444 -0.465965 0.474471 0.324919 +1403715389.26214 0.034130 1.234850 1.570350 0.673668 -0.464038 0.473583 0.326434 +1403715389.31214 0.003838 1.211960 1.576500 0.674580 -0.462674 0.473028 0.327291 +1403715389.36214 -0.025783 1.189420 1.582250 0.675646 -0.461160 0.472549 0.327920 +1403715389.41214 -0.054757 1.167080 1.587510 0.676484 -0.459841 0.472039 0.328778 +1403715389.46214 -0.082954 1.145050 1.592060 0.677134 -0.459257 0.471798 0.328601 +1403715389.51214 -0.110384 1.123350 1.596330 0.677402 -0.459113 0.472066 0.327865 +1403715389.56214 -0.137138 1.101980 1.600220 0.676957 -0.459672 0.473089 0.326524 +1403715389.61214 -0.163079 1.080940 1.603910 0.676195 -0.460248 0.475284 0.324096 +1403715389.66214 -0.188026 1.060120 1.606880 0.676451 -0.459779 0.477438 0.321046 +1403715389.71214 -0.212288 1.039450 1.609450 0.677468 -0.458292 0.479748 0.317565 +1403715389.76214 -0.236074 1.018890 1.611450 0.679259 -0.455882 0.482109 0.313608 +1403715389.81214 -0.259419 0.998490 1.613050 0.681752 -0.452039 0.484880 0.309462 +1403715389.86214 -0.282521 0.978292 1.613710 0.685585 -0.447928 0.486515 0.304362 +1403715389.91214 -0.305428 0.958128 1.613800 0.690620 -0.443043 0.487204 0.298980 +1403715389.96214 -0.328196 0.937762 1.613390 0.696114 -0.437921 0.487410 0.293397 +1403715390.01214 -0.350777 0.917177 1.612200 0.702610 -0.432255 0.486494 0.287781 +1403715390.06214 -0.373137 0.896183 1.610080 0.709114 -0.426152 0.485758 0.282118 +1403715390.11214 -0.394954 0.874700 1.607790 0.715437 -0.419346 0.485520 0.276711 +1403715390.16214 -0.415908 0.852312 1.605240 0.721878 -0.411612 0.485198 0.272124 +1403715390.21214 -0.435783 0.829054 1.602250 0.727984 -0.403444 0.485460 0.267585 +1403715390.26214 -0.454373 0.805091 1.598470 0.734329 -0.395260 0.485224 0.262846 +1403715390.31214 -0.471263 0.780098 1.594620 0.739091 -0.386063 0.487382 0.259149 +1403715390.36214 -0.486984 0.754435 1.590620 0.743689 -0.377031 0.489702 0.254885 +1403715390.41214 -0.501372 0.728062 1.586750 0.748322 -0.367086 0.491786 0.251811 +1403715390.46214 -0.514333 0.701095 1.582840 0.753028 -0.356206 0.493721 0.249611 +1403715390.51214 -0.525646 0.673945 1.578870 0.757431 -0.345776 0.495857 0.246703 +1403715390.56214 -0.535285 0.646594 1.575030 0.761434 -0.334832 0.498393 0.244357 +1403715390.61214 -0.543349 0.619487 1.571310 0.764826 -0.323875 0.501577 0.242006 +1403715390.66214 -0.549727 0.592572 1.567300 0.767962 -0.314497 0.504773 0.237760 +1403715390.71214 -0.554327 0.566200 1.563210 0.770566 -0.307158 0.508461 0.230976 +1403715390.76214 -0.557095 0.540466 1.558950 0.772571 -0.302487 0.512639 0.220991 +1403715390.81214 -0.558470 0.514672 1.554760 0.775136 -0.297565 0.515205 0.212562 +1403715390.86214 -0.558712 0.488592 1.550470 0.777114 -0.294191 0.517234 0.204973 +1403715390.91214 -0.557828 0.462333 1.546230 0.779170 -0.290798 0.518049 0.199889 +1403715390.96214 -0.555764 0.435723 1.542160 0.780784 -0.288785 0.518676 0.194818 +1403715391.01214 -0.552780 0.408703 1.537970 0.782406 -0.287099 0.518913 0.190117 +1403715391.06214 -0.548663 0.381291 1.533640 0.783862 -0.285014 0.519759 0.184874 +1403715391.11214 -0.543578 0.353324 1.529240 0.785400 -0.282614 0.520764 0.179114 +1403715391.16214 -0.537160 0.324768 1.525300 0.786059 -0.280096 0.523375 0.172440 +1403715391.21214 -0.529754 0.295388 1.521560 0.786851 -0.276875 0.525773 0.166640 +1403715391.26214 -0.521546 0.264907 1.518460 0.786370 -0.274217 0.529433 0.161641 +1403715391.31214 -0.512892 0.233275 1.515750 0.785834 -0.271893 0.532510 0.158026 +1403715391.36214 -0.503804 0.200425 1.512950 0.785663 -0.269350 0.534613 0.156118 +1403715391.41214 -0.494506 0.166543 1.509970 0.785809 -0.267018 0.535850 0.155145 +1403715391.46214 -0.485069 0.131796 1.506750 0.786246 -0.266044 0.536064 0.153863 +1403715391.51214 -0.475051 0.095828 1.503570 0.786697 -0.265082 0.535998 0.153449 +1403715391.56214 -0.464557 0.059108 1.500540 0.786539 -0.264664 0.536829 0.152066 +1403715391.61214 -0.453618 0.021705 1.497700 0.786458 -0.264882 0.537929 0.148167 +1403715391.66214 -0.442389 -0.016931 1.495850 0.786267 -0.263870 0.539617 0.144809 +1403715391.71214 -0.430893 -0.056698 1.496400 0.786420 -0.260892 0.541416 0.142645 +1403715391.76214 -0.419283 -0.097438 1.499900 0.786803 -0.256711 0.543444 0.140389 +1403715391.81214 -0.407131 -0.139516 1.506730 0.787982 -0.250237 0.544863 0.139961 +1403715391.86214 -0.394537 -0.182731 1.516250 0.790137 -0.242141 0.545277 0.140444 +1403715391.91214 -0.382017 -0.226607 1.528390 0.792313 -0.234736 0.545432 0.140154 +1403715391.96214 -0.369456 -0.271118 1.541950 0.794937 -0.228410 0.544423 0.139666 +1403715392.01214 -0.356506 -0.315847 1.555220 0.798515 -0.224137 0.541342 0.138147 +1403715392.06214 -0.342968 -0.360988 1.568330 0.800993 -0.220343 0.539598 0.136727 +1403715392.11214 -0.328721 -0.406566 1.581000 0.802948 -0.218225 0.538006 0.134914 +1403715392.16214 -0.313574 -0.452488 1.593410 0.804373 -0.216025 0.537115 0.133512 +1403715392.21214 -0.297449 -0.498768 1.605930 0.804916 -0.213393 0.537857 0.131466 +1403715392.26214 -0.280108 -0.545167 1.618780 0.804987 -0.209096 0.539915 0.129490 +1403715392.31214 -0.261626 -0.591414 1.631030 0.804820 -0.204051 0.542838 0.126311 +1403715392.36214 -0.241781 -0.637819 1.643760 0.803612 -0.196574 0.547931 0.123844 +1403715392.41214 -0.221442 -0.684019 1.656880 0.800238 -0.188616 0.556371 0.120394 +1403715392.46214 -0.200805 -0.730101 1.670140 0.795843 -0.179530 0.566260 0.117271 +1403715392.51214 -0.180610 -0.775567 1.682380 0.793079 -0.169361 0.573803 0.114419 +1403715392.56214 -0.161006 -0.820148 1.692960 0.792740 -0.159584 0.577878 0.110243 +1403715392.61214 -0.141989 -0.863691 1.702060 0.794571 -0.149968 0.578813 0.105552 +1403715392.66214 -0.123973 -0.906273 1.710540 0.795684 -0.140256 0.580710 0.099954 +1403715392.71214 -0.107037 -0.948180 1.718360 0.796333 -0.130605 0.583060 0.094004 +1403715392.76214 -0.091074 -0.989138 1.724940 0.797870 -0.120959 0.583993 0.087885 +1403715392.81214 -0.075607 -1.029130 1.730460 0.801624 -0.110988 0.581741 0.081599 +1403715392.86214 -0.060906 -1.067980 1.735360 0.806483 -0.101407 0.577712 0.074507 +1403715392.91214 -0.046737 -1.105820 1.740060 0.810653 -0.091230 0.574411 0.067610 +1403715392.96214 -0.033080 -1.142460 1.744310 0.814761 -0.080170 0.570955 0.061220 +1403715393.01214 -0.019137 -1.178260 1.748860 0.817711 -0.068998 0.568868 0.054559 +1403715393.06214 -0.005045 -1.213200 1.753680 0.819910 -0.058633 0.567590 0.046389 +1403715393.11214 0.009446 -1.247170 1.758200 0.821406 -0.046480 0.567044 0.039905 +1403715393.16214 0.024074 -1.280050 1.762010 0.821897 -0.032896 0.567619 0.034820 +1403715393.21214 0.038813 -1.311550 1.764860 0.821839 -0.018580 0.568639 0.029757 +1403715393.26214 0.053726 -1.341500 1.767370 0.820725 -0.004898 0.570826 0.023303 +1403715393.31214 0.068599 -1.369590 1.769750 0.819187 0.009057 0.573219 0.016470 +1403715393.36214 0.083298 -1.396210 1.771880 0.817797 0.022825 0.574982 0.009104 +1403715393.41214 0.097717 -1.421290 1.773910 0.816461 0.037181 0.576198 0.002414 +1403715393.46214 0.111768 -1.444630 1.775180 -0.815034 -0.051693 -0.577088 0.004171 +1403715393.51214 0.125220 -1.466170 1.775940 -0.812865 -0.065686 -0.578622 0.011513 +1403715393.56214 0.137838 -1.485560 1.776420 -0.810559 -0.080083 -0.579861 0.018518 +1403715393.61214 0.149527 -1.502790 1.776560 -0.808447 -0.093524 -0.580450 0.027272 +1403715393.66214 0.159818 -1.517900 1.776110 -0.806881 -0.104842 -0.580024 0.039029 +1403715393.71214 0.169480 -1.530930 1.775180 -0.806475 -0.115272 -0.577580 0.052081 +1403715393.76214 0.177965 -1.541960 1.773930 -0.806433 -0.125078 -0.574203 0.065662 +1403715393.81214 0.185847 -1.551350 1.772290 -0.806612 -0.135450 -0.570003 0.078275 +1403715393.86214 0.193054 -1.559730 1.770950 -0.806450 -0.145336 -0.565891 0.091010 +1403715393.91214 0.199879 -1.567200 1.769720 -0.805201 -0.157035 -0.562875 0.100810 +1403715393.96214 0.206241 -1.573720 1.768420 -0.804077 -0.167514 -0.559356 0.111895 +1403715394.01214 0.212194 -1.579610 1.767140 -0.801869 -0.178090 -0.556964 0.122808 +1403715394.06214 0.218008 -1.584730 1.765970 -0.799209 -0.189322 -0.554751 0.132944 +1403715394.11214 0.223737 -1.589240 1.764600 -0.796445 -0.201178 -0.552146 0.142610 +1403715394.16214 0.229300 -1.593100 1.763280 -0.792651 -0.214253 -0.550495 0.150849 +1403715394.21214 0.234377 -1.596320 1.761610 -0.788981 -0.227245 -0.548001 0.159885 +1403715394.26214 0.238924 -1.599010 1.759660 -0.784935 -0.240508 -0.545474 0.168795 +1403715394.31214 0.243079 -1.601040 1.758040 -0.780031 -0.253059 -0.543666 0.178720 +1403715394.36214 0.247111 -1.602410 1.756790 -0.773837 -0.266922 -0.543112 0.186969 +1403715394.41214 0.250627 -1.603340 1.755870 -0.767381 -0.280625 -0.542337 0.195567 +1403715394.46214 0.253785 -1.603620 1.755520 -0.759869 -0.294323 -0.542682 0.203639 +1403715394.51214 0.256072 -1.603440 1.755090 -0.752649 -0.308014 -0.542182 0.211389 +1403715394.56214 0.257269 -1.602890 1.754530 -0.746047 -0.321314 -0.540215 0.219861 +1403715394.61214 0.257279 -1.602030 1.753710 -0.739949 -0.333877 -0.536971 0.229486 +1403715394.66214 0.255628 -1.601110 1.752530 -0.734399 -0.346062 -0.532278 0.239959 +1403715394.71214 0.252640 -1.599840 1.751100 -0.729200 -0.358595 -0.526565 0.249811 +1403715394.76214 0.248185 -1.598520 1.749330 -0.724533 -0.371588 -0.519395 0.259237 +1403715394.81214 0.242782 -1.597200 1.747650 -0.719564 -0.384848 -0.511988 0.268304 +1403715394.86214 0.236675 -1.595910 1.746130 -0.713802 -0.398433 -0.504657 0.277594 +1403715394.91214 0.229925 -1.594460 1.744520 -0.707347 -0.412896 -0.497106 0.286465 +1403715394.96214 0.222637 -1.592500 1.743260 -0.699904 -0.427320 -0.489873 0.295899 +1403715395.01214 0.214944 -1.590330 1.741950 -0.691779 -0.442321 -0.482793 0.304474 +1403715395.06214 0.206471 -1.587800 1.740510 -0.682947 -0.456963 -0.475767 0.313711 +1403715395.11214 0.197525 -1.584690 1.739070 -0.673786 -0.470930 -0.468960 0.322976 +1403715395.16214 0.188223 -1.581040 1.737550 -0.664794 -0.484422 -0.462218 0.331268 +1403715395.21214 0.178560 -1.576970 1.735810 -0.656968 -0.496462 -0.454194 0.340039 +1403715395.26214 0.168393 -1.572530 1.733980 -0.648368 -0.508216 -0.447799 0.347578 +1403715395.31214 0.157721 -1.567450 1.731740 -0.639673 -0.519368 -0.442077 0.354462 +1403715395.36214 0.146757 -1.562080 1.728940 -0.631551 -0.529741 -0.436394 0.360663 +1403715395.41214 0.135420 -1.556530 1.725460 -0.623992 -0.539303 -0.430424 0.366772 +1403715395.46214 0.123757 -1.550580 1.721310 -0.617259 -0.548198 -0.423875 0.372558 +1403715395.51214 0.111895 -1.544200 1.716430 -0.610516 -0.556422 -0.417787 0.378311 +1403715395.56214 0.099725 -1.537330 1.710960 -0.603984 -0.563945 -0.411781 0.384195 +1403715395.61214 0.087339 -1.530190 1.704760 -0.598072 -0.570261 -0.406019 0.390206 +1403715395.66214 0.074801 -1.522450 1.698290 -0.591680 -0.576715 -0.401367 0.395247 +1403715395.71214 0.062104 -1.514270 1.691040 -0.585398 -0.583997 -0.396909 0.398397 +1403715395.76214 0.049298 -1.505230 1.683560 -0.578536 -0.590365 -0.393454 0.402442 +1403715395.81214 0.036342 -1.495480 1.675700 -0.571926 -0.596653 -0.390901 0.405095 +1403715395.86214 0.023133 -1.485320 1.667650 -0.567712 -0.600664 -0.386578 0.409223 +1403715395.91214 0.009817 -1.474660 1.659390 -0.564911 -0.603352 -0.382301 0.413144 +1403715395.96214 -0.003616 -1.463390 1.651160 -0.563788 -0.604364 -0.377485 0.417603 +1403715396.01214 -0.017073 -1.451490 1.642950 -0.563598 -0.604236 -0.372585 0.422417 +1403715396.06214 -0.030088 -1.439050 1.635280 -0.564609 -0.602258 -0.367717 0.428118 +1403715396.11214 -0.042166 -1.426680 1.628120 -0.565798 -0.600181 -0.363996 0.432623 +1403715396.16214 -0.052984 -1.413850 1.621560 -0.566551 -0.597762 -0.362102 0.436558 +1403715396.21214 -0.062336 -1.400720 1.615590 -0.566826 -0.596162 -0.361907 0.438545 +1403715396.26214 -0.070291 -1.387340 1.610250 -0.565871 -0.595831 -0.364467 0.438109 +1403715396.31214 -0.076860 -1.373380 1.605180 -0.564052 -0.597160 -0.368710 0.435085 +1403715396.36214 -0.082332 -1.359060 1.600480 -0.561272 -0.598777 -0.374370 0.431609 +1403715396.41214 -0.087240 -1.344800 1.595690 -0.559350 -0.599893 -0.378331 0.429095 +1403715396.46214 -0.091681 -1.330690 1.590570 -0.557404 -0.601929 -0.381975 0.425531 +1403715396.51214 -0.096296 -1.316550 1.585680 -0.554466 -0.604136 -0.384756 0.423733 +1403715396.56214 -0.101358 -1.302340 1.580800 -0.551591 -0.605856 -0.386140 0.423770 +1403715396.61214 -0.106954 -1.288370 1.575680 -0.548231 -0.608562 -0.386521 0.423907 +1403715396.66214 -0.113094 -1.274750 1.570370 -0.544024 -0.611076 -0.386113 0.426075 +1403715396.71214 -0.119596 -1.261780 1.564230 -0.540366 -0.613646 -0.384453 0.428532 +1403715396.76214 -0.126485 -1.249280 1.557400 -0.538294 -0.616228 -0.380806 0.430685 +1403715396.81214 -0.133780 -1.237120 1.550350 -0.536817 -0.618552 -0.376374 0.433086 +1403715396.86214 -0.141343 -1.225110 1.542930 -0.535616 -0.621583 -0.371970 0.434037 +1403715396.91214 -0.149103 -1.213310 1.535070 -0.534680 -0.624440 -0.367907 0.434553 +1403715396.96214 -0.157066 -1.201460 1.526270 -0.534467 -0.628805 -0.363341 0.432357 +1403715397.01214 -0.164958 -1.189250 1.516880 -0.535313 -0.632334 -0.358104 0.430529 +1403715397.06214 -0.172813 -1.176550 1.507200 -0.535622 -0.636032 -0.353877 0.428186 +1403715397.11214 -0.180735 -1.163100 1.497370 -0.536166 -0.638405 -0.349911 0.427232 +1403715397.16214 -0.188928 -1.148220 1.487320 -0.537284 -0.639624 -0.345509 0.427588 +1403715397.21214 -0.197324 -1.132100 1.477360 -0.539181 -0.639373 -0.340557 0.429543 +1403715397.26214 -0.205764 -1.114650 1.467370 -0.541727 -0.638255 -0.334891 0.432448 +1403715397.31214 -0.213873 -1.095440 1.458020 -0.543905 -0.635983 -0.330684 0.436281 +1403715397.36214 -0.221096 -1.074590 1.448680 -0.545497 -0.634122 -0.327450 0.439430 +1403715397.41214 -0.227497 -1.052120 1.439570 -0.546626 -0.632791 -0.325273 0.441559 +1403715397.46214 -0.232815 -1.028010 1.430750 -0.547453 -0.632239 -0.323152 0.442878 +1403715397.51214 -0.236913 -1.002310 1.422530 -0.547815 -0.631991 -0.322271 0.443427 +1403715397.56214 -0.239687 -0.974872 1.414600 -0.547586 -0.631251 -0.321968 0.444980 +1403715397.61214 -0.240866 -0.945739 1.407670 -0.547108 -0.630136 -0.322232 0.446953 +1403715397.66214 -0.240467 -0.915153 1.402150 -0.545445 -0.628946 -0.324543 0.448985 +1403715397.71214 -0.238646 -0.883409 1.397980 -0.542693 -0.627213 -0.328316 0.451992 +1403715397.76214 -0.235506 -0.850858 1.394670 -0.540137 -0.626172 -0.332442 0.453480 +1403715397.81214 -0.231279 -0.817866 1.392150 -0.538020 -0.624747 -0.336018 0.455322 +1403715397.86214 -0.225814 -0.784234 1.390320 -0.536178 -0.623978 -0.339302 0.456113 +1403715397.91214 -0.219234 -0.750281 1.389070 -0.533758 -0.623795 -0.343695 0.455912 +1403715397.96214 -0.211804 -0.716241 1.388650 -0.530394 -0.622276 -0.349566 0.457448 +1403715398.01214 -0.203759 -0.682299 1.388110 -0.526759 -0.620513 -0.356023 0.459060 +1403715398.06214 -0.195233 -0.649010 1.387190 -0.523555 -0.618513 -0.361872 0.460848 +1403715398.11214 -0.186322 -0.616551 1.385310 -0.521018 -0.616697 -0.366701 0.462336 +1403715398.16214 -0.177261 -0.584996 1.382920 -0.518895 -0.615096 -0.370991 0.463433 +1403715398.21214 -0.168017 -0.554996 1.379550 -0.518076 -0.614401 -0.373591 0.463184 +1403715398.26214 -0.158603 -0.526797 1.375050 -0.518682 -0.614397 -0.374395 0.461859 +1403715398.31214 -0.148961 -0.500267 1.369770 -0.519740 -0.615255 -0.374797 0.459194 +1403715398.36214 -0.139192 -0.475307 1.364110 -0.520758 -0.615792 -0.375487 0.456750 +1403715398.41214 -0.129565 -0.451473 1.358360 -0.522812 -0.615205 -0.374479 0.456023 +1403715398.46214 -0.119819 -0.428856 1.352420 -0.523798 -0.615950 -0.375242 0.453249 +1403715398.51214 -0.110118 -0.407470 1.346550 -0.524701 -0.616239 -0.376346 0.450890 +1403715398.56214 -0.100762 -0.387219 1.341140 -0.524940 -0.616377 -0.378132 0.448925 +1403715398.61214 -0.091760 -0.368138 1.336630 -0.524537 -0.614784 -0.380807 0.449318 +1403715398.66214 -0.083120 -0.350348 1.332670 -0.522691 -0.613825 -0.385435 0.448836 +1403715398.71214 -0.074899 -0.333921 1.329180 -0.519603 -0.613093 -0.391609 0.448076 +1403715398.76214 -0.067280 -0.319079 1.326050 -0.516464 -0.612639 -0.398056 0.446642 +1403715398.81214 -0.060548 -0.306193 1.322990 -0.514086 -0.612569 -0.402870 0.445163 +1403715398.86214 -0.055226 -0.295269 1.319950 -0.512228 -0.612910 -0.406427 0.443600 +1403715398.91214 -0.051508 -0.286237 1.317000 -0.510956 -0.613075 -0.408764 0.442692 +1403715398.96214 -0.049524 -0.279055 1.314240 -0.510502 -0.613082 -0.409435 0.442585 +1403715399.01214 -0.049004 -0.274047 1.312130 -0.509668 -0.613071 -0.410275 0.442783 +1403715399.06214 -0.050017 -0.271295 1.310260 -0.510048 -0.613151 -0.409013 0.443403 +1403715399.11214 -0.052638 -0.270633 1.308080 -0.511353 -0.613733 -0.405935 0.443921 +1403715399.16214 -0.056842 -0.271812 1.305960 -0.512866 -0.613402 -0.402263 0.445972 +1403715399.21214 -0.062263 -0.274878 1.304360 -0.513470 -0.613564 -0.399718 0.447341 +1403715399.26214 -0.068679 -0.280217 1.303340 -0.513698 -0.613156 -0.397821 0.449324 +1403715399.31214 -0.075914 -0.287282 1.302090 -0.513740 -0.614641 -0.396369 0.448530 +1403715399.36214 -0.083865 -0.296020 1.300800 -0.514326 -0.616631 -0.394633 0.446654 +1403715399.41214 -0.092722 -0.306211 1.299400 -0.515046 -0.619609 -0.392634 0.443453 +1403715399.46214 -0.102490 -0.317703 1.298410 -0.515335 -0.621870 -0.391476 0.440971 +1403715399.51214 -0.113153 -0.330246 1.297820 -0.514698 -0.623816 -0.392345 0.438185 +1403715399.56214 -0.124908 -0.344192 1.296300 -0.516751 -0.626942 -0.389657 0.433681 +1403715399.61214 -0.138030 -0.359013 1.294120 -0.522084 -0.629031 -0.382735 0.430421 +1403715399.66214 -0.152314 -0.374395 1.292270 -0.527185 -0.630813 -0.376300 0.427258 +1403715399.71214 -0.167790 -0.389652 1.290780 -0.531942 -0.632124 -0.370578 0.424416 +1403715399.76214 -0.184127 -0.404192 1.290450 -0.535481 -0.633047 -0.366865 0.421808 +1403715399.81214 -0.201118 -0.417981 1.291070 -0.538167 -0.633372 -0.364469 0.419973 +1403715399.86214 -0.218760 -0.431239 1.292180 -0.539904 -0.633796 -0.363068 0.418315 +1403715399.91214 -0.237046 -0.443596 1.293850 -0.541274 -0.634253 -0.362368 0.416456 +1403715399.96214 -0.255866 -0.454651 1.296010 -0.542892 -0.634105 -0.362913 0.414093 +1403715400.01214 -0.275222 -0.464490 1.299080 -0.544455 -0.632907 -0.365517 0.411577 +1403715400.06214 -0.295347 -0.472957 1.302840 -0.546185 -0.630504 -0.369319 0.409574 +1403715400.11214 -0.316399 -0.479938 1.306740 -0.548253 -0.627504 -0.374035 0.407130 +1403715400.16214 -0.338134 -0.485901 1.310630 -0.551802 -0.623438 -0.378414 0.404527 +1403715400.21214 -0.360805 -0.490687 1.314830 -0.555483 -0.619071 -0.383918 0.400995 +1403715400.26214 -0.384608 -0.494299 1.319440 -0.558614 -0.615940 -0.390954 0.394618 +1403715400.31214 -0.409636 -0.496858 1.324090 -0.562982 -0.611812 -0.397293 0.388453 +1403715400.36214 -0.436165 -0.498482 1.328350 -0.567628 -0.607085 -0.404077 0.382058 +1403715400.41214 -0.464186 -0.499332 1.332050 -0.573897 -0.601531 -0.409436 0.375720 +1403715400.46214 -0.493829 -0.499188 1.335590 -0.581588 -0.593795 -0.413630 0.371583 +1403715400.51214 -0.525050 -0.497996 1.338810 -0.590760 -0.584907 -0.416561 0.367918 +1403715400.56214 -0.557757 -0.495718 1.341440 -0.600609 -0.575631 -0.419167 0.363617 +1403715400.61214 -0.591562 -0.492555 1.343630 -0.611290 -0.565019 -0.421418 0.359839 +1403715400.66214 -0.626153 -0.488498 1.345220 -0.622354 -0.554448 -0.423606 0.354712 +1403715400.71214 -0.661367 -0.483225 1.346360 -0.633046 -0.543461 -0.426675 0.349072 +1403715400.76214 -0.697011 -0.476695 1.346990 -0.644082 -0.531903 -0.429129 0.343636 +1403715400.81214 -0.733064 -0.468918 1.347320 -0.654686 -0.518946 -0.431913 0.339901 +1403715400.86214 -0.769121 -0.459926 1.347140 -0.664987 -0.505387 -0.434758 0.336692 +1403715400.91214 -0.805177 -0.449621 1.346020 -0.674945 -0.493865 -0.435838 0.332554 +1403715400.96214 -0.840966 -0.437901 1.344390 -0.683741 -0.483822 -0.436095 0.328993 +1403715401.01214 -0.875958 -0.424982 1.342960 -0.691532 -0.474955 -0.436107 0.325594 +1403715401.06214 -0.909819 -0.410738 1.341930 -0.697687 -0.469024 -0.436336 0.320719 +1403715401.11214 -0.942262 -0.395345 1.341710 -0.702059 -0.463835 -0.437462 0.317171 +1403715401.16214 -0.973401 -0.378442 1.342080 -0.705340 -0.460518 -0.439185 0.312307 +1403715401.21214 -1.003070 -0.359985 1.343080 -0.707210 -0.459032 -0.441491 0.306968 +1403715401.26214 -1.031200 -0.339507 1.344520 -0.708161 -0.458707 -0.443895 0.301751 +1403715401.31214 -1.058390 -0.317162 1.346190 -0.708844 -0.458151 -0.446308 0.297401 +1403715401.36214 -1.084830 -0.292458 1.348680 -0.708733 -0.456491 -0.448964 0.296219 +1403715401.41214 -1.110540 -0.265316 1.352030 -0.708325 -0.454800 -0.451331 0.296199 +1403715401.46214 -1.135040 -0.236373 1.355680 -0.707394 -0.453608 -0.453936 0.296269 +1403715401.51214 -1.158300 -0.205802 1.359840 -0.706303 -0.451541 -0.456316 0.298367 +1403715401.56214 -1.180510 -0.174417 1.364420 -0.705853 -0.449009 -0.457711 0.301105 +1403715401.61214 -1.201490 -0.142151 1.370070 -0.704255 -0.445631 -0.460343 0.305814 +1403715401.66214 -1.221300 -0.109293 1.375910 -0.703229 -0.442512 -0.462748 0.309059 +1403715401.71214 -1.239920 -0.075539 1.381970 -0.703174 -0.435827 -0.465167 0.314994 +1403715401.76214 -1.257310 -0.041338 1.387500 -0.704725 -0.427518 -0.466485 0.320909 +1403715401.81214 -1.273100 -0.007211 1.393190 -0.705740 -0.421490 -0.469231 0.322645 +1403715401.86214 -1.287400 0.026004 1.399000 -0.707212 -0.416189 -0.471574 0.322886 +1403715401.91214 -1.300560 0.058608 1.404550 -0.707335 -0.414819 -0.474578 0.319966 +1403715401.96214 -1.312360 0.090618 1.409570 -0.706481 -0.415748 -0.478154 0.315289 +1403715402.01214 -1.323410 0.121730 1.414060 -0.705183 -0.417423 -0.481512 0.310838 +1403715402.06214 -1.333760 0.152856 1.418620 -0.703982 -0.419605 -0.483883 0.306918 +1403715402.11214 -1.343500 0.184061 1.423100 -0.701140 -0.420167 -0.487846 0.306381 +1403715402.16214 -1.352840 0.214431 1.427870 -0.695912 -0.418935 -0.495252 0.308100 +1403715402.21214 -1.362110 0.243959 1.431930 -0.692486 -0.416649 -0.501017 0.309595 +1403715402.26214 -1.371330 0.272080 1.435090 -0.691064 -0.414176 -0.504977 0.309656 +1403715402.31214 -1.380580 0.298575 1.436940 -0.691831 -0.413788 -0.506851 0.305372 +1403715402.36214 -1.389870 0.323679 1.438110 -0.694466 -0.413666 -0.507606 0.298215 +1403715402.41214 -1.399260 0.347701 1.439360 -0.696779 -0.411834 -0.510218 0.290808 +1403715402.46214 -1.409000 0.370704 1.440300 -0.698909 -0.409109 -0.514281 0.282260 +1403715402.51214 -1.419600 0.393491 1.441560 -0.699174 -0.405912 -0.520771 0.274204 +1403715402.56214 -1.431300 0.416279 1.442760 -0.700172 -0.402591 -0.525137 0.268163 +1403715402.61214 -1.444260 0.438934 1.444290 -0.699961 -0.398808 -0.530325 0.264126 +1403715402.66214 -1.458750 0.461513 1.445310 -0.700293 -0.395570 -0.534126 0.260431 +1403715402.71214 -1.475170 0.484027 1.446030 -0.701176 -0.392005 -0.536519 0.258518 +1403715402.76214 -1.493590 0.506215 1.445830 -0.706336 -0.386860 -0.532958 0.259585 +1403715402.81214 -1.513780 0.527685 1.445640 -0.711385 -0.381592 -0.528936 0.261813 +1403715402.86214 -1.535270 0.548601 1.445340 -0.716291 -0.376778 -0.524432 0.264456 +1403715402.91214 -1.557580 0.569124 1.444800 -0.721267 -0.372179 -0.519581 0.267005 +1403715402.96214 -1.580350 0.589404 1.444240 -0.726842 -0.368480 -0.513716 0.268364 +1403715403.01214 -1.603020 0.609475 1.443700 -0.732993 -0.365121 -0.506511 0.269914 +1403715403.06214 -1.624980 0.628992 1.443450 -0.738942 -0.363671 -0.499420 0.268862 +1403715403.11214 -1.645780 0.648290 1.443670 -0.744219 -0.362192 -0.492871 0.268389 +1403715403.16214 -1.665220 0.667334 1.444280 -0.748478 -0.361597 -0.487246 0.267617 +1403715403.21214 -1.682950 0.686674 1.446140 -0.751539 -0.360684 -0.483381 0.267282 +1403715403.26214 -1.698700 0.706496 1.448540 -0.752901 -0.362328 -0.481463 0.264672 +1403715403.31214 -1.712690 0.726805 1.451150 -0.752732 -0.364239 -0.481603 0.262267 +1403715403.36214 -1.724950 0.747280 1.454100 -0.751897 -0.365349 -0.483415 0.259772 +1403715403.41214 -1.735220 0.768255 1.457170 -0.751301 -0.365227 -0.485844 0.257122 +1403715403.46214 -1.743590 0.789799 1.460520 -0.751178 -0.363634 -0.488645 0.254417 +1403715403.51214 -1.750150 0.811881 1.463900 -0.751617 -0.360106 -0.492102 0.251458 +1403715403.56214 -1.755280 0.834494 1.466820 -0.753330 -0.354727 -0.494844 0.248580 +1403715403.61214 -1.759170 0.857476 1.469040 -0.756537 -0.348854 -0.496388 0.244033 +1403715403.66214 -1.761990 0.880654 1.470860 -0.760204 -0.342132 -0.497967 0.238881 +1403715403.71214 -1.763630 0.904160 1.471830 -0.765357 -0.334653 -0.497760 0.233391 +1403715403.76214 -1.763860 0.928059 1.472780 -0.771109 -0.325519 -0.497102 0.228730 +1403715403.81214 -1.762310 0.952668 1.474120 -0.776406 -0.315546 -0.497328 0.224251 +1403715403.86214 -1.758850 0.977781 1.476170 -0.780937 -0.305400 -0.498696 0.219478 +1403715403.91214 -1.753440 1.003180 1.478340 -0.785254 -0.295604 -0.500298 0.213766 +1403715403.96214 -1.746000 1.029100 1.480830 -0.789064 -0.285603 -0.502443 0.208231 +1403715404.01214 -1.736820 1.055200 1.483830 -0.791946 -0.276379 -0.505712 0.201719 +1403715404.06214 -1.725890 1.081240 1.487860 -0.793203 -0.266888 -0.511331 0.195296 +1403715404.11214 -1.713390 1.107510 1.492150 -0.793965 -0.258532 -0.517232 0.187756 +1403715404.16214 -1.699470 1.134020 1.496690 -0.793523 -0.251859 -0.524703 0.177694 +1403715404.21214 -1.684500 1.160850 1.500880 -0.793537 -0.245141 -0.530954 0.168205 +1403715404.26214 -1.669070 1.188390 1.504620 -0.792904 -0.240053 -0.537086 0.158794 +1403715404.31214 -1.653200 1.216830 1.507370 -0.792818 -0.236032 -0.541590 0.149697 +1403715404.36214 -1.637420 1.246270 1.509520 -0.793475 -0.231881 -0.544060 0.143621 +1403715404.41214 -1.621740 1.276570 1.511350 -0.793553 -0.228839 -0.546731 0.137810 +1403715404.46214 -1.606220 1.308020 1.512960 -0.793228 -0.225517 -0.549431 0.134374 +1403715404.51214 -1.590930 1.340580 1.514100 -0.792633 -0.223676 -0.551900 0.130800 +1403715404.56214 -1.576150 1.374100 1.514490 -0.792098 -0.221879 -0.553887 0.128687 +1403715404.61214 -1.562290 1.408440 1.513700 -0.791656 -0.219665 -0.555552 0.128018 +1403715404.66214 -1.548930 1.444010 1.512040 -0.791728 -0.215893 -0.556220 0.131055 +1403715404.71214 -1.536240 1.480130 1.509960 -0.791543 -0.212744 -0.557026 0.133873 +1403715404.76214 -1.524040 1.516870 1.507650 -0.791314 -0.208749 -0.557787 0.138277 +1403715404.81214 -1.512180 1.553680 1.504820 -0.792094 -0.205209 -0.557424 0.140551 +1403715404.86214 -1.500350 1.590370 1.501720 -0.793166 -0.200889 -0.557368 0.140968 +1403715404.91214 -1.488880 1.626990 1.498370 -0.793737 -0.195569 -0.558483 0.140822 +1403715404.96214 -1.477700 1.663220 1.494780 -0.794304 -0.188573 -0.560210 0.140308 +1403715405.01214 -1.466520 1.698780 1.491070 -0.794795 -0.180119 -0.562552 0.139261 +1403715405.06214 -1.455760 1.733460 1.487240 -0.795921 -0.170120 -0.564527 0.137396 +1403715405.11214 -1.445760 1.767090 1.483180 -0.797780 -0.158019 -0.565802 0.135817 +1403715405.16214 -1.436300 1.799200 1.478830 -0.800656 -0.145229 -0.566111 0.131822 +1403715405.21214 -1.427350 1.829600 1.474420 -0.803920 -0.131491 -0.566079 0.126399 +1403715405.26214 -1.418710 1.858500 1.469730 -0.807163 -0.117214 -0.566054 0.119717 +1403715405.31214 -1.410110 1.885740 1.465120 -0.810114 -0.103729 -0.566297 0.110739 +1403715405.36214 -1.401450 1.911510 1.460560 -0.812919 -0.090594 -0.566368 0.100911 +1403715405.41214 -1.392900 1.935710 1.456020 -0.815709 -0.078106 -0.566060 0.089970 +1403715405.46214 -1.384330 1.958730 1.451390 -0.818500 -0.064915 -0.565195 0.079991 +1403715405.51214 -1.375680 1.980350 1.447030 -0.820597 -0.051484 -0.564858 0.070038 +1403715405.56214 -1.366960 2.000800 1.442840 -0.822362 -0.038257 -0.564533 0.059667 +1403715405.61214 -1.358170 2.019890 1.438780 -0.823922 -0.026830 -0.564110 0.047038 +1403715405.66214 -1.348960 2.038130 1.434520 -0.825963 -0.016632 -0.562488 0.033390 +1403715405.71214 -1.339210 2.055910 1.430260 -0.827775 -0.006226 -0.560631 0.021035 +1403715405.76214 -1.328790 2.073260 1.426190 -0.829079 0.004011 -0.559045 0.008961 +1403715405.81214 -1.318020 2.090340 1.421690 0.830719 -0.015096 0.556484 0.001600 +1403715405.86214 -1.306360 2.107140 1.417290 0.831878 -0.026197 0.554211 0.011968 +1403715405.91214 -1.294180 2.123890 1.412580 0.831514 -0.039157 0.553741 0.020543 +1403715405.96214 -1.280890 2.140420 1.407840 0.829504 -0.052332 0.555291 0.028918 +1403715406.01214 -1.266550 2.156660 1.403300 0.826176 -0.065258 0.558315 0.038192 +1403715406.06214 -1.251720 2.172910 1.398160 0.822732 -0.079077 0.560965 0.046655 +1403715406.11214 -1.236500 2.188710 1.392310 0.819628 -0.092019 0.562693 0.055843 +1403715406.16214 -1.221200 2.204400 1.385430 0.816754 -0.105502 0.563620 0.064153 +1403715406.21214 -1.205720 2.219770 1.378050 0.813978 -0.119113 0.563977 0.071992 +1403715406.26214 -1.190340 2.234900 1.370100 0.811681 -0.131952 0.563291 0.080408 +1403715406.31214 -1.174820 2.249870 1.361830 0.809587 -0.144843 0.561991 0.088068 +1403715406.36214 -1.159560 2.264700 1.352920 0.807978 -0.158572 0.559662 0.093832 +1403715406.41214 -1.144070 2.278860 1.343660 0.806512 -0.171991 0.556796 0.099677 +1403715406.46214 -1.128360 2.292290 1.333970 0.804569 -0.186372 0.554229 0.103756 +1403715406.51214 -1.112740 2.305090 1.324100 0.802843 -0.199319 0.551124 0.109443 +1403715406.56214 -1.097140 2.317140 1.313770 0.800668 -0.212316 0.548335 0.114811 +1403715406.61214 -1.081760 2.328090 1.303530 0.797884 -0.224480 0.546245 0.120858 +1403715406.66214 -1.066440 2.337790 1.293640 0.794757 -0.235962 0.544459 0.127469 +1403715406.71214 -1.051060 2.346000 1.283490 0.791454 -0.246813 0.542803 0.134344 +1403715406.76214 -1.035600 2.352760 1.273080 0.787792 -0.256530 0.541380 0.143123 +1403715406.81214 -1.020420 2.358420 1.262780 0.783788 -0.266289 0.540102 0.151843 +1403715406.86214 -1.005320 2.362960 1.252840 0.779906 -0.275769 0.538337 0.160908 +1403715406.91214 -0.990235 2.366660 1.243270 0.776286 -0.285142 0.535981 0.169700 +1403715406.96214 -0.975270 2.369540 1.234390 0.772259 -0.294343 0.533891 0.178711 +1403715407.01214 -0.960247 2.371710 1.225910 0.768621 -0.303983 0.531138 0.186300 +1403715407.06214 -0.944981 2.372840 1.217820 0.765075 -0.314294 0.527979 0.192658 +1403715407.11214 -0.930081 2.373140 1.209710 0.761837 -0.324564 0.524182 0.198739 +1403715407.16214 -0.915363 2.372820 1.201510 0.759313 -0.334387 0.519632 0.203989 +1403715407.21214 -0.900772 2.371980 1.193580 0.758707 -0.343052 0.513252 0.207971 +1403715407.26214 -0.885728 2.369930 1.186310 0.758770 -0.350790 0.506767 0.210719 +1403715407.31214 -0.870151 2.366810 1.179240 0.759867 -0.356511 0.499917 0.213507 +1403715407.36214 -0.853578 2.362130 1.173460 0.760167 -0.361122 0.495120 0.215855 +1403715407.41214 -0.835885 2.355480 1.168530 0.759848 -0.364150 0.492255 0.218428 +1403715407.46214 -0.816914 2.347010 1.164670 0.758163 -0.365990 0.492301 0.221089 +1403715407.51214 -0.797090 2.336590 1.161650 0.757056 -0.366735 0.492001 0.224293 +1403715407.56214 -0.776119 2.324790 1.159110 0.755163 -0.367834 0.493340 0.225928 +1403715407.61214 -0.754361 2.311760 1.157630 0.753506 -0.367387 0.494905 0.228747 +1403715407.66214 -0.731796 2.297530 1.157350 0.752367 -0.365156 0.496253 0.233104 +1403715407.71214 -0.708324 2.282460 1.158130 0.751373 -0.360640 0.498071 0.239380 +1403715407.76214 -0.683767 2.266750 1.159700 0.750902 -0.356488 0.499346 0.244370 +1403715407.81214 -0.658413 2.250680 1.161310 0.751001 -0.353307 0.499939 0.247452 +1403715407.86214 -0.632248 2.234530 1.162640 0.750879 -0.350817 0.500803 0.249610 +1403715407.91214 -0.604900 2.218400 1.163830 0.750054 -0.350414 0.502750 0.248739 +1403715407.96214 -0.576820 2.202280 1.166380 0.750113 -0.349997 0.503314 0.248007 +1403715408.01214 -0.547917 2.186150 1.171160 0.748553 -0.351072 0.505942 0.245845 +1403715408.06214 -0.518677 2.170240 1.178340 0.748337 -0.351539 0.506648 0.244375 +1403715408.11214 -0.488963 2.154450 1.189030 0.747540 -0.352008 0.508189 0.242935 +1403715408.16214 -0.458914 2.138300 1.203270 0.746832 -0.352230 0.509808 0.241394 +1403715408.21214 -0.428571 2.121920 1.220400 0.745783 -0.352237 0.511900 0.240199 +1403715408.26214 -0.398131 2.105230 1.238220 0.745459 -0.351929 0.512811 0.239714 +1403715408.31214 -0.367641 2.088530 1.255300 0.745120 -0.352148 0.513751 0.238425 +1403715408.36214 -0.336857 2.071620 1.270540 0.744503 -0.351977 0.515016 0.237878 +1403715408.41214 -0.305694 2.054530 1.283230 0.743271 -0.350711 0.517910 0.237317 +1403715408.46214 -0.274552 2.037780 1.292420 0.742272 -0.347713 0.521364 0.237294 +1403715408.51214 -0.243397 2.021320 1.298170 0.741001 -0.343559 0.526534 0.235896 +1403715408.56214 -0.212508 2.005410 1.300240 0.740939 -0.337731 0.531031 0.234421 +1403715408.61214 -0.181805 1.990020 1.299440 0.740350 -0.330958 0.537132 0.232030 +1403715408.66214 -0.151577 1.975280 1.296720 0.741157 -0.321912 0.542153 0.230496 +1403715408.71214 -0.122287 1.961780 1.293440 0.742441 -0.312861 0.547190 0.226899 +1403715408.76214 -0.093995 1.949600 1.290070 0.744583 -0.303555 0.551743 0.221428 +1403715408.81214 -0.066578 1.938500 1.287380 0.747434 -0.293147 0.555786 0.215661 +1403715408.86214 -0.039950 1.928770 1.285100 0.751137 -0.283043 0.558958 0.207957 +1403715408.91214 -0.014477 1.920260 1.283570 0.755142 -0.272244 0.561931 0.199694 +1403715408.96214 0.010066 1.913250 1.282590 0.759585 -0.260613 0.564286 0.191553 +1403715409.01214 0.033456 1.907260 1.282410 0.763361 -0.248744 0.567503 0.182610 +1403715409.06214 0.055555 1.902500 1.283060 0.767655 -0.236548 0.569714 0.173713 +1403715409.11214 0.076211 1.898780 1.285050 0.771243 -0.225601 0.572438 0.163104 +1403715409.16214 0.095101 1.895570 1.287370 0.774162 -0.216383 0.575045 0.152234 +1403715409.21214 0.112291 1.892790 1.290410 0.777524 -0.208004 0.576036 0.142738 +1403715409.26214 0.127883 1.890300 1.294160 0.781222 -0.201305 0.575343 0.134720 +1403715409.31214 0.142140 1.888000 1.299160 0.783796 -0.195769 0.575389 0.127535 +1403715409.36214 0.155073 1.885630 1.305170 0.785693 -0.190649 0.575639 0.122386 +1403715409.41214 0.166428 1.883000 1.312080 0.787055 -0.186026 0.575927 0.119362 +1403715409.46214 0.176326 1.880270 1.319930 0.787913 -0.181234 0.576421 0.118685 +1403715409.51214 0.185025 1.877560 1.328800 0.788255 -0.176434 0.577069 0.120482 +1403715409.56214 0.192286 1.874740 1.337830 0.789683 -0.173412 0.575233 0.124243 +1403715409.61214 0.198606 1.872210 1.346730 0.791726 -0.174783 0.571842 0.124970 +1403715409.66214 0.204254 1.870210 1.355950 0.793716 -0.176905 0.568381 0.125149 +1403715409.71214 0.209273 1.868310 1.365240 0.796468 -0.179951 0.563667 0.124642 +1403715409.76214 0.213837 1.866390 1.374900 0.799363 -0.183100 0.558528 0.124658 +1403715409.81214 0.218485 1.864370 1.384900 0.802280 -0.186247 0.553243 0.124827 +1403715409.86214 0.223259 1.862290 1.395640 0.804534 -0.189443 0.548680 0.125647 +1403715409.91214 0.228491 1.860020 1.406210 0.807290 -0.193393 0.543220 0.125679 +1403715409.96214 0.234478 1.857320 1.417000 0.809545 -0.196298 0.538574 0.126657 +1403715410.01214 0.241412 1.854060 1.427940 0.810871 -0.199661 0.535217 0.127142 +1403715410.06214 0.249614 1.850230 1.439310 0.811015 -0.202103 0.533820 0.128240 +1403715410.11214 0.259251 1.845570 1.451280 0.809319 -0.203604 0.535268 0.130525 +1403715410.16214 0.269978 1.840200 1.462990 0.806410 -0.203681 0.538808 0.133804 +1403715410.21214 0.281326 1.834420 1.472410 0.803369 -0.204162 0.542635 0.135882 +1403715410.26214 0.293116 1.828530 1.478520 0.800435 -0.204404 0.546339 0.137972 +1403715410.31214 0.305445 1.822610 1.481240 0.798075 -0.204417 0.549290 0.139894 +1403715410.36214 0.318048 1.817080 1.480930 0.796358 -0.204215 0.551512 0.141224 +1403715410.41214 0.331122 1.811640 1.479150 0.795576 -0.203528 0.552437 0.142998 +1403715410.46214 0.344058 1.806470 1.476470 0.795634 -0.202151 0.552294 0.145167 +1403715410.51214 0.357004 1.801640 1.473760 0.796266 -0.199829 0.551378 0.148361 +1403715410.56214 0.370390 1.797380 1.471490 0.796396 -0.197416 0.551279 0.151232 +1403715410.61214 0.384458 1.793880 1.468810 0.797052 -0.195746 0.550661 0.152198 +1403715410.66214 0.399091 1.791050 1.466320 0.797049 -0.194315 0.551022 0.152736 +1403715410.71214 0.414172 1.788910 1.463750 0.796675 -0.194025 0.552029 0.151417 +1403715410.76214 0.429651 1.787250 1.461940 0.794445 -0.193101 0.555859 0.150298 +1403715410.81214 0.445234 1.786290 1.460730 0.790273 -0.192400 0.562451 0.148659 +1403715410.86214 0.460398 1.786000 1.459390 0.786842 -0.190287 0.567997 0.148491 +1403715410.91214 0.474812 1.786670 1.457280 0.784558 -0.189586 0.572038 0.145938 +1403715410.96214 0.488274 1.788300 1.454420 0.784940 -0.187935 0.572334 0.144855 +1403715411.01214 0.500914 1.791030 1.450690 0.786932 -0.187529 0.570585 0.141436 +1403715411.06214 0.512530 1.794620 1.446670 0.789228 -0.186982 0.568380 0.138212 +1403715411.11214 0.523484 1.798740 1.442680 0.791897 -0.186332 0.565597 0.135205 +1403715411.16214 0.534287 1.803210 1.438960 0.793770 -0.186678 0.563830 0.131057 +1403715411.21214 0.544617 1.807730 1.435940 0.794631 -0.187906 0.563310 0.126234 +1403715411.26214 0.554551 1.812340 1.433460 0.795093 -0.188564 0.563337 0.122152 +1403715411.31214 0.563774 1.816800 1.431370 0.794260 -0.188878 0.565056 0.119117 +1403715411.36214 0.572359 1.821180 1.429540 0.792321 -0.188624 0.568303 0.116962 +1403715411.41214 0.580161 1.825230 1.427530 0.789683 -0.188547 0.572459 0.114636 +1403715411.46214 0.587166 1.828940 1.425420 0.786762 -0.188094 0.576937 0.113006 +1403715411.51214 0.592860 1.832380 1.422960 0.785493 -0.186627 0.579137 0.113012 +1403715411.56214 0.597244 1.835730 1.419880 0.786603 -0.184891 0.578136 0.113266 +1403715411.61214 0.600404 1.838870 1.416910 0.788449 -0.183080 0.576021 0.114144 +1403715411.66214 0.602663 1.841900 1.413990 0.790829 -0.181317 0.573170 0.114847 +1403715411.71214 0.604192 1.844750 1.411360 0.792480 -0.179752 0.571270 0.115388 +1403715411.76214 0.605174 1.847460 1.408830 0.793887 -0.178163 0.569694 0.115976 +1403715411.81214 0.605402 1.850130 1.406120 0.794251 -0.176780 0.569465 0.116719 +1403715411.86214 0.604963 1.853110 1.402710 0.794977 -0.175930 0.568729 0.116652 +1403715411.91214 0.603875 1.856200 1.399480 0.795161 -0.175460 0.568649 0.116493 +1403715411.96214 0.602135 1.859460 1.396420 0.795151 -0.175628 0.568833 0.115404 +1403715412.01214 0.600004 1.862680 1.393370 0.795395 -0.175647 0.568598 0.114853 +1403715412.06214 0.597410 1.865900 1.390200 0.795720 -0.176022 0.568165 0.114168 +1403715412.11214 0.594282 1.869220 1.387430 0.795907 -0.176259 0.567911 0.113760 +1403715412.16214 0.590702 1.872440 1.384640 0.796998 -0.176293 0.566296 0.114124 +1403715412.21214 0.586838 1.875850 1.381800 0.797761 -0.176347 0.565199 0.114147 +1403715412.26214 0.582623 1.879270 1.378780 0.798296 -0.176214 0.564389 0.114616 +1403715412.31214 0.578038 1.882650 1.375660 0.798804 -0.176257 0.563618 0.114810 +1403715412.36214 0.573318 1.885930 1.372620 0.799300 -0.176628 0.562797 0.114814 +1403715412.41214 0.568393 1.889270 1.369720 0.799697 -0.176994 0.562141 0.114692 +1403715412.46214 0.563267 1.892690 1.366880 0.800594 -0.177898 0.560728 0.113956 +1403715412.51214 0.558021 1.896090 1.364200 0.801474 -0.178414 0.559363 0.113673 +1403715412.56214 0.552926 1.899330 1.361390 0.802335 -0.178856 0.558062 0.113295 +1403715412.61214 0.548062 1.902430 1.359000 0.803001 -0.178546 0.557037 0.114104 +1403715412.66214 0.543626 1.905340 1.356830 0.803484 -0.178495 0.556343 0.114171 +1403715412.71214 0.539249 1.907990 1.354790 0.804736 -0.178206 0.554549 0.114537 +1403715412.76214 0.535302 1.910360 1.353380 0.805385 -0.178057 0.553573 0.114925 +1403715412.81214 0.531532 1.912710 1.352080 0.806042 -0.178015 0.552573 0.115190 +1403715412.86214 0.528233 1.914920 1.351150 0.806592 -0.177920 0.551801 0.115194 +1403715412.91214 0.525517 1.916960 1.350620 0.806697 -0.177789 0.551601 0.115620 +1403715412.96214 0.523376 1.918830 1.350540 0.806122 -0.177910 0.552325 0.115984 +1403715413.01214 0.521657 1.920620 1.350080 0.804852 -0.177606 0.554076 0.116915 +1403715413.06214 0.520150 1.922480 1.347150 0.804021 -0.177195 0.555144 0.118183 +1403715413.11214 0.519039 1.924420 1.341710 0.803296 -0.176818 0.556141 0.118989 +1403715413.16214 0.518290 1.926430 1.334170 0.802395 -0.176754 0.557356 0.119475 +1403715413.21214 0.517634 1.928540 1.324040 0.801789 -0.176234 0.558214 0.120309 +1403715413.26214 0.516889 1.930880 1.311560 0.801088 -0.176542 0.559198 0.119948 +1403715413.31214 0.515978 1.933470 1.296720 0.800109 -0.178163 0.560507 0.117961 +1403715413.36214 0.514995 1.936260 1.280600 0.798953 -0.180366 0.562112 0.114770 +1403715413.41214 0.513912 1.938860 1.264900 0.797956 -0.182569 0.563412 0.111810 +1403715413.46214 0.512638 1.941210 1.250180 0.797231 -0.184426 0.564326 0.109301 +1403715413.51214 0.510967 1.943100 1.236730 0.796666 -0.185260 0.565097 0.108014 +1403715413.56214 0.508786 1.944440 1.224690 0.796661 -0.185042 0.565071 0.108555 +1403715413.61214 0.506003 1.945310 1.214160 0.796534 -0.184229 0.565204 0.110174 +1403715413.66214 0.502838 1.945580 1.205040 0.796273 -0.182710 0.565600 0.112530 +1403715413.71214 0.499302 1.945700 1.196890 0.796113 -0.180736 0.565859 0.115508 +1403715413.76214 0.495501 1.945810 1.188140 0.796627 -0.179483 0.565056 0.117827 +1403715413.81214 0.491395 1.945980 1.177760 0.797361 -0.178820 0.563962 0.119103 +1403715413.86214 0.487339 1.946290 1.166040 0.798097 -0.178247 0.562836 0.120351 +1403715413.91214 0.483278 1.946740 1.153510 0.797966 -0.177595 0.563017 0.121336 +1403715413.96214 0.479010 1.947440 1.140750 0.797661 -0.176194 0.563522 0.123027 +1403715414.01214 0.474407 1.948590 1.129550 0.797709 -0.175724 0.563404 0.123925 +1403715414.06214 0.469583 1.950520 1.121100 0.798164 -0.175839 0.562791 0.123613 +1403715414.11214 0.464570 1.953010 1.115550 0.799594 -0.176115 0.560672 0.123610 +1403715414.16214 0.459566 1.956040 1.112900 0.802055 -0.177017 0.557068 0.122674 +1403715414.21214 0.454832 1.959440 1.112480 0.805559 -0.178349 0.551780 0.121675 +1403715414.26214 0.450857 1.963260 1.114800 0.808640 -0.179358 0.547133 0.120739 +1403715414.31214 0.448031 1.966970 1.118720 0.811681 -0.180396 0.542463 0.119855 +1403715414.36214 0.446531 1.970290 1.123010 0.814032 -0.180499 0.538789 0.120329 +1403715414.41214 0.446462 1.973320 1.127070 0.814702 -0.180080 0.537747 0.121080 +1403715414.46214 0.447730 1.976150 1.129770 0.814449 -0.179591 0.538111 0.121886 +1403715414.51214 0.450311 1.979000 1.131110 0.813484 -0.178858 0.539547 0.123053 +1403715414.56214 0.454067 1.981920 1.130650 0.811378 -0.178068 0.542700 0.124236 +1403715414.61214 0.458851 1.985120 1.128650 0.808906 -0.177055 0.546368 0.125712 +1403715414.66214 0.464447 1.988730 1.125420 0.806722 -0.177627 0.549515 0.125222 +1403715414.71214 0.470626 1.993040 1.121220 0.804154 -0.178830 0.553098 0.124255 +1403715414.76214 0.477091 1.997810 1.115970 0.801926 -0.180948 0.556147 0.121956 +1403715414.81214 0.483484 2.002730 1.109660 0.800434 -0.184183 0.557961 0.118578 +1403715414.86214 0.490139 2.007490 1.102410 0.798757 -0.188445 0.559899 0.113970 +1403715414.91214 0.496566 2.011860 1.093720 0.796757 -0.193139 0.562146 0.108933 +1403715414.96214 0.502567 2.015630 1.084310 0.795330 -0.197216 0.563543 0.104761 +1403715415.01214 0.507724 2.018700 1.074570 0.793730 -0.201150 0.565060 0.101185 +1403715415.06214 0.512382 2.020950 1.064410 0.792518 -0.204261 0.566059 0.098845 +1403715415.11214 0.516534 2.022170 1.054100 0.791615 -0.206738 0.566605 0.097790 +1403715415.16214 0.519679 2.022270 1.043730 0.790881 -0.208935 0.566902 0.097340 +1403715415.21214 0.521700 2.021300 1.034070 0.789930 -0.209996 0.567606 0.098667 +1403715415.26214 0.522943 2.019320 1.024840 0.789620 -0.210419 0.567571 0.100433 +1403715415.31214 0.523186 2.016090 1.016840 0.790144 -0.206875 0.566754 0.107999 +1403715415.36214 0.522908 2.012040 1.009520 0.791273 -0.203486 0.564891 0.115668 +1403715415.41214 0.522194 2.007670 1.003810 0.791607 -0.199683 0.563957 0.124248 +1403715415.46214 0.521045 2.003380 0.998826 0.793440 -0.196109 0.560830 0.132151 +1403715415.51214 0.519967 1.999410 0.995645 0.793495 -0.193189 0.560213 0.138578 +1403715415.56214 0.519145 1.996340 0.992591 0.793798 -0.191851 0.559393 0.141978 +1403715415.61214 0.518422 1.994260 0.988697 0.793182 -0.190750 0.559843 0.145095 +1403715415.66214 0.517371 1.993010 0.982313 0.792877 -0.190469 0.559718 0.147593 +1403715415.71214 0.516259 1.992710 0.973077 0.793035 -0.190998 0.559090 0.148437 +1403715415.76214 0.516097 1.992310 0.969360 0.793791 -0.192129 0.557983 0.147096 +1403715415.81214 0.516618 1.993020 0.972738 0.793708 -0.191254 0.558064 0.148374 +1403715415.86214 0.517187 1.994520 0.974900 0.792483 -0.190791 0.559753 0.149152 +1403715415.91214 0.518016 1.996940 0.974646 0.790962 -0.191599 0.561704 0.148853 +1403715415.96214 0.518712 1.999870 0.972311 0.791091 -0.191190 0.561619 0.149017 +1403715416.01214 0.518768 2.000470 0.971290 0.793141 -0.190146 0.559001 0.149300 +1403715416.06214 0.518366 1.999610 0.972445 0.793060 -0.189824 0.558827 0.150780 +1403715416.11214 0.518573 1.999580 0.973005 0.792595 -0.190259 0.559254 0.151094 +1403715416.16214 0.518855 1.999740 0.972494 0.792294 -0.190588 0.559647 0.150804 +1403715416.21214 0.518956 1.999620 0.972258 0.792964 -0.191456 0.558659 0.149844 +1403715416.26214 0.519069 2.000120 0.971618 0.793628 -0.191871 0.557797 0.149006 +1403715416.31214 0.519052 2.000360 0.971218 0.793698 -0.192113 0.557693 0.148710 +1403715416.36214 0.519256 1.999940 0.971111 0.794073 -0.192107 0.557162 0.148707 +1403715416.41214 0.519532 1.999450 0.971200 0.794165 -0.192242 0.557020 0.148575 +1403715416.46214 0.519687 1.999360 0.970975 0.794501 -0.192281 0.556561 0.148446 +1403715416.51214 0.519734 1.999700 0.970590 0.794314 -0.192488 0.556747 0.148482 +1403715416.56214 0.519683 1.999670 0.970525 0.793976 -0.192164 0.557258 0.148794 +1403715416.61214 0.519782 1.999290 0.970376 0.794254 -0.192214 0.556869 0.148700 +1403715416.66214 0.519875 1.999130 0.970192 0.794279 -0.192495 0.556831 0.148345 +1403715416.71214 0.519754 1.999250 0.969966 0.794291 -0.192425 0.556819 0.148414 +1403715416.76214 0.519555 1.999440 0.969786 0.794317 -0.192435 0.556793 0.148364 +1403715416.81214 0.519442 1.999510 0.969682 0.794006 -0.192354 0.557221 0.148524 +1403715416.86214 0.519558 1.999440 0.969581 0.794248 -0.192391 0.556907 0.148356 +1403715416.91214 0.519602 1.999290 0.969511 0.794439 -0.192514 0.556627 0.148230 +1403715416.96214 0.519501 1.999440 0.969503 0.794266 -0.192318 0.556889 0.148423 +1403715417.01214 0.519438 1.999650 0.969379 0.794059 -0.192359 0.557185 0.148369 +1403715417.06214 0.519499 1.999570 0.969327 0.794110 -0.192213 0.557119 0.148530 +1403715417.11214 0.519687 1.999350 0.969271 0.794268 -0.192353 0.556895 0.148347 +1403715417.16214 0.519771 1.999240 0.969274 0.794275 -0.192379 0.556881 0.148327 +1403715417.21214 0.519778 1.999350 0.969269 0.794128 -0.192302 0.557101 0.148391 +1403715417.26214 0.519822 1.999510 0.969243 0.794141 -0.192244 0.557099 0.148400 +1403715417.31214 0.519879 1.999540 0.969278 0.794044 -0.192237 0.557222 0.148467 +1403715417.36214 0.520018 1.999470 0.969264 0.794190 -0.192244 0.557042 0.148351 +1403715417.41214 0.520080 1.999450 0.969258 0.794190 -0.192316 0.557017 0.148353 +1403715417.46214 0.520024 1.999610 0.969221 0.794122 -0.192305 0.557121 0.148344 +1403715417.51214 0.519912 1.999710 0.969177 0.794048 -0.192271 0.557240 0.148336 +1403715417.56214 0.519843 1.999630 0.969178 0.794021 -0.192318 0.557253 0.148369 +1403715417.61214 0.519788 1.999490 0.969150 0.794075 -0.192400 0.557168 0.148296 +1403715417.66214 0.519690 1.999470 0.969107 0.794101 -0.192418 0.557133 0.148264 +1403715417.71214 0.519588 1.999510 0.969113 0.794017 -0.192460 0.557253 0.148205 +1403715417.76214 0.519508 1.999540 0.969140 0.793974 -0.192441 0.557318 0.148217 +1403715417.81214 0.519491 1.999450 0.969143 0.794021 -0.192507 0.557231 0.148204 +1403715417.86214 0.519481 1.999320 0.969171 0.794043 -0.192526 0.557182 0.148248 +1403715417.91214 0.519484 1.999250 0.969201 0.794068 -0.192514 0.557141 0.148284 +1403715417.96214 0.519458 1.999260 0.969236 0.794037 -0.192483 0.557206 0.148245 diff --git a/test/data/V101_openvins.txt b/test/data/V101_openvins.txt new file mode 100644 index 00000000..d7cfc4f6 --- /dev/null +++ b/test/data/V101_openvins.txt @@ -0,0 +1,2776 @@ +1.403715278862139940e+09 3.595999999999999804e-03 1.406199999999999985e-02 9.410999999999999921e-02 8.089129999999999932e-01 -8.635999999999999580e-03 5.878640000000000532e-01 1.103999999999999947e-03 +1.403715278912139893e+09 4.653399999999999898e-02 1.238599999999999944e-02 9.670700000000000129e-02 8.119279999999999831e-01 -7.661000000000000275e-03 5.837069999999999759e-01 6.970000000000000284e-04 +1.403715278962140083e+09 5.474799999999999806e-02 1.412399999999999940e-02 1.154000000000000026e-01 8.113489999999999869e-01 -7.453999999999999689e-03 5.845139999999999780e-01 8.220000000000000310e-04 +1.403715279012140036e+09 6.289200000000000346e-02 1.528299999999999971e-02 1.289720000000000033e-01 8.110079999999999512e-01 -6.701000000000000359e-03 5.849940000000000140e-01 1.552999999999999910e-03 +1.403715279062139988e+09 7.000599999999999878e-02 1.657899999999999999e-02 1.379209999999999881e-01 8.112169999999999659e-01 -6.445000000000000208e-03 5.847069999999999768e-01 1.750999999999999952e-03 +1.403715279112139940e+09 7.618600000000000372e-02 1.779800000000000132e-02 1.420569999999999888e-01 8.112669999999999604e-01 -6.278999999999999859e-03 5.846379999999999910e-01 2.027000000000000156e-03 +1.403715279162139893e+09 8.204599999999999393e-02 1.905199999999999949e-02 1.404469999999999885e-01 8.116100000000000536e-01 -5.598999999999999810e-03 5.841669999999999918e-01 2.671000000000000197e-03 +1.403715279212140083e+09 8.737599999999999534e-02 1.989399999999999849e-02 1.351499999999999924e-01 8.121549999999999603e-01 -5.109999999999999959e-03 5.834099999999999842e-01 3.439000000000000216e-03 +1.403715279262140036e+09 9.295499999999999596e-02 1.992100000000000121e-02 1.270509999999999973e-01 8.122629999999999573e-01 -4.597999999999999657e-03 5.832640000000000047e-01 3.396999999999999846e-03 +1.403715279312139988e+09 9.810199999999999476e-02 2.092199999999999963e-02 1.190739999999999993e-01 8.128260000000000485e-01 -4.511000000000000253e-03 5.824799999999999978e-01 3.330000000000000061e-03 +1.403715279362139940e+09 1.026129999999999959e-01 2.152000000000000093e-02 1.122159999999999963e-01 8.133979999999999544e-01 -5.002000000000000370e-03 5.816789999999999461e-01 2.841000000000000209e-03 +1.403715279412139893e+09 1.064329999999999998e-01 2.105100000000000027e-02 1.061600000000000044e-01 8.132639999999999869e-01 -5.336999999999999730e-03 5.818680000000000518e-01 1.701999999999999954e-03 +1.403715279462140083e+09 1.100420000000000009e-01 2.116200000000000025e-02 1.019980000000000053e-01 8.138649999999999496e-01 -5.393000000000000224e-03 5.810269999999999602e-01 1.410000000000000012e-03 +1.403715279512140036e+09 1.139180000000000054e-01 2.262899999999999981e-02 9.784900000000000542e-02 8.137780000000000014e-01 -5.568000000000000033e-03 5.811469999999999692e-01 1.270999999999999994e-03 +1.403715279562139988e+09 1.170940000000000036e-01 2.290899999999999881e-02 9.875599999999999656e-02 8.135689999999999866e-01 -4.995999999999999573e-03 5.814439999999999609e-01 1.917000000000000084e-03 +1.403715279612139940e+09 1.197759999999999936e-01 2.295799999999999924e-02 1.006259999999999932e-01 8.138600000000000279e-01 -4.917000000000000363e-03 5.810370000000000257e-01 2.161000000000000160e-03 +1.403715279662139893e+09 1.217390000000000000e-01 2.276299999999999851e-02 1.038089999999999985e-01 8.140110000000000401e-01 -4.632999999999999965e-03 5.808280000000000109e-01 2.186000000000000009e-03 +1.403715279712140083e+09 1.235679999999999973e-01 2.230599999999999944e-02 1.076779999999999959e-01 8.138069999999999471e-01 -4.617999999999999709e-03 5.811129999999999907e-01 2.180000000000000080e-03 +1.403715279762140036e+09 1.250610000000000055e-01 2.193499999999999964e-02 1.125820000000000015e-01 8.138729999999999576e-01 -4.641000000000000160e-03 5.810199999999999809e-01 2.082000000000000083e-03 +1.403715279812139988e+09 1.259490000000000054e-01 2.121800000000000075e-02 1.183209999999999956e-01 8.140060000000000073e-01 -4.969000000000000326e-03 5.808320000000000149e-01 1.804999999999999964e-03 +1.403715279862139940e+09 1.262179999999999969e-01 2.028999999999999901e-02 1.248999999999999971e-01 8.142939999999999623e-01 -4.823000000000000030e-03 5.804300000000000015e-01 1.755999999999999965e-03 +1.403715279912139893e+09 1.261569999999999914e-01 1.924100000000000116e-02 1.321340000000000015e-01 8.147889999999999855e-01 -4.773999999999999598e-03 5.797360000000000291e-01 1.907000000000000058e-03 +1.403715279962140083e+09 1.259899999999999909e-01 1.822199999999999862e-02 1.397430000000000061e-01 8.163629999999999498e-01 -4.543000000000000163e-03 5.775169999999999471e-01 2.276999999999999944e-03 +1.403715280012140036e+09 1.255509999999999959e-01 1.721999999999999920e-02 1.464949999999999863e-01 8.198079999999999812e-01 -4.713000000000000175e-03 5.726139999999999564e-01 2.260999999999999989e-03 +1.403715280062139988e+09 1.253009999999999957e-01 1.621699999999999878e-02 1.526450000000000029e-01 8.241150000000000420e-01 -4.683999999999999796e-03 5.663979999999999571e-01 2.322999999999999978e-03 +1.403715280112139940e+09 1.254939999999999944e-01 1.501000000000000077e-02 1.589129999999999987e-01 8.279680000000000373e-01 -2.882000000000000013e-03 5.607450000000000490e-01 5.134999999999999808e-03 +1.403715280162139893e+09 1.268539999999999945e-01 1.389499999999999937e-02 1.655369999999999897e-01 8.301169999999999938e-01 -9.669999999999999776e-04 5.575379999999999781e-01 7.494999999999999926e-03 +1.403715280212140083e+09 1.293269999999999975e-01 1.266499999999999918e-02 1.730089999999999961e-01 8.308830000000000382e-01 2.096000000000000207e-03 5.563230000000000119e-01 1.157900000000000075e-02 +1.403715280262140036e+09 1.330840000000000078e-01 1.183200000000000050e-02 1.811510000000000065e-01 8.304810000000000247e-01 4.839999999999999684e-03 5.568149999999999489e-01 1.534699999999999953e-02 +1.403715280312139988e+09 1.380730000000000013e-01 1.174399999999999923e-02 1.896970000000000045e-01 8.295860000000000456e-01 7.087000000000000417e-03 5.580399999999999805e-01 1.814199999999999841e-02 +1.403715280362139940e+09 1.441729999999999956e-01 1.238299999999999991e-02 1.987130000000000007e-01 8.281859999999999777e-01 8.583999999999999617e-03 5.600089999999999790e-01 2.056900000000000048e-02 +1.403715280412139893e+09 1.515499999999999903e-01 1.340700000000000051e-02 2.079689999999999872e-01 8.266470000000000207e-01 8.942999999999999561e-03 5.621690000000000298e-01 2.325100000000000083e-02 +1.403715280462140083e+09 1.599770000000000081e-01 1.497199999999999920e-02 2.169169999999999987e-01 8.259940000000000060e-01 5.812999999999999591e-03 5.631730000000000347e-01 2.316299999999999956e-02 +1.403715280512140036e+09 1.690840000000000121e-01 1.699399999999999869e-02 2.254919999999999980e-01 8.249049999999999994e-01 -6.629999999999999609e-04 5.648410000000000375e-01 2.207299999999999887e-02 +1.403715280562139988e+09 1.784340000000000093e-01 1.951299999999999910e-02 2.339150000000000118e-01 8.238220000000000542e-01 -8.070000000000000784e-03 5.663660000000000361e-01 2.196199999999999888e-02 +1.403715280612139940e+09 1.883259999999999934e-01 2.200600000000000125e-02 2.421919999999999906e-01 8.225050000000000416e-01 -1.688299999999999870e-02 5.680370000000000141e-01 2.312099999999999919e-02 +1.403715280662139893e+09 1.992120000000000002e-01 2.452299999999999966e-02 2.507499999999999729e-01 8.214219999999999855e-01 -2.601099999999999940e-02 5.690889999999999560e-01 2.697599999999999998e-02 +1.403715280712140083e+09 2.101339999999999875e-01 2.672599999999999976e-02 2.587499999999999800e-01 8.202110000000000234e-01 -3.630300000000000193e-02 5.700490000000000279e-01 3.130000000000000143e-02 +1.403715280762140036e+09 2.201150000000000051e-01 2.954499999999999835e-02 2.651339999999999808e-01 8.193000000000000282e-01 -4.693800000000000056e-02 5.702479999999999771e-01 3.688600000000000212e-02 +1.403715280812139988e+09 2.297460000000000058e-01 3.223700000000000176e-02 2.705170000000000075e-01 8.187029999999999585e-01 -5.787699999999999789e-02 5.696790000000000465e-01 4.291199999999999876e-02 +1.403715280862139940e+09 2.391119999999999912e-01 3.516400000000000081e-02 2.756750000000000034e-01 8.173129999999999562e-01 -6.853599999999999970e-02 5.699480000000000102e-01 4.962300000000000044e-02 +1.403715280912139893e+09 2.485769999999999924e-01 3.863899999999999973e-02 2.806100000000000261e-01 8.161230000000000429e-01 -7.825400000000000411e-02 5.697929999999999939e-01 5.616600000000000065e-02 +1.403715280962140083e+09 2.577650000000000219e-01 4.243799999999999656e-02 2.853120000000000100e-01 8.148750000000000160e-01 -8.645300000000000207e-02 5.698069999999999524e-01 6.184800000000000020e-02 +1.403715281012140036e+09 2.669119999999999826e-01 4.628999999999999782e-02 2.900079999999999880e-01 8.137560000000000349e-01 -9.398299999999999710e-02 5.696949999999999514e-01 6.645199999999999718e-02 +1.403715281062139988e+09 2.762430000000000163e-01 5.018000000000000238e-02 2.948080000000000145e-01 8.131429999999999492e-01 -9.995300000000000018e-02 5.689689999999999470e-01 7.128800000000000414e-02 +1.403715281112139940e+09 2.860360000000000125e-01 5.408299999999999913e-02 2.998160000000000269e-01 8.122719999999999940e-01 -1.052710000000000035e-01 5.687710000000000266e-01 7.504600000000000160e-02 +1.403715281162139893e+09 2.957690000000000041e-01 5.766700000000000298e-02 3.045849999999999946e-01 8.112279999999999491e-01 -1.093770000000000020e-01 5.690349999999999575e-01 7.838599999999999735e-02 +1.403715281212140083e+09 3.054000000000000048e-01 6.110000000000000153e-02 3.090530000000000221e-01 8.104580000000000117e-01 -1.132370000000000043e-01 5.689400000000000013e-01 8.150000000000000300e-02 +1.403715281262140036e+09 3.147750000000000270e-01 6.419900000000000606e-02 3.129770000000000052e-01 8.097579999999999778e-01 -1.178379999999999983e-01 5.685900000000000398e-01 8.433200000000000418e-02 +1.403715281312139988e+09 3.236720000000000153e-01 6.660900000000000154e-02 3.158679999999999821e-01 8.093329999999999691e-01 -1.229250000000000065e-01 5.675820000000000309e-01 8.786499999999999866e-02 +1.403715281362139940e+09 3.328349999999999920e-01 6.915899999999999825e-02 3.184159999999999768e-01 8.088610000000000522e-01 -1.286599999999999966e-01 5.663770000000000193e-01 9.169599999999999973e-02 +1.403715281412139893e+09 3.422859999999999792e-01 7.138799999999999313e-02 3.204949999999999743e-01 8.083669999999999467e-01 -1.347980000000000012e-01 5.649159999999999737e-01 9.614000000000000323e-02 +1.403715281462140083e+09 3.515570000000000084e-01 7.243199999999999639e-02 3.217389999999999972e-01 8.069619999999999571e-01 -1.417170000000000096e-01 5.642629999999999590e-01 1.016620000000000024e-01 +1.403715281512140036e+09 3.607819999999999916e-01 7.401199999999999446e-02 3.226390000000000091e-01 8.055740000000000123e-01 -1.496000000000000107e-01 5.630490000000000217e-01 1.079220000000000040e-01 +1.403715281562139988e+09 3.703119999999999745e-01 7.502899999999999847e-02 3.229819999999999913e-01 8.041530000000000067e-01 -1.583009999999999973e-01 5.612660000000000426e-01 1.151459999999999984e-01 +1.403715281612139940e+09 3.799890000000000212e-01 7.596300000000000274e-02 3.226410000000000111e-01 8.022529999999999939e-01 -1.680679999999999952e-01 5.595360000000000333e-01 1.227270000000000028e-01 +1.403715281662139893e+09 3.898829999999999796e-01 7.671600000000000641e-02 3.215250000000000052e-01 7.999070000000000347e-01 -1.791159999999999974e-01 5.577499999999999680e-01 1.303090000000000082e-01 +1.403715281712140083e+09 4.001569999999999849e-01 7.725700000000000622e-02 3.200819999999999776e-01 7.974529999999999674e-01 -1.905479999999999952e-01 5.554599999999999538e-01 1.386509999999999965e-01 +1.403715281762140036e+09 4.109519999999999840e-01 7.811999999999999500e-02 3.184089999999999976e-01 7.949610000000000287e-01 -2.027339999999999975e-01 5.526309999999999834e-01 1.467499999999999916e-01 +1.403715281812139988e+09 4.212690000000000046e-01 7.854300000000000170e-02 3.162719999999999976e-01 7.921310000000000295e-01 -2.151460000000000039e-01 5.497499999999999609e-01 1.549699999999999966e-01 +1.403715281862139940e+09 4.322400000000000131e-01 7.872899999999999343e-02 3.139109999999999956e-01 7.884689999999999754e-01 -2.277609999999999912e-01 5.475139999999999452e-01 1.633080000000000087e-01 +1.403715281912139893e+09 4.460689999999999933e-01 7.860300000000000620e-02 3.110840000000000272e-01 7.853050000000000308e-01 -2.402360000000000051e-01 5.442129999999999468e-01 1.715059999999999918e-01 +1.403715281962140083e+09 4.575089999999999990e-01 7.871100000000000319e-02 3.073049999999999948e-01 7.815090000000000092e-01 -2.526100000000000012e-01 5.415309999999999846e-01 1.793770000000000087e-01 +1.403715282012140036e+09 4.693820000000000214e-01 7.878000000000000280e-02 3.030390000000000028e-01 7.776229999999999531e-01 -2.649039999999999728e-01 5.387020000000000142e-01 1.868940000000000046e-01 +1.403715282062139988e+09 4.819129999999999803e-01 7.814400000000000512e-02 2.983129999999999948e-01 7.735739999999999839e-01 -2.768169999999999797e-01 5.359530000000000127e-01 1.941900000000000015e-01 +1.403715282112139940e+09 4.949549999999999783e-01 7.795699999999999852e-02 2.930969999999999964e-01 7.698300000000000143e-01 -2.872600000000000153e-01 5.326969999999999761e-01 2.026759999999999950e-01 +1.403715282162139893e+09 5.084520000000000151e-01 7.770599999999999730e-02 2.874869999999999925e-01 7.660240000000000382e-01 -2.983770000000000033e-01 5.294349999999999890e-01 2.094650000000000123e-01 +1.403715282212140083e+09 5.221890000000000143e-01 7.722700000000000398e-02 2.820779999999999954e-01 7.619219999999999882e-01 -3.084200000000000275e-01 5.264569999999999528e-01 2.172459999999999947e-01 +1.403715282262140036e+09 5.367610000000000436e-01 7.700400000000000300e-02 2.761859999999999871e-01 7.581240000000000201e-01 -3.190470000000000250e-01 5.225919999999999455e-01 2.243989999999999874e-01 +1.403715282312139988e+09 5.516919999999999602e-01 7.680499999999999827e-02 2.702570000000000250e-01 7.541959999999999775e-01 -3.293630000000000169e-01 5.187859999999999694e-01 2.314519999999999911e-01 +1.403715282362139940e+09 5.664759999999999796e-01 7.666299999999999504e-02 2.646839999999999749e-01 7.499460000000000015e-01 -3.394449999999999967e-01 5.150949999999999696e-01 2.388210000000000055e-01 +1.403715282412139893e+09 5.817729999999999846e-01 7.648199999999999443e-02 2.588349999999999818e-01 7.465279999999999694e-01 -3.485770000000000257e-01 5.100609999999999866e-01 2.470400000000000096e-01 +1.403715282462140083e+09 5.975139999999999896e-01 7.659100000000000630e-02 2.528349999999999764e-01 7.419750000000000512e-01 -3.589700000000000113e-01 5.063029999999999475e-01 2.535200000000000231e-01 +1.403715282512140036e+09 6.147559999999999691e-01 7.609299999999999398e-02 2.465839999999999976e-01 7.371980000000000199e-01 -3.683480000000000087e-01 5.028620000000000312e-01 2.607459999999999778e-01 +1.403715282562139988e+09 6.314610000000000500e-01 7.562399999999999678e-02 2.404949999999999866e-01 7.322089999999999987e-01 -3.778199999999999892e-01 4.994439999999999991e-01 2.677249999999999908e-01 +1.403715282612139940e+09 6.484670000000000156e-01 7.519599999999999895e-02 2.346910000000000107e-01 7.265300000000000091e-01 -3.863480000000000247e-01 4.971900000000000208e-01 2.751210000000000044e-01 +1.403715282662139893e+09 6.661289999999999711e-01 7.378300000000000136e-02 2.285169999999999979e-01 7.203969999999999541e-01 -3.954289999999999750e-01 4.954990000000000228e-01 2.813249999999999917e-01 +1.403715282712140083e+09 6.838610000000000522e-01 7.349400000000000377e-02 2.223090000000000066e-01 7.141380000000000505e-01 -4.046469999999999789e-01 4.936429999999999985e-01 2.873740000000000183e-01 +1.403715282762140036e+09 7.018400000000000194e-01 7.319299999999999418e-02 2.158839999999999926e-01 7.077930000000000055e-01 -4.140110000000000179e-01 4.921409999999999951e-01 2.922679999999999723e-01 +1.403715282812139988e+09 7.197109999999999896e-01 7.296099999999999808e-02 2.090269999999999906e-01 7.018809999999999771e-01 -4.236800000000000010e-01 4.896610000000000129e-01 2.968009999999999815e-01 +1.403715282862139940e+09 7.378270000000000106e-01 7.224500000000000366e-02 2.020790000000000086e-01 6.959809999999999608e-01 -4.320640000000000036e-01 4.869550000000000267e-01 3.029939999999999856e-01 +1.403715282912139893e+09 7.559519999999999573e-01 7.173799999999999621e-02 1.950050000000000117e-01 6.898379999999999512e-01 -4.400129999999999875e-01 4.843649999999999900e-01 3.096829999999999861e-01 +1.403715282962140083e+09 7.741749999999999465e-01 7.113200000000000078e-02 1.877010000000000067e-01 6.838269999999999627e-01 -4.486680000000000113e-01 4.812719999999999776e-01 3.153639999999999777e-01 +1.403715283012140036e+09 7.924759999999999582e-01 7.073100000000000220e-02 1.804759999999999975e-01 6.773439999999999461e-01 -4.572640000000000038e-01 4.786030000000000006e-01 3.210200000000000276e-01 +1.403715283062139988e+09 8.107550000000000034e-01 7.032299999999999662e-02 1.732049999999999979e-01 6.704590000000000272e-01 -4.661109999999999975e-01 4.762569999999999859e-01 3.261979999999999880e-01 +1.403715283112139940e+09 8.294280000000000541e-01 6.983999999999999930e-02 1.658759999999999957e-01 6.636900000000000022e-01 -4.751349999999999740e-01 4.737950000000000217e-01 3.305770000000000097e-01 +1.403715283162139893e+09 8.472060000000000146e-01 6.938300000000000023e-02 1.587129999999999930e-01 6.564370000000000482e-01 -4.841340000000000088e-01 4.720030000000000059e-01 3.345420000000000060e-01 +1.403715283212140083e+09 8.645389999999999464e-01 6.935600000000000098e-02 1.518829999999999902e-01 6.491829999999999545e-01 -4.928000000000000158e-01 4.699740000000000029e-01 3.388720000000000065e-01 +1.403715283262140036e+09 8.814680000000000293e-01 6.936399999999999511e-02 1.454010000000000025e-01 6.424950000000000383e-01 -5.007559999999999789e-01 4.672729999999999939e-01 3.436560000000000170e-01 +1.403715283312139988e+09 8.978990000000000027e-01 6.946700000000000097e-02 1.388949999999999907e-01 6.357760000000000078e-01 -5.089789999999999592e-01 4.646140000000000270e-01 3.476549999999999918e-01 +1.403715283362139940e+09 9.133639999999999537e-01 6.973000000000000032e-02 1.330479999999999996e-01 6.293130000000000113e-01 -5.159190000000000165e-01 4.617519999999999958e-01 3.529559999999999920e-01 +1.403715283412139893e+09 9.279730000000000478e-01 7.040599999999999636e-02 1.268900000000000028e-01 6.242320000000000091e-01 -5.235290000000000221e-01 4.572459999999999858e-01 3.566210000000000213e-01 +1.403715283462140083e+09 9.419610000000000483e-01 7.116799999999999515e-02 1.208560000000000051e-01 6.195929999999999493e-01 -5.310679999999999845e-01 4.522709999999999786e-01 3.598919999999999897e-01 +1.403715283512140036e+09 9.553970000000000518e-01 7.157499999999999973e-02 1.150199999999999972e-01 6.158010000000000428e-01 -5.377469999999999750e-01 4.462050000000000183e-01 3.640300000000000202e-01 +1.403715283562139988e+09 9.686740000000000350e-01 7.142700000000000438e-02 1.094549999999999967e-01 6.123220000000000329e-01 -5.440720000000000001e-01 4.399299999999999877e-01 3.681150000000000255e-01 +1.403715283612139940e+09 9.811950000000000394e-01 7.233399999999999552e-02 1.047489999999999949e-01 6.093190000000000550e-01 -5.500089999999999701e-01 4.337289999999999757e-01 3.716180000000000039e-01 +1.403715283662139893e+09 9.936690000000000245e-01 7.285400000000000209e-02 1.003099999999999964e-01 6.069149999999999823e-01 -5.546450000000000546e-01 4.286499999999999755e-01 3.745419999999999860e-01 +1.403715283712140083e+09 1.006099999999999994e+00 7.303099999999999870e-02 9.602900000000000325e-02 6.045500000000000318e-01 -5.581709999999999727e-01 4.249780000000000224e-01 3.773039999999999727e-01 +1.403715283762140036e+09 1.018666000000000071e+00 7.278600000000000347e-02 9.184799999999999909e-02 6.022699999999999720e-01 -5.611129999999999729e-01 4.226590000000000069e-01 3.791860000000000230e-01 +1.403715283812139988e+09 1.031219000000000108e+00 7.230100000000000415e-02 8.800399999999999889e-02 5.994350000000000511e-01 -5.633219999999999894e-01 4.222060000000000257e-01 3.809040000000000203e-01 +1.403715283862139940e+09 1.043711999999999973e+00 7.158299999999999386e-02 8.396900000000000197e-02 5.975160000000000471e-01 -5.643479999999999608e-01 4.214160000000000128e-01 3.832679999999999976e-01 +1.403715283912139893e+09 1.056044999999999900e+00 7.050599999999999923e-02 7.982799999999999618e-02 5.953180000000000138e-01 -5.653359999999999497e-01 4.221650000000000125e-01 3.844069999999999987e-01 +1.403715283962140083e+09 1.068337000000000092e+00 6.919200000000000350e-02 7.531599999999999406e-02 5.939200000000000035e-01 -5.660549999999999748e-01 4.222710000000000075e-01 3.853929999999999856e-01 +1.403715284012140036e+09 1.080762000000000000e+00 6.724099999999999522e-02 6.970899999999999319e-02 5.940769999999999662e-01 -5.675569999999999782e-01 4.211389999999999856e-01 3.841800000000000215e-01 +1.403715284062139988e+09 1.093223000000000056e+00 6.513399999999999745e-02 6.427599999999999980e-02 5.948419999999999819e-01 -5.686809999999999921e-01 4.197779999999999845e-01 3.828199999999999936e-01 +1.403715284112139940e+09 1.105523000000000033e+00 6.278599999999999459e-02 5.884199999999999847e-02 5.954129999999999701e-01 -5.700790000000000024e-01 4.191019999999999746e-01 3.805870000000000086e-01 +1.403715284162139893e+09 1.117323000000000066e+00 5.978800000000000087e-02 5.301700000000000162e-02 5.958930000000000060e-01 -5.712409999999999988e-01 4.192989999999999773e-01 3.778670000000000084e-01 +1.403715284212140083e+09 1.128446000000000060e+00 5.682299999999999851e-02 4.769000000000000322e-02 5.954580000000000428e-01 -5.729659999999999753e-01 4.209999999999999853e-01 3.740299999999999736e-01 +1.403715284262140036e+09 1.138989999999999947e+00 5.311099999999999849e-02 4.271599999999999703e-02 5.949579999999999869e-01 -5.743500000000000272e-01 4.230010000000000159e-01 3.704290000000000083e-01 +1.403715284312139988e+09 1.149080000000000101e+00 4.854800000000000088e-02 3.789399999999999713e-02 5.942359999999999864e-01 -5.756869999999999488e-01 4.255550000000000166e-01 3.665649999999999742e-01 +1.403715284362139940e+09 1.157820000000000071e+00 4.322899999999999660e-02 3.354800000000000143e-02 5.937120000000000175e-01 -5.759349999999999747e-01 4.279529999999999723e-01 3.642270000000000230e-01 +1.403715284412139893e+09 1.165526999999999980e+00 3.683600000000000069e-02 2.976300000000000126e-02 5.950180000000000469e-01 -5.737379999999999702e-01 4.279800000000000271e-01 3.655289999999999928e-01 +1.403715284462140083e+09 1.172074000000000060e+00 2.983299999999999841e-02 2.618200000000000041e-02 5.968670000000000364e-01 -5.709999999999999520e-01 4.274720000000000186e-01 3.673919999999999964e-01 +1.403715284512140036e+09 1.177815000000000056e+00 2.222299999999999970e-02 2.295499999999999971e-02 5.994119999999999449e-01 -5.673219999999999930e-01 4.261860000000000093e-01 3.704279999999999795e-01 +1.403715284562139988e+09 1.183063999999999893e+00 1.388099999999999924e-02 1.982799999999999840e-02 6.013009999999999744e-01 -5.637280000000000069e-01 4.259530000000000260e-01 3.731129999999999725e-01 +1.403715284612139940e+09 1.187721999999999944e+00 5.466000000000000372e-03 1.673300000000000134e-02 6.030149999999999677e-01 -5.600330000000000030e-01 4.260470000000000090e-01 3.757929999999999882e-01 +1.403715284662139893e+09 1.192255999999999982e+00 -3.199000000000000021e-03 1.361099999999999983e-02 6.050579999999999847e-01 -5.567959999999999576e-01 4.255579999999999918e-01 3.778679999999999817e-01 +1.403715284712140083e+09 1.196914999999999951e+00 -1.208200000000000073e-02 1.060299999999999958e-02 6.063819999999999766e-01 -5.543339999999999934e-01 4.258319999999999883e-01 3.790540000000000020e-01 +1.403715284762140036e+09 1.201289999999999969e+00 -2.051599999999999951e-02 8.030000000000000679e-03 6.070980000000000265e-01 -5.524080000000000101e-01 4.257830000000000226e-01 3.807699999999999974e-01 +1.403715284812139988e+09 1.205791000000000057e+00 -2.913200000000000164e-02 5.377999999999999968e-03 6.064939999999999776e-01 -5.517229999999999634e-01 4.254459999999999908e-01 3.830950000000000188e-01 +1.403715284862139940e+09 1.210363000000000078e+00 -3.747199999999999837e-02 3.341999999999999919e-03 6.039839999999999653e-01 -5.522369999999999779e-01 4.256199999999999983e-01 3.861169999999999880e-01 +1.403715284912139893e+09 1.214860999999999969e+00 -4.563899999999999901e-02 1.567999999999999949e-03 5.993640000000000079e-01 -5.549410000000000176e-01 4.265680000000000027e-01 3.883840000000000070e-01 +1.403715284962140083e+09 1.219093999999999900e+00 -5.356099999999999750e-02 2.680000000000000090e-04 5.929520000000000346e-01 -5.583869999999999667e-01 4.272630000000000039e-01 3.925020000000000175e-01 +1.403715285012140036e+09 1.223036000000000012e+00 -6.039400000000000324e-02 -1.348000000000000023e-03 5.840520000000000156e-01 -5.635099999999999554e-01 4.290660000000000029e-01 3.965380000000000016e-01 +1.403715285062139988e+09 1.226742999999999917e+00 -6.747400000000000619e-02 -1.794000000000000022e-03 5.753610000000000113e-01 -5.690730000000000510e-01 4.291490000000000027e-01 4.011819999999999831e-01 +1.403715285112139940e+09 1.229975999999999958e+00 -7.349999999999999589e-02 -1.753000000000000001e-03 5.675459999999999949e-01 -5.750319999999999876e-01 4.260889999999999955e-01 4.070349999999999802e-01 +1.403715285162139893e+09 1.232987000000000055e+00 -7.794299999999999840e-02 -1.178999999999999927e-03 5.606389999999999985e-01 -5.821720000000000228e-01 4.214120000000000088e-01 4.113060000000000049e-01 +1.403715285212140083e+09 1.236024000000000012e+00 -8.119700000000000528e-02 -5.460000000000000443e-04 5.539830000000000032e-01 -5.907130000000000436e-01 4.159900000000000264e-01 4.136580000000000257e-01 +1.403715285262140036e+09 1.239030000000000076e+00 -8.370199999999999863e-02 1.165000000000000020e-03 5.482019999999999671e-01 -5.988919999999999799e-01 4.110199999999999965e-01 4.145670000000000188e-01 +1.403715285312139988e+09 1.241891999999999996e+00 -8.495199999999999974e-02 4.904999999999999638e-03 5.433649999999999869e-01 -6.073159999999999670e-01 4.065389999999999837e-01 4.130960000000000187e-01 +1.403715285362139940e+09 1.244469000000000047e+00 -8.562699999999999478e-02 1.145900000000000044e-02 5.395400000000000196e-01 -6.150099999999999456e-01 4.020150000000000112e-01 4.111469999999999847e-01 +1.403715285412139893e+09 1.246558999999999973e+00 -8.656400000000000206e-02 2.198699999999999960e-02 5.373360000000000358e-01 -6.214260000000000339e-01 3.973579999999999890e-01 4.089099999999999957e-01 +1.403715285462140083e+09 1.247978000000000032e+00 -8.741000000000000159e-02 3.627500000000000169e-02 5.356630000000000003e-01 -6.260390000000000121e-01 3.936720000000000219e-01 4.076310000000000211e-01 +1.403715285512140036e+09 1.248491999999999935e+00 -8.828300000000000036e-02 5.332400000000000334e-02 5.339979999999999727e-01 -6.298580000000000290e-01 3.911680000000000157e-01 4.063399999999999790e-01 +1.403715285562139988e+09 1.247668999999999917e+00 -8.958299999999999597e-02 7.250399999999999900e-02 5.316969999999999752e-01 -6.329580000000000206e-01 3.903590000000000115e-01 4.053169999999999829e-01 +1.403715285612139940e+09 1.245700000000000029e+00 -9.092200000000000282e-02 9.158800000000000274e-02 5.294370000000000465e-01 -6.353220000000000534e-01 3.901740000000000208e-01 4.047549999999999759e-01 +1.403715285662139893e+09 1.242831000000000019e+00 -9.317300000000000582e-02 1.114959999999999979e-01 5.283280000000000198e-01 -6.368099999999999872e-01 3.892369999999999997e-01 4.047689999999999899e-01 +1.403715285712140083e+09 1.238421999999999912e+00 -9.613499999999999823e-02 1.306819999999999926e-01 5.269629999999999592e-01 -6.383860000000000090e-01 3.888719999999999954e-01 4.044150000000000245e-01 +1.403715285762140036e+09 1.232531000000000043e+00 -9.952199999999999935e-02 1.497130000000000127e-01 5.261209999999999498e-01 -6.381029999999999758e-01 3.881720000000000170e-01 4.066250000000000142e-01 +1.403715285812139988e+09 1.225284000000000040e+00 -1.032860000000000028e-01 1.681179999999999897e-01 5.255360000000000031e-01 -6.379270000000000218e-01 3.873949999999999894e-01 4.083950000000000080e-01 +1.403715285862139940e+09 1.217095000000000038e+00 -1.074220000000000036e-01 1.855300000000000005e-01 5.268080000000000540e-01 -6.367329999999999934e-01 3.845060000000000144e-01 4.113390000000000102e-01 +1.403715285912139893e+09 1.208102999999999927e+00 -1.120850000000000041e-01 2.026519999999999988e-01 5.289239999999999498e-01 -6.347239999999999549e-01 3.809509999999999841e-01 4.150190000000000268e-01 +1.403715285962140083e+09 1.198360000000000092e+00 -1.167040000000000022e-01 2.191549999999999887e-01 5.315680000000000405e-01 -6.334670000000000023e-01 3.767750000000000266e-01 4.173689999999999900e-01 +1.403715286012140036e+09 1.188596999999999904e+00 -1.221909999999999941e-01 2.349140000000000117e-01 5.339880000000000182e-01 -6.317840000000000122e-01 3.731499999999999817e-01 4.200769999999999782e-01 +1.403715286062139988e+09 1.178798000000000012e+00 -1.282310000000000116e-01 2.496939999999999993e-01 5.358089999999999797e-01 -6.304880000000000484e-01 3.700049999999999728e-01 4.224800000000000222e-01 +1.403715286112139940e+09 1.169192000000000009e+00 -1.346340000000000037e-01 2.634159999999999835e-01 5.363329999999999487e-01 -6.304110000000000547e-01 3.686940000000000217e-01 4.230749999999999789e-01 +1.403715286162139893e+09 1.159601000000000104e+00 -1.417849999999999944e-01 2.765880000000000005e-01 5.355769999999999698e-01 -6.314870000000000205e-01 3.690849999999999964e-01 4.220880000000000187e-01 +1.403715286212140083e+09 1.149860000000000104e+00 -1.494880000000000098e-01 2.890199999999999991e-01 5.343229999999999924e-01 -6.333440000000000181e-01 3.699899999999999856e-01 4.200969999999999982e-01 +1.403715286262140036e+09 1.140001999999999960e+00 -1.579260000000000108e-01 3.009299999999999753e-01 5.336870000000000225e-01 -6.344279999999999919e-01 3.705620000000000025e-01 4.187640000000000251e-01 +1.403715286312139988e+09 1.130003000000000091e+00 -1.670949999999999935e-01 3.127489999999999992e-01 5.340030000000000054e-01 -6.341299999999999715e-01 3.699790000000000023e-01 4.193259999999999765e-01 +1.403715286362139940e+09 1.119879000000000069e+00 -1.770809999999999884e-01 3.241269999999999984e-01 5.341810000000000169e-01 -6.333410000000000428e-01 3.696630000000000194e-01 4.205690000000000262e-01 +1.403715286412139893e+09 1.109976000000000074e+00 -1.876950000000000007e-01 3.347999999999999865e-01 5.346210000000000129e-01 -6.327589999999999604e-01 3.689589999999999814e-01 4.215050000000000185e-01 +1.403715286462140083e+09 1.100174999999999903e+00 -1.988620000000000110e-01 3.456310000000000215e-01 5.351599999999999691e-01 -6.315669999999999895e-01 3.682690000000000130e-01 4.232069999999999999e-01 +1.403715286512140036e+09 1.090400000000000036e+00 -2.108119999999999994e-01 3.554019999999999957e-01 5.354820000000000135e-01 -6.308690000000000131e-01 3.672190000000000176e-01 4.247509999999999897e-01 +1.403715286562139988e+09 1.081172000000000022e+00 -2.235270000000000035e-01 3.649870000000000059e-01 5.350610000000000088e-01 -6.300510000000000277e-01 3.670089999999999741e-01 4.266730000000000245e-01 +1.403715286612139940e+09 1.071741000000000055e+00 -2.366669999999999885e-01 3.741619999999999946e-01 5.330479999999999663e-01 -6.303090000000000082e-01 3.674200000000000244e-01 4.284540000000000015e-01 +1.403715286662139893e+09 1.062364000000000086e+00 -2.502750000000000252e-01 3.835230000000000028e-01 5.291759999999999797e-01 -6.309090000000000531e-01 3.677759999999999918e-01 4.320499999999999896e-01 +1.403715286712140083e+09 1.053223999999999938e+00 -2.641040000000000054e-01 3.926390000000000158e-01 5.237410000000000121e-01 -6.314349999999999685e-01 3.685800000000000187e-01 4.371889999999999943e-01 +1.403715286762140036e+09 1.043671999999999933e+00 -2.779860000000000109e-01 4.007519999999999971e-01 5.183809999999999807e-01 -6.332539999999999836e-01 3.674810000000000021e-01 4.418469999999999898e-01 +1.403715286812139988e+09 1.034448000000000034e+00 -2.917540000000000133e-01 4.078309999999999991e-01 5.145889999999999631e-01 -6.367410000000000014e-01 3.636429999999999940e-01 4.444350000000000245e-01 +1.403715286862139940e+09 1.026092999999999922e+00 -3.050240000000000173e-01 4.140159999999999951e-01 5.118070000000000119e-01 -6.413879999999999582e-01 3.589910000000000045e-01 4.447479999999999767e-01 +1.403715286912139893e+09 1.017997000000000041e+00 -3.186189999999999856e-01 4.201909999999999812e-01 5.104180000000000383e-01 -6.455670000000000019e-01 3.534849999999999937e-01 4.447070000000000189e-01 +1.403715286962140083e+09 1.010480000000000045e+00 -3.324130000000000140e-01 4.265209999999999835e-01 5.089430000000000343e-01 -6.491430000000000256e-01 3.487290000000000112e-01 4.449480000000000102e-01 +1.403715287012140036e+09 1.003387000000000029e+00 -3.468829999999999969e-01 4.332090000000000107e-01 5.074990000000000334e-01 -6.517880000000000340e-01 3.444829999999999837e-01 4.460359999999999880e-01 +1.403715287062139988e+09 9.973109999999999475e-01 -3.623179999999999734e-01 4.402719999999999967e-01 5.053800000000000514e-01 -6.542139999999999622e-01 3.418269999999999920e-01 4.469330000000000247e-01 +1.403715287112139940e+09 9.915300000000000225e-01 -3.774330000000000185e-01 4.471300000000000274e-01 5.039069999999999938e-01 -6.551890000000000214e-01 3.392299999999999760e-01 4.491419999999999857e-01 +1.403715287162139893e+09 9.867620000000000280e-01 -3.935339999999999949e-01 4.541740000000000221e-01 5.013600000000000279e-01 -6.554309999999999858e-01 3.386770000000000058e-01 4.520469999999999766e-01 +1.403715287212140083e+09 9.822119999999999740e-01 -4.100030000000000063e-01 4.614880000000000093e-01 4.984739999999999727e-01 -6.545189999999999619e-01 3.394869999999999832e-01 4.559349999999999792e-01 +1.403715287262140036e+09 9.783979999999999899e-01 -4.263620000000000188e-01 4.685570000000000013e-01 4.959810000000000052e-01 -6.538969999999999505e-01 3.400150000000000117e-01 4.591419999999999946e-01 +1.403715287312139988e+09 9.755920000000000147e-01 -4.422570000000000112e-01 4.758040000000000047e-01 4.933119999999999727e-01 -6.532980000000000453e-01 3.418249999999999900e-01 4.615199999999999858e-01 +1.403715287362139940e+09 9.730729999999999658e-01 -4.586160000000000236e-01 4.824660000000000060e-01 4.914069999999999827e-01 -6.532510000000000261e-01 3.427830000000000044e-01 4.629070000000000129e-01 +1.403715287412139893e+09 9.712709999999999955e-01 -4.749149999999999761e-01 4.890100000000000002e-01 4.894930000000000114e-01 -6.540300000000000002e-01 3.447060000000000124e-01 4.624070000000000125e-01 +1.403715287462140083e+09 9.698299999999999699e-01 -4.909640000000000115e-01 4.957949999999999857e-01 4.865940000000000265e-01 -6.560009999999999453e-01 3.473640000000000061e-01 4.606799999999999784e-01 +1.403715287512140036e+09 9.683760000000000145e-01 -5.066270000000000495e-01 5.031670000000000309e-01 4.832580000000000209e-01 -6.586130000000000040e-01 3.491480000000000139e-01 4.591149999999999953e-01 +1.403715287562139988e+09 9.667799999999999727e-01 -5.214659999999999851e-01 5.107770000000000366e-01 4.785869999999999846e-01 -6.622059999999999613e-01 3.499539999999999873e-01 4.582240000000000202e-01 +1.403715287612139940e+09 9.647390000000000132e-01 -5.354459999999999775e-01 5.186079999999999579e-01 4.727660000000000196e-01 -6.673099999999999588e-01 3.497330000000000161e-01 4.570290000000000186e-01 +1.403715287662139893e+09 9.618389999999999995e-01 -5.497680000000000344e-01 5.268950000000000022e-01 4.660549999999999971e-01 -6.727440000000000087e-01 3.484800000000000120e-01 4.569139999999999868e-01 +1.403715287712140083e+09 9.578370000000000495e-01 -5.626299999999999635e-01 5.356610000000000538e-01 4.589130000000000154e-01 -6.781620000000000426e-01 3.458450000000000135e-01 4.581330000000000124e-01 +1.403715287762140036e+09 9.528940000000000188e-01 -5.747200000000000086e-01 5.451409999999999867e-01 4.515290000000000137e-01 -6.831779999999999520e-01 3.420560000000000267e-01 4.608550000000000146e-01 +1.403715287812139988e+09 9.468900000000000095e-01 -5.860440000000000094e-01 5.547400000000000109e-01 4.440939999999999888e-01 -6.873860000000000525e-01 3.366830000000000100e-01 4.657519999999999993e-01 +1.403715287862139940e+09 9.399020000000000152e-01 -5.980809999999999738e-01 5.647710000000000230e-01 4.359290000000000109e-01 -6.916830000000000478e-01 3.309099999999999819e-01 4.712100000000000177e-01 +1.403715287912139893e+09 9.320589999999999709e-01 -6.083490000000000286e-01 5.749140000000000361e-01 4.272940000000000071e-01 -6.957349999999999923e-01 3.238590000000000080e-01 4.780039999999999845e-01 +1.403715287962140083e+09 9.231460000000000221e-01 -6.175890000000000546e-01 5.843779999999999530e-01 4.181650000000000089e-01 -7.000170000000000003e-01 3.161559999999999926e-01 4.849319999999999742e-01 +1.403715288012140036e+09 9.138840000000000297e-01 -6.261309999999999931e-01 5.932429999999999648e-01 4.082620000000000138e-01 -7.047849999999999948e-01 3.084100000000000175e-01 4.914089999999999847e-01 +1.403715288062139988e+09 9.049979999999999691e-01 -6.341440000000000410e-01 6.019780000000000131e-01 3.978689999999999727e-01 -7.094279999999999475e-01 3.015100000000000002e-01 4.974970000000000225e-01 +1.403715288112139940e+09 8.961280000000000356e-01 -6.415790000000000104e-01 6.098109999999999919e-01 3.883099999999999885e-01 -7.141349999999999643e-01 2.955690000000000262e-01 5.018620000000000303e-01 +1.403715288162139893e+09 8.874750000000000139e-01 -6.486929999999999641e-01 6.159839999999999760e-01 3.805040000000000089e-01 -7.182070000000000398e-01 2.898459999999999925e-01 5.053569999999999451e-01 +1.403715288212140083e+09 8.791510000000000158e-01 -6.552200000000000246e-01 6.192729999999999624e-01 3.742949999999999888e-01 -7.218879999999999741e-01 2.844860000000000166e-01 5.077890000000000459e-01 +1.403715288262140036e+09 8.709329999999999572e-01 -6.619950000000000001e-01 6.197240000000000526e-01 3.690379999999999772e-01 -7.253690000000000415e-01 2.798510000000000164e-01 5.092489999999999517e-01 +1.403715288312139988e+09 8.624969999999999581e-01 -6.677859999999999907e-01 6.173349999999999671e-01 3.655120000000000036e-01 -7.273739999999999650e-01 2.751569999999999849e-01 5.114859999999999962e-01 +1.403715288362139940e+09 8.547090000000000520e-01 -6.735550000000000148e-01 6.124249999999999972e-01 3.623480000000000034e-01 -7.295460000000000278e-01 2.719820000000000015e-01 5.123400000000000176e-01 +1.403715288412139893e+09 8.467829999999999524e-01 -6.791230000000000322e-01 6.048820000000000308e-01 3.594200000000000172e-01 -7.314150000000000373e-01 2.704520000000000257e-01 5.125490000000000324e-01 +1.403715288462140083e+09 8.391840000000000410e-01 -6.838340000000000529e-01 5.983939999999999815e-01 3.569959999999999800e-01 -7.327390000000000292e-01 2.698470000000000035e-01 5.126690000000000413e-01 +1.403715288512140036e+09 8.312159999999999549e-01 -6.871399999999999730e-01 5.955369999999999830e-01 3.554599999999999982e-01 -7.331769999999999676e-01 2.694309999999999761e-01 5.133280000000000065e-01 +1.403715288562139988e+09 8.238769999999999705e-01 -6.906550000000000189e-01 5.939969999999999972e-01 3.543270000000000031e-01 -7.342279999999999918e-01 2.695009999999999906e-01 5.125729999999999453e-01 +1.403715288612139940e+09 8.163810000000000233e-01 -6.935489999999999711e-01 5.961649999999999450e-01 3.531079999999999774e-01 -7.346899999999999542e-01 2.706350000000000144e-01 5.121550000000000269e-01 +1.403715288662139893e+09 8.082559999999999745e-01 -6.959389999999999743e-01 6.028540000000000010e-01 3.527140000000000275e-01 -7.354399999999999826e-01 2.709799999999999986e-01 5.111660000000000093e-01 +1.403715288712140083e+09 7.999230000000000507e-01 -6.978980000000000183e-01 6.109750000000000458e-01 3.530949999999999922e-01 -7.350719999999999477e-01 2.710060000000000247e-01 5.114189999999999570e-01 +1.403715288762140036e+09 7.915590000000000126e-01 -6.992969999999999464e-01 6.198080000000000256e-01 3.553359999999999852e-01 -7.345770000000000355e-01 2.686870000000000092e-01 5.118009999999999504e-01 +1.403715288812139988e+09 7.831420000000000048e-01 -6.999239999999999906e-01 6.273919999999999497e-01 3.569579999999999975e-01 -7.342079999999999718e-01 2.671620000000000106e-01 5.120000000000000107e-01 +1.403715288862139940e+09 7.745999999999999552e-01 -6.998440000000000216e-01 6.317460000000000298e-01 3.585999999999999743e-01 -7.338639999999999608e-01 2.643389999999999906e-01 5.128110000000000168e-01 +1.403715288912139893e+09 7.659620000000000317e-01 -6.990629999999999900e-01 6.329709999999999503e-01 3.594910000000000050e-01 -7.337339999999999973e-01 2.604380000000000028e-01 5.143670000000000186e-01 +1.403715288962140083e+09 7.571890000000000009e-01 -6.979480000000000128e-01 6.305460000000000509e-01 3.588689999999999936e-01 -7.342170000000000085e-01 2.566669999999999785e-01 5.160040000000000182e-01 +1.403715289012140036e+09 7.487890000000000379e-01 -6.962380000000000235e-01 6.245429999999999593e-01 3.568890000000000118e-01 -7.360569999999999613e-01 2.531320000000000237e-01 5.165020000000000167e-01 +1.403715289062139988e+09 7.406289999999999818e-01 -6.940129999999999910e-01 6.152659999999999796e-01 3.537580000000000169e-01 -7.383079999999999643e-01 2.496589999999999920e-01 5.171329999999999538e-01 +1.403715289112139940e+09 7.330510000000000081e-01 -6.900330000000000075e-01 6.034030000000000227e-01 3.502589999999999870e-01 -7.405699999999999505e-01 2.452320000000000055e-01 5.183980000000000254e-01 +1.403715289162139893e+09 7.252859999999999863e-01 -6.880709999999999882e-01 5.896799999999999820e-01 3.472729999999999984e-01 -7.424960000000000448e-01 2.405079999999999996e-01 5.198620000000000463e-01 +1.403715289212140083e+09 7.177409999999999624e-01 -6.864249999999999519e-01 5.753139999999999921e-01 3.444150000000000267e-01 -7.438919999999999977e-01 2.361810000000000020e-01 5.217479999999999896e-01 +1.403715289262140036e+09 7.108539999999999859e-01 -6.845520000000000493e-01 5.606259999999999577e-01 3.410259999999999958e-01 -7.459419999999999940e-01 2.325520000000000087e-01 5.226769999999999472e-01 +1.403715289312139988e+09 7.037980000000000347e-01 -6.832679999999999865e-01 5.458439999999999959e-01 3.373809999999999865e-01 -7.479820000000000357e-01 2.277139999999999997e-01 5.242550000000000265e-01 +1.403715289362139940e+09 6.970790000000000042e-01 -6.819669999999999899e-01 5.307819999999999760e-01 3.326339999999999852e-01 -7.501240000000000130e-01 2.228340000000000043e-01 5.263210000000000388e-01 +1.403715289412139893e+09 6.906989999999999519e-01 -6.812810000000000255e-01 5.148970000000000491e-01 3.267800000000000149e-01 -7.533849999999999714e-01 2.180769999999999931e-01 5.273219999999999574e-01 +1.403715289462140083e+09 6.844689999999999941e-01 -6.811019999999999852e-01 4.981880000000000197e-01 3.200990000000000224e-01 -7.570270000000000055e-01 2.134139999999999926e-01 5.281120000000000259e-01 +1.403715289512140036e+09 6.785010000000000208e-01 -6.815139999999999532e-01 4.809189999999999854e-01 3.132389999999999897e-01 -7.609829999999999650e-01 2.081139999999999934e-01 5.286539999999999573e-01 +1.403715289562139988e+09 6.725940000000000252e-01 -6.826160000000000005e-01 4.631549999999999834e-01 3.057000000000000273e-01 -7.645790000000000086e-01 2.031850000000000045e-01 5.297939999999999872e-01 +1.403715289612139940e+09 6.668450000000000211e-01 -6.845040000000000013e-01 4.448559999999999737e-01 2.986110000000000153e-01 -7.683590000000000142e-01 1.983550000000000035e-01 5.302000000000000046e-01 +1.403715289662139893e+09 6.612649999999999917e-01 -6.870730000000000448e-01 4.261269999999999780e-01 2.929709999999999814e-01 -7.720740000000000380e-01 1.935790000000000011e-01 5.297129999999999894e-01 +1.403715289712140083e+09 6.555760000000000476e-01 -6.913209999999999633e-01 4.066199999999999815e-01 2.874490000000000101e-01 -7.751860000000000417e-01 1.908630000000000049e-01 5.291799999999999837e-01 +1.403715289762140036e+09 6.501289999999999569e-01 -6.960199999999999720e-01 3.888710000000000222e-01 2.840650000000000119e-01 -7.765929999999999778e-01 1.880159999999999887e-01 5.299629999999999619e-01 +1.403715289812139988e+09 6.448730000000000295e-01 -7.017790000000000417e-01 3.733960000000000057e-01 2.814699999999999980e-01 -7.776720000000000299e-01 1.867080000000000128e-01 5.302270000000000039e-01 +1.403715289862139940e+09 6.392989999999999506e-01 -7.089090000000000114e-01 3.602949999999999764e-01 2.795019999999999727e-01 -7.779260000000000064e-01 1.866960000000000008e-01 5.309000000000000385e-01 +1.403715289912139893e+09 6.339110000000000023e-01 -7.168339999999999712e-01 3.500940000000000163e-01 2.778390000000000026e-01 -7.780369999999999786e-01 1.883980000000000099e-01 5.310080000000000355e-01 +1.403715289962140083e+09 6.284859999999999891e-01 -7.254530000000000145e-01 3.424980000000000246e-01 2.782560000000000033e-01 -7.783079999999999998e-01 1.891019999999999923e-01 5.301430000000000309e-01 +1.403715290012140036e+09 6.226159999999999473e-01 -7.350200000000000067e-01 3.375650000000000039e-01 2.791219999999999812e-01 -7.783600000000000518e-01 1.902679999999999927e-01 5.291930000000000245e-01 +1.403715290062139988e+09 6.164469999999999672e-01 -7.453229999999999578e-01 3.359059999999999824e-01 2.809180000000000010e-01 -7.773860000000000214e-01 1.917270000000000085e-01 5.291470000000000340e-01 +1.403715290112139940e+09 6.102819999999999911e-01 -7.564079999999999693e-01 3.371919999999999917e-01 2.833330000000000015e-01 -7.752010000000000289e-01 1.933120000000000116e-01 5.304870000000000418e-01 +1.403715290162139893e+09 6.035669999999999646e-01 -7.684410000000000407e-01 3.411440000000000028e-01 2.865369999999999862e-01 -7.737380000000000368e-01 1.948930000000000107e-01 5.303240000000000176e-01 +1.403715290262140036e+09 5.895700000000000385e-01 -7.948260000000000325e-01 3.559570000000000234e-01 2.937779999999999836e-01 -7.738469999999999516e-01 1.961749999999999883e-01 5.257089999999999819e-01 +1.403715290312139988e+09 5.822429999999999550e-01 -8.093970000000000331e-01 3.640760000000000107e-01 2.964680000000000093e-01 -7.741820000000000368e-01 1.976160000000000139e-01 5.231599999999999584e-01 +1.403715290362139940e+09 5.747510000000000119e-01 -8.253019999999999801e-01 3.707289999999999752e-01 2.989009999999999723e-01 -7.749530000000000030e-01 1.989380000000000037e-01 5.201240000000000308e-01 +1.403715290412139893e+09 5.673930000000000362e-01 -8.415409999999999835e-01 3.768929999999999780e-01 2.996789999999999732e-01 -7.765159999999999840e-01 2.014509999999999912e-01 5.163640000000000452e-01 +1.403715290462140083e+09 5.601369999999999960e-01 -8.584800000000000209e-01 3.822499999999999787e-01 3.006240000000000023e-01 -7.778920000000000279e-01 2.030740000000000045e-01 5.130989999999999718e-01 +1.403715290512140036e+09 5.524860000000000326e-01 -8.761259999999999604e-01 3.872680000000000011e-01 3.008140000000000258e-01 -7.773550000000000182e-01 2.052889999999999993e-01 5.129190000000000138e-01 +1.403715290562139988e+09 5.438520000000000021e-01 -8.946319999999999828e-01 3.920339999999999936e-01 3.012159999999999838e-01 -7.759759999999999991e-01 2.063049999999999884e-01 5.143630000000000146e-01 +1.403715290612139940e+09 5.349380000000000246e-01 -9.138100000000000112e-01 3.962140000000000106e-01 2.999339999999999784e-01 -7.743480000000000363e-01 2.088009999999999866e-01 5.165520000000000111e-01 +1.403715290662139893e+09 5.258699999999999486e-01 -9.333930000000000282e-01 3.991379999999999928e-01 2.986309999999999798e-01 -7.740909999999999735e-01 2.104060000000000097e-01 5.170409999999999728e-01 +1.403715290712140083e+09 5.161010000000000320e-01 -9.534789999999999655e-01 4.019030000000000102e-01 2.980389999999999984e-01 -7.720770000000000133e-01 2.105339999999999989e-01 5.203320000000000167e-01 +1.403715290762140036e+09 5.061069999999999736e-01 -9.739029999999999632e-01 4.042220000000000257e-01 2.973319999999999852e-01 -7.699570000000000025e-01 2.104550000000000032e-01 5.238969999999999461e-01 +1.403715290812139988e+09 4.961849999999999872e-01 -9.945899999999999741e-01 4.064969999999999972e-01 2.957069999999999976e-01 -7.686619999999999564e-01 2.115759999999999863e-01 5.262609999999999788e-01 +1.403715290862139940e+09 4.867340000000000000e-01 -1.015406999999999949e+00 4.077999999999999958e-01 2.937759999999999816e-01 -7.688030000000000141e-01 2.130249999999999921e-01 5.265520000000000200e-01 +1.403715290912139893e+09 4.773430000000000173e-01 -1.036261000000000099e+00 4.089409999999999989e-01 2.923870000000000080e-01 -7.695260000000000433e-01 2.131170000000000009e-01 5.262329999999999508e-01 +1.403715290962140083e+09 4.683570000000000233e-01 -1.057015999999999956e+00 4.098820000000000241e-01 2.891500000000000181e-01 -7.699129999999999585e-01 2.148349999999999982e-01 5.267570000000000308e-01 +1.403715291012140036e+09 4.593800000000000106e-01 -1.077717999999999954e+00 4.110240000000000005e-01 2.845349999999999824e-01 -7.703619999999999912e-01 2.176289999999999891e-01 5.274659999999999904e-01 +1.403715291062139988e+09 4.503019999999999801e-01 -1.098219000000000056e+00 4.121099999999999763e-01 2.792850000000000055e-01 -7.711719999999999686e-01 2.212339999999999862e-01 5.275879999999999459e-01 +1.403715291112139940e+09 4.408299999999999996e-01 -1.118157999999999985e+00 4.130309999999999815e-01 2.738099999999999978e-01 -7.726899999999999880e-01 2.240099999999999869e-01 5.270650000000000057e-01 +1.403715291162139893e+09 4.306880000000000153e-01 -1.137235999999999914e+00 4.133470000000000200e-01 2.683070000000000177e-01 -7.738140000000000018e-01 2.267919999999999936e-01 5.270559999999999690e-01 +1.403715291212140083e+09 4.201119999999999854e-01 -1.155181999999999931e+00 4.135380000000000167e-01 2.631040000000000045e-01 -7.749399999999999622e-01 2.281390000000000085e-01 5.274440000000000239e-01 +1.403715291262140036e+09 4.088310000000000000e-01 -1.171821000000000002e+00 4.125900000000000123e-01 2.583710000000000173e-01 -7.760930000000000328e-01 2.281130000000000102e-01 5.280989999999999851e-01 +1.403715291312139988e+09 3.969980000000000175e-01 -1.186865999999999977e+00 4.106759999999999855e-01 2.543440000000000145e-01 -7.774250000000000327e-01 2.267029999999999879e-01 5.287020000000000053e-01 +1.403715291362139940e+09 3.843849999999999767e-01 -1.200849000000000055e+00 4.083330000000000015e-01 2.504549999999999832e-01 -7.784290000000000376e-01 2.248499999999999943e-01 5.298720000000000097e-01 +1.403715291412139893e+09 3.710399999999999809e-01 -1.213715000000000099e+00 4.048979999999999801e-01 2.467959999999999876e-01 -7.801970000000000294e-01 2.223819999999999963e-01 5.300289999999999724e-01 +1.403715291462140083e+09 3.570969999999999978e-01 -1.225278000000000089e+00 4.009889999999999843e-01 2.434230000000000005e-01 -7.820479999999999654e-01 2.191059999999999952e-01 5.302249999999999464e-01 +1.403715291512140036e+09 3.422870000000000079e-01 -1.235328999999999899e+00 3.964440000000000186e-01 2.411280000000000090e-01 -7.846849999999999659e-01 2.141909999999999925e-01 5.293849999999999945e-01 +1.403715291562139988e+09 3.271700000000000164e-01 -1.243986000000000036e+00 3.914199999999999902e-01 2.375120000000000009e-01 -7.873809999999999976e-01 2.104779999999999984e-01 5.285060000000000313e-01 +1.403715291612139940e+09 3.106400000000000272e-01 -1.252197999999999922e+00 3.866439999999999877e-01 2.334259999999999946e-01 -7.899789999999999868e-01 2.076000000000000068e-01 5.275879999999999459e-01 +1.403715291662139893e+09 2.933910000000000129e-01 -1.259249999999999980e+00 3.815669999999999895e-01 2.292700000000000016e-01 -7.921439999999999593e-01 2.053780000000000050e-01 5.270329999999999737e-01 +1.403715291712140083e+09 2.739409999999999901e-01 -1.266691000000000011e+00 3.766630000000000256e-01 2.254819999999999880e-01 -7.943459999999999965e-01 2.032579999999999942e-01 5.261740000000000306e-01 +1.403715291762140036e+09 2.541329999999999978e-01 -1.272393000000000107e+00 3.721430000000000016e-01 2.244780000000000109e-01 -7.952820000000000444e-01 1.982760000000000078e-01 5.270890000000000297e-01 +1.403715291812139988e+09 2.333500000000000019e-01 -1.277493999999999907e+00 3.674939999999999873e-01 2.244120000000000004e-01 -7.955550000000000122e-01 1.928709999999999869e-01 5.287070000000000380e-01 +1.403715291862139940e+09 2.114129999999999898e-01 -1.282033999999999896e+00 3.625229999999999841e-01 2.273809999999999998e-01 -7.949680000000000080e-01 1.842890000000000084e-01 5.313769999999999882e-01 +1.403715291912139893e+09 1.887590000000000101e-01 -1.286513999999999935e+00 3.569049999999999723e-01 2.302750000000000075e-01 -7.943639999999999590e-01 1.764259999999999995e-01 5.336980000000000057e-01 +1.403715291962140083e+09 1.654609999999999970e-01 -1.291166999999999954e+00 3.504070000000000240e-01 2.311390000000000111e-01 -7.945670000000000233e-01 1.721880000000000077e-01 5.344060000000000477e-01 +1.403715292012140036e+09 1.419920000000000071e-01 -1.296078999999999981e+00 3.438539999999999930e-01 2.323500000000000010e-01 -7.948079999999999590e-01 1.682960000000000012e-01 5.347619999999999596e-01 +1.403715292062139988e+09 1.184769999999999990e-01 -1.301687999999999956e+00 3.375110000000000054e-01 2.331390000000000129e-01 -7.948530000000000317e-01 1.662540000000000129e-01 5.349909999999999943e-01 +1.403715292112139940e+09 9.474699999999999789e-02 -1.308208000000000037e+00 3.311120000000000174e-01 2.347490000000000132e-01 -7.946010000000000018e-01 1.666080000000000061e-01 5.345499999999999696e-01 +1.403715292162139893e+09 7.097399999999999542e-02 -1.315269999999999939e+00 3.242999999999999772e-01 2.378989999999999994e-01 -7.940840000000000121e-01 1.680210000000000037e-01 5.334830000000000405e-01 +1.403715292212140083e+09 4.673499999999999877e-02 -1.323493999999999948e+00 3.178989999999999871e-01 2.430970000000000075e-01 -7.926159999999999872e-01 1.702299999999999924e-01 5.326210000000000111e-01 +1.403715292262140036e+09 2.269300000000000136e-02 -1.332484999999999919e+00 3.117179999999999951e-01 2.496069999999999955e-01 -7.909530000000000172e-01 1.734110000000000096e-01 5.310540000000000260e-01 +1.403715292312139988e+09 -1.946000000000000030e-03 -1.342538999999999927e+00 3.056329999999999880e-01 2.579250000000000154e-01 -7.888960000000000417e-01 1.772910000000000041e-01 5.288530000000000175e-01 +1.403715292362139940e+09 -2.687499999999999958e-02 -1.353248000000000006e+00 2.993970000000000242e-01 2.680660000000000265e-01 -7.858490000000000197e-01 1.806470000000000020e-01 5.272090000000000387e-01 +1.403715292412139893e+09 -5.165600000000000053e-02 -1.365159999999999929e+00 2.932109999999999994e-01 2.776390000000000247e-01 -7.824269999999999836e-01 1.863569999999999949e-01 5.253529999999999589e-01 +1.403715292462140083e+09 -7.704600000000000337e-02 -1.378233000000000041e+00 2.870730000000000226e-01 2.891750000000000154e-01 -7.792909999999999560e-01 1.913420000000000121e-01 5.219869999999999788e-01 +1.403715292512140036e+09 -1.024280000000000052e-01 -1.392520999999999898e+00 2.816159999999999775e-01 2.994439999999999880e-01 -7.743470000000000075e-01 1.992279999999999884e-01 5.206039999999999557e-01 +1.403715292562139988e+09 -1.274939999999999962e-01 -1.407985000000000042e+00 2.768849999999999922e-01 3.101559999999999873e-01 -7.675229999999999553e-01 2.083649999999999947e-01 5.208610000000000184e-01 +1.403715292612139940e+09 -1.525559999999999972e-01 -1.424347999999999947e+00 2.729119999999999879e-01 3.219750000000000112e-01 -7.592560000000000420e-01 2.171130000000000004e-01 5.222299999999999720e-01 +1.403715292662139893e+09 -1.773820000000000119e-01 -1.441624000000000017e+00 2.702490000000000170e-01 3.339909999999999823e-01 -7.483800000000000452e-01 2.266170000000000129e-01 5.263290000000000468e-01 +1.403715292712140083e+09 -2.010669999999999957e-01 -1.459281000000000050e+00 2.677760000000000140e-01 3.466839999999999922e-01 -7.392030000000000545e-01 2.351900000000000102e-01 5.273280000000000189e-01 +1.403715292762140036e+09 -2.237470000000000014e-01 -1.477524000000000060e+00 2.665529999999999844e-01 3.595189999999999775e-01 -7.294760000000000133e-01 2.435849999999999960e-01 5.284670000000000201e-01 +1.403715292812139988e+09 -2.448110000000000008e-01 -1.495807000000000109e+00 2.669710000000000139e-01 3.721369999999999956e-01 -7.208459999999999868e-01 2.519779999999999798e-01 5.276389999999999691e-01 +1.403715292862139940e+09 -2.641339999999999799e-01 -1.513975999999999988e+00 2.696379999999999888e-01 3.847570000000000157e-01 -7.141110000000000513e-01 2.596490000000000187e-01 5.240129999999999511e-01 +1.403715292912139893e+09 -2.814030000000000142e-01 -1.532184999999999908e+00 2.747060000000000057e-01 3.970119999999999760e-01 -7.094179999999999930e-01 2.672869999999999968e-01 5.173640000000000461e-01 +1.403715292962140083e+09 -2.971719999999999917e-01 -1.550354999999999928e+00 2.827600000000000113e-01 4.071179999999999799e-01 -7.057269999999999932e-01 2.768530000000000157e-01 5.094670000000000032e-01 +1.403715293012140036e+09 -3.114750000000000019e-01 -1.568259999999999987e+00 2.939260000000000206e-01 4.155090000000000172e-01 -7.013540000000000330e-01 2.874309999999999921e-01 5.028299999999999992e-01 +1.403715293062139988e+09 -3.245029999999999859e-01 -1.585917000000000021e+00 3.078429999999999778e-01 4.238029999999999853e-01 -6.966630000000000322e-01 2.978060000000000151e-01 4.963500000000000134e-01 +1.403715293112139940e+09 -3.369739999999999958e-01 -1.603863000000000039e+00 3.231999999999999873e-01 4.311670000000000225e-01 -6.916020000000000501e-01 3.083449999999999802e-01 4.906179999999999986e-01 +1.403715293162139893e+09 -3.490770000000000262e-01 -1.621623000000000037e+00 3.386020000000000141e-01 4.390109999999999846e-01 -6.870049999999999768e-01 3.171289999999999942e-01 4.844820000000000237e-01 +1.403715293212140083e+09 -3.607279999999999931e-01 -1.639054999999999929e+00 3.542139999999999733e-01 4.475489999999999746e-01 -6.818419999999999481e-01 3.247129999999999739e-01 4.789089999999999736e-01 +1.403715293262140036e+09 -3.721889999999999921e-01 -1.656406999999999963e+00 3.700339999999999741e-01 4.547399999999999776e-01 -6.760289999999999910e-01 3.331970000000000209e-01 4.745269999999999766e-01 +1.403715293312139988e+09 -3.835350000000000148e-01 -1.673480999999999996e+00 3.855100000000000193e-01 4.626259999999999817e-01 -6.690869999999999873e-01 3.402999999999999914e-01 4.716960000000000042e-01 +1.403715293362139940e+09 -3.950350000000000250e-01 -1.689834000000000058e+00 4.009869999999999823e-01 4.698069999999999746e-01 -6.618309999999999471e-01 3.476230000000000153e-01 4.694889999999999897e-01 +1.403715293412139893e+09 -4.065259999999999985e-01 -1.705143000000000075e+00 4.165749999999999731e-01 4.755070000000000130e-01 -6.542299999999999782e-01 3.564820000000000211e-01 4.677569999999999784e-01 +1.403715293462140083e+09 -4.180030000000000134e-01 -1.719465000000000021e+00 4.322309999999999763e-01 4.816469999999999918e-01 -6.471959999999999935e-01 3.635769999999999835e-01 4.657959999999999878e-01 +1.403715293512140036e+09 -4.292009999999999992e-01 -1.732563000000000075e+00 4.476390000000000091e-01 4.887790000000000190e-01 -6.420040000000000191e-01 3.685610000000000275e-01 4.616149999999999975e-01 +1.403715293562139988e+09 -4.402099999999999902e-01 -1.744534000000000029e+00 4.632149999999999879e-01 4.957610000000000072e-01 -6.375809999999999533e-01 3.731590000000000185e-01 4.565790000000000126e-01 +1.403715293612139940e+09 -4.511950000000000127e-01 -1.755554000000000059e+00 4.787080000000000224e-01 5.030820000000000292e-01 -6.338660000000000405e-01 3.764509999999999801e-01 4.510069999999999912e-01 +1.403715293662139893e+09 -4.622490000000000210e-01 -1.766691999999999929e+00 4.938779999999999837e-01 5.106910000000000061e-01 -6.307239999999999513e-01 3.785930000000000129e-01 4.450279999999999792e-01 +1.403715293712140083e+09 -4.733149999999999857e-01 -1.776974999999999971e+00 5.094809999999999617e-01 5.178890000000000438e-01 -6.267549999999999510e-01 3.812130000000000241e-01 4.400510000000000255e-01 +1.403715293762140036e+09 -4.844490000000000185e-01 -1.786645999999999956e+00 5.248260000000000147e-01 5.250179999999999847e-01 -6.230480000000000462e-01 3.836629999999999763e-01 4.347070000000000101e-01 +1.403715293812139988e+09 -4.954509999999999748e-01 -1.795859000000000094e+00 5.399329999999999963e-01 5.320139999999999869e-01 -6.186009999999999565e-01 3.863030000000000075e-01 4.301909999999999901e-01 +1.403715293862139940e+09 -5.063490000000000490e-01 -1.804585000000000106e+00 5.545099999999999474e-01 5.383820000000000272e-01 -6.144429999999999614e-01 3.898679999999999923e-01 4.249800000000000244e-01 +1.403715293912139893e+09 -5.172200000000000131e-01 -1.813234000000000012e+00 5.685510000000000286e-01 5.452299999999999924e-01 -6.097669999999999479e-01 3.929989999999999872e-01 4.200710000000000277e-01 +1.403715293962140083e+09 -5.283259999999999623e-01 -1.821882999999999919e+00 5.822079999999999478e-01 5.518020000000000147e-01 -6.040590000000000126e-01 3.969579999999999775e-01 4.159950000000000037e-01 +1.403715294012140036e+09 -5.394189999999999818e-01 -1.830184000000000033e+00 5.935610000000000053e-01 5.583120000000000305e-01 -5.977940000000000476e-01 4.015009999999999968e-01 4.119789999999999841e-01 +1.403715294062139988e+09 -5.504829999999999446e-01 -1.838349000000000011e+00 6.016049999999999454e-01 5.649629999999999930e-01 -5.912629999999999830e-01 4.061919999999999975e-01 4.077169999999999961e-01 +1.403715294112139940e+09 -5.614569999999999839e-01 -1.846934999999999993e+00 6.069020000000000525e-01 5.706259999999999666e-01 -5.841749999999999998e-01 4.123459999999999903e-01 4.038519999999999888e-01 +1.403715294162139893e+09 -5.725190000000000001e-01 -1.855291000000000023e+00 6.092130000000000045e-01 5.757660000000000000e-01 -5.766809999999999992e-01 4.191050000000000053e-01 4.003539999999999877e-01 +1.403715294212140083e+09 -5.838370000000000504e-01 -1.862449999999999939e+00 6.083899999999999864e-01 5.807959999999999789e-01 -5.691150000000000375e-01 4.259499999999999953e-01 3.966749999999999998e-01 +1.403715294262140036e+09 -5.952110000000000456e-01 -1.869154999999999900e+00 6.045089999999999630e-01 5.859090000000000131e-01 -5.619699999999999696e-01 4.326960000000000250e-01 3.920130000000000003e-01 +1.403715294312139988e+09 -6.067329999999999668e-01 -1.875721999999999889e+00 5.972929999999999628e-01 5.913119999999999488e-01 -5.547379999999999534e-01 4.387300000000000089e-01 3.874690000000000079e-01 +1.403715294362139940e+09 -6.188900000000000512e-01 -1.881372999999999962e+00 5.867179999999999618e-01 5.972840000000000371e-01 -5.476790000000000269e-01 4.439100000000000268e-01 3.824179999999999802e-01 +1.403715294412139893e+09 -6.311139999999999528e-01 -1.886562999999999990e+00 5.738320000000000087e-01 6.031790000000000207e-01 -5.399589999999999668e-01 4.492120000000000002e-01 3.779259999999999842e-01 +1.403715294462140083e+09 -6.436460000000000514e-01 -1.890919000000000016e+00 5.600979999999999848e-01 6.096770000000000245e-01 -5.319650000000000212e-01 4.534059999999999757e-01 3.738049999999999984e-01 +1.403715294512140036e+09 -6.568199999999999594e-01 -1.894203000000000081e+00 5.463069999999999871e-01 6.164420000000000455e-01 -5.238500000000000378e-01 4.572419999999999818e-01 3.694740000000000246e-01 +1.403715294562139988e+09 -6.695449999999999458e-01 -1.896784000000000026e+00 5.317659999999999609e-01 6.242400000000000171e-01 -5.170379999999999976e-01 4.596609999999999863e-01 3.629149999999999876e-01 +1.403715294612139940e+09 -6.823789999999999578e-01 -1.898916000000000048e+00 5.172959999999999781e-01 6.330949999999999633e-01 -5.103320000000000078e-01 4.605580000000000229e-01 3.558629999999999849e-01 +1.403715294662139893e+09 -6.955620000000000136e-01 -1.899880999999999931e+00 5.027049999999999574e-01 6.425370000000000248e-01 -5.026319999999999677e-01 4.604010000000000047e-01 3.500559999999999783e-01 +1.403715294712140083e+09 -7.089699999999999891e-01 -1.900568999999999953e+00 4.883140000000000258e-01 6.519690000000000207e-01 -4.949040000000000106e-01 4.600929999999999742e-01 3.439780000000000060e-01 +1.403715294762140036e+09 -7.218780000000000197e-01 -1.901639999999999997e+00 4.741929999999999756e-01 6.604299999999999615e-01 -4.869510000000000227e-01 4.607129999999999836e-01 3.383129999999999749e-01 +1.403715294812139988e+09 -7.342210000000000125e-01 -1.902884999999999938e+00 4.603039999999999909e-01 6.678770000000000540e-01 -4.792770000000000086e-01 4.624619999999999842e-01 3.322089999999999765e-01 +1.403715294862139940e+09 -7.461790000000000367e-01 -1.904398000000000035e+00 4.464739999999999820e-01 6.747459999999999569e-01 -4.710900000000000087e-01 4.646279999999999855e-01 3.269759999999999889e-01 +1.403715294912139893e+09 -7.572590000000000154e-01 -1.906430999999999987e+00 4.330350000000000033e-01 6.809030000000000360e-01 -4.623789999999999845e-01 4.674470000000000014e-01 3.225979999999999959e-01 +1.403715294962140083e+09 -7.675950000000000273e-01 -1.908477999999999897e+00 4.204939999999999789e-01 6.855649999999999800e-01 -4.528809999999999780e-01 4.721670000000000034e-01 3.193079999999999807e-01 +1.403715295012140036e+09 -7.771799999999999820e-01 -1.910492000000000079e+00 4.084559999999999858e-01 6.893270000000000231e-01 -4.441080000000000028e-01 4.777600000000000180e-01 3.151860000000000217e-01 +1.403715295062139988e+09 -7.859840000000000160e-01 -1.912120999999999960e+00 3.965949999999999753e-01 6.932340000000000169e-01 -4.358899999999999997e-01 4.828850000000000087e-01 3.102389999999999870e-01 +1.403715295112139940e+09 -7.945520000000000360e-01 -1.914430999999999994e+00 3.850080000000000169e-01 6.956510000000000193e-01 -4.281229999999999758e-01 4.900789999999999869e-01 3.043069999999999942e-01 +1.403715295162139893e+09 -8.025120000000000031e-01 -1.915372000000000074e+00 3.746909999999999963e-01 6.975799999999999779e-01 -4.206529999999999991e-01 4.973730000000000095e-01 2.984160000000000146e-01 +1.403715295212140083e+09 -8.101589999999999625e-01 -1.915718999999999950e+00 3.656900000000000150e-01 6.998480000000000256e-01 -4.129550000000000165e-01 5.040400000000000436e-01 2.926190000000000180e-01 +1.403715295262140036e+09 -8.176679999999999504e-01 -1.915435999999999916e+00 3.590220000000000078e-01 7.030119999999999703e-01 -4.058100000000000041e-01 5.092339999999999645e-01 2.859599999999999920e-01 +1.403715295312139988e+09 -8.253470000000000528e-01 -1.914711000000000052e+00 3.560269999999999824e-01 7.072260000000000213e-01 -3.975529999999999897e-01 5.133510000000000018e-01 2.797390000000000154e-01 +1.403715295362139940e+09 -8.330880000000000507e-01 -1.913307000000000091e+00 3.558189999999999964e-01 7.135780000000000456e-01 -3.890250000000000097e-01 5.152200000000000113e-01 2.720540000000000180e-01 +1.403715295412139893e+09 -8.406569999999999876e-01 -1.911899999999999933e+00 3.582580000000000209e-01 7.197609999999999841e-01 -3.795470000000000232e-01 5.172480000000000411e-01 2.652209999999999845e-01 +1.403715295462140083e+09 -8.482499999999999485e-01 -1.910133999999999999e+00 3.633480000000000043e-01 7.259520000000000417e-01 -3.694689999999999919e-01 5.194370000000000376e-01 2.582090000000000218e-01 +1.403715295512140036e+09 -8.561100000000000376e-01 -1.908158000000000021e+00 3.687199999999999922e-01 7.318660000000000165e-01 -3.590909999999999935e-01 5.215459999999999541e-01 2.518219999999999903e-01 +1.403715295562139988e+09 -8.639670000000000405e-01 -1.907839999999999980e+00 3.715570000000000261e-01 7.373009999999999842e-01 -3.483700000000000130e-01 5.230850000000000222e-01 2.478059999999999985e-01 +1.403715295612139940e+09 -8.723520000000000163e-01 -1.905631999999999993e+00 3.707840000000000025e-01 7.415739999999999554e-01 -3.394229999999999747e-01 5.248990000000000045e-01 2.435990000000000100e-01 +1.403715295662139893e+09 -8.807380000000000209e-01 -1.903186999999999962e+00 3.664680000000000160e-01 7.443140000000000311e-01 -3.315210000000000101e-01 5.273240000000000149e-01 2.408750000000000058e-01 +1.403715295712140083e+09 -8.883750000000000258e-01 -1.901961000000000013e+00 3.583509999999999751e-01 7.462029999999999497e-01 -3.250879999999999881e-01 5.298850000000000504e-01 2.381620000000000126e-01 +1.403715295762140036e+09 -8.962999999999999856e-01 -1.898910000000000098e+00 3.489729999999999777e-01 7.482440000000000202e-01 -3.186169999999999836e-01 5.324389999999999956e-01 2.347839999999999927e-01 +1.403715295812139988e+09 -9.038979999999999793e-01 -1.895118000000000080e+00 3.384150000000000214e-01 7.495169999999999888e-01 -3.130660000000000109e-01 5.361550000000000482e-01 2.296779999999999933e-01 +1.403715295862139940e+09 -9.113710000000000422e-01 -1.890787999999999913e+00 3.280870000000000175e-01 7.500050000000000328e-01 -3.075590000000000268e-01 5.407039999999999624e-01 2.248070000000000068e-01 +1.403715295912139893e+09 -9.191249999999999698e-01 -1.885931000000000024e+00 3.170510000000000272e-01 7.515140000000000153e-01 -3.023270000000000124e-01 5.439850000000000518e-01 2.188730000000000120e-01 +1.403715295962140083e+09 -9.272989999999999844e-01 -1.880770000000000053e+00 3.058100000000000263e-01 7.518550000000000511e-01 -2.976400000000000157e-01 5.485100000000000531e-01 2.127479999999999927e-01 +1.403715296012140036e+09 -9.363409999999999789e-01 -1.875156999999999963e+00 2.932239999999999847e-01 7.522940000000000182e-01 -2.936699999999999866e-01 5.522000000000000242e-01 2.070929999999999993e-01 +1.403715296062139988e+09 -9.466170000000000417e-01 -1.869240999999999930e+00 2.797649999999999859e-01 7.533760000000000456e-01 -2.917199999999999793e-01 5.543609999999999927e-01 2.000210000000000043e-01 +1.403715296112139940e+09 -9.574850000000000305e-01 -1.863078000000000012e+00 2.653619999999999868e-01 7.556370000000000031e-01 -2.912089999999999956e-01 5.542230000000000212e-01 1.924740000000000062e-01 +1.403715296162139893e+09 -9.695369999999999822e-01 -1.858457000000000026e+00 2.503650000000000042e-01 7.598749999999999671e-01 -2.897580000000000156e-01 5.515689999999999760e-01 1.854790000000000050e-01 +1.403715296212140083e+09 -9.820010000000000128e-01 -1.852897000000000016e+00 2.346739999999999937e-01 7.645340000000000469e-01 -2.870880000000000098e-01 5.483759999999999746e-01 1.798690000000000011e-01 +1.403715296262140036e+09 -9.952130000000000143e-01 -1.848076999999999970e+00 2.187979999999999925e-01 7.694670000000000121e-01 -2.840469999999999939e-01 5.449370000000000047e-01 1.740160000000000040e-01 +1.403715296312139988e+09 -1.008645999999999932e+00 -1.844797999999999938e+00 2.028290000000000093e-01 7.758779999999999566e-01 -2.807819999999999760e-01 5.393160000000000176e-01 1.682639999999999969e-01 +1.403715296362139940e+09 -1.022545000000000037e+00 -1.842044000000000015e+00 1.895590000000000053e-01 7.822050000000000392e-01 -2.763650000000000273e-01 5.338190000000000435e-01 1.637530000000000097e-01 +1.403715296412139893e+09 -1.036416999999999922e+00 -1.840587999999999891e+00 1.792370000000000074e-01 7.868060000000000054e-01 -2.714469999999999938e-01 5.311350000000000238e-01 1.585809999999999997e-01 +1.403715296462140083e+09 -1.049949000000000021e+00 -1.840904000000000096e+00 1.716530000000000000e-01 7.895590000000000108e-01 -2.667340000000000266e-01 5.310810000000000253e-01 1.529780000000000029e-01 +1.403715296512140036e+09 -1.063979999999999926e+00 -1.842503999999999920e+00 1.662409999999999999e-01 7.916840000000000543e-01 -2.631160000000000165e-01 5.312590000000000368e-01 1.475470000000000115e-01 +1.403715296562139988e+09 -1.077166999999999986e+00 -1.846297999999999995e+00 1.635520000000000029e-01 7.931820000000000537e-01 -2.582889999999999908e-01 5.321810000000000151e-01 1.446840000000000070e-01 +1.403715296612139940e+09 -1.090357000000000021e+00 -1.851839999999999931e+00 1.638940000000000119e-01 7.943689999999999918e-01 -2.524939999999999962e-01 5.331690000000000040e-01 1.447620000000000018e-01 +1.403715296662139893e+09 -1.103042999999999996e+00 -1.858915000000000095e+00 1.656670000000000087e-01 7.938250000000000028e-01 -2.463660000000000017e-01 5.363630000000000342e-01 1.464900000000000091e-01 +1.403715296712140083e+09 -1.115080999999999989e+00 -1.867431999999999981e+00 1.672659999999999980e-01 7.932379999999999987e-01 -2.413829999999999865e-01 5.391709999999999559e-01 1.476550000000000085e-01 +1.403715296762140036e+09 -1.126295999999999964e+00 -1.877248000000000028e+00 1.691449999999999898e-01 7.926149999999999585e-01 -2.378919999999999924e-01 5.415940000000000198e-01 1.478019999999999889e-01 +1.403715296812139988e+09 -1.137254999999999905e+00 -1.887680999999999942e+00 1.703179999999999972e-01 7.924609999999999710e-01 -2.330830000000000124e-01 5.434350000000000014e-01 1.495190000000000130e-01 +1.403715296862139940e+09 -1.147715000000000041e+00 -1.898705000000000087e+00 1.718129999999999935e-01 7.920690000000000230e-01 -2.274879999999999958e-01 5.456419999999999604e-01 1.521569999999999867e-01 +1.403715296912139893e+09 -1.156968999999999914e+00 -1.908347999999999933e+00 1.740659999999999985e-01 7.921209999999999640e-01 -2.208269999999999955e-01 5.478589999999999849e-01 1.537199999999999955e-01 +1.403715296962140083e+09 -1.166234999999999911e+00 -1.919100000000000028e+00 1.747269999999999934e-01 7.921970000000000400e-01 -2.135189999999999866e-01 5.505790000000000406e-01 1.539369999999999905e-01 +1.403715297062139988e+09 -1.184121999999999897e+00 -1.938498000000000054e+00 1.730099999999999971e-01 7.974440000000000417e-01 -2.031679999999999875e-01 5.507180000000000408e-01 1.397009999999999919e-01 +1.403715297112139940e+09 -1.193243999999999971e+00 -1.947359000000000062e+00 1.716110000000000135e-01 8.005780000000000118e-01 -1.977919999999999956e-01 5.504839999999999733e-01 1.300800000000000012e-01 +1.403715297162139893e+09 -1.201507000000000103e+00 -1.956674000000000024e+00 1.681549999999999989e-01 8.063500000000000112e-01 -1.924720000000000042e-01 5.465550000000000130e-01 1.184540000000000037e-01 +1.403715297212140083e+09 -1.208593000000000028e+00 -1.966728999999999949e+00 1.642639999999999934e-01 8.123550000000000493e-01 -1.853190000000000115e-01 5.424219999999999597e-01 1.073049999999999976e-01 +1.403715297262140036e+09 -1.214299000000000017e+00 -1.977751999999999954e+00 1.603690000000000115e-01 8.169689999999999452e-01 -1.770539999999999892e-01 5.403750000000000497e-01 9.596200000000000563e-02 +1.403715297312139988e+09 -1.218779999999999974e+00 -1.990275999999999934e+00 1.560660000000000103e-01 8.204110000000000014e-01 -1.673379999999999868e-01 5.399909999999999988e-01 8.564099999999999491e-02 +1.403715297362139940e+09 -1.221996000000000082e+00 -2.004218999999999973e+00 1.509399999999999908e-01 8.233679999999999888e-01 -1.566929999999999990e-01 5.400399999999999645e-01 7.661400000000000154e-02 +1.403715297412139893e+09 -1.224153999999999964e+00 -2.019979000000000191e+00 1.461530000000000051e-01 8.251089999999999813e-01 -1.442710000000000103e-01 5.416400000000000103e-01 7.076000000000000345e-02 +1.403715297462140083e+09 -1.225027000000000088e+00 -2.037574000000000218e+00 1.415679999999999994e-01 8.265609999999999902e-01 -1.327740000000000031e-01 5.430620000000000447e-01 6.520399999999999807e-02 +1.403715297512140036e+09 -1.224763000000000046e+00 -2.056712000000000096e+00 1.374910000000000021e-01 8.273880000000000123e-01 -1.208390000000000020e-01 5.450859999999999594e-01 6.089900000000000174e-02 +1.403715297562139988e+09 -1.224935000000000107e+00 -2.076775000000000038e+00 1.320749999999999980e-01 8.284589999999999455e-01 -1.113259999999999944e-01 5.461110000000000131e-01 5.500399999999999734e-02 +1.403715297612139940e+09 -1.222099999999999964e+00 -2.097989999999999799e+00 1.268279999999999963e-01 8.305989999999999762e-01 -1.034840000000000065e-01 5.450949999999999962e-01 4.762899999999999773e-02 +1.403715297662139893e+09 -1.217888000000000082e+00 -2.120216999999999796e+00 1.213609999999999967e-01 8.327179999999999582e-01 -9.699299999999999589e-02 5.436839999999999451e-01 3.976099999999999773e-02 +1.403715297712140083e+09 -1.212557000000000107e+00 -2.143282999999999827e+00 1.161819999999999936e-01 8.339410000000000434e-01 -9.156799999999999662e-02 5.433099999999999596e-01 3.118299999999999891e-02 +1.403715297762140036e+09 -1.205459999999999976e+00 -2.167403000000000191e+00 1.111179999999999946e-01 8.344690000000000163e-01 -8.605000000000000149e-02 5.438110000000000444e-01 2.292599999999999846e-02 +1.403715297812139988e+09 -1.196619000000000099e+00 -2.192743000000000109e+00 1.076769999999999949e-01 8.319999999999999618e-01 -7.929899999999999449e-02 5.488279999999999825e-01 1.659899999999999917e-02 +1.403715297862139940e+09 -1.188025000000000109e+00 -2.218507999999999925e+00 1.044930000000000025e-01 8.281640000000000112e-01 -7.186499999999999833e-02 5.557579999999999742e-01 1.066300000000000060e-02 +1.403715297912139893e+09 -1.176509999999999945e+00 -2.246357000000000159e+00 1.031760000000000038e-01 8.237269999999999870e-01 -6.358300000000000063e-02 5.633810000000000207e-01 5.781999999999999813e-03 +1.403715297962140083e+09 -1.164191999999999894e+00 -2.275222999999999995e+00 1.024459999999999954e-01 -8.170870000000000077e-01 5.562500000000000083e-02 -5.738250000000000295e-01 5.240000000000000517e-04 +1.403715298012140036e+09 -1.152249000000000079e+00 -2.304838999999999860e+00 1.018759999999999943e-01 -8.102040000000000353e-01 4.534699999999999842e-02 -5.843660000000000521e-01 5.446999999999999585e-03 +1.403715298062139988e+09 -1.141405999999999921e+00 -2.335039000000000087e+00 1.012829999999999980e-01 -8.050249999999999906e-01 3.316100000000000297e-02 -5.922410000000000174e-01 9.279000000000000789e-03 +1.403715298112139940e+09 -1.131807000000000007e+00 -2.365906999999999982e+00 1.009349999999999969e-01 -8.010770000000000390e-01 1.835000000000000173e-02 -5.981990000000000363e-01 9.851999999999999647e-03 +1.403715298162139893e+09 -1.123164999999999969e+00 -2.397053999999999796e+00 9.966700000000000559e-02 -7.999049999999999772e-01 1.270000000000000078e-03 -6.000750000000000250e-01 7.803000000000000040e-03 +1.403715298212140083e+09 -1.116341000000000028e+00 -2.428351000000000148e+00 9.789200000000000679e-02 -8.001369999999999871e-01 -1.674099999999999894e-02 -5.995679999999999898e-01 4.377999999999999947e-03 +1.403715298262140036e+09 -1.110757999999999912e+00 -2.458854000000000095e+00 9.624499999999999722e-02 -8.007119999999999793e-01 -3.395900000000000307e-02 -5.980820000000000025e-01 2.115999999999999825e-03 +1.403715298312139988e+09 -1.106567999999999996e+00 -2.488264000000000031e+00 9.496799999999999686e-02 -8.014400000000000412e-01 -4.810999999999999999e-02 -5.961359999999999992e-01 1.523999999999999964e-03 +1.403715298362139940e+09 -1.103852000000000055e+00 -2.516058999999999823e+00 9.366199999999999526e-02 -8.035539999999999905e-01 -5.957199999999999995e-02 -5.922399999999999887e-01 1.881999999999999992e-03 +1.403715298412139893e+09 -1.102360000000000007e+00 -2.541784999999999961e+00 9.328599999999999393e-02 -8.059500000000000552e-01 -6.818699999999999761e-02 -5.880370000000000319e-01 2.658000000000000206e-03 +1.403715298462140083e+09 -1.101639999999999953e+00 -2.565614000000000061e+00 9.393200000000000160e-02 -8.079920000000000435e-01 -7.506300000000000472e-02 -5.843840000000000146e-01 2.990000000000000036e-03 +1.403715298512140036e+09 -1.101482000000000072e+00 -2.587256000000000000e+00 9.499499999999999611e-02 -8.091380000000000239e-01 -8.136200000000000376e-02 -5.819560000000000288e-01 1.781000000000000031e-03 +1.403715298562139988e+09 -1.101197999999999899e+00 -2.605929000000000162e+00 9.694200000000000039e-02 8.097569999999999490e-01 8.741799999999999571e-02 5.802150000000000363e-01 1.652999999999999955e-03 +1.403715298612139940e+09 -1.101618999999999904e+00 -2.621932000000000151e+00 9.936699999999999700e-02 8.095040000000000013e-01 9.270000000000000462e-02 5.797200000000000131e-01 5.923000000000000313e-03 +1.403715298662139893e+09 -1.102789000000000019e+00 -2.634605000000000086e+00 1.019759999999999972e-01 8.088990000000000347e-01 9.726600000000000523e-02 5.797609999999999708e-01 9.983000000000000554e-03 +1.403715298712140083e+09 -1.104753000000000096e+00 -2.643933000000000089e+00 1.053250000000000020e-01 8.084059999999999580e-01 1.002259999999999956e-01 5.798729999999999718e-01 1.345499999999999995e-02 +1.403715298762140036e+09 -1.107936000000000032e+00 -2.649236000000000146e+00 1.095779999999999949e-01 8.077550000000000008e-01 1.011390000000000067e-01 5.805730000000000057e-01 1.542499999999999948e-02 +1.403715298812139988e+09 -1.111749000000000098e+00 -2.651120999999999839e+00 1.140639999999999987e-01 8.084909999999999597e-01 9.942900000000000349e-02 5.798720000000000541e-01 1.430700000000000027e-02 +1.403715298862139940e+09 -1.116659000000000068e+00 -2.649382999999999821e+00 1.173850000000000032e-01 8.132890000000000397e-01 9.222500000000000142e-02 5.744780000000000442e-01 5.507999999999999875e-03 +1.403715298912139893e+09 -1.121877999999999931e+00 -2.643912999999999958e+00 1.206590000000000024e-01 -8.184839999999999893e-01 -8.336200000000000554e-02 -5.683970000000000411e-01 7.723999999999999963e-03 +1.403715298962140083e+09 -1.127040000000000042e+00 -2.635889999999999844e+00 1.237680000000000030e-01 -8.233549999999999480e-01 -7.590700000000000225e-02 -5.619950000000000223e-01 2.203400000000000150e-02 +1.403715299012140036e+09 -1.131461999999999968e+00 -2.625925000000000065e+00 1.271539999999999893e-01 -8.271060000000000079e-01 -7.264900000000000524e-02 -5.563550000000000439e-01 3.297300000000000231e-02 +1.403715299062139988e+09 -1.134773999999999949e+00 -2.614628000000000174e+00 1.306049999999999989e-01 -8.295590000000000463e-01 -7.195500000000000507e-02 -5.521019999999999817e-01 4.286800000000000332e-02 +1.403715299112139940e+09 -1.138905000000000056e+00 -2.602081999999999784e+00 1.349940000000000029e-01 -8.306970000000000187e-01 -7.415599999999999969e-02 -5.494229999999999947e-01 5.078099999999999975e-02 +1.403715299162139893e+09 -1.139094000000000051e+00 -2.589589999999999836e+00 1.393629999999999869e-01 -8.311699999999999644e-01 -7.778599999999999404e-02 -5.475160000000000027e-01 5.772299999999999653e-02 +1.403715299212140083e+09 -1.138096999999999914e+00 -2.576779000000000153e+00 1.436189999999999967e-01 -8.312239999999999629e-01 -8.294600000000000584e-02 -5.459650000000000336e-01 6.410799999999999832e-02 +1.403715299262140036e+09 -1.135232000000000019e+00 -2.563613000000000142e+00 1.475760000000000127e-01 -8.313639999999999919e-01 -8.904499999999999915e-02 -5.440129999999999688e-01 7.039399999999999824e-02 +1.403715299362139940e+09 -1.123980999999999897e+00 -2.536713000000000218e+00 1.552240000000000009e-01 -8.298379999999999646e-01 -1.035120000000000068e-01 -5.418690000000000451e-01 8.386100000000000498e-02 +1.403715299412139893e+09 -1.115309000000000106e+00 -2.523445999999999856e+00 1.599299999999999888e-01 -8.284859999999999447e-01 -1.116489999999999982e-01 -5.411449999999999871e-01 9.114300000000000179e-02 +1.403715299462140083e+09 -1.105067000000000021e+00 -2.510140999999999956e+00 1.644579999999999931e-01 -8.265770000000000062e-01 -1.207280000000000020e-01 -5.408669999999999867e-01 9.827600000000000224e-02 +1.403715299512140036e+09 -1.092964000000000047e+00 -2.496853999999999907e+00 1.689579999999999971e-01 -8.236019999999999452e-01 -1.302800000000000069e-01 -5.417180000000000328e-01 1.060600000000000015e-01 +1.403715299562139988e+09 -1.079854000000000092e+00 -2.483633000000000202e+00 1.730790000000000106e-01 -8.204510000000000414e-01 -1.406110000000000138e-01 -5.423210000000000530e-01 1.139160000000000034e-01 +1.403715299612139940e+09 -1.065506000000000064e+00 -2.470813000000000148e+00 1.770450000000000079e-01 -8.163340000000000041e-01 -1.514310000000000100e-01 -5.439819999999999656e-01 1.214520000000000044e-01 +1.403715299662139893e+09 -1.050292000000000003e+00 -2.457511999999999919e+00 1.800920000000000021e-01 -8.130610000000000337e-01 -1.624510000000000121e-01 -5.437859999999999916e-01 1.297649999999999915e-01 +1.403715299712140083e+09 -1.034243000000000023e+00 -2.444494000000000167e+00 1.829600000000000115e-01 -8.090929999999999511e-01 -1.731260000000000021e-01 -5.441399999999999570e-01 1.389539999999999942e-01 +1.403715299762140036e+09 -1.017292000000000085e+00 -2.431920999999999999e+00 1.854560000000000097e-01 -8.060000000000000497e-01 -1.853899999999999992e-01 -5.425740000000000007e-01 1.469969999999999888e-01 +1.403715299812139988e+09 -9.997160000000000490e-01 -2.419483000000000050e+00 1.877620000000000122e-01 -8.018880000000000452e-01 -1.970619999999999872e-01 -5.418619999999999548e-01 1.566140000000000032e-01 +1.403715299862139940e+09 -9.815589999999999593e-01 -2.407598000000000127e+00 1.893640000000000045e-01 -7.983120000000000216e-01 -2.092330000000000023e-01 -5.398140000000000160e-01 1.658920000000000117e-01 +1.403715299912139893e+09 -9.627160000000000162e-01 -2.395913999999999877e+00 1.907339999999999869e-01 -7.937140000000000306e-01 -2.222320000000000129e-01 -5.387849999999999584e-01 1.741900000000000115e-01 +1.403715299962140083e+09 -9.435740000000000238e-01 -2.384424000000000099e+00 1.921049999999999980e-01 -7.889199999999999546e-01 -2.349080000000000057e-01 -5.376840000000000508e-01 1.825390000000000068e-01 +1.403715300012140036e+09 -9.231080000000000396e-01 -2.373329000000000022e+00 1.936849999999999961e-01 -7.849589999999999623e-01 -2.466000000000000136e-01 -5.357600000000000140e-01 1.897069999999999868e-01 +1.403715300062139988e+09 -9.022200000000000220e-01 -2.362684999999999924e+00 1.954899999999999971e-01 -7.787030000000000340e-01 -2.570959999999999912e-01 -5.376800000000000468e-01 1.960189999999999988e-01 +1.403715300112139940e+09 -8.811320000000000263e-01 -2.353057999999999872e+00 1.972460000000000047e-01 -7.729230000000000267e-01 -2.653909999999999880e-01 -5.397610000000000463e-01 2.020280000000000131e-01 +1.403715300162139893e+09 -8.598599999999999577e-01 -2.344422999999999924e+00 1.989390000000000047e-01 -7.672689999999999788e-01 -2.742100000000000093e-01 -5.425769999999999760e-01 2.042460000000000109e-01 +1.403715300212140083e+09 -8.376850000000000129e-01 -2.336180999999999841e+00 2.002559999999999896e-01 -7.618549999999999489e-01 -2.833109999999999795e-01 -5.458570000000000366e-01 2.033500000000000030e-01 +1.403715300262140036e+09 -8.168060000000000320e-01 -2.328294000000000086e+00 2.015649999999999942e-01 -7.562999999999999723e-01 -2.897020000000000151e-01 -5.500030000000000197e-01 2.039120000000000099e-01 +1.403715300312139988e+09 -7.971219999999999972e-01 -2.321002000000000010e+00 2.031129999999999880e-01 -7.527420000000000222e-01 -2.922799999999999843e-01 -5.520639999999999992e-01 2.077910000000000035e-01 +1.403715300362139940e+09 -7.784349999999999881e-01 -2.313934999999999853e+00 2.045960000000000001e-01 -7.500320000000000320e-01 -2.928850000000000064e-01 -5.536670000000000202e-01 2.124230000000000007e-01 +1.403715300412139893e+09 -7.612539999999999862e-01 -2.308041999999999927e+00 2.071310000000000096e-01 -7.486680000000000001e-01 -2.921429999999999860e-01 -5.538960000000000550e-01 2.175940000000000096e-01 +1.403715300462140083e+09 -7.449980000000000491e-01 -2.302712000000000092e+00 2.091109999999999913e-01 -7.479550000000000365e-01 -2.906730000000000147e-01 -5.539399999999999880e-01 2.218610000000000027e-01 +1.403715300512140036e+09 -7.297890000000000210e-01 -2.298223000000000127e+00 2.108790000000000109e-01 -7.475169999999999870e-01 -2.902910000000000212e-01 -5.540389999999999482e-01 2.235870000000000080e-01 +1.403715300562139988e+09 -7.161720000000000308e-01 -2.294907999999999948e+00 2.124580000000000080e-01 -7.481609999999999649e-01 -2.889369999999999994e-01 -5.531960000000000210e-01 2.252639999999999920e-01 +1.403715300612139940e+09 -7.030650000000000510e-01 -2.292898000000000103e+00 2.138309999999999933e-01 -7.493980000000000086e-01 -2.879050000000000220e-01 -5.519180000000000197e-01 2.256080000000000030e-01 +1.403715300662139893e+09 -6.912049999999999583e-01 -2.291843000000000075e+00 2.153029999999999944e-01 -7.504750000000000032e-01 -2.867069999999999896e-01 -5.511009999999999520e-01 2.255520000000000025e-01 +1.403715300712140083e+09 -6.809739999999999682e-01 -2.292342999999999797e+00 2.175900000000000056e-01 -7.518740000000000423e-01 -2.848470000000000169e-01 -5.500119999999999454e-01 2.259079999999999977e-01 +1.403715300762140036e+09 -6.705919999999999659e-01 -2.293724000000000096e+00 2.189419999999999977e-01 -7.525500000000000522e-01 -2.830599999999999783e-01 -5.502010000000000511e-01 2.254430000000000045e-01 +1.403715300812139988e+09 -6.610479999999999690e-01 -2.296372999999999998e+00 2.202739999999999976e-01 -7.524600000000000177e-01 -2.822180000000000244e-01 -5.514339999999999797e-01 2.237780000000000047e-01 +1.403715300862139940e+09 -6.521630000000000482e-01 -2.300019999999999953e+00 2.214550000000000129e-01 -7.519230000000000080e-01 -2.823359999999999759e-01 -5.533709999999999463e-01 2.206289999999999918e-01 +1.403715300912139893e+09 -6.443349999999999911e-01 -2.304732000000000003e+00 2.223030000000000006e-01 -7.514129999999999976e-01 -2.831650000000000000e-01 -5.552550000000000541e-01 2.165380000000000082e-01 +1.403715300962140083e+09 -6.375760000000000316e-01 -2.310080999999999829e+00 2.228310000000000013e-01 -7.509169999999999456e-01 -2.840159999999999907e-01 -5.570469999999999589e-01 2.125029999999999974e-01 +1.403715301012140036e+09 -6.316070000000000295e-01 -2.315926999999999847e+00 2.230050000000000088e-01 -7.505049999999999777e-01 -2.845079999999999831e-01 -5.585970000000000102e-01 2.092070000000000041e-01 +1.403715301062139988e+09 -6.269580000000000153e-01 -2.322738999999999887e+00 2.231539999999999913e-01 -7.496239999999999570e-01 -2.847439999999999971e-01 -5.608109999999999484e-01 2.060960000000000014e-01 +1.403715301112139940e+09 -6.236319999999999641e-01 -2.330249999999999932e+00 2.235330000000000095e-01 -7.479449999999999710e-01 -2.848149999999999848e-01 -5.640990000000000171e-01 2.031020000000000048e-01 +1.403715301162139893e+09 -6.219069999999999876e-01 -2.338106999999999935e+00 2.238179999999999892e-01 -7.459740000000000260e-01 -2.854689999999999728e-01 -5.675379999999999869e-01 1.998270000000000046e-01 +1.403715301212140083e+09 -6.212469999999999937e-01 -2.346569999999999823e+00 2.240590000000000082e-01 -7.438839999999999897e-01 -2.861779999999999879e-01 -5.711119999999999530e-01 1.963920000000000110e-01 +1.403715301262140036e+09 -6.225100000000000078e-01 -2.355141999999999847e+00 2.236309999999999965e-01 -7.423640000000000239e-01 -2.873729999999999896e-01 -5.735620000000000163e-01 1.932319999999999871e-01 +1.403715301312139988e+09 -6.258650000000000047e-01 -2.363783000000000190e+00 2.227409999999999946e-01 -7.408749999999999503e-01 -2.883600000000000052e-01 -5.756440000000000445e-01 1.912770000000000026e-01 +1.403715301362139940e+09 -6.321219999999999617e-01 -2.372638999999999943e+00 2.213330000000000020e-01 -7.402199999999999891e-01 -2.887120000000000242e-01 -5.766019999999999479e-01 1.903950000000000087e-01 +1.403715301412139893e+09 -6.410240000000000382e-01 -2.381762000000000157e+00 2.190229999999999955e-01 -7.408310000000000173e-01 -2.886259999999999937e-01 -5.757710000000000328e-01 1.906599999999999961e-01 +1.403715301462140083e+09 -6.517500000000000515e-01 -2.390664999999999818e+00 2.161180000000000045e-01 -7.429559999999999498e-01 -2.866440000000000099e-01 -5.728889999999999816e-01 1.940369999999999873e-01 +1.403715301512140036e+09 -6.643799999999999706e-01 -2.399888999999999939e+00 2.119729999999999948e-01 -7.474049999999999860e-01 -2.845070000000000099e-01 -5.669119999999999715e-01 1.976179999999999881e-01 +1.403715301562139988e+09 -6.785299999999999665e-01 -2.409380000000000077e+00 2.068109999999999948e-01 -7.528820000000000512e-01 -2.829420000000000268e-01 -5.595999999999999863e-01 1.999019999999999964e-01 +1.403715301612139940e+09 -6.936579999999999968e-01 -2.419156000000000084e+00 2.012160000000000060e-01 -7.583699999999999886e-01 -2.814639999999999920e-01 -5.523709999999999454e-01 2.013409999999999922e-01 +1.403715301662139893e+09 -7.094340000000000090e-01 -2.429238999999999926e+00 1.953799999999999981e-01 -7.627639999999999976e-01 -2.795000000000000262e-01 -5.466999999999999638e-01 2.029509999999999925e-01 +1.403715301712140083e+09 -7.254899999999999682e-01 -2.439589999999999925e+00 1.893029999999999990e-01 -7.655119999999999703e-01 -2.783289999999999931e-01 -5.434729999999999839e-01 2.028820000000000068e-01 +1.403715301762140036e+09 -7.413899999999999935e-01 -2.450232999999999883e+00 1.825640000000000041e-01 -7.669129999999999558e-01 -2.780839999999999979e-01 -5.423249999999999460e-01 2.009900000000000020e-01 +1.403715301812139988e+09 -7.581839999999999691e-01 -2.461180999999999841e+00 1.758170000000000011e-01 -7.660660000000000247e-01 -2.792769999999999975e-01 -5.442169999999999508e-01 1.974180000000000101e-01 +1.403715301862139940e+09 -7.745560000000000223e-01 -2.471492000000000022e+00 1.696340000000000070e-01 -7.649960000000000093e-01 -2.805750000000000188e-01 -5.464560000000000528e-01 1.935060000000000113e-01 +1.403715301912139893e+09 -7.914609999999999701e-01 -2.481682999999999861e+00 1.635149999999999937e-01 -7.645669999999999966e-01 -2.813039999999999985e-01 -5.478399999999999936e-01 1.902040000000000119e-01 +1.403715301962140083e+09 -8.090779999999999639e-01 -2.491508000000000056e+00 1.579800000000000093e-01 -7.652640000000000553e-01 -2.804909999999999903e-01 -5.475809999999999844e-01 1.893450000000000133e-01 +1.403715302012140036e+09 -8.272249999999999881e-01 -2.500792000000000126e+00 1.533720000000000083e-01 -7.648989999999999956e-01 -2.806060000000000221e-01 -5.488300000000000400e-01 1.870159999999999878e-01 +1.403715302062139988e+09 -8.463039999999999452e-01 -2.509527999999999981e+00 1.493200000000000083e-01 -7.648869999999999836e-01 -2.806750000000000078e-01 -5.495919999999999694e-01 1.847100000000000131e-01 +1.403715302112139940e+09 -8.661919999999999620e-01 -2.518013999999999974e+00 1.458019999999999872e-01 -7.658019999999999827e-01 -2.808579999999999965e-01 -5.490000000000000435e-01 1.823869999999999936e-01 +1.403715302162139893e+09 -8.872179999999999511e-01 -2.525377000000000205e+00 1.423129999999999951e-01 -7.676490000000000258e-01 -2.812790000000000012e-01 -5.471799999999999997e-01 1.794189999999999952e-01 +1.403715302212140083e+09 -9.084189999999999765e-01 -2.532370999999999928e+00 1.394440000000000124e-01 -7.693990000000000551e-01 -2.811580000000000190e-01 -5.456490000000000506e-01 1.767559999999999965e-01 +1.403715302262140036e+09 -9.301439999999999708e-01 -2.538457999999999881e+00 1.369889999999999997e-01 -7.716499999999999471e-01 -2.808809999999999918e-01 -5.435090000000000199e-01 1.739559999999999995e-01 +1.403715302312139988e+09 -9.519269999999999676e-01 -2.543143000000000153e+00 1.354809999999999903e-01 -7.731029999999999847e-01 -2.808999999999999830e-01 -5.424510000000000165e-01 1.707460000000000089e-01 +1.403715302362139940e+09 -9.742030000000000411e-01 -2.546701999999999799e+00 1.347109999999999974e-01 -7.740240000000000453e-01 -2.801130000000000009e-01 -5.423630000000000395e-01 1.681269999999999987e-01 +1.403715302412139893e+09 -9.967730000000000201e-01 -2.549005999999999883e+00 1.344529999999999892e-01 -7.743170000000000330e-01 -2.791759999999999797e-01 -5.430930000000000479e-01 1.659640000000000004e-01 +1.403715302462140083e+09 -1.019562999999999997e+00 -2.550068000000000001e+00 1.345949999999999924e-01 -7.750709999999999544e-01 -2.761239999999999806e-01 -5.433329999999999549e-01 1.667649999999999966e-01 +1.403715302512140036e+09 -1.042763000000000106e+00 -2.550174000000000163e+00 1.350949999999999929e-01 -7.769470000000000542e-01 -2.709940000000000127e-01 -5.419819999999999638e-01 1.707940000000000014e-01 +1.403715302562139988e+09 -1.066129000000000104e+00 -2.549151000000000167e+00 1.359779999999999878e-01 -7.794060000000000432e-01 -2.664699999999999847e-01 -5.396900000000000031e-01 1.739370000000000083e-01 +1.403715302612139940e+09 -1.089461000000000013e+00 -2.547490999999999950e+00 1.364869999999999972e-01 -7.813440000000000385e-01 -2.622030000000000194e-01 -5.378690000000000415e-01 1.773339999999999916e-01 +1.403715302662139893e+09 -1.112662000000000040e+00 -2.545576000000000061e+00 1.368610000000000104e-01 -7.830880000000000063e-01 -2.597450000000000037e-01 -5.362630000000000452e-01 1.781250000000000056e-01 +1.403715302712140083e+09 -1.135183000000000053e+00 -2.543372999999999884e+00 1.369660000000000044e-01 -7.850489999999999968e-01 -2.565290000000000070e-01 -5.341169999999999529e-01 1.805809999999999915e-01 +1.403715302762140036e+09 -1.156925999999999899e+00 -2.541439000000000004e+00 1.351110000000000089e-01 -7.869369999999999976e-01 -2.546510000000000162e-01 -5.318850000000000522e-01 1.816069999999999907e-01 +1.403715302812139988e+09 -1.177767999999999926e+00 -2.538288000000000100e+00 1.327450000000000019e-01 -7.896199999999999886e-01 -2.532340000000000146e-01 -5.283069999999999711e-01 1.823869999999999936e-01 +1.403715302862139940e+09 -1.197330000000000005e+00 -2.534917000000000087e+00 1.296200000000000130e-01 -7.920099999999999918e-01 -2.534049999999999914e-01 -5.249519999999999742e-01 1.814709999999999934e-01 +1.403715302912139893e+09 -1.215646999999999922e+00 -2.530710000000000015e+00 1.260900000000000076e-01 -7.938990000000000213e-01 -2.543329999999999758e-01 -5.213449999999999473e-01 1.823140000000000038e-01 +1.403715302962140083e+09 -1.232599999999999918e+00 -2.525923000000000140e+00 1.228780000000000011e-01 -7.948159999999999670e-01 -2.571729999999999849e-01 -5.180190000000000072e-01 1.838090000000000002e-01 +1.403715303012140036e+09 -1.248156000000000043e+00 -2.520631999999999984e+00 1.193550000000000028e-01 -7.948250000000000037e-01 -2.622249999999999859e-01 -5.149299999999999988e-01 1.853029999999999955e-01 +1.403715303062139988e+09 -1.262448000000000015e+00 -2.514431999999999778e+00 1.159420000000000034e-01 -7.941240000000000521e-01 -2.680640000000000245e-01 -5.118610000000000104e-01 1.884329999999999894e-01 +1.403715303112139940e+09 -1.275470000000000104e+00 -2.507413999999999810e+00 1.122480000000000006e-01 -7.924189999999999845e-01 -2.760360000000000036e-01 -5.088970000000000438e-01 1.920959999999999890e-01 +1.403715303162139893e+09 -1.286842000000000041e+00 -2.499442000000000164e+00 1.088500000000000023e-01 -7.892829999999999568e-01 -2.855159999999999920e-01 -5.068550000000000555e-01 1.964990000000000070e-01 +1.403715303212140083e+09 -1.297641999999999962e+00 -2.490432000000000201e+00 1.059080000000000021e-01 -7.844290000000000429e-01 -2.958160000000000234e-01 -5.061160000000000103e-01 2.025109999999999966e-01 +1.403715303262140036e+09 -1.306027000000000049e+00 -2.479636999999999869e+00 1.044069999999999998e-01 -7.771740000000000315e-01 -3.067549999999999999e-01 -5.077509999999999524e-01 2.099779999999999980e-01 +1.403715303312139988e+09 -1.313196999999999948e+00 -2.468141999999999836e+00 1.033059999999999951e-01 -7.687370000000000037e-01 -3.189199999999999813e-01 -5.100550000000000361e-01 2.172050000000000092e-01 +1.403715303362139940e+09 -1.319682000000000022e+00 -2.456148999999999916e+00 1.018919999999999965e-01 -7.599059999999999704e-01 -3.319159999999999888e-01 -5.120710000000000539e-01 2.239579999999999904e-01 +1.403715303412139893e+09 -1.325673000000000101e+00 -2.443506999999999874e+00 1.008860000000000035e-01 -7.513269999999999671e-01 -3.447490000000000276e-01 -5.133630000000000138e-01 2.304640000000000022e-01 +1.403715303462140083e+09 -1.331800000000000095e+00 -2.430238000000000120e+00 9.947899999999999798e-02 -7.435850000000000515e-01 -3.574660000000000060e-01 -5.130109999999999948e-01 2.368969999999999965e-01 +1.403715303512140036e+09 -1.338422999999999918e+00 -2.416570000000000107e+00 9.782100000000000517e-02 -7.368249999999999522e-01 -3.693119999999999736e-01 -5.108660000000000423e-01 2.443629999999999969e-01 +1.403715303562139988e+09 -1.345819000000000099e+00 -2.402372999999999870e+00 9.630099999999999771e-02 -7.291670000000000096e-01 -3.816169999999999840e-01 -5.097899999999999654e-01 2.505970000000000142e-01 +1.403715303612139940e+09 -1.353736000000000050e+00 -2.387290999999999830e+00 9.446899999999999742e-02 -7.232159999999999700e-01 -3.914779999999999927e-01 -5.058240000000000514e-01 2.604699999999999793e-01 +1.403715303662139893e+09 -1.362042999999999893e+00 -2.371821999999999875e+00 9.313200000000000645e-02 -7.164850000000000385e-01 -4.001959999999999962e-01 -5.026169999999999805e-01 2.717849999999999988e-01 +1.403715303712140083e+09 -1.371113000000000026e+00 -2.355752999999999986e+00 9.162099999999999411e-02 -7.103949999999999987e-01 -4.089550000000000129e-01 -4.982369999999999854e-01 2.825849999999999751e-01 +1.403715303762140036e+09 -1.379987999999999992e+00 -2.339596999999999927e+00 9.015399999999999803e-02 -7.040650000000000519e-01 -4.170449999999999990e-01 -4.939899999999999847e-01 2.938350000000000128e-01 +1.403715303812139988e+09 -1.390350999999999893e+00 -2.323259000000000185e+00 8.725800000000000223e-02 -6.971469999999999612e-01 -4.257199999999999873e-01 -4.905599999999999961e-01 3.034789999999999988e-01 +1.403715303862139940e+09 -1.399529000000000023e+00 -2.307538999999999785e+00 8.593399999999999650e-02 -6.903660000000000352e-01 -4.328270000000000173e-01 -4.871619999999999839e-01 3.142099999999999893e-01 +1.403715303912139893e+09 -1.408946000000000032e+00 -2.292996000000000034e+00 8.474199999999999788e-02 -6.844179999999999708e-01 -4.391740000000000088e-01 -4.840960000000000263e-01 3.230319999999999858e-01 +1.403715303962140083e+09 -1.418026999999999926e+00 -2.279225999999999974e+00 8.353900000000000214e-02 -6.793329999999999647e-01 -4.447139999999999982e-01 -4.816469999999999918e-01 3.297760000000000136e-01 +1.403715304012140036e+09 -1.426986000000000088e+00 -2.266525999999999819e+00 8.197100000000000219e-02 -6.754440000000000444e-01 -4.494029999999999969e-01 -4.790150000000000241e-01 3.351970000000000227e-01 +1.403715304062139988e+09 -1.435700999999999894e+00 -2.254589999999999872e+00 8.001999999999999391e-02 -6.722879999999999967e-01 -4.531290000000000040e-01 -4.769630000000000258e-01 3.394240000000000035e-01 +1.403715304112139940e+09 -1.444188000000000027e+00 -2.243790000000000173e+00 7.790999999999999315e-02 -6.701759999999999939e-01 -4.550239999999999840e-01 -4.749760000000000093e-01 3.438260000000000205e-01 +1.403715304162139893e+09 -1.452147000000000077e+00 -2.234046000000000198e+00 7.589400000000000313e-02 -6.681479999999999642e-01 -4.563969999999999971e-01 -4.740269999999999762e-01 3.472450000000000259e-01 +1.403715304212140083e+09 -1.458974999999999911e+00 -2.224574000000000051e+00 7.291300000000000558e-02 -6.674529999999999630e-01 -4.579280000000000017e-01 -4.723700000000000121e-01 3.488180000000000169e-01 +1.403715304262140036e+09 -1.466224999999999890e+00 -2.217433999999999905e+00 6.960500000000000020e-02 -6.677779999999999827e-01 -4.590489999999999848e-01 -4.703700000000000103e-01 3.494269999999999876e-01 +1.403715304312139988e+09 -1.473157999999999967e+00 -2.211574000000000151e+00 6.623199999999999921e-02 -6.686189999999999634e-01 -4.601040000000000130e-01 -4.683329999999999993e-01 3.491659999999999764e-01 +1.403715304362139940e+09 -1.479672000000000098e+00 -2.206224000000000185e+00 6.217299999999999910e-02 -6.697840000000000460e-01 -4.604980000000000184e-01 -4.668470000000000120e-01 3.484019999999999895e-01 +1.403715304412139893e+09 -1.486085000000000100e+00 -2.201886000000000010e+00 5.792100000000000026e-02 -6.711939999999999573e-01 -4.607620000000000049e-01 -4.655850000000000266e-01 3.470269999999999744e-01 +1.403715304462140083e+09 -1.491719000000000017e+00 -2.198468999999999784e+00 5.319900000000000323e-02 -6.723510000000000320e-01 -4.606029999999999847e-01 -4.655190000000000161e-01 3.450819999999999999e-01 +1.403715304512140036e+09 -1.496801999999999966e+00 -2.195816000000000212e+00 4.761900000000000160e-02 -6.719019999999999992e-01 -4.608340000000000214e-01 -4.682089999999999863e-01 3.419949999999999934e-01 +1.403715304562139988e+09 -1.501697999999999977e+00 -2.193618999999999986e+00 3.888599999999999696e-02 -6.720979999999999732e-01 -4.608300000000000174e-01 -4.702330000000000121e-01 3.388249999999999873e-01 +1.403715304612139940e+09 -1.506455000000000100e+00 -2.191828999999999805e+00 2.744500000000000065e-02 -6.722150000000000070e-01 -4.604920000000000124e-01 -4.723760000000000181e-01 3.360560000000000214e-01 +1.403715304662139893e+09 -1.511366999999999905e+00 -2.190665999999999780e+00 1.452099999999999919e-02 -6.723379999999999912e-01 -4.588550000000000129e-01 -4.744800000000000129e-01 3.350870000000000237e-01 +1.403715304712140083e+09 -1.516421999999999937e+00 -2.190056999999999920e+00 8.329999999999999731e-04 -6.727950000000000319e-01 -4.576529999999999765e-01 -4.761529999999999929e-01 3.334349999999999814e-01 +1.403715304762140036e+09 -1.521722999999999937e+00 -2.189429000000000070e+00 -1.316400000000000035e-02 -6.736769999999999703e-01 -4.573240000000000083e-01 -4.772870000000000168e-01 3.304719999999999880e-01 +1.403715304812139988e+09 -1.528235000000000010e+00 -2.190586999999999840e+00 -2.463200000000000112e-02 -6.745320000000000205e-01 -4.565250000000000141e-01 -4.780070000000000152e-01 3.287869999999999959e-01 +1.403715304862139940e+09 -1.533689999999999998e+00 -2.190819999999999990e+00 -3.405500000000000194e-02 -6.757459999999999578e-01 -4.561589999999999812e-01 -4.781020000000000270e-01 3.266569999999999752e-01 +1.403715304912139893e+09 -1.539193999999999951e+00 -2.191202000000000094e+00 -4.011900000000000188e-02 -6.765660000000000007e-01 -4.560109999999999997e-01 -4.785019999999999829e-01 3.245739999999999736e-01 +1.403715304962140083e+09 -1.544858999999999982e+00 -2.191651999999999934e+00 -4.282699999999999702e-02 -6.778089999999999948e-01 -4.557709999999999817e-01 -4.778259999999999730e-01 3.233110000000000150e-01 +1.403715305012140036e+09 -1.551004000000000049e+00 -2.192289999999999850e+00 -4.242300000000000237e-02 -6.782449999999999868e-01 -4.555870000000000197e-01 -4.778609999999999802e-01 3.226040000000000019e-01 +1.403715305062139988e+09 -1.557439000000000018e+00 -2.193156999999999801e+00 -3.960899999999999838e-02 -6.794170000000000487e-01 -4.551509999999999723e-01 -4.765800000000000036e-01 3.226490000000000191e-01 +1.403715305112139940e+09 -1.564076999999999940e+00 -2.194075999999999915e+00 -3.450199999999999795e-02 -6.799579999999999513e-01 -4.548610000000000153e-01 -4.759700000000000042e-01 3.228159999999999918e-01 +1.403715305162139893e+09 -1.570937999999999946e+00 -2.195041999999999938e+00 -2.868000000000000063e-02 -6.806600000000000428e-01 -4.551359999999999850e-01 -4.748760000000000203e-01 3.225600000000000134e-01 +1.403715305212140083e+09 -1.577571999999999974e+00 -2.196019999999999861e+00 -2.351599999999999871e-02 -6.818680000000000296e-01 -4.553309999999999858e-01 -4.727410000000000223e-01 3.228719999999999923e-01 +1.403715305262140036e+09 -1.583941000000000043e+00 -2.196924999999999795e+00 -1.879700000000000121e-02 -6.825919999999999765e-01 -4.553940000000000210e-01 -4.712910000000000155e-01 3.233719999999999928e-01 +1.403715305312139988e+09 -1.590260000000000007e+00 -2.198011000000000159e+00 -1.456499999999999982e-02 -6.824700000000000211e-01 -4.563679999999999959e-01 -4.707189999999999985e-01 3.230890000000000151e-01 +1.403715305362139940e+09 -1.597763000000000044e+00 -2.200118999999999936e+00 -1.020399999999999953e-02 -6.831080000000000485e-01 -4.568679999999999963e-01 -4.687609999999999832e-01 3.238809999999999745e-01 +1.403715305412139893e+09 -1.604198999999999931e+00 -2.201316999999999968e+00 -6.078000000000000069e-03 -6.825649999999999773e-01 -4.583749999999999769e-01 -4.683019999999999960e-01 3.235589999999999855e-01 +1.403715305462140083e+09 -1.610424999999999995e+00 -2.202142999999999962e+00 -1.008999999999999914e-03 -6.813329999999999664e-01 -4.595719999999999805e-01 -4.681629999999999958e-01 3.246569999999999734e-01 +1.403715305512140036e+09 -1.616554000000000046e+00 -2.203235999999999972e+00 6.662999999999999652e-03 -6.800910000000000011e-01 -4.602240000000000220e-01 -4.677870000000000084e-01 3.268730000000000246e-01 +1.403715305562139988e+09 -1.622506999999999922e+00 -2.204277999999999960e+00 1.755699999999999969e-02 -6.786379999999999635e-01 -4.618539999999999868e-01 -4.673689999999999789e-01 3.281899999999999817e-01 +1.403715305612139940e+09 -1.628258999999999901e+00 -2.205465999999999926e+00 3.138200000000000017e-02 -6.776339999999999586e-01 -4.638709999999999778e-01 -4.660880000000000023e-01 3.292370000000000019e-01 +1.403715305662139893e+09 -1.633933999999999997e+00 -2.206179999999999808e+00 4.898399999999999976e-02 -6.759290000000000020e-01 -4.653769999999999851e-01 -4.657729999999999926e-01 3.310589999999999922e-01 +1.403715305712140083e+09 -1.639343999999999912e+00 -2.206758000000000219e+00 6.887500000000000566e-02 -6.759150000000000436e-01 -4.655590000000000006e-01 -4.633909999999999973e-01 3.341609999999999858e-01 +1.403715305762140036e+09 -1.644139999999999935e+00 -2.207498999999999878e+00 9.030499999999999639e-02 -6.748359999999999914e-01 -4.666870000000000185e-01 -4.626739999999999742e-01 3.357580000000000009e-01 +1.403715305812139988e+09 -1.648330999999999991e+00 -2.208269000000000037e+00 1.116499999999999992e-01 -6.744139999999999580e-01 -4.675699999999999856e-01 -4.614260000000000028e-01 3.370900000000000007e-01 +1.403715305862139940e+09 -1.651704000000000061e+00 -2.208994999999999820e+00 1.323940000000000117e-01 -6.738380000000000480e-01 -4.690719999999999890e-01 -4.608360000000000234e-01 3.369630000000000125e-01 +1.403715305912139893e+09 -1.654701999999999895e+00 -2.209891999999999967e+00 1.523940000000000017e-01 -6.738779999999999770e-01 -4.703379999999999783e-01 -4.598220000000000085e-01 3.365040000000000253e-01 +1.403715305962140083e+09 -1.656139000000000028e+00 -2.209378000000000064e+00 1.718480000000000008e-01 -6.736630000000000118e-01 -4.711489999999999845e-01 -4.595409999999999773e-01 3.361810000000000076e-01 +1.403715306012140036e+09 -1.658184000000000102e+00 -2.209416000000000047e+00 1.906289999999999929e-01 -6.737680000000000335e-01 -4.716899999999999982e-01 -4.590449999999999808e-01 3.358900000000000219e-01 +1.403715306062139988e+09 -1.659818000000000016e+00 -2.209913999999999934e+00 2.079350000000000087e-01 -6.740990000000000038e-01 -4.726980000000000071e-01 -4.584790000000000254e-01 3.345810000000000173e-01 +1.403715306112139940e+09 -1.661116999999999955e+00 -2.210297999999999874e+00 2.241539999999999921e-01 -6.752280000000000504e-01 -4.732660000000000200e-01 -4.568550000000000111e-01 3.337220000000000186e-01 +1.403715306162139893e+09 -1.662099999999999911e+00 -2.210379999999999789e+00 2.396959999999999924e-01 -6.769929999999999559e-01 -4.715940000000000132e-01 -4.542680000000000051e-01 3.360349999999999726e-01 +1.403715306212140083e+09 -1.662309000000000037e+00 -2.210163000000000100e+00 2.549899999999999944e-01 -6.784620000000000095e-01 -4.676060000000000216e-01 -4.531970000000000165e-01 3.400679999999999814e-01 +1.403715306262140036e+09 -1.661494999999999944e+00 -2.210147999999999779e+00 2.696770000000000000e-01 -6.799009999999999776e-01 -4.621779999999999777e-01 -4.532280000000000197e-01 3.445440000000000169e-01 +1.403715306312139988e+09 -1.659577999999999998e+00 -2.210517999999999983e+00 2.837549999999999795e-01 -6.816990000000000549e-01 -4.548349999999999893e-01 -4.540529999999999844e-01 3.496389999999999776e-01 +1.403715306362139940e+09 -1.656336999999999948e+00 -2.211411000000000016e+00 2.979609999999999759e-01 -6.835820000000000229e-01 -4.470720000000000249e-01 -4.559119999999999839e-01 3.535340000000000149e-01 +1.403715306412139893e+09 -1.651377000000000095e+00 -2.213191000000000130e+00 3.123699999999999810e-01 -6.848490000000000411e-01 -4.383079999999999754e-01 -4.598149999999999737e-01 3.569840000000000235e-01 +1.403715306462140083e+09 -1.644455999999999918e+00 -2.216148000000000007e+00 3.266160000000000174e-01 -6.867860000000000076e-01 -4.300889999999999991e-01 -4.641830000000000123e-01 3.576070000000000082e-01 +1.403715306512140036e+09 -1.635801999999999978e+00 -2.220889999999999809e+00 3.402959999999999874e-01 -6.888910000000000311e-01 -4.225439999999999752e-01 -4.695940000000000114e-01 3.554820000000000202e-01 +1.403715306562139988e+09 -1.624671999999999894e+00 -2.226735999999999827e+00 3.535369999999999902e-01 -6.911770000000000413e-01 -4.150679999999999925e-01 -4.758740000000000192e-01 3.514789999999999859e-01 +1.403715306612139940e+09 -1.612522999999999929e+00 -2.235271000000000008e+00 3.673520000000000119e-01 -6.932450000000000001e-01 -4.064590000000000147e-01 -4.833219999999999739e-01 3.472790000000000044e-01 +1.403715306662139893e+09 -1.599275000000000002e+00 -2.245658999999999850e+00 3.813719999999999888e-01 -6.951490000000000169e-01 -3.980620000000000269e-01 -4.917270000000000252e-01 3.413499999999999868e-01 +1.403715306712140083e+09 -1.585155000000000092e+00 -2.258955999999999964e+00 3.951410000000000200e-01 -6.969610000000000527e-01 -3.907869999999999955e-01 -5.007420000000000204e-01 3.328479999999999772e-01 +1.403715306762140036e+09 -1.570567000000000046e+00 -2.274634999999999962e+00 4.082399999999999918e-01 -6.990290000000000115e-01 -3.840660000000000185e-01 -5.099129999999999496e-01 3.222430000000000017e-01 +1.403715306812139988e+09 -1.556024999999999991e+00 -2.292815000000000047e+00 4.216260000000000008e-01 -6.999940000000000051e-01 -3.756950000000000012e-01 -5.205189999999999539e-01 3.129239999999999799e-01 +1.403715306862139940e+09 -1.542010000000000103e+00 -2.313258999999999954e+00 4.344790000000000041e-01 -7.008029999999999538e-01 -3.672279999999999989e-01 -5.312919999999999865e-01 3.028970000000000273e-01 +1.403715306912139893e+09 -1.528783000000000003e+00 -2.335706000000000060e+00 4.459480000000000111e-01 -7.021709999999999896e-01 -3.598990000000000244e-01 -5.414560000000000484e-01 2.902649999999999952e-01 +1.403715306962140083e+09 -1.516866000000000048e+00 -2.360148999999999830e+00 4.567089999999999761e-01 -7.045550000000000423e-01 -3.540610000000000146e-01 -5.500150000000000317e-01 2.751850000000000129e-01 +1.403715307012140036e+09 -1.506507999999999958e+00 -2.386083000000000176e+00 4.658019999999999938e-01 -7.071809999999999485e-01 -3.491029999999999966e-01 -5.580030000000000268e-01 2.581760000000000166e-01 +1.403715307062139988e+09 -1.498393000000000086e+00 -2.413489999999999913e+00 4.716350000000000264e-01 -7.109720000000000484e-01 -3.436279999999999890e-01 -5.639349999999999641e-01 2.416929999999999912e-01 +1.403715307112139940e+09 -1.492818999999999896e+00 -2.442152000000000100e+00 4.735030000000000072e-01 -7.169419999999999682e-01 -3.376620000000000177e-01 -5.663669999999999538e-01 2.262909999999999922e-01 +1.403715307162139893e+09 -1.489673999999999943e+00 -2.471092000000000066e+00 4.713089999999999780e-01 -7.244380000000000264e-01 -3.316790000000000016e-01 -5.663030000000000008e-01 2.109030000000000071e-01 +1.403715307212140083e+09 -1.488877000000000006e+00 -2.499886000000000053e+00 4.659849999999999826e-01 -7.316679999999999851e-01 -3.250870000000000148e-01 -5.659750000000000059e-01 1.966040000000000010e-01 +1.403715307262140036e+09 -1.490572000000000008e+00 -2.527906000000000208e+00 4.584960000000000147e-01 -7.386390000000000455e-01 -3.186680000000000068e-01 -5.652589999999999559e-01 1.826039999999999885e-01 +1.403715307312139988e+09 -1.494628999999999985e+00 -2.554851000000000205e+00 4.484839999999999938e-01 -7.455779999999999630e-01 -3.106389999999999985e-01 -5.641969999999999485e-01 1.711689999999999878e-01 +1.403715307362139940e+09 -1.500965000000000105e+00 -2.580397000000000052e+00 4.364810000000000079e-01 -7.535589999999999788e-01 -3.008370000000000211e-01 -5.613409999999999789e-01 1.629200000000000093e-01 +1.403715307412139893e+09 -1.509316000000000102e+00 -2.603975000000000151e+00 4.236159999999999926e-01 -7.629390000000000338e-01 -2.880770000000000275e-01 -5.563949999999999729e-01 1.592510000000000037e-01 +1.403715307462140083e+09 -1.519416000000000100e+00 -2.626152999999999960e+00 4.108149999999999857e-01 -7.713689999999999714e-01 -2.748209999999999820e-01 -5.520960000000000312e-01 1.570139999999999869e-01 +1.403715307512140036e+09 -1.530596000000000068e+00 -2.647095999999999894e+00 3.983579999999999899e-01 -7.787739999999999663e-01 -2.621839999999999726e-01 -5.484820000000000251e-01 1.547179999999999944e-01 +1.403715307562139988e+09 -1.542365999999999904e+00 -2.666805000000000092e+00 3.860720000000000263e-01 -7.852749999999999453e-01 -2.494979999999999976e-01 -5.456940000000000124e-01 1.526830000000000132e-01 +1.403715307612139940e+09 -1.553981000000000057e+00 -2.685086999999999779e+00 3.739700000000000246e-01 -7.907380000000000519e-01 -2.374070000000000069e-01 -5.439410000000000078e-01 1.499989999999999934e-01 +1.403715307662139893e+09 -1.565290000000000070e+00 -2.703374000000000166e+00 3.622219999999999884e-01 -7.954879999999999729e-01 -2.257000000000000117e-01 -5.430249999999999799e-01 1.462249999999999939e-01 +1.403715307712140083e+09 -1.576297000000000059e+00 -2.720650000000000013e+00 3.497979999999999978e-01 -8.000340000000000229e-01 -2.148849999999999927e-01 -5.423529999999999740e-01 1.400869999999999893e-01 +1.403715307762140036e+09 -1.586770999999999932e+00 -2.737147999999999914e+00 3.372550000000000270e-01 -8.036410000000000498e-01 -2.045990000000000031e-01 -5.429040000000000532e-01 1.324950000000000017e-01 +1.403715307812139988e+09 -1.596846999999999905e+00 -2.753480000000000150e+00 3.243010000000000059e-01 -8.069690000000000474e-01 -1.943910000000000082e-01 -5.437469999999999803e-01 1.239029999999999992e-01 +1.403715307862139940e+09 -1.606155999999999917e+00 -2.768940999999999875e+00 3.112449999999999939e-01 -8.098090000000000011e-01 -1.841619999999999924e-01 -5.449800000000000200e-01 1.152839999999999976e-01 +1.403715307912139893e+09 -1.615312000000000081e+00 -2.783910999999999802e+00 2.983850000000000113e-01 -8.125529999999999697e-01 -1.744420000000000137e-01 -5.459540000000000504e-01 1.061219999999999941e-01 +1.403715307962140083e+09 -1.623129999999999962e+00 -2.797896999999999856e+00 2.854689999999999728e-01 -8.146459999999999813e-01 -1.647889999999999910e-01 -5.475370000000000514e-01 9.695199999999999652e-02 +1.403715308012140036e+09 -1.630366999999999900e+00 -2.810980999999999952e+00 2.729260000000000019e-01 -8.163200000000000456e-01 -1.547260000000000024e-01 -5.494689999999999852e-01 8.812499999999999500e-02 +1.403715308062139988e+09 -1.636503999999999959e+00 -2.822967999999999922e+00 2.603110000000000146e-01 -8.179729999999999501e-01 -1.445839999999999903e-01 -5.510450000000000070e-01 7.978000000000000369e-02 +1.403715308112139940e+09 -1.641890999999999989e+00 -2.833848000000000145e+00 2.480360000000000065e-01 -8.194209999999999550e-01 -1.345659999999999912e-01 -5.525360000000000271e-01 7.173599999999999421e-02 +1.403715308162139893e+09 -1.646498999999999935e+00 -2.843195000000000139e+00 2.363580000000000125e-01 -8.208290000000000308e-01 -1.255870000000000042e-01 -5.534729999999999928e-01 6.430600000000000205e-02 +1.403715308212140083e+09 -1.650128999999999957e+00 -2.851764000000000188e+00 2.245870000000000088e-01 -8.215510000000000312e-01 -1.175859999999999961e-01 -5.548739999999999783e-01 5.781200000000000228e-02 +1.403715308262140036e+09 -1.653189000000000020e+00 -2.859140000000000015e+00 2.122459999999999902e-01 -8.226750000000000451e-01 -1.093370000000000036e-01 -5.554789999999999450e-01 5.191400000000000181e-02 +1.403715308312139988e+09 -1.655540000000000012e+00 -2.865238999999999869e+00 1.996850000000000014e-01 -8.235029999999999850e-01 -1.017480000000000051e-01 -5.562559999999999727e-01 4.548599999999999866e-02 +1.403715308362139940e+09 -1.655780999999999947e+00 -2.868463999999999903e+00 1.870900000000000063e-01 -8.239349999999999730e-01 -9.395799999999999985e-02 -5.573580000000000201e-01 4.068200000000000288e-02 +1.403715308412139893e+09 -1.657111999999999918e+00 -2.872345999999999844e+00 1.746389999999999887e-01 -8.248379999999999601e-01 -8.663700000000000567e-02 -5.574379999999999891e-01 3.740399999999999975e-02 +1.403715308462140083e+09 -1.657580999999999971e+00 -2.875004000000000115e+00 1.620590000000000086e-01 -8.252979999999999761e-01 -7.998800000000000354e-02 -5.578530000000000433e-01 3.584400000000000086e-02 +1.403715308512140036e+09 -1.657199000000000089e+00 -2.876481000000000066e+00 1.501810000000000089e-01 -8.254709999999999548e-01 -7.381200000000000261e-02 -5.584289999999999532e-01 3.614699999999999858e-02 +1.403715308562139988e+09 -1.655664999999999942e+00 -2.876599000000000128e+00 1.400859999999999883e-01 -8.258919999999999595e-01 -6.848899999999999433e-02 -5.583850000000000202e-01 3.764699999999999991e-02 +1.403715308612139940e+09 -1.653583999999999943e+00 -2.877263999999999822e+00 1.328930000000000111e-01 -8.263390000000000457e-01 -6.427700000000000080e-02 -5.581030000000000157e-01 3.940400000000000152e-02 +1.403715308662139893e+09 -1.649847000000000063e+00 -2.876878000000000046e+00 1.284800000000000109e-01 -8.264590000000000547e-01 -6.150900000000000117e-02 -5.581500000000000350e-01 4.062299999999999939e-02 +1.403715308712140083e+09 -1.644911999999999930e+00 -2.876323000000000185e+00 1.266480000000000106e-01 -8.271410000000000151e-01 -5.910100000000000076e-02 -5.572880000000000056e-01 4.213800000000000184e-02 +1.403715308762140036e+09 -1.638795000000000002e+00 -2.875723999999999947e+00 1.279129999999999989e-01 -8.273500000000000298e-01 -5.789099999999999802e-02 -5.570330000000000004e-01 4.307699999999999724e-02 +1.403715308812139988e+09 -1.631524999999999892e+00 -2.875227999999999895e+00 1.313209999999999933e-01 -8.280549999999999855e-01 -5.753199999999999981e-02 -5.559809999999999475e-01 4.359199999999999880e-02 +1.403715308862139940e+09 -1.623083999999999971e+00 -2.874877999999999822e+00 1.362599999999999922e-01 -8.288919999999999622e-01 -5.673099999999999671e-02 -5.546830000000000371e-01 4.523200000000000137e-02 +1.403715308912139893e+09 -1.613653999999999922e+00 -2.874706000000000206e+00 1.412190000000000112e-01 -8.295879999999999921e-01 -5.614999999999999852e-02 -5.535060000000000535e-01 4.755000000000000199e-02 +1.403715308962140083e+09 -1.601452000000000098e+00 -2.875058999999999809e+00 1.469479999999999953e-01 -8.293289999999999829e-01 -5.599400000000000210e-02 -5.536870000000000402e-01 5.009500000000000064e-02 +1.403715309012140036e+09 -1.589328000000000074e+00 -2.875716999999999857e+00 1.520799999999999930e-01 -8.283399999999999652e-01 -5.621500000000000108e-02 -5.548450000000000326e-01 5.328900000000000303e-02 +1.403715309062139988e+09 -1.576740000000000030e+00 -2.876183000000000156e+00 1.569589999999999874e-01 -8.266520000000000534e-01 -5.605000000000000260e-02 -5.569549999999999779e-01 5.748700000000000337e-02 +1.403715309112139940e+09 -1.563436999999999966e+00 -2.877292999999999878e+00 1.614119999999999999e-01 -8.253779999999999450e-01 -5.590699999999999836e-02 -5.583599999999999675e-01 6.212899999999999673e-02 +1.403715309162139893e+09 -1.549180000000000001e+00 -2.879456999999999933e+00 1.648189999999999933e-01 -8.236419999999999852e-01 -5.665499999999999703e-02 -5.603709999999999525e-01 6.624700000000000033e-02 +1.403715309212140083e+09 -1.534467000000000025e+00 -2.882093999999999934e+00 1.695450000000000013e-01 -8.206299999999999706e-01 -5.658200000000000035e-02 -5.640969999999999596e-01 7.183699999999999808e-02 +1.403715309262140036e+09 -1.519271000000000038e+00 -2.885848999999999887e+00 1.746759999999999979e-01 -8.157689999999999664e-01 -5.655899999999999817e-02 -5.703730000000000189e-01 7.743600000000000483e-02 +1.403715309312139988e+09 -1.504175999999999958e+00 -2.891042999999999807e+00 1.795619999999999994e-01 -8.112080000000000402e-01 -5.792599999999999832e-02 -5.761439999999999895e-01 8.151500000000000412e-02 +1.403715309362139940e+09 -1.489446000000000048e+00 -2.897664999999999935e+00 1.835269999999999957e-01 -8.091819999999999569e-01 -6.184599999999999820e-02 -5.785550000000000415e-01 8.169899999999999385e-02 +1.403715309412139893e+09 -1.475311000000000039e+00 -2.905527999999999889e+00 1.869649999999999923e-01 -8.085869999999999447e-01 -6.747000000000000219e-02 -5.790659999999999696e-01 7.947700000000000597e-02 +1.403715309462140083e+09 -1.461816999999999922e+00 -2.914476000000000067e+00 1.903950000000000087e-01 -8.087750000000000217e-01 -7.328999999999999404e-02 -5.785310000000000175e-01 7.624699999999999533e-02 +1.403715309512140036e+09 -1.449006999999999934e+00 -2.924179999999999779e+00 1.940989999999999938e-01 -8.087349999999999817e-01 -7.873499999999999943e-02 -5.782329999999999970e-01 7.344499999999999640e-02 +1.403715309562139988e+09 -1.436905000000000099e+00 -2.934077999999999964e+00 1.974980000000000069e-01 -8.090450000000000141e-01 -8.343299999999999328e-02 -5.773979999999999668e-01 7.138799999999999313e-02 +1.403715309612139940e+09 -1.425307000000000102e+00 -2.944284999999999819e+00 2.015319999999999889e-01 -8.090039999999999454e-01 -8.703299999999999925e-02 -5.770699999999999719e-01 7.019699999999999551e-02 +1.403715309662139893e+09 -1.414328999999999947e+00 -2.954753000000000185e+00 2.054610000000000047e-01 -8.090019999999999989e-01 -9.010600000000000553e-02 -5.766350000000000087e-01 6.992199999999999804e-02 +1.403715309712140083e+09 -1.403998000000000079e+00 -2.965199000000000140e+00 2.089699999999999891e-01 -8.094400000000000484e-01 -9.188300000000000634e-02 -5.755909999999999638e-01 7.113200000000000078e-02 +1.403715309762140036e+09 -1.394366999999999912e+00 -2.975532999999999983e+00 2.117320000000000035e-01 -8.100319999999999743e-01 -9.300400000000000333e-02 -5.743479999999999697e-01 7.295699999999999408e-02 +1.403715309812139988e+09 -1.385469000000000062e+00 -2.986035999999999913e+00 2.152799999999999991e-01 -8.108360000000000012e-01 -9.325500000000000456e-02 -5.727200000000000069e-01 7.642000000000000182e-02 +1.403715309862139940e+09 -1.376786000000000065e+00 -2.996833000000000080e+00 2.186659999999999993e-01 -8.120370000000000088e-01 -9.150899999999999312e-02 -5.706069999999999753e-01 8.142199999999999438e-02 +1.403715309912139893e+09 -1.367871999999999977e+00 -3.007556999999999814e+00 2.211440000000000072e-01 -8.135080000000000089e-01 -8.931699999999999362e-02 -5.679750000000000076e-01 8.735600000000000309e-02 +1.403715309962140083e+09 -1.358983000000000052e+00 -3.019487999999999950e+00 2.232679999999999942e-01 -8.134620000000000184e-01 -8.725900000000000323e-02 -5.675499999999999989e-01 9.248299999999999577e-02 +1.403715310012140036e+09 -1.349647999999999959e+00 -3.032211999999999907e+00 2.249279999999999891e-01 -8.119210000000000038e-01 -8.566600000000000603e-02 -5.692789999999999795e-01 9.678699999999999803e-02 +1.403715310062139988e+09 -1.339679999999999982e+00 -3.045754000000000072e+00 2.265800000000000036e-01 -8.088269999999999627e-01 -8.369600000000000650e-02 -5.734920000000000018e-01 9.950799999999999923e-02 +1.403715310112139940e+09 -1.329747000000000012e+00 -3.060859999999999914e+00 2.279269999999999907e-01 -8.055259999999999643e-01 -8.142199999999999438e-02 -5.783749999999999725e-01 9.990599999999999481e-02 +1.403715310162139893e+09 -1.320211000000000023e+00 -3.077293000000000056e+00 2.292649999999999966e-01 -8.022110000000000074e-01 -7.895900000000000141e-02 -5.836240000000000316e-01 9.800999999999999990e-02 +1.403715310212140083e+09 -1.311393000000000031e+00 -3.096009000000000011e+00 2.308300000000000074e-01 -7.998549999999999827e-01 -7.690299999999999914e-02 -5.879090000000000149e-01 9.317599999999999494e-02 +1.403715310262140036e+09 -1.303501999999999938e+00 -3.116222000000000047e+00 2.325669999999999960e-01 -7.981329999999999814e-01 -7.561700000000000366e-02 -5.916329999999999645e-01 8.507000000000000672e-02 +1.403715310312139988e+09 -1.297134999999999927e+00 -3.137847999999999971e+00 2.345730000000000037e-01 -7.968979999999999952e-01 -7.455799999999999927e-02 -5.948010000000000241e-01 7.486900000000000499e-02 +1.403715310362139940e+09 -1.292221999999999982e+00 -3.160193000000000030e+00 2.365750000000000075e-01 -7.964799999999999658e-01 -7.155200000000000449e-02 -5.968170000000000419e-01 6.564899999999999902e-02 +1.403715310412139893e+09 -1.289258999999999933e+00 -3.182558000000000220e+00 2.392410000000000092e-01 -7.970199999999999507e-01 -6.713199999999999723e-02 -5.975270000000000303e-01 5.669500000000000234e-02 +1.403715310462140083e+09 -1.288091000000000097e+00 -3.205198000000000214e+00 2.418319999999999914e-01 -7.983179999999999721e-01 -6.128999999999999726e-02 -5.971340000000000536e-01 4.861200000000000243e-02 +1.403715310512140036e+09 -1.288756999999999930e+00 -3.227809000000000150e+00 2.441909999999999914e-01 -8.010890000000000510e-01 -5.579499999999999738e-02 -5.945030000000000037e-01 4.134800000000000281e-02 +1.403715310562139988e+09 -1.290168999999999899e+00 -3.249931000000000125e+00 2.464290000000000092e-01 -8.046010000000000106e-01 -5.058300000000000296e-02 -5.906120000000000259e-01 3.515499999999999875e-02 +1.403715310612139940e+09 -1.292756999999999934e+00 -3.271669000000000160e+00 2.489220000000000044e-01 -8.085919999999999774e-01 -4.607499999999999790e-02 -5.858130000000000281e-01 2.965699999999999933e-02 +1.403715310712140083e+09 -1.299679999999999946e+00 -3.312838999999999867e+00 2.540299999999999780e-01 -8.158199999999999896e-01 -3.844999999999999807e-02 -5.766289999999999472e-01 2.139299999999999882e-02 +1.403715310762140036e+09 -1.303817999999999921e+00 -3.332548000000000066e+00 2.563389999999999835e-01 -8.183190000000000186e-01 -3.534299999999999942e-02 -5.733740000000000503e-01 1.863799999999999832e-02 +1.403715310812139988e+09 -1.307847999999999900e+00 -3.351388000000000034e+00 2.585759999999999725e-01 -8.199159999999999782e-01 -3.247900000000000093e-02 -5.713049999999999518e-01 1.713900000000000146e-02 +1.403715310862139940e+09 -1.311452000000000062e+00 -3.369918000000000191e+00 2.606789999999999941e-01 -8.205980000000000496e-01 -2.983099999999999988e-02 -5.705019999999999536e-01 1.600199999999999886e-02 +1.403715310912139893e+09 -1.315012000000000070e+00 -3.387782000000000071e+00 2.625990000000000268e-01 -8.208530000000000548e-01 -2.756099999999999869e-02 -5.702720000000000011e-01 1.518500000000000058e-02 +1.403715310962140083e+09 -1.318405999999999967e+00 -3.404878000000000071e+00 2.646990000000000176e-01 -8.216219999999999635e-01 -2.474700000000000163e-02 -5.692930000000000490e-01 1.519900000000000070e-02 +1.403715311012140036e+09 -1.321787999999999963e+00 -3.421609999999999818e+00 2.659560000000000257e-01 -8.228440000000000198e-01 -2.130900000000000155e-02 -5.676290000000000502e-01 1.649600000000000025e-02 +1.403715311062139988e+09 -1.325466999999999951e+00 -3.437679000000000151e+00 2.660529999999999839e-01 -8.241680000000000117e-01 -1.690499999999999989e-02 -5.657699999999999951e-01 1.911500000000000005e-02 +1.403715311112139940e+09 -1.327599999999999891e+00 -3.453892999999999880e+00 2.666499999999999981e-01 -8.253169999999999673e-01 -1.370999999999999996e-02 -5.641199999999999548e-01 2.078999999999999945e-02 +1.403715311162139893e+09 -1.328977999999999993e+00 -3.469937999999999967e+00 2.663320000000000132e-01 -8.260560000000000125e-01 -1.054800000000000008e-02 -5.630300000000000304e-01 2.274299999999999933e-02 +1.403715311212140083e+09 -1.329371000000000080e+00 -3.486206000000000138e+00 2.666549999999999754e-01 -8.263139999999999930e-01 -6.956000000000000377e-03 -5.625900000000000345e-01 2.545700000000000046e-02 +1.403715311262140036e+09 -1.329088000000000047e+00 -3.503257000000000065e+00 2.660170000000000035e-01 -8.267489999999999561e-01 -4.788999999999999854e-03 -5.619229999999999503e-01 2.655700000000000074e-02 +1.403715311312139988e+09 -1.327565000000000106e+00 -3.520503000000000160e+00 2.662479999999999847e-01 -8.272159999999999513e-01 -2.340000000000000066e-03 -5.611540000000000417e-01 2.852000000000000021e-02 +1.403715311362139940e+09 -1.325126999999999944e+00 -3.538472000000000062e+00 2.667519999999999891e-01 -8.280340000000000478e-01 -6.009999999999999717e-04 -5.598990000000000355e-01 2.954000000000000029e-02 +1.403715311412139893e+09 -1.321385000000000032e+00 -3.557247999999999966e+00 2.682240000000000180e-01 -8.286599999999999522e-01 -6.329999999999999906e-04 -5.590540000000000509e-01 2.794100000000000056e-02 +1.403715311462140083e+09 -1.316600999999999910e+00 -3.576804000000000094e+00 2.700770000000000115e-01 -8.291849999999999499e-01 -2.311999999999999819e-03 -5.584390000000000187e-01 2.434000000000000052e-02 +1.403715311512140036e+09 -1.311131000000000046e+00 -3.597255999999999787e+00 2.721040000000000125e-01 -8.295249999999999568e-01 -4.606999999999999984e-03 -5.581159999999999455e-01 1.930799999999999877e-02 +1.403715311562139988e+09 -1.304818000000000033e+00 -3.619085000000000107e+00 2.743120000000000003e-01 -8.293329999999999869e-01 -6.361000000000000335e-03 -5.585059999999999469e-01 1.541700000000000015e-02 +1.403715311612139940e+09 -1.297341999999999995e+00 -3.639784999999999826e+00 2.769590000000000107e-01 -8.287839999999999652e-01 -7.460999999999999750e-03 -5.593770000000000131e-01 1.257400000000000011e-02 +1.403715311662139893e+09 -1.289120999999999961e+00 -3.660499999999999865e+00 2.796060000000000212e-01 -8.284449999999999870e-01 -8.167000000000000648e-03 -5.599210000000000020e-01 1.000599999999999927e-02 +1.403715311712140083e+09 -1.280003999999999920e+00 -3.680988000000000149e+00 2.820480000000000209e-01 -8.279720000000000413e-01 -7.073000000000000294e-03 -5.606330000000000480e-01 1.014499999999999950e-02 +1.403715311762140036e+09 -1.269970999999999961e+00 -3.701579999999999870e+00 2.845799999999999996e-01 -8.275510000000000366e-01 -5.800999999999999733e-03 -5.612580000000000346e-01 1.070199999999999971e-02 +1.403715311812139988e+09 -1.258984000000000103e+00 -3.722052000000000138e+00 2.870820000000000038e-01 -8.271669999999999856e-01 -3.836000000000000000e-03 -5.618260000000000476e-01 1.142800000000000066e-02 +1.403715311862139940e+09 -1.247249999999999970e+00 -3.742601000000000067e+00 2.896889999999999743e-01 -8.266200000000000214e-01 -6.080000000000000335e-04 -5.626029999999999642e-01 1.331199999999999918e-02 +1.403715311912139893e+09 -1.234755000000000047e+00 -3.763069000000000219e+00 2.923790000000000000e-01 -8.257569999999999633e-01 1.286999999999999950e-03 -5.638689999999999536e-01 1.324099999999999930e-02 +1.403715311962140083e+09 -1.221661000000000108e+00 -3.783783999999999814e+00 2.948029999999999817e-01 -8.256430000000000158e-01 2.160000000000000028e-03 -5.640770000000000506e-01 1.122199999999999934e-02 +1.403715312012140036e+09 -1.207527000000000017e+00 -3.804647000000000112e+00 2.970220000000000082e-01 -8.257520000000000415e-01 1.894999999999999983e-03 -5.639790000000000081e-01 7.596999999999999587e-03 +1.403715312062139988e+09 -1.192768999999999968e+00 -3.825562000000000129e+00 2.990869999999999918e-01 -8.259619999999999740e-01 1.211999999999999970e-03 -5.637140000000000484e-01 3.500000000000000073e-03 +1.403715312112139940e+09 -1.177672000000000052e+00 -3.846413000000000082e+00 3.013159999999999727e-01 -8.253390000000000448e-01 1.347000000000000107e-03 -5.646360000000000268e-01 6.509999999999999945e-04 +1.403715312162139893e+09 -1.161923999999999957e+00 -3.867468999999999824e+00 3.040379999999999749e-01 8.248739999999999961e-01 -1.191000000000000001e-03 5.653099999999999792e-01 2.462999999999999912e-03 +1.403715312212140083e+09 -1.146114000000000077e+00 -3.887522999999999840e+00 3.066130000000000244e-01 8.247330000000000494e-01 -1.587000000000000086e-03 5.655010000000000314e-01 4.688000000000000327e-03 +1.403715312262140036e+09 -1.130352999999999941e+00 -3.907081999999999944e+00 3.094480000000000008e-01 8.247419999999999751e-01 -2.759999999999999867e-03 5.654719999999999747e-01 5.890000000000000270e-03 +1.403715312312139988e+09 -1.113987000000000060e+00 -3.926260999999999779e+00 3.119080000000000186e-01 8.245460000000000012e-01 -5.099000000000000234e-03 5.657489999999999464e-01 5.075999999999999783e-03 +1.403715312362139940e+09 -1.097423000000000037e+00 -3.945103000000000026e+00 3.144449999999999745e-01 8.247459999999999791e-01 -7.621000000000000170e-03 5.654390000000000249e-01 3.872000000000000008e-03 +1.403715312412139893e+09 -1.080252999999999908e+00 -3.964170999999999889e+00 3.167189999999999728e-01 8.245090000000000474e-01 -9.920999999999999264e-03 5.657560000000000366e-01 2.693000000000000081e-03 +1.403715312462140083e+09 -1.063328999999999969e+00 -3.982822000000000084e+00 3.194449999999999790e-01 8.239819999999999922e-01 -1.226600000000000086e-02 5.664820000000000411e-01 1.381999999999999982e-03 +1.403715312512140036e+09 -1.045309000000000044e+00 -4.001298000000000243e+00 3.207220000000000071e-01 8.227029999999999621e-01 -1.369100000000000004e-02 5.683070000000000066e-01 3.800000000000000209e-04 +1.403715312562139988e+09 -1.027053999999999911e+00 -4.019916000000000267e+00 3.213509999999999978e-01 8.218349999999999822e-01 -1.345799999999999948e-02 5.695649999999999880e-01 1.356999999999999916e-03 +1.403715312612139940e+09 -1.008780000000000010e+00 -4.038636999999999588e+00 3.217539999999999845e-01 8.199739999999999807e-01 -1.215499999999999914e-02 5.722629999999999661e-01 3.245000000000000055e-03 +1.403715312662139893e+09 -9.904619999999999536e-01 -4.057483999999999646e+00 3.216229999999999922e-01 8.174649999999999972e-01 -9.934000000000000122e-03 5.758640000000000425e-01 5.710999999999999931e-03 +1.403715312712140083e+09 -9.725289999999999768e-01 -4.075968999999999731e+00 3.208179999999999921e-01 8.148499999999999632e-01 -8.019000000000000086e-03 5.795700000000000296e-01 7.289999999999999605e-03 +1.403715312762140036e+09 -9.547590000000000243e-01 -4.093996999999999886e+00 3.189690000000000025e-01 8.128260000000000485e-01 -5.224000000000000345e-03 5.824089999999999545e-01 9.338000000000000814e-03 +1.403715312812139988e+09 -9.373500000000000165e-01 -4.111341999999999608e+00 3.166840000000000210e-01 8.111049999999999649e-01 -1.417000000000000074e-03 5.847780000000000200e-01 1.190699999999999918e-02 +1.403715312862139940e+09 -9.206969999999999876e-01 -4.127951000000000370e+00 3.149419999999999997e-01 8.081949999999999967e-01 2.412000000000000081e-03 5.887590000000000323e-01 1.329699999999999979e-02 +1.403715312912139893e+09 -9.053280000000000216e-01 -4.143538000000000388e+00 3.144179999999999753e-01 8.053780000000000383e-01 5.863000000000000156e-03 5.925780000000000491e-01 1.353200000000000063e-02 +1.403715312962140083e+09 -8.911639999999999562e-01 -4.158102000000000409e+00 3.164680000000000271e-01 8.029220000000000246e-01 9.482000000000000844e-03 5.958539999999999948e-01 1.356500000000000067e-02 +1.403715313012140036e+09 -8.789339999999999931e-01 -4.170822000000000251e+00 3.212200000000000055e-01 8.011679999999999913e-01 1.269799999999999922e-02 5.981589999999999963e-01 1.319900000000000066e-02 +1.403715313062139988e+09 -8.681440000000000268e-01 -4.182205999999999868e+00 3.284210000000000185e-01 8.005189999999999806e-01 1.605699999999999836e-02 5.989480000000000359e-01 1.313800000000000037e-02 +1.403715313112139940e+09 -8.597609999999999975e-01 -4.192782000000000231e+00 3.374710000000000210e-01 8.010209999999999830e-01 1.924000000000000016e-02 5.981849999999999667e-01 1.302299999999999985e-02 +1.403715313162139893e+09 -8.528010000000000312e-01 -4.202271999999999785e+00 3.486639999999999739e-01 8.012040000000000273e-01 2.160400000000000167e-02 5.978820000000000245e-01 1.194699999999999929e-02 +1.403715313212140083e+09 -8.470509999999999984e-01 -4.209914000000000378e+00 3.601579999999999782e-01 8.020460000000000367e-01 2.234799999999999981e-02 5.967759999999999732e-01 8.963999999999999746e-03 +1.403715313262140036e+09 -8.428259999999999641e-01 -4.216339999999999755e+00 3.710370000000000057e-01 8.037630000000000052e-01 2.234399999999999928e-02 5.945070000000000077e-01 5.139999999999999604e-03 +1.403715313312139988e+09 -8.406369999999999676e-01 -4.221932999999999936e+00 3.808409999999999851e-01 8.058340000000000503e-01 2.214299999999999949e-02 5.917259999999999742e-01 1.399000000000000070e-03 +1.403715313362139940e+09 -8.388870000000000493e-01 -4.226886999999999617e+00 3.899889999999999746e-01 -8.081810000000000382e-01 -2.200300000000000172e-02 -5.885209999999999608e-01 1.368000000000000075e-03 +1.403715313412139893e+09 -8.380450000000000399e-01 -4.231287000000000020e+00 3.988900000000000223e-01 -8.106309999999999905e-01 -2.222599999999999923e-02 -5.851269999999999527e-01 3.018999999999999982e-03 +1.403715313462140083e+09 -8.379590000000000094e-01 -4.235473999999999961e+00 4.072649999999999881e-01 -8.125679999999999570e-01 -2.092000000000000109e-02 -5.824770000000000225e-01 4.010999999999999809e-03 +1.403715313512140036e+09 -8.386130000000000528e-01 -4.239677999999999614e+00 4.162239999999999829e-01 -8.135080000000000089e-01 -1.930199999999999971e-02 -5.812289999999999957e-01 2.343000000000000031e-03 +1.403715313562139988e+09 -8.397179999999999644e-01 -4.243624999999999758e+00 4.252179999999999849e-01 8.145280000000000298e-01 1.683000000000000121e-02 5.798799999999999510e-01 2.159999999999999919e-04 +1.403715313612139940e+09 -8.410170000000000146e-01 -4.246770999999999852e+00 4.344410000000000216e-01 8.155810000000000004e-01 1.496199999999999961e-02 5.784329999999999750e-01 4.435999999999999839e-03 +1.403715313662139893e+09 -8.425650000000000084e-01 -4.249128999999999934e+00 4.437329999999999885e-01 8.159560000000000146e-01 1.334300000000000069e-02 5.778950000000000475e-01 8.718000000000000055e-03 +1.403715313712140083e+09 -8.451539999999999608e-01 -4.250581000000000387e+00 4.532399999999999762e-01 8.160640000000000116e-01 1.169899999999999933e-02 5.777179999999999538e-01 1.200599999999999931e-02 +1.403715313762140036e+09 -8.476559999999999651e-01 -4.251803999999999917e+00 4.634179999999999966e-01 8.165280000000000316e-01 9.138000000000000289e-03 5.770800000000000374e-01 1.333299999999999937e-02 +1.403715313812139988e+09 -8.504150000000000320e-01 -4.251827999999999719e+00 4.739510000000000112e-01 8.165320000000000356e-01 6.758000000000000118e-03 5.770809999999999551e-01 1.442099999999999979e-02 +1.403715313862139940e+09 -8.532859999999999889e-01 -4.251089000000000340e+00 4.844629999999999770e-01 8.166579999999999950e-01 4.575000000000000074e-03 5.768929999999999891e-01 1.557799999999999983e-02 +1.403715313912139893e+09 -8.557390000000000274e-01 -4.249276000000000053e+00 4.949790000000000023e-01 8.165590000000000348e-01 1.758000000000000014e-03 5.770710000000000006e-01 1.475899999999999955e-02 +1.403715313962140083e+09 -8.589189999999999880e-01 -4.246968999999999994e+00 5.045629999999999837e-01 8.163209999999999633e-01 -1.570999999999999914e-03 5.774620000000000308e-01 1.242099999999999975e-02 +1.403715314012140036e+09 -8.623480000000000034e-01 -4.244290000000000340e+00 5.126319999999999766e-01 8.169459999999999500e-01 -4.977999999999999786e-03 5.765799999999999814e-01 1.144200000000000078e-02 +1.403715314062139988e+09 -8.662379999999999525e-01 -4.241703000000000223e+00 5.197869999999999990e-01 8.177050000000000152e-01 -8.137000000000000136e-03 5.754139999999999810e-01 1.381499999999999916e-02 +1.403715314112139940e+09 -8.705990000000000117e-01 -4.239260999999999946e+00 5.258460000000000356e-01 8.182770000000000321e-01 -1.182300000000000018e-02 5.743589999999999529e-01 1.987699999999999884e-02 +1.403715314162139893e+09 -8.749310000000000143e-01 -4.236971999999999738e+00 5.314670000000000227e-01 8.185210000000000541e-01 -1.778300000000000020e-02 5.735580000000000123e-01 2.718100000000000030e-02 +1.403715314212140083e+09 -8.794009999999999883e-01 -4.234496000000000038e+00 5.359169999999999767e-01 8.192610000000000170e-01 -2.457499999999999962e-02 5.717579999999999885e-01 3.606399999999999884e-02 +1.403715314262140036e+09 -8.836929999999999508e-01 -4.231359000000000314e+00 5.401709999999999567e-01 8.191049999999999720e-01 -3.238200000000000106e-02 5.709520000000000151e-01 4.508000000000000201e-02 +1.403715314312139988e+09 -8.871879999999999766e-01 -4.226663000000000281e+00 5.433489999999999709e-01 8.198199999999999932e-01 -4.137400000000000105e-02 5.686309999999999976e-01 5.331000000000000322e-02 +1.403715314362139940e+09 -8.909310000000000285e-01 -4.221905999999999715e+00 5.467309999999999670e-01 8.198630000000000084e-01 -5.046500000000000291e-02 5.670250000000000012e-01 6.133399999999999963e-02 +1.403715314412139893e+09 -8.943170000000000286e-01 -4.215906000000000375e+00 5.491679999999999895e-01 8.195310000000000095e-01 -5.997600000000000153e-02 5.659570000000000434e-01 6.682200000000000639e-02 +1.403715314462140083e+09 -8.972250000000000503e-01 -4.208872999999999642e+00 5.506339999999999568e-01 8.198819999999999997e-01 -6.790499999999999314e-02 5.638919999999999488e-01 7.216699999999999504e-02 +1.403715314512140036e+09 -8.990240000000000453e-01 -4.200553000000000203e+00 5.522989999999999844e-01 8.196120000000000072e-01 -7.542999999999999705e-02 5.628360000000000030e-01 7.591299999999999437e-02 +1.403715314562139988e+09 -9.002240000000000242e-01 -4.191308000000000256e+00 5.534660000000000135e-01 8.197250000000000369e-01 -8.313500000000000056e-02 5.613829999999999654e-01 7.738100000000000533e-02 +1.403715314612139940e+09 -9.009139999999999926e-01 -4.181377999999999595e+00 5.537410000000000387e-01 8.191730000000000400e-01 -8.992400000000000393e-02 5.610429999999999584e-01 7.810300000000000575e-02 +1.403715314662139893e+09 -9.013719999999999510e-01 -4.170532999999999824e+00 5.541709999999999692e-01 8.182679999999999954e-01 -9.505600000000000160e-02 5.613369999999999749e-01 7.939200000000000423e-02 +1.403715314712140083e+09 -9.019279999999999520e-01 -4.159296000000000326e+00 5.540599999999999969e-01 8.176839999999999664e-01 -9.901600000000000679e-02 5.613230000000000164e-01 8.065899999999999459e-02 +1.403715314762140036e+09 -9.023560000000000469e-01 -4.147317000000000142e+00 5.531319999999999570e-01 8.169130000000000003e-01 -1.017210000000000059e-01 5.616879999999999651e-01 8.253499999999999726e-02 +1.403715314812139988e+09 -9.012639999999999540e-01 -4.134749000000000230e+00 5.531110000000000193e-01 8.154200000000000337e-01 -1.036330000000000029e-01 5.632800000000000029e-01 8.405700000000000671e-02 +1.403715314862139940e+09 -8.995670000000000055e-01 -4.121804000000000023e+00 5.529439999999999911e-01 8.148090000000000055e-01 -1.044280000000000069e-01 5.636740000000000084e-01 8.633200000000000596e-02 +1.403715314912139893e+09 -8.976180000000000270e-01 -4.108226000000000155e+00 5.525799999999999601e-01 8.141260000000000163e-01 -1.054589999999999972e-01 5.643120000000000358e-01 8.735099999999999809e-02 +1.403715314962140083e+09 -8.953619999999999912e-01 -4.094104999999999883e+00 5.523109999999999964e-01 8.133749999999999591e-01 -1.065839999999999982e-01 5.652160000000000517e-01 8.713100000000000012e-02 +1.403715315012140036e+09 -8.922799999999999621e-01 -4.079188000000000258e+00 5.519659999999999567e-01 8.126870000000000482e-01 -1.075389999999999957e-01 5.661899999999999711e-01 8.605000000000000149e-02 +1.403715315062139988e+09 -8.883560000000000345e-01 -4.063767000000000351e+00 5.514099999999999557e-01 8.110380000000000367e-01 -1.089999999999999997e-01 5.685510000000000286e-01 8.418299999999999395e-02 +1.403715315112139940e+09 -8.844480000000000119e-01 -4.047966999999999871e+00 5.505529999999999591e-01 8.104959999999999942e-01 -1.094180000000000014e-01 5.693730000000000180e-01 8.329999999999999905e-02 +1.403715315162139893e+09 -8.806990000000000096e-01 -4.031971999999999667e+00 5.496769999999999712e-01 8.107860000000000067e-01 -1.100129999999999997e-01 5.690199999999999703e-01 8.209700000000000331e-02 +1.403715315212140083e+09 -8.769789999999999530e-01 -4.015934999999999810e+00 5.490960000000000285e-01 8.112070000000000114e-01 -1.102039999999999964e-01 5.685369999999999591e-01 8.102299999999999780e-02 +1.403715315262140036e+09 -8.734089999999999909e-01 -3.999760999999999900e+00 5.490439999999999765e-01 8.113070000000000004e-01 -1.105180000000000051e-01 5.683580000000000298e-01 8.084600000000000120e-02 +1.403715315312139988e+09 -8.701569999999999583e-01 -3.983785999999999827e+00 5.492129999999999512e-01 8.113510000000000444e-01 -1.121219999999999994e-01 5.678410000000000402e-01 8.181800000000000184e-02 +1.403715315362139940e+09 -8.673349999999999671e-01 -3.967816000000000010e+00 5.503219999999999779e-01 8.107269999999999754e-01 -1.149320000000000064e-01 5.678220000000000489e-01 8.420900000000000607e-02 +1.403715315412139893e+09 -8.644870000000000054e-01 -3.951769000000000087e+00 5.510220000000000118e-01 8.101300000000000168e-01 -1.193629999999999969e-01 5.674339999999999939e-01 8.636900000000000133e-02 +1.403715315462140083e+09 -8.619259999999999700e-01 -3.935562000000000005e+00 5.518840000000000412e-01 8.092939999999999579e-01 -1.250819999999999987e-01 5.669939999999999980e-01 8.897099999999999453e-02 +1.403715315512140036e+09 -8.597869999999999679e-01 -3.919414000000000176e+00 5.531880000000000130e-01 8.080610000000000293e-01 -1.313900000000000068e-01 5.668539999999999690e-01 9.192599999999999383e-02 +1.403715315562139988e+09 -8.576110000000000122e-01 -3.903397000000000006e+00 5.545379999999999754e-01 8.066229999999999789e-01 -1.378530000000000033e-01 5.668950000000000378e-01 9.479500000000000426e-02 +1.403715315612139940e+09 -8.563520000000000021e-01 -3.887361999999999984e+00 5.559009999999999785e-01 8.052059999999999773e-01 -1.446890000000000120e-01 5.666520000000000445e-01 9.805700000000000527e-02 +1.403715315662139893e+09 -8.560759999999999481e-01 -3.871490999999999794e+00 5.572070000000000078e-01 8.033580000000000165e-01 -1.519490000000000007e-01 5.667020000000000390e-01 1.018649999999999972e-01 +1.403715315712140083e+09 -8.551389999999999825e-01 -3.856180999999999859e+00 5.580640000000000045e-01 8.006940000000000168e-01 -1.618010000000000004e-01 5.675320000000000364e-01 1.030360000000000026e-01 +1.403715315762140036e+09 -8.547150000000000025e-01 -3.841056000000000026e+00 5.591209999999999791e-01 7.979829999999999979e-01 -1.727210000000000134e-01 5.680309999999999526e-01 1.035969999999999946e-01 +1.403715315812139988e+09 -8.548789999999999445e-01 -3.826706000000000163e+00 5.595299999999999718e-01 7.955649999999999666e-01 -1.838869999999999949e-01 5.677119999999999944e-01 1.047130000000000005e-01 +1.403715315862139940e+09 -8.554070000000000285e-01 -3.813651000000000124e+00 5.596780000000000088e-01 7.934470000000000134e-01 -1.942260000000000097e-01 5.666069999999999718e-01 1.080529999999999963e-01 +1.403715315912139893e+09 -8.567150000000000043e-01 -3.801452999999999971e+00 5.595170000000000421e-01 7.917729999999999491e-01 -2.034910000000000052e-01 5.646379999999999733e-01 1.134519999999999973e-01 +1.403715315962140083e+09 -8.593349999999999600e-01 -3.789969999999999839e+00 5.587940000000000129e-01 7.896450000000000413e-01 -2.119649999999999868e-01 5.630330000000000057e-01 1.205269999999999953e-01 +1.403715316012140036e+09 -8.620889999999999942e-01 -3.779449000000000058e+00 5.575419999999999821e-01 7.880580000000000362e-01 -2.205280000000000018e-01 5.603550000000000475e-01 1.278070000000000039e-01 +1.403715316062139988e+09 -8.655939999999999745e-01 -3.769887999999999906e+00 5.557739999999999903e-01 7.862029999999999852e-01 -2.279329999999999967e-01 5.578640000000000265e-01 1.368219999999999992e-01 +1.403715316112139940e+09 -8.692199999999999926e-01 -3.761197000000000124e+00 5.532299999999999995e-01 7.847140000000000226e-01 -2.349219999999999919e-01 5.545480000000000409e-01 1.466679999999999928e-01 +1.403715316162139893e+09 -8.732499999999999707e-01 -3.753308999999999784e+00 5.494609999999999772e-01 7.833769999999999900e-01 -2.419540000000000024e-01 5.505980000000000318e-01 1.569059999999999899e-01 +1.403715316212140083e+09 -8.775840000000000307e-01 -3.745912999999999826e+00 5.447009999999999907e-01 7.823689999999999811e-01 -2.491780000000000106e-01 5.457929999999999726e-01 1.670870000000000133e-01 +1.403715316262140036e+09 -8.833870000000000333e-01 -3.738811000000000107e+00 5.393520000000000536e-01 7.826319999999999943e-01 -2.565089999999999870e-01 5.385379999999999612e-01 1.779530000000000001e-01 +1.403715316312139988e+09 -8.877460000000000351e-01 -3.732083999999999957e+00 5.335999999999999632e-01 7.830359999999999543e-01 -2.649349999999999761e-01 5.304940000000000211e-01 1.877240000000000020e-01 +1.403715316362139940e+09 -8.914410000000000389e-01 -3.725048999999999833e+00 5.266250000000000098e-01 7.844259999999999566e-01 -2.723740000000000050e-01 5.212219999999999631e-01 1.970159999999999967e-01 +1.403715316412139893e+09 -8.941029999999999811e-01 -3.717639999999999834e+00 5.194579999999999753e-01 7.854689999999999728e-01 -2.791440000000000032e-01 5.129240000000000466e-01 2.050019999999999898e-01 +1.403715316462140083e+09 -8.949030000000000040e-01 -3.709747000000000128e+00 5.126220000000000221e-01 7.852219999999999756e-01 -2.852770000000000028e-01 5.071639999999999482e-01 2.117259999999999975e-01 +1.403715316512140036e+09 -8.933710000000000262e-01 -3.701538000000000217e+00 5.057509999999999506e-01 7.837950000000000195e-01 -2.913740000000000219e-01 5.041579999999999950e-01 2.158499999999999863e-01 +1.403715316562139988e+09 -8.908310000000000395e-01 -3.692763999999999935e+00 4.995430000000000148e-01 7.811620000000000230e-01 -2.966610000000000080e-01 5.035220000000000251e-01 2.196450000000000069e-01 +1.403715316612139940e+09 -8.854929999999999746e-01 -3.684585000000000221e+00 4.920970000000000066e-01 7.777889999999999526e-01 -3.016599999999999837e-01 5.047840000000000105e-01 2.218970000000000109e-01 +1.403715316662139893e+09 -8.784140000000000281e-01 -3.676381999999999817e+00 4.844600000000000017e-01 7.738070000000000226e-01 -3.054279999999999773e-01 5.075749999999999984e-01 2.242850000000000121e-01 +1.403715316712140083e+09 -8.698169999999999513e-01 -3.668489999999999807e+00 4.757149999999999990e-01 7.696579999999999533e-01 -3.098310000000000231e-01 5.103769999999999696e-01 2.261569999999999969e-01 +1.403715316762140036e+09 -8.602469999999999839e-01 -3.660458000000000212e+00 4.667060000000000097e-01 7.655239999999999823e-01 -3.144159999999999733e-01 5.125549999999999828e-01 2.289170000000000094e-01 +1.403715316812139988e+09 -8.499010000000000176e-01 -3.652696000000000165e+00 4.569869999999999766e-01 7.616709999999999869e-01 -3.192909999999999915e-01 5.137890000000000512e-01 2.322299999999999920e-01 +1.403715316862139940e+09 -8.382669999999999844e-01 -3.645081999999999933e+00 4.468150000000000177e-01 7.575349999999999584e-01 -3.250029999999999863e-01 5.144109999999999516e-01 2.364209999999999923e-01 +1.403715316912139893e+09 -8.265240000000000364e-01 -3.637774999999999981e+00 4.358600000000000252e-01 7.528629999999999489e-01 -3.318349999999999911e-01 5.148880000000000123e-01 2.407759999999999900e-01 +1.403715316962140083e+09 -8.144130000000000535e-01 -3.630396999999999874e+00 4.254629999999999801e-01 7.475260000000000238e-01 -3.385270000000000223e-01 5.151759999999999673e-01 2.473829999999999918e-01 +1.403715317012140036e+09 -8.024879999999999791e-01 -3.622783000000000087e+00 4.151239999999999930e-01 7.409289999999999488e-01 -3.466029999999999944e-01 5.162600000000000522e-01 2.537039999999999851e-01 +1.403715317062139988e+09 -7.902970000000000272e-01 -3.614129999999999843e+00 4.044989999999999974e-01 7.352670000000000039e-01 -3.563089999999999868e-01 5.151890000000000081e-01 2.588559999999999750e-01 +1.403715317112139940e+09 -7.783430000000000071e-01 -3.605090000000000128e+00 3.940000000000000169e-01 7.305000000000000382e-01 -3.666920000000000179e-01 5.118589999999999529e-01 2.643989999999999951e-01 +1.403715317162139893e+09 -7.660190000000000055e-01 -3.596220000000000194e+00 3.832880000000000176e-01 7.260309999999999819e-01 -3.777190000000000270e-01 5.072510000000000074e-01 2.700080000000000258e-01 +1.403715317212140083e+09 -7.540810000000000013e-01 -3.586605000000000043e+00 3.736380000000000257e-01 7.214380000000000237e-01 -3.889159999999999839e-01 5.020559999999999468e-01 2.760630000000000028e-01 +1.403715317262140036e+09 -7.420299999999999674e-01 -3.576858000000000093e+00 3.646559999999999802e-01 7.166690000000000005e-01 -3.991689999999999960e-01 4.966360000000000219e-01 2.835539999999999727e-01 +1.403715317312139988e+09 -7.298540000000000028e-01 -3.567074999999999996e+00 3.557980000000000032e-01 7.112140000000000128e-01 -4.098550000000000249e-01 4.915180000000000105e-01 2.908680000000000154e-01 +1.403715317362139940e+09 -7.175259999999999971e-01 -3.556842000000000059e+00 3.472290000000000099e-01 7.049830000000000263e-01 -4.214559999999999973e-01 4.868930000000000202e-01 2.971690000000000165e-01 +1.403715317412139893e+09 -7.050600000000000200e-01 -3.546444000000000152e+00 3.392089999999999828e-01 6.976290000000000546e-01 -4.336059999999999914e-01 4.834060000000000024e-01 3.026840000000000086e-01 +1.403715317462140083e+09 -6.916369999999999463e-01 -3.536807000000000034e+00 3.314500000000000224e-01 6.907440000000000246e-01 -4.453329999999999789e-01 4.792040000000000188e-01 3.080820000000000225e-01 +1.403715317562139988e+09 -6.658619999999999539e-01 -3.516875000000000195e+00 3.169069999999999943e-01 6.764270000000000005e-01 -4.664619999999999878e-01 4.712109999999999910e-01 3.206559999999999966e-01 +1.403715317612139940e+09 -6.529399999999999649e-01 -3.508284000000000180e+00 3.099410000000000220e-01 6.690249999999999808e-01 -4.764669999999999739e-01 4.675250000000000239e-01 3.268099999999999894e-01 +1.403715317662139893e+09 -6.399510000000000476e-01 -3.499884000000000217e+00 3.031960000000000210e-01 6.611040000000000250e-01 -4.867259999999999920e-01 4.645440000000000125e-01 3.320219999999999838e-01 +1.403715317712140083e+09 -6.255450000000000177e-01 -3.493180000000000174e+00 2.964820000000000233e-01 6.535320000000000018e-01 -4.965820000000000234e-01 4.610040000000000249e-01 3.373090000000000255e-01 +1.403715317762140036e+09 -6.134089999999999820e-01 -3.484733999999999998e+00 2.903390000000000137e-01 6.454269999999999730e-01 -5.069970000000000310e-01 4.580929999999999724e-01 3.413619999999999988e-01 +1.403715317812139988e+09 -6.013239999999999696e-01 -3.476535999999999849e+00 2.843649999999999789e-01 6.360670000000000490e-01 -5.187100000000000044e-01 4.569639999999999813e-01 3.428450000000000109e-01 +1.403715317862139940e+09 -5.901239999999999819e-01 -3.468526999999999916e+00 2.786219999999999808e-01 6.269430000000000280e-01 -5.306330000000000213e-01 4.550130000000000008e-01 3.439980000000000260e-01 +1.403715317912139893e+09 -5.799330000000000318e-01 -3.460798000000000041e+00 2.733169999999999766e-01 6.188630000000000519e-01 -5.404480000000000395e-01 4.521200000000000219e-01 3.471480000000000121e-01 +1.403715317962140083e+09 -5.702570000000000139e-01 -3.454051000000000204e+00 2.678079999999999905e-01 6.116669999999999607e-01 -5.492070000000000007e-01 4.481769999999999921e-01 3.512460000000000027e-01 +1.403715318012140036e+09 -5.623000000000000220e-01 -3.446785000000000210e+00 2.622059999999999946e-01 6.048609999999999820e-01 -5.572840000000000016e-01 4.439879999999999938e-01 3.556010000000000004e-01 +1.403715318062139988e+09 -5.554729999999999945e-01 -3.439773999999999887e+00 2.567809999999999815e-01 5.981079999999999730e-01 -5.640469999999999651e-01 4.415640000000000120e-01 3.593600000000000128e-01 +1.403715318112139940e+09 -5.500369999999999981e-01 -3.433105999999999991e+00 2.514580000000000148e-01 5.922650000000000414e-01 -5.701619999999999466e-01 4.395939999999999848e-01 3.617949999999999777e-01 +1.403715318162139893e+09 -5.461110000000000131e-01 -3.426829999999999821e+00 2.462050000000000072e-01 5.876540000000000097e-01 -5.746660000000000101e-01 4.373690000000000078e-01 3.648700000000000276e-01 +1.403715318212140083e+09 -5.437710000000000043e-01 -3.421180000000000110e+00 2.404729999999999923e-01 5.846829999999999528e-01 -5.781549999999999745e-01 4.343040000000000234e-01 3.677819999999999978e-01 +1.403715318262140036e+09 -5.428169999999999940e-01 -3.415754000000000179e+00 2.347970000000000057e-01 5.818449999999999456e-01 -5.810760000000000369e-01 4.322520000000000251e-01 3.700879999999999725e-01 +1.403715318312139988e+09 -5.436029999999999474e-01 -3.410257999999999790e+00 2.289829999999999921e-01 5.798600000000000421e-01 -5.835850000000000204e-01 4.292000000000000259e-01 3.727969999999999895e-01 +1.403715318362139940e+09 -5.457819999999999894e-01 -3.405583000000000027e+00 2.233489999999999920e-01 5.776879999999999793e-01 -5.859309999999999796e-01 4.261490000000000000e-01 3.759750000000000036e-01 +1.403715318412139893e+09 -5.496569999999999512e-01 -3.400952999999999893e+00 2.176730000000000054e-01 5.764000000000000234e-01 -5.878910000000000524e-01 4.216289999999999760e-01 3.799679999999999724e-01 +1.403715318462140083e+09 -5.552559999999999718e-01 -3.395760000000000112e+00 2.123240000000000127e-01 5.758569999999999522e-01 -5.893509999999999582e-01 4.150639999999999885e-01 3.857149999999999745e-01 +1.403715318512140036e+09 -5.614299999999999846e-01 -3.391709000000000085e+00 2.064410000000000134e-01 5.757039999999999935e-01 -5.908839999999999648e-01 4.075250000000000261e-01 3.915919999999999956e-01 +1.403715318562139988e+09 -5.684869999999999646e-01 -3.386518000000000139e+00 2.007990000000000053e-01 5.749910000000000299e-01 -5.939729999999999732e-01 3.996730000000000005e-01 3.960339999999999971e-01 +1.403715318612139940e+09 -5.755369999999999653e-01 -3.383226000000000067e+00 1.946809999999999929e-01 5.744869999999999699e-01 -5.987299999999999844e-01 3.908309999999999840e-01 3.984199999999999964e-01 +1.403715318662139893e+09 -5.828250000000000375e-01 -3.380989000000000022e+00 1.880449999999999899e-01 5.734240000000000448e-01 -6.048519999999999452e-01 3.818130000000000135e-01 3.994469999999999965e-01 +1.403715318712140083e+09 -5.900919999999999499e-01 -3.379828999999999972e+00 1.811510000000000065e-01 5.721439999999999859e-01 -6.122119999999999784e-01 3.725890000000000035e-01 3.987789999999999946e-01 +1.403715318762140036e+09 -5.973610000000000309e-01 -3.380370999999999793e+00 1.745649999999999979e-01 5.683629999999999516e-01 -6.197249999999999703e-01 3.661130000000000217e-01 3.985810000000000186e-01 +1.403715318812139988e+09 -6.050119999999999942e-01 -3.383046000000000220e+00 1.682400000000000007e-01 5.647290000000000365e-01 -6.263079999999999758e-01 3.585780000000000078e-01 4.003019999999999912e-01 +1.403715318862139940e+09 -6.123389999999999667e-01 -3.388058000000000014e+00 1.626890000000000003e-01 5.593019999999999659e-01 -6.318960000000000132e-01 3.536560000000000259e-01 4.035050000000000026e-01 +1.403715318912139893e+09 -6.195779999999999621e-01 -3.395656999999999925e+00 1.572850000000000081e-01 5.538340000000000485e-01 -6.360919999999999908e-01 3.496980000000000088e-01 4.078800000000000203e-01 +1.403715318962140083e+09 -6.268080000000000318e-01 -3.405634000000000050e+00 1.522499999999999964e-01 5.484050000000000313e-01 -6.392799999999999594e-01 3.466219999999999857e-01 4.128279999999999728e-01 +1.403715319012140036e+09 -6.338240000000000540e-01 -3.417355999999999838e+00 1.473889999999999922e-01 5.419990000000000085e-01 -6.425870000000000193e-01 3.441549999999999887e-01 4.181819999999999982e-01 +1.403715319062139988e+09 -6.406479999999999952e-01 -3.431061000000000138e+00 1.426739999999999953e-01 5.355360000000000120e-01 -6.454060000000000352e-01 3.411370000000000235e-01 4.245909999999999962e-01 +1.403715319112139940e+09 -6.473250000000000393e-01 -3.445917999999999815e+00 1.385089999999999932e-01 5.290249999999999675e-01 -6.473370000000000513e-01 3.379960000000000186e-01 4.322570000000000023e-01 +1.403715319162139893e+09 -6.536399999999999988e-01 -3.462539000000000033e+00 1.343119999999999870e-01 5.224609999999999532e-01 -6.492219999999999658e-01 3.344320000000000070e-01 4.401149999999999785e-01 +1.403715319212140083e+09 -6.592130000000000489e-01 -3.480866999999999933e+00 1.304160000000000041e-01 5.153189999999999715e-01 -6.519880000000000120e-01 3.308079999999999909e-01 4.471289999999999987e-01 +1.403715319262140036e+09 -6.644750000000000378e-01 -3.499855000000000160e+00 1.267909999999999870e-01 5.083739999999999926e-01 -6.556729999999999503e-01 3.262450000000000072e-01 4.530040000000000178e-01 +1.403715319312139988e+09 -6.689319999999999711e-01 -3.519868000000000219e+00 1.236929999999999974e-01 5.016500000000000403e-01 -6.591920000000000002e-01 3.211780000000000190e-01 4.589739999999999931e-01 +1.403715319362139940e+09 -6.725060000000000482e-01 -3.540526999999999980e+00 1.208599999999999952e-01 4.946760000000000046e-01 -6.630660000000000442e-01 3.157249999999999779e-01 4.647109999999999852e-01 +1.403715319412139893e+09 -6.749789999999999957e-01 -3.561977999999999867e+00 1.181939999999999935e-01 4.871440000000000214e-01 -6.669929999999999470e-01 3.113139999999999796e-01 4.699949999999999961e-01 +1.403715319462140083e+09 -6.767320000000000002e-01 -3.584185000000000176e+00 1.153900000000000065e-01 4.785900000000000154e-01 -6.716469999999999940e-01 3.085910000000000042e-01 4.739349999999999952e-01 +1.403715319512140036e+09 -6.779450000000000198e-01 -3.606771000000000171e+00 1.125390000000000001e-01 4.696000000000000174e-01 -6.766969999999999930e-01 3.057090000000000085e-01 4.775969999999999938e-01 +1.403715319562139988e+09 -6.785290000000000488e-01 -3.630125000000000046e+00 1.098670000000000063e-01 4.615009999999999946e-01 -6.814919999999999867e-01 3.017029999999999990e-01 4.812069999999999959e-01 +1.403715319612139940e+09 -6.781310000000000393e-01 -3.654161999999999910e+00 1.085050000000000042e-01 4.534460000000000157e-01 -6.860260000000000247e-01 2.989370000000000083e-01 4.841409999999999880e-01 +1.403715319662139893e+09 -6.768199999999999772e-01 -3.678672999999999860e+00 1.093549999999999939e-01 4.479529999999999901e-01 -6.893540000000000223e-01 2.950760000000000050e-01 4.868879999999999875e-01 +1.403715319712140083e+09 -6.745740000000000069e-01 -3.703521999999999981e+00 1.127940000000000054e-01 4.430339999999999834e-01 -6.922840000000000105e-01 2.932919999999999972e-01 4.883069999999999911e-01 +1.403715319762140036e+09 -6.714520000000000488e-01 -3.729353000000000140e+00 1.189810000000000034e-01 4.404359999999999942e-01 -6.944590000000000485e-01 2.909740000000000104e-01 4.889549999999999730e-01 +1.403715319812139988e+09 -6.674909999999999455e-01 -3.756292999999999882e+00 1.283350000000000046e-01 4.381740000000000079e-01 -6.960020000000000095e-01 2.904539999999999900e-01 4.891030000000000100e-01 +1.403715319862139940e+09 -6.629040000000000488e-01 -3.783767000000000102e+00 1.405109999999999970e-01 4.363369999999999749e-01 -6.972420000000000284e-01 2.896679999999999811e-01 4.894450000000000189e-01 +1.403715319912139893e+09 -6.578100000000000058e-01 -3.812043000000000070e+00 1.549149999999999971e-01 4.342059999999999809e-01 -6.991119999999999557e-01 2.889109999999999734e-01 4.891190000000000260e-01 +1.403715319962140083e+09 -6.520559999999999690e-01 -3.840673999999999921e+00 1.703250000000000042e-01 4.324310000000000098e-01 -7.001969999999999583e-01 2.876850000000000240e-01 4.898620000000000196e-01 +1.403715320012140036e+09 -6.457249999999999934e-01 -3.870206000000000035e+00 1.854790000000000050e-01 4.296949999999999936e-01 -7.015850000000000142e-01 2.861040000000000250e-01 4.912079999999999780e-01 +1.403715320062139988e+09 -6.388439999999999674e-01 -3.900297000000000125e+00 2.000780000000000058e-01 4.262819999999999943e-01 -7.035160000000000302e-01 2.837569999999999815e-01 4.927790000000000226e-01 +1.403715320112139940e+09 -6.315190000000000525e-01 -3.930728999999999917e+00 2.139800000000000035e-01 4.221409999999999885e-01 -7.049710000000000143e-01 2.802689999999999904e-01 4.962480000000000224e-01 +1.403715320162139893e+09 -6.237709999999999644e-01 -3.961205999999999783e+00 2.270389999999999908e-01 4.167469999999999786e-01 -7.075559999999999627e-01 2.758459999999999801e-01 4.995950000000000113e-01 +1.403715320212140083e+09 -6.152819999999999956e-01 -3.992274000000000100e+00 2.393949999999999967e-01 4.091270000000000184e-01 -7.102159999999999584e-01 2.716430000000000233e-01 5.043990000000000418e-01 +1.403715320262140036e+09 -6.061649999999999539e-01 -4.022674999999999557e+00 2.522559999999999802e-01 3.995099999999999763e-01 -7.123199999999999532e-01 2.675279999999999880e-01 5.112929999999999975e-01 +1.403715320312139988e+09 -5.964439999999999742e-01 -4.052952000000000332e+00 2.646249999999999991e-01 3.868960000000000177e-01 -7.150990000000000402e-01 2.651689999999999880e-01 5.182959999999999789e-01 +1.403715320362139940e+09 -5.858919999999999684e-01 -4.082696000000000325e+00 2.763209999999999833e-01 3.722739999999999938e-01 -7.196810000000000151e-01 2.628860000000000086e-01 5.237969999999999571e-01 +1.403715320412139893e+09 -5.747569999999999624e-01 -4.111674999999999969e+00 2.874900000000000233e-01 3.571409999999999862e-01 -7.259060000000000512e-01 2.593210000000000237e-01 5.275079999999999769e-01 +1.403715320462140083e+09 -5.628480000000000150e-01 -4.139636999999999567e+00 2.984319999999999751e-01 3.417870000000000075e-01 -7.324929999999999497e-01 2.543070000000000053e-01 5.310019999999999740e-01 +1.403715320512140036e+09 -5.500779999999999559e-01 -4.165960000000000107e+00 3.086820000000000119e-01 3.266029999999999767e-01 -7.399289999999999479e-01 2.484089999999999909e-01 5.330369999999999830e-01 +1.403715320562139988e+09 -5.368990000000000151e-01 -4.191301000000000165e+00 3.184139999999999748e-01 3.111269999999999869e-01 -7.470489999999999631e-01 2.427080000000000071e-01 5.349869999999999903e-01 +1.403715320612139940e+09 -5.234050000000000091e-01 -4.215607999999999578e+00 3.283820000000000072e-01 2.954490000000000172e-01 -7.539719999999999756e-01 2.376459999999999961e-01 5.364330000000000487e-01 +1.403715320662139893e+09 -5.096549999999999692e-01 -4.238523999999999958e+00 3.380779999999999896e-01 2.791890000000000205e-01 -7.604250000000000176e-01 2.333230000000000026e-01 5.379289999999999905e-01 +1.403715320712140083e+09 -4.955220000000000180e-01 -4.259792000000000023e+00 3.472819999999999796e-01 2.636350000000000082e-01 -7.662529999999999619e-01 2.298749999999999960e-01 5.389899999999999691e-01 +1.403715320762140036e+09 -4.816739999999999911e-01 -4.280190000000000161e+00 3.559910000000000019e-01 2.484429999999999972e-01 -7.712040000000000006e-01 2.288219999999999976e-01 5.395929999999999893e-01 +1.403715320812139988e+09 -4.679030000000000133e-01 -4.299136999999999986e+00 3.641130000000000200e-01 2.350579999999999892e-01 -7.751519999999999522e-01 2.285770000000000024e-01 5.400359999999999605e-01 +1.403715320862139940e+09 -4.544770000000000199e-01 -4.315514000000000294e+00 3.712529999999999997e-01 2.240179999999999949e-01 -7.795809999999999684e-01 2.280189999999999995e-01 5.385879999999999557e-01 +1.403715320912139893e+09 -4.419409999999999727e-01 -4.329837999999999631e+00 3.777619999999999867e-01 2.156869999999999898e-01 -7.840629999999999544e-01 2.263489999999999946e-01 5.361810000000000187e-01 +1.403715320962140083e+09 -4.305910000000000015e-01 -4.341479999999999784e+00 3.840879999999999850e-01 2.100360000000000005e-01 -7.875670000000000170e-01 2.231110000000000038e-01 5.346450000000000369e-01 +1.403715321012140036e+09 -4.204069999999999752e-01 -4.350806999999999647e+00 3.901580000000000048e-01 2.068230000000000068e-01 -7.904660000000000020e-01 2.183470000000000133e-01 5.335839999999999472e-01 +1.403715321062139988e+09 -4.115659999999999874e-01 -4.358221000000000345e+00 3.960259999999999891e-01 2.050690000000000013e-01 -7.923909999999999565e-01 2.133279999999999899e-01 5.334370000000000500e-01 +1.403715321112139940e+09 -4.039349999999999885e-01 -4.363909999999999734e+00 4.016529999999999823e-01 2.041330000000000089e-01 -7.936980000000000146e-01 2.086639999999999884e-01 5.336969999999999770e-01 +1.403715321162139893e+09 -3.965259999999999896e-01 -4.366252000000000244e+00 4.079070000000000196e-01 2.037549999999999917e-01 -7.945929999999999938e-01 2.045770000000000088e-01 5.340920000000000112e-01 +1.403715321212140083e+09 -3.915600000000000191e-01 -4.368859999999999744e+00 4.123240000000000238e-01 2.041630000000000111e-01 -7.956590000000000051e-01 2.006300000000000028e-01 5.338469999999999605e-01 +1.403715321262140036e+09 -3.873590000000000089e-01 -4.369826999999999906e+00 4.165070000000000161e-01 2.043919999999999904e-01 -7.964350000000000041e-01 1.980049999999999866e-01 5.335809999999999720e-01 +1.403715321312139988e+09 -3.842459999999999765e-01 -4.368826000000000320e+00 4.206099999999999839e-01 2.042259999999999909e-01 -7.971369999999999845e-01 1.972520000000000107e-01 5.328749999999999876e-01 +1.403715321362139940e+09 -3.825660000000000172e-01 -4.366337999999999830e+00 4.244330000000000047e-01 2.040389999999999981e-01 -7.976349999999999829e-01 1.971559999999999979e-01 5.322369999999999601e-01 +1.403715321412139893e+09 -3.820830000000000060e-01 -4.362195999999999962e+00 4.282880000000000020e-01 2.035200000000000065e-01 -7.974059999999999482e-01 1.980520000000000058e-01 5.324459999999999749e-01 +1.403715321462140083e+09 -3.829960000000000031e-01 -4.356340999999999575e+00 4.321949999999999958e-01 2.035369999999999957e-01 -7.966119999999999868e-01 1.988600000000000090e-01 5.333269999999999955e-01 +1.403715321512140036e+09 -3.852749999999999786e-01 -4.348873000000000211e+00 4.360149999999999859e-01 2.050329999999999930e-01 -7.961629999999999541e-01 1.988370000000000137e-01 5.334320000000000173e-01 +1.403715321562139988e+09 -3.888690000000000202e-01 -4.339973999999999776e+00 4.397949999999999915e-01 2.069269999999999998e-01 -7.961030000000000051e-01 1.991660000000000097e-01 5.326659999999999728e-01 +1.403715321612139940e+09 -3.938010000000000121e-01 -4.329614000000000296e+00 4.437240000000000073e-01 2.104459999999999942e-01 -7.954219999999999624e-01 1.979990000000000083e-01 5.327410000000000201e-01 +1.403715321662139893e+09 -4.001259999999999817e-01 -4.317911999999999750e+00 4.480859999999999843e-01 2.125960000000000072e-01 -7.942080000000000251e-01 1.966459999999999875e-01 5.341979999999999507e-01 +1.403715321712140083e+09 -4.077279999999999793e-01 -4.304954999999999643e+00 4.530600000000000183e-01 2.120460000000000123e-01 -7.917070000000000496e-01 1.967710000000000015e-01 5.380679999999999907e-01 +1.403715321762140036e+09 -4.161270000000000246e-01 -4.290232999999999741e+00 4.583409999999999984e-01 2.104530000000000012e-01 -7.900620000000000420e-01 1.964380000000000015e-01 5.412249999999999561e-01 +1.403715321812139988e+09 -4.252949999999999786e-01 -4.274067999999999756e+00 4.632200000000000206e-01 2.056870000000000087e-01 -7.885419999999999652e-01 1.986380000000000090e-01 5.444600000000000550e-01 +1.403715321862139940e+09 -4.352409999999999890e-01 -4.256243999999999694e+00 4.685420000000000140e-01 1.996610000000000051e-01 -7.860500000000000265e-01 2.021850000000000036e-01 5.489819999999999700e-01 +1.403715321912139893e+09 -4.457690000000000263e-01 -4.236206000000000138e+00 4.735849999999999782e-01 1.946670000000000067e-01 -7.840620000000000367e-01 2.035750000000000060e-01 5.530899999999999705e-01 +1.403715321962140083e+09 -4.565009999999999901e-01 -4.213462999999999958e+00 4.779320000000000235e-01 1.901869999999999949e-01 -7.842839999999999812e-01 2.023909999999999876e-01 5.547659999999999814e-01 +1.403715322012140036e+09 -4.671810000000000129e-01 -4.187740999999999936e+00 4.817850000000000188e-01 1.866389999999999993e-01 -7.867889999999999606e-01 1.984889999999999988e-01 5.538340000000000485e-01 +1.403715322062139988e+09 -4.782850000000000157e-01 -4.159743999999999886e+00 4.856509999999999994e-01 1.828720000000000068e-01 -7.907399999999999984e-01 1.952720000000000011e-01 5.505970000000000031e-01 +1.403715322112139940e+09 -4.900149999999999784e-01 -4.129621000000000208e+00 4.902360000000000051e-01 1.813190000000000079e-01 -7.942869999999999653e-01 1.893600000000000005e-01 5.480639999999999956e-01 +1.403715322162139893e+09 -5.022259999999999502e-01 -4.097565999999999597e+00 4.949279999999999791e-01 1.835759999999999892e-01 -7.966929999999999845e-01 1.796590000000000131e-01 5.470859999999999612e-01 +1.403715322212140083e+09 -5.154029999999999445e-01 -4.064167999999999559e+00 4.999239999999999795e-01 1.864470000000000016e-01 -7.979810000000000514e-01 1.691769999999999941e-01 5.475799999999999557e-01 +1.403715322262140036e+09 -5.291000000000000147e-01 -4.029600000000000293e+00 5.047329999999999872e-01 1.873809999999999920e-01 -7.994299999999999740e-01 1.589409999999999989e-01 5.482129999999999503e-01 +1.403715322312139988e+09 -5.430270000000000374e-01 -3.994531999999999972e+00 5.090820000000000345e-01 1.869260000000000088e-01 -8.017499999999999627e-01 1.492030000000000023e-01 5.477170000000000094e-01 +1.403715322362139940e+09 -5.577280000000000015e-01 -3.959165000000000045e+00 5.117890000000000494e-01 1.846820000000000128e-01 -8.042489999999999917e-01 1.397839999999999916e-01 5.472989999999999799e-01 +1.403715322412139893e+09 -5.728090000000000126e-01 -3.923744000000000121e+00 5.118409999999999904e-01 1.809020000000000072e-01 -8.068520000000000136e-01 1.300910000000000122e-01 5.471200000000000507e-01 +1.403715322462140083e+09 -5.882749999999999924e-01 -3.888676999999999939e+00 5.086479999999999890e-01 1.759219999999999950e-01 -8.098030000000000506e-01 1.214680000000000065e-01 5.463670000000000471e-01 +1.403715322512140036e+09 -6.037930000000000241e-01 -3.854471999999999898e+00 5.023819999999999952e-01 1.706950000000000134e-01 -8.124449999999999728e-01 1.141380000000000033e-01 5.456820000000000004e-01 +1.403715322562139988e+09 -6.197089999999999543e-01 -3.821235000000000159e+00 4.932790000000000230e-01 1.657099999999999962e-01 -8.151709999999999789e-01 1.089600000000000013e-01 5.442090000000000538e-01 +1.403715322612139940e+09 -6.361580000000000013e-01 -3.789238999999999802e+00 4.825809999999999822e-01 1.621029999999999971e-01 -8.171110000000000317e-01 1.038540000000000019e-01 5.433839999999999781e-01 +1.403715322662139893e+09 -6.536300000000000443e-01 -3.758888999999999925e+00 4.713390000000000080e-01 1.589319999999999899e-01 -8.189170000000000060e-01 1.002149999999999985e-01 5.422839999999999883e-01 +1.403715322712140083e+09 -6.725170000000000314e-01 -3.730013000000000023e+00 4.600400000000000045e-01 1.563120000000000065e-01 -8.197879999999999612e-01 9.759900000000000519e-02 5.422080000000000233e-01 +1.403715322762140036e+09 -6.930089999999999861e-01 -3.702637000000000178e+00 4.489270000000000205e-01 1.541480000000000072e-01 -8.197140000000000537e-01 9.582799999999999652e-02 5.432529999999999859e-01 +1.403715322812139988e+09 -7.143950000000000022e-01 -3.676636999999999933e+00 4.383460000000000134e-01 1.529270000000000074e-01 -8.199830000000000174e-01 9.396200000000000385e-02 5.435189999999999744e-01 +1.403715322862139940e+09 -7.364880000000000315e-01 -3.652210000000000178e+00 4.307619999999999783e-01 1.527010000000000034e-01 -8.202899999999999636e-01 9.206000000000000294e-02 5.434440000000000381e-01 +1.403715322912139893e+09 -7.597019999999999884e-01 -3.629389000000000198e+00 4.254200000000000204e-01 1.530360000000000054e-01 -8.195219999999999727e-01 8.997900000000000342e-02 5.448560000000000070e-01 +1.403715322962140083e+09 -7.837380000000000457e-01 -3.608556999999999793e+00 4.231739999999999946e-01 1.531309999999999893e-01 -8.188029999999999475e-01 8.852100000000000246e-02 5.461479999999999668e-01 +1.403715323012140036e+09 -8.084630000000000427e-01 -3.589402000000000204e+00 4.239479999999999915e-01 1.536790000000000100e-01 -8.182530000000000081e-01 8.743299999999999683e-02 5.469920000000000337e-01 +1.403715323062139988e+09 -8.340990000000000348e-01 -3.571988999999999859e+00 4.275010000000000199e-01 1.541690000000000005e-01 -8.180060000000000109e-01 8.710299999999999987e-02 5.472759999999999847e-01 +1.403715323112139940e+09 -8.609799999999999676e-01 -3.556385999999999825e+00 4.324009999999999798e-01 1.548090000000000022e-01 -8.177149999999999697e-01 8.636900000000000133e-02 5.476459999999999662e-01 +1.403715323162139893e+09 -8.886060000000000070e-01 -3.542672000000000043e+00 4.357610000000000094e-01 1.558900000000000008e-01 -8.175750000000000517e-01 8.556300000000000017e-02 5.476750000000000229e-01 +1.403715323212140083e+09 -9.182599999999999651e-01 -3.532343000000000011e+00 4.365470000000000184e-01 1.576790000000000136e-01 -8.169290000000000163e-01 8.424500000000000044e-02 5.483310000000000128e-01 +1.403715323262140036e+09 -9.465909999999999602e-01 -3.521166000000000018e+00 4.342059999999999809e-01 1.587659999999999905e-01 -8.159760000000000346e-01 8.340799999999999603e-02 5.495630000000000237e-01 +1.403715323312139988e+09 -9.755270000000000330e-01 -3.511886000000000063e+00 4.288759999999999795e-01 1.596720000000000084e-01 -8.156050000000000244e-01 8.297999999999999821e-02 5.499159999999999604e-01 +1.403715323362139940e+09 -1.005082000000000031e+00 -3.504284999999999872e+00 4.224490000000000189e-01 1.593700000000000117e-01 -8.152690000000000214e-01 8.387500000000000511e-02 5.503660000000000219e-01 +1.403715323412139893e+09 -1.035182999999999964e+00 -3.498762999999999845e+00 4.179439999999999822e-01 1.594559999999999866e-01 -8.150450000000000195e-01 8.384900000000000686e-02 5.506769999999999721e-01 +1.403715323462140083e+09 -1.065711000000000075e+00 -3.494994999999999852e+00 4.157170000000000032e-01 1.593749999999999889e-01 -8.155160000000000187e-01 8.397300000000000597e-02 5.499840000000000284e-01 +1.403715323512140036e+09 -1.096985000000000099e+00 -3.493304999999999882e+00 4.158700000000000174e-01 1.592919999999999892e-01 -8.155869999999999509e-01 8.395199999999999885e-02 5.499049999999999772e-01 +1.403715323562139988e+09 -1.128255999999999926e+00 -3.493114999999999970e+00 4.188830000000000053e-01 1.590040000000000064e-01 -8.159859999999999891e-01 8.386699999999999711e-02 5.494090000000000362e-01 +1.403715323612139940e+09 -1.160031999999999952e+00 -3.494629000000000207e+00 4.259939999999999838e-01 1.576059999999999961e-01 -8.124059999999999615e-01 8.568800000000000028e-02 5.548100000000000254e-01 +1.403715323662139893e+09 -1.192163000000000084e+00 -3.497527999999999970e+00 4.350499999999999923e-01 1.553730000000000111e-01 -8.066510000000000069e-01 8.852500000000000646e-02 5.633270000000000222e-01 +1.403715323712140083e+09 -1.223862000000000005e+00 -3.501475999999999811e+00 4.444839999999999902e-01 1.534079999999999888e-01 -8.002799999999999914e-01 9.032600000000000351e-02 5.725900000000000434e-01 +1.403715323762140036e+09 -1.254234000000000071e+00 -3.506416000000000199e+00 4.535489999999999799e-01 1.516460000000000030e-01 -7.931049999999999489e-01 9.221100000000000130e-02 5.826529999999999765e-01 +1.403715323812139988e+09 -1.283833999999999920e+00 -3.513227999999999795e+00 4.610489999999999866e-01 1.499489999999999990e-01 -7.868950000000000111e-01 9.440999999999999392e-02 5.910990000000000411e-01 +1.403715323862139940e+09 -1.310961000000000043e+00 -3.520522000000000151e+00 4.691500000000000115e-01 1.483410000000000006e-01 -7.814130000000000242e-01 9.614499999999999436e-02 5.984519999999999840e-01 +1.403715323912139893e+09 -1.336116000000000081e+00 -3.528505000000000003e+00 4.776469999999999883e-01 1.472710000000000130e-01 -7.757129999999999859e-01 9.755400000000000182e-02 6.058580000000000076e-01 +1.403715323962140083e+09 -1.358189000000000091e+00 -3.536951999999999874e+00 4.865340000000000220e-01 1.458979999999999999e-01 -7.685070000000000512e-01 1.002829999999999971e-01 6.148609999999999909e-01 +1.403715324012140036e+09 -1.376827000000000023e+00 -3.545551000000000119e+00 4.950370000000000048e-01 1.443929999999999936e-01 -7.630740000000000300e-01 1.032040000000000041e-01 6.214640000000000164e-01 +1.403715324062139988e+09 -1.392581999999999987e+00 -3.554657000000000178e+00 5.022919999999999607e-01 1.435259999999999869e-01 -7.609759999999999858e-01 1.056210000000000065e-01 6.238270000000000204e-01 +1.403715324112139940e+09 -1.404352999999999962e+00 -3.562891000000000030e+00 5.082029999999999603e-01 1.427579999999999960e-01 -7.628779999999999450e-01 1.080020000000000008e-01 6.212670000000000137e-01 +1.403715324162139893e+09 -1.412851999999999997e+00 -3.570454999999999934e+00 5.138500000000000290e-01 1.422779999999999878e-01 -7.666899999999999826e-01 1.100060000000000066e-01 6.163140000000000285e-01 +1.403715324212140083e+09 -1.418539999999999912e+00 -3.577866000000000213e+00 5.193640000000000478e-01 1.413290000000000102e-01 -7.704929999999999835e-01 1.124870000000000037e-01 6.113199999999999745e-01 +1.403715324262140036e+09 -1.422196000000000016e+00 -3.584852000000000150e+00 5.251320000000000432e-01 1.400079999999999936e-01 -7.739200000000000523e-01 1.157780000000000059e-01 6.066639999999999810e-01 +1.403715324312139988e+09 -1.422449999999999992e+00 -3.591283999999999921e+00 5.305959999999999566e-01 1.379440000000000111e-01 -7.771569999999999867e-01 1.204260000000000053e-01 6.020769999999999733e-01 +1.403715324362139940e+09 -1.420346000000000108e+00 -3.596865000000000201e+00 5.363780000000000214e-01 1.342800000000000105e-01 -7.814370000000000482e-01 1.267159999999999953e-01 5.960429999999999895e-01 +1.403715324412139893e+09 -1.416166999999999954e+00 -3.601309000000000093e+00 5.412590000000000456e-01 1.319259999999999877e-01 -7.879840000000000177e-01 1.316370000000000040e-01 5.868130000000000290e-01 +1.403715324462140083e+09 -1.410809999999999897e+00 -3.604347999999999885e+00 5.463559999999999528e-01 1.305939999999999879e-01 -7.954809999999999937e-01 1.345099999999999907e-01 5.762490000000000112e-01 +1.403715324512140036e+09 -1.404838999999999949e+00 -3.606056999999999846e+00 5.513109999999999955e-01 1.298070000000000057e-01 -8.017680000000000362e-01 1.360210000000000030e-01 5.672890000000000432e-01 +1.403715324562139988e+09 -1.399356999999999962e+00 -3.606494999999999784e+00 5.569049999999999834e-01 1.297770000000000035e-01 -8.068800000000000416e-01 1.359470000000000123e-01 5.600180000000000158e-01 +1.403715324612139940e+09 -1.394700000000000051e+00 -3.606057999999999986e+00 5.634710000000000552e-01 1.299839999999999884e-01 -8.099229999999999485e-01 1.351239999999999941e-01 5.557609999999999495e-01 +1.403715324662139893e+09 -1.390756000000000103e+00 -3.604487000000000219e+00 5.700640000000000152e-01 1.309389999999999998e-01 -8.113230000000000164e-01 1.333219999999999961e-01 5.539269999999999472e-01 +1.403715324712140083e+09 -1.387415999999999983e+00 -3.601723999999999926e+00 5.769570000000000531e-01 1.318660000000000110e-01 -8.115970000000000129e-01 1.314460000000000073e-01 5.537539999999999685e-01 +1.403715324762140036e+09 -1.384759999999999991e+00 -3.598100000000000076e+00 5.835690000000000044e-01 1.337190000000000045e-01 -8.111369999999999969e-01 1.284480000000000066e-01 5.546860000000000124e-01 +1.403715324812139988e+09 -1.382571999999999912e+00 -3.593895999999999979e+00 5.899550000000000072e-01 1.375250000000000083e-01 -8.098189999999999555e-01 1.230139999999999983e-01 5.569089999999999874e-01 +1.403715324862139940e+09 -1.380368999999999957e+00 -3.589424999999999866e+00 5.960229999999999695e-01 1.419519999999999949e-01 -8.075369999999999493e-01 1.169789999999999996e-01 5.604010000000000380e-01 +1.403715324912139893e+09 -1.378765999999999936e+00 -3.585024999999999906e+00 6.017700000000000271e-01 1.457259999999999944e-01 -8.042510000000000492e-01 1.123170000000000002e-01 5.650929999999999565e-01 +1.403715324962140083e+09 -1.377097000000000016e+00 -3.580897000000000219e+00 6.070149999999999713e-01 1.476820000000000077e-01 -8.007579999999999698e-01 1.104849999999999999e-01 5.698849999999999749e-01 +1.403715325012140036e+09 -1.374730000000000008e+00 -3.576605999999999952e+00 6.121189999999999687e-01 1.489379999999999871e-01 -7.974339999999999762e-01 1.099780000000000063e-01 5.743009999999999504e-01 +1.403715325062139988e+09 -1.371312000000000086e+00 -3.572505000000000042e+00 6.166329999999999867e-01 1.493200000000000083e-01 -7.948340000000000405e-01 1.104379999999999945e-01 5.777079999999999993e-01 +1.403715325112139940e+09 -1.366983000000000059e+00 -3.568440999999999974e+00 6.204129999999999923e-01 1.490569999999999951e-01 -7.923299999999999788e-01 1.123999999999999999e-01 5.808280000000000109e-01 +1.403715325162139893e+09 -1.362109000000000014e+00 -3.564594000000000040e+00 6.236509999999999554e-01 1.493669999999999998e-01 -7.909739999999999549e-01 1.134339999999999932e-01 5.823930000000000495e-01 +1.403715325212140083e+09 -1.356340000000000101e+00 -3.560703000000000173e+00 6.267420000000000213e-01 1.495879999999999987e-01 -7.897969999999999713e-01 1.145710000000000062e-01 5.837099999999999511e-01 +1.403715325262140036e+09 -1.349394999999999900e+00 -3.556747000000000103e+00 6.286819999999999631e-01 1.496190000000000020e-01 -7.898570000000000313e-01 1.160999999999999949e-01 5.833180000000000032e-01 +1.403715325312139988e+09 -1.341193000000000080e+00 -3.552697000000000216e+00 6.303760000000000474e-01 1.498019999999999907e-01 -7.907290000000000152e-01 1.175210000000000005e-01 5.818039999999999878e-01 +1.403715325362139940e+09 -1.331998000000000015e+00 -3.548134000000000121e+00 6.318559999999999732e-01 1.501250000000000084e-01 -7.926739999999999897e-01 1.183469999999999939e-01 5.788990000000000524e-01 +1.403715325412139893e+09 -1.322049999999999947e+00 -3.543318999999999885e+00 6.327220000000000066e-01 1.498140000000000027e-01 -7.954620000000000024e-01 1.203580000000000066e-01 5.747250000000000414e-01 +1.403715325462140083e+09 -1.311685999999999908e+00 -3.538196000000000119e+00 6.330599999999999561e-01 1.492829999999999990e-01 -7.989239999999999675e-01 1.219839999999999952e-01 5.696970000000000089e-01 +1.403715325512140036e+09 -1.301544000000000034e+00 -3.533011000000000124e+00 6.331210000000000448e-01 1.486139999999999961e-01 -8.020589999999999664e-01 1.235819999999999974e-01 5.651040000000000507e-01 +1.403715325562139988e+09 -1.291533000000000042e+00 -3.527785999999999866e+00 6.331309999999999993e-01 1.468289999999999873e-01 -8.042880000000000029e-01 1.262260000000000049e-01 5.618090000000000028e-01 +1.403715325612139940e+09 -1.282602000000000020e+00 -3.522514999999999841e+00 6.335220000000000296e-01 1.430099999999999982e-01 -8.058119999999999727e-01 1.314240000000000130e-01 5.594130000000000491e-01 +1.403715325662139893e+09 -1.274582000000000104e+00 -3.516204000000000107e+00 6.331959999999999811e-01 1.390419999999999989e-01 -8.070850000000000524e-01 1.366449999999999887e-01 5.573230000000000128e-01 +1.403715325712140083e+09 -1.266664000000000012e+00 -3.508941000000000088e+00 6.328249999999999709e-01 1.361380000000000090e-01 -8.083749999999999547e-01 1.402450000000000085e-01 5.552719999999999878e-01 +1.403715325762140036e+09 -1.259899000000000102e+00 -3.500236000000000125e+00 6.324889999999999679e-01 1.341060000000000030e-01 -8.099340000000000428e-01 1.424189999999999900e-01 5.529370000000000118e-01 +1.403715325812139988e+09 -1.253395000000000037e+00 -3.489933999999999870e+00 6.324629999999999974e-01 1.337009999999999865e-01 -8.112970000000000459e-01 1.422259999999999913e-01 5.510829999999999895e-01 +1.403715325862139940e+09 -1.247705000000000064e+00 -3.478483000000000214e+00 6.319529999999999870e-01 1.339059999999999973e-01 -8.122620000000000395e-01 1.410839999999999872e-01 5.499049999999999772e-01 +1.403715325912139893e+09 -1.242888999999999911e+00 -3.465949000000000169e+00 6.310980000000000478e-01 1.343250000000000000e-01 -8.131450000000000067e-01 1.394239999999999924e-01 5.489190000000000458e-01 +1.403715325962140083e+09 -1.239244000000000012e+00 -3.452490000000000059e+00 6.299439999999999484e-01 1.352869999999999906e-01 -8.140129999999999866e-01 1.372569999999999901e-01 5.479429999999999579e-01 +1.403715326012140036e+09 -1.237076000000000064e+00 -3.438063999999999787e+00 6.285889999999999533e-01 1.363820000000000032e-01 -8.140619999999999523e-01 1.342039999999999900e-01 5.483540000000000081e-01 +1.403715326062139988e+09 -1.236304999999999987e+00 -3.422908000000000062e+00 6.269510000000000360e-01 1.380379999999999940e-01 -8.134120000000000239e-01 1.301229999999999887e-01 5.498849999999999572e-01 +1.403715326112139940e+09 -1.236631999999999953e+00 -3.407102000000000075e+00 6.246850000000000458e-01 1.404880000000000018e-01 -8.124559999999999560e-01 1.246720000000000050e-01 5.519380000000000397e-01 +1.403715326162139893e+09 -1.237832000000000043e+00 -3.391131000000000117e+00 6.221630000000000216e-01 1.430410000000000015e-01 -8.110519999999999952e-01 1.191460000000000019e-01 5.545609999999999706e-01 +1.403715326212140083e+09 -1.239686999999999983e+00 -3.375070000000000014e+00 6.188010000000000455e-01 1.449940000000000118e-01 -8.098349999999999715e-01 1.144899999999999946e-01 5.568079999999999696e-01 +1.403715326262140036e+09 -1.242216999999999905e+00 -3.359293000000000085e+00 6.148069999999999924e-01 1.467070000000000041e-01 -8.080289999999999973e-01 1.102869999999999961e-01 5.598229999999999595e-01 +1.403715326312139988e+09 -1.245004999999999917e+00 -3.343938000000000077e+00 6.110269999999999868e-01 1.472009999999999985e-01 -8.055809999999999915e-01 1.079630000000000034e-01 5.636619999999999964e-01 +1.403715326362139940e+09 -1.247519999999999962e+00 -3.328724999999999934e+00 6.073509999999999742e-01 1.470519999999999883e-01 -8.017790000000000195e-01 1.063739999999999963e-01 5.693949999999999845e-01 +1.403715326412139893e+09 -1.250383000000000022e+00 -3.314381000000000022e+00 6.039470000000000116e-01 1.459670000000000134e-01 -7.976339999999999542e-01 1.062899999999999956e-01 5.754789999999999628e-01 +1.403715326462140083e+09 -1.253130000000000077e+00 -3.300602000000000036e+00 6.002499999999999503e-01 1.445929999999999993e-01 -7.944120000000000070e-01 1.066369999999999957e-01 5.802000000000000490e-01 +1.403715326512140036e+09 -1.254898999999999987e+00 -3.286763000000000101e+00 5.966029999999999944e-01 1.435460000000000069e-01 -7.911110000000000086e-01 1.066919999999999952e-01 5.849400000000000155e-01 +1.403715326562139988e+09 -1.254966999999999944e+00 -3.272530999999999857e+00 5.920959999999999557e-01 1.425639999999999963e-01 -7.887920000000000487e-01 1.065299999999999997e-01 5.883310000000000484e-01 +1.403715326612139940e+09 -1.253557999999999950e+00 -3.258233000000000157e+00 5.873399999999999732e-01 1.423220000000000041e-01 -7.868239999999999679e-01 1.055330000000000018e-01 5.911990000000000300e-01 +1.403715326712140083e+09 -1.245856999999999992e+00 -3.228842999999999908e+00 5.778029999999999555e-01 1.404880000000000018e-01 -7.865889999999999826e-01 1.045220000000000038e-01 5.921279999999999877e-01 +1.403715326762140036e+09 -1.240561000000000025e+00 -3.213963000000000125e+00 5.718020000000000325e-01 1.387269999999999892e-01 -7.890500000000000291e-01 1.052209999999999951e-01 5.891380000000000505e-01 +1.403715326812139988e+09 -1.233805000000000041e+00 -3.198942000000000174e+00 5.655329999999999524e-01 1.366110000000000102e-01 -7.926630000000000065e-01 1.066760000000000069e-01 5.845019999999999660e-01 +1.403715326862139940e+09 -1.225519999999999943e+00 -3.183844000000000118e+00 5.588999999999999524e-01 1.340189999999999992e-01 -7.964320000000000288e-01 1.082510000000000000e-01 5.796700000000000186e-01 +1.403715326912139893e+09 -1.216792000000000096e+00 -3.168578000000000117e+00 5.522789999999999644e-01 1.326219999999999899e-01 -8.003259999999999819e-01 1.087209999999999982e-01 5.745160000000000267e-01 +1.403715326962140083e+09 -1.206844999999999946e+00 -3.152597999999999789e+00 5.464740000000000153e-01 1.302129999999999954e-01 -8.031650000000000178e-01 1.100430000000000019e-01 5.708419999999999606e-01 +1.403715327012140036e+09 -1.196890000000000009e+00 -3.136604000000000170e+00 5.410260000000000069e-01 1.273620000000000030e-01 -8.055379999999999763e-01 1.123269999999999963e-01 5.676889999999999992e-01 +1.403715327062139988e+09 -1.186925999999999926e+00 -3.120038000000000089e+00 5.363550000000000262e-01 1.246300000000000047e-01 -8.072599999999999776e-01 1.147419999999999968e-01 5.653599999999999737e-01 +1.403715327112139940e+09 -1.177537999999999974e+00 -3.102964000000000055e+00 5.316539999999999599e-01 1.223169999999999952e-01 -8.090629999999999766e-01 1.165360000000000007e-01 5.629170000000000007e-01 +1.403715327162139893e+09 -1.168595999999999968e+00 -3.085160999999999820e+00 5.271670000000000522e-01 1.208690000000000042e-01 -8.108889999999999709e-01 1.176289999999999975e-01 5.603690000000000060e-01 +1.403715327212140083e+09 -1.160261999999999905e+00 -3.066457999999999906e+00 5.225720000000000365e-01 1.193049999999999944e-01 -8.126670000000000282e-01 1.188179999999999931e-01 5.578720000000000345e-01 +1.403715327262140036e+09 -1.152557999999999971e+00 -3.046745000000000037e+00 5.185939999999999994e-01 1.177139999999999992e-01 -8.143590000000000551e-01 1.196900000000000047e-01 5.555520000000000458e-01 +1.403715327312139988e+09 -1.145839999999999970e+00 -3.026254000000000222e+00 5.152179999999999538e-01 1.159459999999999935e-01 -8.156430000000000069e-01 1.208020000000000066e-01 5.537959999999999550e-01 +1.403715327362139940e+09 -1.140263999999999944e+00 -3.004850999999999939e+00 5.117990000000000039e-01 1.143369999999999942e-01 -8.168950000000000378e-01 1.216349999999999931e-01 5.521009999999999529e-01 +1.403715327412139893e+09 -1.135623000000000049e+00 -2.982364000000000015e+00 5.080719999999999681e-01 1.124900000000000067e-01 -8.178800000000000514e-01 1.224760000000000015e-01 5.508349999999999635e-01 +1.403715327462140083e+09 -1.132176000000000071e+00 -2.959095000000000031e+00 5.045600000000000085e-01 1.128809999999999952e-01 -8.184099999999999708e-01 1.224309999999999982e-01 5.499749999999999917e-01 +1.403715327512140036e+09 -1.129647999999999985e+00 -2.934368999999999783e+00 5.014210000000000056e-01 1.138330000000000036e-01 -8.184740000000000348e-01 1.235239999999999949e-01 5.494409999999999572e-01 +1.403715327562139988e+09 -1.128748000000000085e+00 -2.908589999999999787e+00 4.981900000000000217e-01 1.180199999999999999e-01 -8.180020000000000069e-01 1.224380000000000052e-01 5.495029999999999637e-01 +1.403715327612139940e+09 -1.129432999999999909e+00 -2.882163999999999948e+00 4.950749999999999873e-01 1.238969999999999932e-01 -8.171509999999999607e-01 1.208950000000000025e-01 5.498159999999999714e-01 +1.403715327662139893e+09 -1.130930999999999909e+00 -2.855363000000000095e+00 4.918159999999999754e-01 1.305929999999999869e-01 -8.161950000000000038e-01 1.205299999999999983e-01 5.497670000000000057e-01 +1.403715327712140083e+09 -1.133655999999999997e+00 -2.828425999999999885e+00 4.884539999999999993e-01 1.385969999999999980e-01 -8.148739999999999872e-01 1.208260000000000028e-01 5.497009999999999952e-01 +1.403715327762140036e+09 -1.137097999999999942e+00 -2.801698000000000022e+00 4.849249999999999949e-01 1.467579999999999996e-01 -8.133669999999999511e-01 1.233989999999999948e-01 5.492439999999999545e-01 +1.403715327812139988e+09 -1.141305000000000014e+00 -2.775034999999999918e+00 4.808490000000000264e-01 1.558569999999999955e-01 -8.120110000000000383e-01 1.264599999999999891e-01 5.480460000000000331e-01 +1.403715327862139940e+09 -1.144819999999999949e+00 -2.747567999999999788e+00 4.765690000000000204e-01 1.651330000000000020e-01 -8.102519999999999722e-01 1.310580000000000078e-01 5.468509999999999760e-01 +1.403715327912139893e+09 -1.150395000000000056e+00 -2.721781000000000006e+00 4.721389999999999754e-01 1.749850000000000017e-01 -8.075900000000000301e-01 1.358300000000000063e-01 5.465600000000000458e-01 +1.403715327962140083e+09 -1.156873000000000040e+00 -2.696336000000000066e+00 4.675790000000000224e-01 1.849349999999999883e-01 -8.043660000000000254e-01 1.403840000000000088e-01 5.468889999999999585e-01 +1.403715328012140036e+09 -1.164120000000000044e+00 -2.670926999999999829e+00 4.633450000000000069e-01 1.938940000000000108e-01 -8.007840000000000513e-01 1.436979999999999924e-01 5.481789999999999718e-01 +1.403715328062139988e+09 -1.171926999999999941e+00 -2.645490000000000119e+00 4.593110000000000248e-01 2.007710000000000050e-01 -7.976689999999999614e-01 1.469100000000000128e-01 5.493940000000000490e-01 +1.403715328112139940e+09 -1.180563999999999947e+00 -2.620712999999999848e+00 4.559150000000000147e-01 2.063629999999999909e-01 -7.940190000000000303e-01 1.491760000000000030e-01 5.519910000000000094e-01 +1.403715328162139893e+09 -1.188989000000000074e+00 -2.595858000000000221e+00 4.531649999999999845e-01 2.106540000000000079e-01 -7.905370000000000452e-01 1.505090000000000039e-01 5.549979999999999913e-01 +1.403715328212140083e+09 -1.197394000000000069e+00 -2.571708000000000105e+00 4.509159999999999835e-01 2.139459999999999973e-01 -7.867910000000000181e-01 1.507600000000000051e-01 5.589800000000000324e-01 +1.403715328262140036e+09 -1.205125000000000002e+00 -2.547848999999999808e+00 4.489790000000000170e-01 2.157779999999999976e-01 -7.834729999999999750e-01 1.510579999999999978e-01 5.628419999999999535e-01 +1.403715328312139988e+09 -1.211815000000000087e+00 -2.524210000000000065e+00 4.472619999999999929e-01 2.168360000000000010e-01 -7.806729999999999503e-01 1.501240000000000074e-01 5.665630000000000388e-01 +1.403715328362139940e+09 -1.217314000000000007e+00 -2.500878999999999852e+00 4.453590000000000049e-01 2.169179999999999997e-01 -7.788460000000000383e-01 1.483389999999999986e-01 5.695099999999999607e-01 +1.403715328412139893e+09 -1.221297999999999995e+00 -2.477917000000000147e+00 4.438139999999999863e-01 2.162340000000000095e-01 -7.775429999999999842e-01 1.463740000000000041e-01 5.720530000000000337e-01 +1.403715328462140083e+09 -1.223141999999999951e+00 -2.454413999999999874e+00 4.423579999999999735e-01 2.152119999999999866e-01 -7.772550000000000292e-01 1.441209999999999991e-01 5.734000000000000208e-01 +1.403715328512140036e+09 -1.223919999999999897e+00 -2.432218999999999909e+00 4.408889999999999754e-01 2.137000000000000011e-01 -7.777600000000000069e-01 1.422279999999999933e-01 5.737529999999999575e-01 +1.403715328562139988e+09 -1.223338999999999954e+00 -2.410724999999999785e+00 4.388340000000000019e-01 2.125029999999999974e-01 -7.800219999999999931e-01 1.401860000000000051e-01 5.716259999999999675e-01 +1.403715328612139940e+09 -1.221460999999999908e+00 -2.390184000000000086e+00 4.364959999999999951e-01 2.131200000000000039e-01 -7.829359999999999653e-01 1.383759999999999990e-01 5.678410000000000402e-01 +1.403715328662139893e+09 -1.218382000000000076e+00 -2.370963000000000154e+00 4.341229999999999811e-01 2.148839999999999917e-01 -7.859930000000000527e-01 1.374229999999999896e-01 5.631650000000000267e-01 +1.403715328712140083e+09 -1.214258000000000060e+00 -2.353031999999999790e+00 4.322799999999999976e-01 2.172840000000000049e-01 -7.875170000000000226e-01 1.386010000000000020e-01 5.598159999999999803e-01 +1.403715328762140036e+09 -1.209000000000000075e+00 -2.336606999999999879e+00 4.298109999999999986e-01 2.207719999999999960e-01 -7.892529999999999824e-01 1.421630000000000116e-01 5.550939999999999763e-01 +1.403715328812139988e+09 -1.203146999999999966e+00 -2.321779999999999955e+00 4.277110000000000078e-01 2.261279999999999957e-01 -7.892470000000000319e-01 1.474540000000000017e-01 5.515539999999999887e-01 +1.403715328862139940e+09 -1.197076999999999947e+00 -2.308739999999999792e+00 4.256139999999999923e-01 2.327869999999999939e-01 -7.877110000000000500e-01 1.547010000000000052e-01 5.489889999999999493e-01 +1.403715328962140083e+09 -1.183646999999999894e+00 -2.286147000000000151e+00 4.216289999999999760e-01 2.517039999999999833e-01 -7.818340000000000289e-01 1.720740000000000047e-01 5.438479999999999981e-01 +1.403715329012140036e+09 -1.176187000000000094e+00 -2.276234999999999786e+00 4.195630000000000193e-01 2.633610000000000118e-01 -7.774339999999999584e-01 1.822850000000000026e-01 5.413029999999999786e-01 +1.403715329062139988e+09 -1.168187000000000086e+00 -2.266764999999999919e+00 4.170769999999999755e-01 2.759460000000000246e-01 -7.730590000000000517e-01 1.927119999999999944e-01 5.376760000000000428e-01 +1.403715329112139940e+09 -1.160617999999999927e+00 -2.257417999999999925e+00 4.146039999999999726e-01 2.884990000000000054e-01 -7.682109999999999772e-01 2.047430000000000083e-01 5.335729999999999640e-01 +1.403715329162139893e+09 -1.153491000000000044e+00 -2.250652999999999793e+00 4.115559999999999774e-01 3.020140000000000047e-01 -7.633029999999999538e-01 2.158980000000000066e-01 5.287190000000000500e-01 +1.403715329212140083e+09 -1.146303000000000072e+00 -2.243184999999999985e+00 4.080820000000000003e-01 3.155229999999999979e-01 -7.584689999999999488e-01 2.258270000000000000e-01 5.236150000000000526e-01 +1.403715329262140036e+09 -1.139194000000000040e+00 -2.236383000000000010e+00 4.039320000000000133e-01 3.284179999999999877e-01 -7.540909999999999558e-01 2.344449999999999867e-01 5.181919999999999860e-01 +1.403715329312139988e+09 -1.132112000000000007e+00 -2.229750000000000121e+00 3.996910000000000185e-01 3.390560000000000240e-01 -7.499540000000000095e-01 2.422580000000000011e-01 5.137319999999999665e-01 +1.403715329362139940e+09 -1.125747000000000053e+00 -2.223320999999999881e+00 3.947189999999999865e-01 3.477239999999999776e-01 -7.465509999999999646e-01 2.488789999999999891e-01 5.097140000000000004e-01 +1.403715329412139893e+09 -1.119566000000000061e+00 -2.217683000000000071e+00 3.887990000000000057e-01 3.545639999999999903e-01 -7.432720000000000438e-01 2.547699999999999965e-01 5.068759999999999932e-01 +1.403715329462140083e+09 -1.113680000000000003e+00 -2.211450999999999834e+00 3.812409999999999966e-01 3.604109999999999814e-01 -7.411689999999999667e-01 2.589719999999999800e-01 5.036920000000000286e-01 +1.403715329512140036e+09 -1.108567000000000080e+00 -2.206535999999999831e+00 3.743190000000000128e-01 3.652759999999999896e-01 -7.390510000000000135e-01 2.617680000000000007e-01 5.018510000000000471e-01 +1.403715329562139988e+09 -1.103186999999999918e+00 -2.201328000000000173e+00 3.669220000000000259e-01 3.688500000000000112e-01 -7.381720000000000503e-01 2.643889999999999851e-01 4.991499999999999826e-01 +1.403715329612139940e+09 -1.098198999999999925e+00 -2.196363999999999983e+00 3.606019999999999781e-01 3.721619999999999928e-01 -7.372319999999999984e-01 2.651839999999999753e-01 4.976570000000000160e-01 +1.403715329662139893e+09 -1.093947000000000003e+00 -2.192031000000000063e+00 3.550630000000000175e-01 3.737909999999999844e-01 -7.360959999999999726e-01 2.662829999999999919e-01 4.975299999999999723e-01 +1.403715329712140083e+09 -1.090225000000000000e+00 -2.190497000000000138e+00 3.510539999999999772e-01 3.746490000000000098e-01 -7.347449999999999815e-01 2.668650000000000189e-01 4.985680000000000112e-01 +1.403715329762140036e+09 -1.086141000000000023e+00 -2.186713000000000129e+00 3.444320000000000159e-01 3.743440000000000101e-01 -7.336369999999999836e-01 2.681049999999999822e-01 4.997630000000000128e-01 +1.403715329812139988e+09 -1.082580000000000098e+00 -2.183510000000000062e+00 3.373240000000000127e-01 3.739310000000000134e-01 -7.328379999999999894e-01 2.690029999999999921e-01 5.007620000000000404e-01 +1.403715329862139940e+09 -1.079163000000000094e+00 -2.180867000000000111e+00 3.297470000000000123e-01 3.731720000000000037e-01 -7.327510000000000412e-01 2.696160000000000223e-01 5.011240000000000139e-01 +1.403715329912139893e+09 -1.076168000000000013e+00 -2.179122000000000003e+00 3.218969999999999887e-01 3.724089999999999900e-01 -7.324760000000000160e-01 2.697459999999999858e-01 5.020229999999999970e-01 +1.403715329962140083e+09 -1.073638000000000092e+00 -2.177779000000000131e+00 3.138380000000000059e-01 3.717170000000000196e-01 -7.326270000000000282e-01 2.702339999999999742e-01 5.020550000000000290e-01 +1.403715330012140036e+09 -1.071349000000000107e+00 -2.177150000000000141e+00 3.057819999999999983e-01 3.717520000000000269e-01 -7.322400000000000020e-01 2.718880000000000186e-01 5.016979999999999773e-01 +1.403715330062139988e+09 -1.068866000000000094e+00 -2.176372999999999891e+00 2.963740000000000263e-01 3.724520000000000053e-01 -7.312769999999999548e-01 2.743249999999999855e-01 5.012579999999999814e-01 +1.403715330112139940e+09 -1.067215000000000025e+00 -2.175872000000000028e+00 2.863850000000000007e-01 3.740959999999999841e-01 -7.308700000000000196e-01 2.754329999999999834e-01 5.000170000000000448e-01 +1.403715330162139893e+09 -1.065528999999999948e+00 -2.174818000000000140e+00 2.754460000000000242e-01 3.769230000000000080e-01 -7.299970000000000070e-01 2.747640000000000082e-01 4.995379999999999820e-01 +1.403715330212140083e+09 -1.064376999999999907e+00 -2.174106000000000094e+00 2.647430000000000061e-01 3.797479999999999745e-01 -7.296690000000000120e-01 2.733970000000000011e-01 4.986260000000000137e-01 +1.403715330262140036e+09 -1.063598000000000043e+00 -2.173894000000000215e+00 2.540769999999999973e-01 3.821899999999999742e-01 -7.301370000000000360e-01 2.716049999999999853e-01 4.970530000000000226e-01 +1.403715330312139988e+09 -1.062910000000000021e+00 -2.172733000000000025e+00 2.433379999999999987e-01 3.841370000000000062e-01 -7.303049999999999820e-01 2.699630000000000085e-01 4.961990000000000012e-01 +1.403715330362139940e+09 -1.062381999999999938e+00 -2.172865999999999964e+00 2.330800000000000094e-01 3.852140000000000009e-01 -7.307360000000000522e-01 2.687760000000000149e-01 4.953719999999999790e-01 +1.403715330412139893e+09 -1.062062999999999979e+00 -2.173684999999999867e+00 2.240840000000000054e-01 3.851990000000000136e-01 -7.307979999999999476e-01 2.692499999999999893e-01 4.950359999999999761e-01 +1.403715330462140083e+09 -1.061881000000000075e+00 -2.174662000000000095e+00 2.175300000000000011e-01 3.843579999999999774e-01 -7.301959999999999562e-01 2.708479999999999777e-01 4.957059999999999800e-01 +1.403715330512140036e+09 -1.061868000000000034e+00 -2.174942999999999849e+00 2.128839999999999899e-01 3.831959999999999811e-01 -7.302889999999999660e-01 2.727069999999999772e-01 4.954489999999999728e-01 +1.403715330562139988e+09 -1.062240999999999991e+00 -2.176527999999999796e+00 2.117249999999999965e-01 3.833980000000000166e-01 -7.298679999999999612e-01 2.727660000000000085e-01 4.958810000000000162e-01 +1.403715330612139940e+09 -1.062802999999999942e+00 -2.178031999999999968e+00 2.143259999999999887e-01 3.819150000000000045e-01 -7.289999999999999813e-01 2.748280000000000167e-01 4.971619999999999928e-01 +1.403715330662139893e+09 -1.063309999999999977e+00 -2.179761000000000060e+00 2.203390000000000071e-01 3.790330000000000088e-01 -7.275390000000000468e-01 2.785639999999999783e-01 4.994239999999999791e-01 +1.403715330712140083e+09 -1.063377000000000017e+00 -2.180655999999999928e+00 2.289180000000000104e-01 3.759779999999999789e-01 -7.266730000000000134e-01 2.829720000000000013e-01 5.005129999999999857e-01 +1.403715330762140036e+09 -1.063531999999999922e+00 -2.181910999999999934e+00 2.390140000000000042e-01 3.734299999999999842e-01 -7.264789999999999859e-01 2.888279999999999736e-01 4.993560000000000221e-01 +1.403715330812139988e+09 -1.063504000000000005e+00 -2.182986999999999789e+00 2.493529999999999913e-01 3.727199999999999958e-01 -7.259609999999999674e-01 2.955209999999999781e-01 4.967170000000000196e-01 +1.403715330862139940e+09 -1.063376000000000099e+00 -2.183678000000000008e+00 2.599380000000000024e-01 3.756729999999999792e-01 -7.245669999999999611e-01 3.003330000000000166e-01 4.936329999999999885e-01 +1.403715330912139893e+09 -1.063245999999999913e+00 -2.183847999999999789e+00 2.708280000000000132e-01 3.801050000000000262e-01 -7.226089999999999458e-01 3.065240000000000187e-01 4.892850000000000255e-01 +1.403715330962140083e+09 -1.063633000000000051e+00 -2.183463000000000154e+00 2.803990000000000093e-01 3.860149999999999970e-01 -7.192939999999999889e-01 3.132989999999999942e-01 4.852330000000000254e-01 +1.403715331012140036e+09 -1.064756999999999953e+00 -2.182183999999999902e+00 2.898649999999999838e-01 3.933150000000000257e-01 -7.154500000000000304e-01 3.203650000000000109e-01 4.804180000000000117e-01 +1.403715331062139988e+09 -1.066540000000000044e+00 -2.179736999999999814e+00 2.995680000000000009e-01 4.012700000000000156e-01 -7.114620000000000388e-01 3.281029999999999780e-01 4.745030000000000081e-01 +1.403715331112139940e+09 -1.069229999999999903e+00 -2.176197000000000159e+00 3.102509999999999990e-01 4.105909999999999838e-01 -7.066599999999999548e-01 3.348309999999999897e-01 4.689720000000000000e-01 +1.403715331212140083e+09 -1.078753999999999991e+00 -2.166465000000000085e+00 3.351219999999999755e-01 4.329450000000000243e-01 -6.958720000000000461e-01 3.416779999999999817e-01 4.599750000000000227e-01 +1.403715331262140036e+09 -1.085992000000000068e+00 -2.160829000000000111e+00 3.491090000000000027e-01 4.429290000000000171e-01 -6.903040000000000287e-01 3.433789999999999898e-01 4.575859999999999927e-01 +1.403715331312139988e+09 -1.094106000000000023e+00 -2.154351000000000127e+00 3.644800000000000262e-01 4.526589999999999780e-01 -6.849960000000000493e-01 3.428959999999999786e-01 4.564019999999999744e-01 +1.403715331362139940e+09 -1.103197999999999901e+00 -2.147698000000000107e+00 3.815419999999999923e-01 4.614240000000000008e-01 -6.797159999999999869e-01 3.415790000000000215e-01 4.565049999999999941e-01 +1.403715331412139893e+09 -1.113229000000000024e+00 -2.141135999999999928e+00 3.999480000000000257e-01 4.678760000000000141e-01 -6.756280000000000063e-01 3.411489999999999800e-01 4.563289999999999846e-01 +1.403715331462140083e+09 -1.124017000000000044e+00 -2.134590999999999905e+00 4.187529999999999863e-01 4.717109999999999914e-01 -6.725830000000000419e-01 3.422529999999999739e-01 4.560529999999999862e-01 +1.403715331512140036e+09 -1.134964000000000084e+00 -2.128073999999999799e+00 4.375229999999999952e-01 4.751949999999999785e-01 -6.701909999999999812e-01 3.427459999999999951e-01 4.555859999999999910e-01 +1.403715331562139988e+09 -1.147426000000000057e+00 -2.123282999999999809e+00 4.553240000000000065e-01 4.773990000000000178e-01 -6.680869999999999864e-01 3.441549999999999887e-01 4.553099999999999925e-01 +1.403715331612139940e+09 -1.159124999999999961e+00 -2.116702999999999779e+00 4.730509999999999993e-01 4.787489999999999801e-01 -6.673700000000000188e-01 3.456239999999999868e-01 4.538280000000000092e-01 +1.403715331662139893e+09 -1.171143999999999963e+00 -2.110457999999999945e+00 4.906599999999999850e-01 4.799689999999999790e-01 -6.657690000000000552e-01 3.461380000000000012e-01 4.545009999999999883e-01 +1.403715331712140083e+09 -1.183516999999999930e+00 -2.104286000000000101e+00 5.076739999999999586e-01 4.816380000000000106e-01 -6.635950000000000459e-01 3.446949999999999736e-01 4.570029999999999926e-01 +1.403715331762140036e+09 -1.196150000000000047e+00 -2.098446000000000033e+00 5.237699999999999578e-01 4.833990000000000231e-01 -6.622329999999999606e-01 3.422560000000000047e-01 4.589469999999999938e-01 +1.403715331812139988e+09 -1.208660000000000068e+00 -2.092795000000000183e+00 5.387250000000000094e-01 4.837239999999999873e-01 -6.615090000000000137e-01 3.408260000000000178e-01 4.607120000000000104e-01 +1.403715331862139940e+09 -1.220769999999999911e+00 -2.087225999999999804e+00 5.525390000000000024e-01 4.827750000000000097e-01 -6.615860000000000074e-01 3.406939999999999968e-01 4.616930000000000200e-01 +1.403715331912139893e+09 -1.232793000000000028e+00 -2.082073999999999980e+00 5.653289999999999704e-01 4.818890000000000118e-01 -6.622890000000000166e-01 3.397560000000000024e-01 4.623010000000000175e-01 +1.403715331962140083e+09 -1.244521999999999906e+00 -2.077001999999999793e+00 5.754559999999999675e-01 4.806619999999999782e-01 -6.649500000000000410e-01 3.393939999999999735e-01 4.600190000000000112e-01 +1.403715332012140036e+09 -1.255978000000000039e+00 -2.072026000000000145e+00 5.827649999999999775e-01 4.779689999999999772e-01 -6.677009999999999890e-01 3.403700000000000059e-01 4.581149999999999944e-01 +1.403715332062139988e+09 -1.267379999999999951e+00 -2.066673999999999900e+00 5.864249999999999741e-01 4.762790000000000079e-01 -6.706809999999999716e-01 3.389039999999999830e-01 4.566069999999999851e-01 +1.403715332112139940e+09 -1.278941000000000106e+00 -2.062174000000000174e+00 5.877919999999999812e-01 4.747569999999999846e-01 -6.734339999999999771e-01 3.370029999999999970e-01 4.555440000000000045e-01 +1.403715332162139893e+09 -1.289887999999999924e+00 -2.056198999999999888e+00 5.859790000000000276e-01 4.714470000000000049e-01 -6.774869999999999504e-01 3.374500000000000277e-01 4.526319999999999788e-01 +1.403715332212140083e+09 -1.301800999999999986e+00 -2.052826000000000040e+00 5.856599999999999584e-01 4.672180000000000222e-01 -6.812420000000000142e-01 3.404260000000000064e-01 4.491390000000000104e-01 +1.403715332262140036e+09 -1.313995000000000024e+00 -2.050362999999999936e+00 5.860720000000000374e-01 4.631779999999999786e-01 -6.832709999999999617e-01 3.451049999999999951e-01 4.466649999999999787e-01 +1.403715332312139988e+09 -1.326748999999999956e+00 -2.048089000000000048e+00 5.871070000000000455e-01 4.603530000000000122e-01 -6.840199999999999614e-01 3.494809999999999861e-01 4.450339999999999852e-01 +1.403715332362139940e+09 -1.341155000000000097e+00 -2.047417999999999960e+00 5.878550000000000164e-01 4.603479999999999794e-01 -6.843909999999999716e-01 3.521790000000000198e-01 4.423329999999999762e-01 +1.403715332412139893e+09 -1.355738000000000110e+00 -2.045790999999999915e+00 5.897480000000000500e-01 4.623450000000000060e-01 -6.838990000000000347e-01 3.531219999999999914e-01 4.402539999999999787e-01 +1.403715332462140083e+09 -1.371539000000000064e+00 -2.044551999999999925e+00 5.918250000000000455e-01 4.653519999999999879e-01 -6.833660000000000290e-01 3.523729999999999918e-01 4.385109999999999841e-01 +1.403715332512140036e+09 -1.388574999999999893e+00 -2.043969000000000147e+00 5.940450000000000452e-01 4.681819999999999871e-01 -6.834170000000000522e-01 3.519880000000000231e-01 4.357190000000000230e-01 +1.403715332562139988e+09 -1.406848000000000098e+00 -2.044293000000000138e+00 5.961469999999999825e-01 4.712089999999999890e-01 -6.829169999999999963e-01 3.505409999999999915e-01 4.344049999999999856e-01 +1.403715332612139940e+09 -1.426439999999999930e+00 -2.045608000000000093e+00 5.989330000000000487e-01 4.725050000000000083e-01 -6.816710000000000269e-01 3.510590000000000099e-01 4.345350000000000046e-01 +1.403715332662139893e+09 -1.447173999999999960e+00 -2.047614999999999963e+00 6.022899999999999920e-01 4.731739999999999835e-01 -6.799709999999999921e-01 3.523530000000000273e-01 4.354219999999999757e-01 +1.403715332712140083e+09 -1.469379999999999908e+00 -2.050260999999999889e+00 6.061010000000000009e-01 4.742000000000000104e-01 -6.777590000000000003e-01 3.535050000000000137e-01 4.368199999999999861e-01 +1.403715332762140036e+09 -1.492493999999999987e+00 -2.053943999999999992e+00 6.100520000000000387e-01 4.762520000000000087e-01 -6.760880000000000223e-01 3.535880000000000134e-01 4.371090000000000253e-01 +1.403715332812139988e+09 -1.516645999999999939e+00 -2.058230000000000004e+00 6.140259999999999607e-01 4.791779999999999928e-01 -6.735050000000000203e-01 3.534539999999999904e-01 4.380060000000000064e-01 +1.403715332862139940e+09 -1.541684999999999972e+00 -2.063787000000000038e+00 6.175150000000000361e-01 4.828450000000000242e-01 -6.706560000000000299e-01 3.532919999999999949e-01 4.384810000000000096e-01 +1.403715332912139893e+09 -1.567164999999999919e+00 -2.070546999999999915e+00 6.220609999999999751e-01 4.843589999999999840e-01 -6.646050000000000013e-01 3.575070000000000192e-01 4.425890000000000102e-01 +1.403715332962140083e+09 -1.593229999999999924e+00 -2.077399000000000218e+00 6.274149999999999450e-01 4.848299999999999832e-01 -6.562080000000000135e-01 3.642389999999999795e-01 4.490669999999999940e-01 +1.403715333012140036e+09 -1.619215999999999989e+00 -2.084623000000000115e+00 6.327819999999999556e-01 4.853410000000000224e-01 -6.472550000000000248e-01 3.719089999999999896e-01 4.551810000000000023e-01 +1.403715333062139988e+09 -1.645723999999999965e+00 -2.091254999999999864e+00 6.375530000000000364e-01 4.859999999999999876e-01 -6.394229999999999636e-01 3.789480000000000071e-01 4.597180000000000155e-01 +1.403715333112139940e+09 -1.672179000000000082e+00 -2.096279000000000003e+00 6.413799999999999502e-01 4.869999999999999885e-01 -6.332149999999999723e-01 3.839540000000000175e-01 4.630870000000000264e-01 +1.403715333162139893e+09 -1.698290999999999995e+00 -2.099988999999999884e+00 6.442069999999999741e-01 4.885700000000000043e-01 -6.284680000000000266e-01 3.869619999999999727e-01 4.653889999999999971e-01 +1.403715333212140083e+09 -1.724223000000000061e+00 -2.101773000000000113e+00 6.454490000000000505e-01 4.902630000000000043e-01 -6.254760000000000320e-01 3.884380000000000055e-01 4.664099999999999913e-01 +1.403715333262140036e+09 -1.749810000000000088e+00 -2.101579000000000086e+00 6.451789999999999470e-01 4.925889999999999991e-01 -6.245540000000000536e-01 3.882749999999999813e-01 4.653289999999999926e-01 +1.403715333312139988e+09 -1.775114000000000081e+00 -2.100023000000000195e+00 6.439470000000000471e-01 4.951099999999999945e-01 -6.249919999999999920e-01 3.872209999999999819e-01 4.629360000000000142e-01 +1.403715333362139940e+09 -1.800189000000000039e+00 -2.096741000000000188e+00 6.417850000000000499e-01 4.977389999999999870e-01 -6.258479999999999599e-01 3.850049999999999861e-01 4.608050000000000201e-01 +1.403715333412139893e+09 -1.824723000000000095e+00 -2.092403000000000013e+00 6.391369999999999552e-01 5.001339999999999675e-01 -6.272349999999999870e-01 3.827280000000000126e-01 4.582160000000000122e-01 +1.403715333462140083e+09 -1.848784999999999901e+00 -2.086580000000000101e+00 6.360099999999999643e-01 5.017519999999999758e-01 -6.284910000000000219e-01 3.810790000000000011e-01 4.560949999999999727e-01 +1.403715333512140036e+09 -1.872352000000000016e+00 -2.079562000000000133e+00 6.331040000000000001e-01 5.020130000000000425e-01 -6.290280000000000316e-01 3.808219999999999938e-01 4.552820000000000200e-01 +1.403715333562139988e+09 -1.895634999999999959e+00 -2.071882000000000001e+00 6.302910000000000457e-01 5.014009999999999856e-01 -6.291179999999999550e-01 3.817039999999999877e-01 4.550930000000000253e-01 +1.403715333612139940e+09 -1.918576999999999977e+00 -2.063467999999999858e+00 6.270900000000000363e-01 5.011060000000000514e-01 -6.283830000000000249e-01 3.822059999999999902e-01 4.560100000000000264e-01 +1.403715333662139893e+09 -1.941113000000000088e+00 -2.054222000000000214e+00 6.226990000000000025e-01 5.020499999999999963e-01 -6.296220000000000150e-01 3.812539999999999818e-01 4.540560000000000151e-01 +1.403715333712140083e+09 -1.963281999999999972e+00 -2.043832000000000093e+00 6.175420000000000353e-01 5.039179999999999771e-01 -6.320440000000000502e-01 3.790240000000000276e-01 4.504750000000000143e-01 +1.403715333762140036e+09 -1.984928999999999943e+00 -2.032134000000000107e+00 6.118780000000000330e-01 5.065089999999999870e-01 -6.357920000000000238e-01 3.755089999999999817e-01 4.452090000000000214e-01 +1.403715333812139988e+09 -2.006317999999999824e+00 -2.019941000000000209e+00 6.064079999999999471e-01 5.093560000000000310e-01 -6.388099999999999890e-01 3.727519999999999722e-01 4.399250000000000105e-01 +1.403715333862139940e+09 -2.027559999999999807e+00 -2.007861999999999814e+00 6.018430000000000168e-01 5.128270000000000328e-01 -6.401440000000000463e-01 3.715319999999999734e-01 4.349569999999999825e-01 +1.403715333912139893e+09 -2.048658999999999786e+00 -1.996008999999999922e+00 5.981340000000000545e-01 5.164130000000000109e-01 -6.401440000000000463e-01 3.716180000000000039e-01 4.306189999999999740e-01 +1.403715333962140083e+09 -2.069087000000000121e+00 -1.984263000000000110e+00 5.954949999999999966e-01 5.205659999999999732e-01 -6.380980000000000540e-01 3.723810000000000175e-01 4.279890000000000083e-01 +1.403715334012140036e+09 -2.089726000000000194e+00 -1.973994999999999944e+00 5.939619999999999900e-01 5.241980000000000528e-01 -6.354349999999999721e-01 3.752269999999999772e-01 4.250220000000000109e-01 +1.403715334062139988e+09 -2.110336999999999907e+00 -1.964787999999999979e+00 5.930250000000000243e-01 5.280610000000000026e-01 -6.327880000000000171e-01 3.783420000000000116e-01 4.214120000000000088e-01 +1.403715334112139940e+09 -2.131266000000000105e+00 -1.956029999999999935e+00 5.927280000000000326e-01 5.315530000000000532e-01 -6.301330000000000542e-01 3.812800000000000078e-01 4.183419999999999916e-01 +1.403715334162139893e+09 -2.152601999999999904e+00 -1.948093000000000075e+00 5.929710000000000258e-01 5.354400000000000270e-01 -6.275539999999999452e-01 3.832420000000000271e-01 4.154570000000000207e-01 +1.403715334212140083e+09 -2.174617000000000022e+00 -1.940322000000000102e+00 5.937639999999999585e-01 5.384370000000000545e-01 -6.257260000000000044e-01 3.851939999999999809e-01 4.125269999999999770e-01 +1.403715334262140036e+09 -2.196903999999999968e+00 -1.933292999999999928e+00 5.950739999999999919e-01 5.411080000000000334e-01 -6.242919999999999581e-01 3.865049999999999875e-01 4.099700000000000011e-01 +1.403715334312139988e+09 -2.219657000000000213e+00 -1.926913000000000098e+00 5.964260000000000117e-01 5.430719999999999992e-01 -6.224880000000000413e-01 3.879799999999999915e-01 4.087210000000000010e-01 +1.403715334362139940e+09 -2.242166999999999799e+00 -1.921103999999999923e+00 5.974770000000000358e-01 5.450080000000000480e-01 -6.210980000000000389e-01 3.886789999999999967e-01 4.075929999999999831e-01 +1.403715334412139893e+09 -2.265948999999999991e+00 -1.916037999999999908e+00 5.987350000000000172e-01 5.463029999999999831e-01 -6.197909999999999808e-01 3.893800000000000039e-01 4.071790000000000131e-01 +1.403715334462140083e+09 -2.290125000000000188e+00 -1.911699999999999955e+00 5.996569999999999956e-01 5.472329999999999695e-01 -6.187789999999999679e-01 3.902930000000000010e-01 4.065969999999999862e-01 +1.403715334512140036e+09 -2.314807000000000059e+00 -1.908015999999999934e+00 6.005300000000000082e-01 5.478300000000000392e-01 -6.178310000000000191e-01 3.909230000000000205e-01 4.066279999999999895e-01 +1.403715334562139988e+09 -2.339767000000000152e+00 -1.904835999999999974e+00 6.014369999999999994e-01 5.482650000000000023e-01 -6.163140000000000285e-01 3.917419999999999791e-01 4.075540000000000274e-01 +1.403715334612139940e+09 -2.364863000000000159e+00 -1.902064999999999895e+00 6.018029999999999768e-01 5.496189999999999687e-01 -6.148569999999999869e-01 3.914170000000000149e-01 4.082439999999999958e-01 +1.403715334662139893e+09 -2.390302999999999845e+00 -1.899834999999999940e+00 6.022319999999999895e-01 5.511639999999999873e-01 -6.135140000000000038e-01 3.902180000000000093e-01 4.093280000000000252e-01 +1.403715334712140083e+09 -2.415802999999999923e+00 -1.897998000000000074e+00 6.023800000000000265e-01 5.515569999999999640e-01 -6.126099999999999879e-01 3.901209999999999956e-01 4.102430000000000243e-01 +1.403715334762140036e+09 -2.441076999999999941e+00 -1.896293000000000006e+00 6.022939999999999960e-01 5.518729999999999469e-01 -6.118679999999999675e-01 3.898619999999999863e-01 4.111710000000000087e-01 +1.403715334812139988e+09 -2.466403000000000123e+00 -1.895588999999999968e+00 6.024990000000000068e-01 5.522909999999999764e-01 -6.115340000000000220e-01 3.890810000000000102e-01 4.118459999999999899e-01 +1.403715334862139940e+09 -2.491136000000000017e+00 -1.896725999999999912e+00 6.016150000000000109e-01 5.524440000000000461e-01 -6.109729999999999883e-01 3.885799999999999810e-01 4.129430000000000045e-01 +1.403715334912139893e+09 -2.516575000000000006e+00 -1.897102999999999984e+00 6.012760000000000327e-01 5.525200000000000111e-01 -6.107420000000000071e-01 3.881839999999999735e-01 4.135570000000000079e-01 +1.403715334962140083e+09 -2.541923999999999850e+00 -1.898991000000000096e+00 6.004909999999999970e-01 5.529140000000000166e-01 -6.109400000000000386e-01 3.870140000000000247e-01 4.138339999999999796e-01 +1.403715335012140036e+09 -2.566797999999999913e+00 -1.900427000000000088e+00 5.994070000000000231e-01 5.529770000000000518e-01 -6.106390000000000429e-01 3.870339999999999892e-01 4.141759999999999886e-01 +1.403715335062139988e+09 -2.591276000000000135e+00 -1.902288999999999897e+00 5.981910000000000283e-01 5.538779999999999815e-01 -6.102800000000000447e-01 3.868440000000000212e-01 4.136759999999999882e-01 +1.403715335112139940e+09 -2.615394000000000219e+00 -1.904833999999999916e+00 5.971340000000000536e-01 5.546759999999999469e-01 -6.097690000000000055e-01 3.867729999999999779e-01 4.134280000000000177e-01 +1.403715335162139893e+09 -2.639174999999999827e+00 -1.908109999999999973e+00 5.962140000000000217e-01 5.555600000000000538e-01 -6.089949999999999530e-01 3.864529999999999910e-01 4.136810000000000209e-01 +1.403715335212140083e+09 -2.662529000000000146e+00 -1.911771000000000109e+00 5.943889999999999452e-01 5.559939999999999882e-01 -6.088909999999999600e-01 3.863770000000000260e-01 4.133220000000000227e-01 +1.403715335262140036e+09 -2.685331999999999830e+00 -1.918331999999999926e+00 5.934399999999999675e-01 5.574329999999999563e-01 -6.078829999999999512e-01 3.861780000000000213e-01 4.130530000000000035e-01 +1.403715335312139988e+09 -2.707707000000000086e+00 -1.923229999999999995e+00 5.919259999999999522e-01 5.590870000000000006e-01 -6.064100000000000046e-01 3.869299999999999962e-01 4.122790000000000066e-01 +1.403715335362139940e+09 -2.729496999999999840e+00 -1.928598999999999952e+00 5.903880000000000239e-01 5.612460000000000226e-01 -6.042739999999999778e-01 3.884659999999999780e-01 4.110349999999999837e-01 +1.403715335412139893e+09 -2.750798000000000076e+00 -1.934542999999999902e+00 5.887710000000000443e-01 5.639720000000000288e-01 -6.014469999999999539e-01 3.904329999999999745e-01 4.095849999999999769e-01 +1.403715335462140083e+09 -2.771545999999999843e+00 -1.940833000000000030e+00 5.869109999999999605e-01 5.667550000000000088e-01 -5.988350000000000062e-01 3.925000000000000155e-01 4.075900000000000079e-01 +1.403715335512140036e+09 -2.791955000000000187e+00 -1.947778000000000009e+00 5.851269999999999527e-01 5.684909999999999686e-01 -5.973469999999999613e-01 3.953900000000000192e-01 4.045509999999999939e-01 +1.403715335562139988e+09 -2.812006999999999923e+00 -1.955446999999999935e+00 5.843810000000000393e-01 5.693449999999999900e-01 -5.961070000000000535e-01 3.988880000000000203e-01 4.017359999999999820e-01 +1.403715335612139940e+09 -2.831747000000000014e+00 -1.963324000000000069e+00 5.827839999999999687e-01 5.706639999999999491e-01 -5.946919999999999984e-01 4.018300000000000205e-01 3.990199999999999858e-01 +1.403715335712140083e+09 -2.869946000000000108e+00 -1.980561000000000016e+00 5.796550000000000313e-01 5.765540000000000109e-01 -5.893049999999999677e-01 4.068200000000000149e-01 3.934500000000000219e-01 +1.403715335762140036e+09 -2.888837999999999795e+00 -1.989697999999999967e+00 5.781539999999999457e-01 5.803260000000000085e-01 -5.852760000000000185e-01 4.096060000000000256e-01 3.910210000000000075e-01 +1.403715335812139988e+09 -2.908018000000000214e+00 -1.999193999999999916e+00 5.764029999999999987e-01 5.839649999999999563e-01 -5.814589999999999481e-01 4.119090000000000251e-01 3.888719999999999954e-01 +1.403715335862139940e+09 -2.927242000000000122e+00 -2.009071000000000051e+00 5.742979999999999752e-01 5.870999999999999552e-01 -5.778910000000000435e-01 4.142100000000000226e-01 3.870199999999999751e-01 +1.403715335912139893e+09 -2.946431000000000022e+00 -2.018171000000000159e+00 5.722159999999999469e-01 5.901610000000000467e-01 -5.745519999999999516e-01 4.159840000000000204e-01 3.854310000000000236e-01 +1.403715335962140083e+09 -2.965606999999999882e+00 -2.028650999999999982e+00 5.704230000000000134e-01 5.916789999999999550e-01 -5.710250000000000048e-01 4.195729999999999738e-01 3.844529999999999892e-01 +1.403715336012140036e+09 -2.984859999999999847e+00 -2.039289000000000129e+00 5.686860000000000248e-01 5.938539999999999930e-01 -5.669039999999999635e-01 4.217529999999999890e-01 3.848139999999999894e-01 +1.403715336062139988e+09 -3.003943000000000030e+00 -2.050149000000000221e+00 5.672460000000000280e-01 5.944939999999999669e-01 -5.633610000000000007e-01 4.250249999999999861e-01 3.854279999999999928e-01 +1.403715336112139940e+09 -3.022940000000000182e+00 -2.061106000000000105e+00 5.656870000000000509e-01 5.943720000000000114e-01 -5.602620000000000378e-01 4.286110000000000197e-01 3.861620000000000053e-01 +1.403715336162139893e+09 -3.042025999999999897e+00 -2.071505999999999847e+00 5.640220000000000233e-01 5.944530000000000092e-01 -5.568729999999999514e-01 4.312199999999999922e-01 3.880299999999999860e-01 +1.403715336212140083e+09 -3.060643999999999920e+00 -2.082053000000000154e+00 5.626039999999999930e-01 5.938020000000000520e-01 -5.544820000000000304e-01 4.343799999999999883e-01 3.889250000000000207e-01 +1.403715336262140036e+09 -3.079263000000000083e+00 -2.091749000000000080e+00 5.605390000000000095e-01 5.940769999999999662e-01 -5.536510000000000042e-01 4.360689999999999844e-01 3.877970000000000028e-01 +1.403715336312139988e+09 -3.097987999999999964e+00 -2.101086000000000009e+00 5.584419999999999940e-01 5.958750000000000435e-01 -5.536170000000000258e-01 4.351809999999999845e-01 3.860819999999999808e-01 +1.403715336362139940e+09 -3.117512000000000061e+00 -2.108913999999999955e+00 5.563770000000000104e-01 5.984000000000000430e-01 -5.542510000000000492e-01 4.335060000000000024e-01 3.831390000000000073e-01 +1.403715336412139893e+09 -3.136277000000000204e+00 -2.117379000000000122e+00 5.541150000000000242e-01 6.006979999999999542e-01 -5.545900000000000274e-01 4.315189999999999859e-01 3.812920000000000198e-01 +1.403715336462140083e+09 -3.154539999999999900e+00 -2.125983999999999874e+00 5.527030000000000554e-01 6.032619999999999649e-01 -5.540869999999999962e-01 4.290390000000000037e-01 3.807740000000000014e-01 +1.403715336512140036e+09 -3.172225000000000072e+00 -2.134841000000000211e+00 5.516170000000000240e-01 6.043650000000000411e-01 -5.544339999999999824e-01 4.281809999999999783e-01 3.794819999999999860e-01 +1.403715336562139988e+09 -3.190074000000000076e+00 -2.143510000000000026e+00 5.506990000000000496e-01 6.046660000000000368e-01 -5.544390000000000152e-01 4.279470000000000218e-01 3.792590000000000128e-01 +1.403715336612139940e+09 -3.207756999999999969e+00 -2.152292000000000094e+00 5.500969999999999471e-01 6.044629999999999725e-01 -5.545069999999999721e-01 4.284000000000000030e-01 3.789730000000000043e-01 +1.403715336662139893e+09 -3.225057000000000063e+00 -2.161312000000000122e+00 5.494799999999999685e-01 6.045080000000000453e-01 -5.546729999999999716e-01 4.280640000000000001e-01 3.790370000000000128e-01 +1.403715336712140083e+09 -3.241429999999999811e+00 -2.170849000000000029e+00 5.492289999999999672e-01 6.043849999999999500e-01 -5.547800000000000509e-01 4.277650000000000063e-01 3.794139999999999735e-01 +1.403715336762140036e+09 -3.257849999999999913e+00 -2.180420999999999943e+00 5.492399999999999505e-01 6.041349999999999776e-01 -5.550110000000000321e-01 4.275619999999999976e-01 3.797030000000000127e-01 +1.403715336812139988e+09 -3.273737999999999815e+00 -2.190205000000000179e+00 5.498899999999999899e-01 6.042380000000000528e-01 -5.546459999999999724e-01 4.270519999999999872e-01 3.806459999999999844e-01 +1.403715336862139940e+09 -3.288959000000000188e+00 -2.200292000000000137e+00 5.511359999999999593e-01 6.040079999999999893e-01 -5.542970000000000397e-01 4.269859999999999767e-01 3.815930000000000155e-01 +1.403715336912139893e+09 -3.303475000000000161e+00 -2.210847999999999924e+00 5.530439999999999801e-01 6.038099999999999579e-01 -5.541500000000000314e-01 4.271260000000000057e-01 3.819609999999999950e-01 +1.403715336962140083e+09 -3.315418000000000198e+00 -2.222745000000000193e+00 5.550640000000000018e-01 6.037120000000000264e-01 -5.533850000000000158e-01 4.269470000000000209e-01 3.834230000000000138e-01 +1.403715337012140036e+09 -3.329553000000000207e+00 -2.233658999999999839e+00 5.587100000000000399e-01 6.040109999999999646e-01 -5.528100000000000236e-01 4.269339999999999802e-01 3.837960000000000260e-01 +1.403715337062139988e+09 -3.342699999999999783e+00 -2.244606000000000101e+00 5.632779999999999454e-01 6.054260000000000197e-01 -5.515290000000000470e-01 4.267500000000000182e-01 3.836129999999999818e-01 +1.403715337112139940e+09 -3.354551999999999978e+00 -2.255669000000000146e+00 5.677389999999999937e-01 6.076880000000000059e-01 -5.505640000000000533e-01 4.269439999999999902e-01 3.811999999999999833e-01 +1.403715337162139893e+09 -3.366016000000000119e+00 -2.266360000000000152e+00 5.727219999999999533e-01 6.116279999999999495e-01 -5.479579999999999451e-01 4.266989999999999950e-01 3.789219999999999811e-01 +1.403715337212140083e+09 -3.376675999999999789e+00 -2.277417999999999942e+00 5.775150000000000006e-01 6.153779999999999806e-01 -5.454890000000000017e-01 4.279470000000000218e-01 3.749839999999999840e-01 +1.403715337262140036e+09 -3.384921999999999986e+00 -2.289429000000000158e+00 5.806940000000000435e-01 6.189930000000000154e-01 -5.429669999999999774e-01 4.306030000000000135e-01 3.696150000000000269e-01 +1.403715337312139988e+09 -3.394041000000000086e+00 -2.301915000000000155e+00 5.850009999999999932e-01 6.231569999999999609e-01 -5.400289999999999813e-01 4.336400000000000254e-01 3.633179999999999743e-01 +1.403715337362139940e+09 -3.403151999999999955e+00 -2.314837999999999951e+00 5.890039999999999720e-01 6.267930000000000446e-01 -5.375879999999999548e-01 4.367639999999999856e-01 3.568839999999999790e-01 +1.403715337412139893e+09 -3.412455000000000016e+00 -2.328399999999999803e+00 5.928999999999999826e-01 6.296920000000000295e-01 -5.355199999999999960e-01 4.400510000000000255e-01 3.508020000000000027e-01 +1.403715337462140083e+09 -3.421727000000000185e+00 -2.342632000000000048e+00 5.968259999999999676e-01 6.311949999999999505e-01 -5.331470000000000375e-01 4.444949999999999735e-01 3.460790000000000255e-01 +1.403715337512140036e+09 -3.431318999999999786e+00 -2.357473999999999847e+00 6.005470000000000530e-01 6.313659999999999828e-01 -5.321860000000000479e-01 4.497570000000000179e-01 3.404030000000000111e-01 +1.403715337562139988e+09 -3.440929999999999822e+00 -2.373740999999999879e+00 6.028949999999999587e-01 6.313969999999999860e-01 -5.302050000000000374e-01 4.542740000000000111e-01 3.374249999999999750e-01 +1.403715337612139940e+09 -3.451754000000000211e+00 -2.390242000000000200e+00 6.066639999999999810e-01 6.330160000000000231e-01 -5.270139999999999825e-01 4.560620000000000229e-01 3.369789999999999730e-01 +1.403715337662139893e+09 -3.463191000000000130e+00 -2.407332999999999945e+00 6.104089999999999794e-01 6.343199999999999950e-01 -5.233689999999999731e-01 4.574989999999999890e-01 3.382569999999999744e-01 +1.403715337712140083e+09 -3.474975000000000147e+00 -2.424557000000000073e+00 6.134889999999999510e-01 6.358800000000000008e-01 -5.204750000000000210e-01 4.578289999999999860e-01 3.393439999999999790e-01 +1.403715337762140036e+09 -3.487153000000000169e+00 -2.442644000000000037e+00 6.165899999999999714e-01 6.370240000000000347e-01 -5.184539999999999704e-01 4.580239999999999867e-01 3.400299999999999989e-01 +1.403715337812139988e+09 -3.499598999999999904e+00 -2.461193000000000186e+00 6.197080000000000366e-01 6.374469999999999859e-01 -5.169949999999999823e-01 4.582809999999999939e-01 3.411100000000000243e-01 +1.403715337862139940e+09 -3.512010000000000076e+00 -2.479954999999999909e+00 6.231050000000000200e-01 6.373980000000000201e-01 -5.160409999999999719e-01 4.582209999999999894e-01 3.427229999999999999e-01 +1.403715337912139893e+09 -3.524554000000000187e+00 -2.498809000000000058e+00 6.265830000000000011e-01 6.377119999999999456e-01 -5.151559999999999473e-01 4.571410000000000196e-01 3.449050000000000171e-01 +1.403715337962140083e+09 -3.537252000000000063e+00 -2.518031999999999826e+00 6.301339999999999719e-01 6.376100000000000101e-01 -5.148749999999999716e-01 4.560569999999999902e-01 3.469419999999999726e-01 +1.403715338012140036e+09 -3.549916000000000071e+00 -2.536582999999999810e+00 6.337599999999999900e-01 6.363760000000000527e-01 -5.155239999999999823e-01 4.559940000000000104e-01 3.483260000000000245e-01 +1.403715338062139988e+09 -3.562635999999999914e+00 -2.554882000000000097e+00 6.371930000000000094e-01 6.346030000000000282e-01 -5.169829999999999703e-01 4.562570000000000237e-01 3.490500000000000269e-01 +1.403715338112139940e+09 -3.575164000000000009e+00 -2.572973000000000177e+00 6.406230000000000535e-01 6.326249999999999929e-01 -5.185729999999999507e-01 4.567720000000000113e-01 3.496099999999999763e-01 +1.403715338162139893e+09 -3.587772000000000183e+00 -2.591397999999999868e+00 6.433999999999999719e-01 6.317720000000000002e-01 -5.191059999999999564e-01 4.572530000000000205e-01 3.497339999999999893e-01 +1.403715338212140083e+09 -3.599908999999999804e+00 -2.609808000000000128e+00 6.458199999999999497e-01 6.312330000000000441e-01 -5.194140000000000423e-01 4.581290000000000084e-01 3.491020000000000234e-01 +1.403715338262140036e+09 -3.611585999999999963e+00 -2.628384000000000054e+00 6.479780000000000539e-01 6.310050000000000381e-01 -5.192039999999999988e-01 4.597700000000000120e-01 3.476679999999999771e-01 +1.403715338312139988e+09 -3.622923000000000116e+00 -2.646847000000000172e+00 6.496389999999999665e-01 6.316100000000000048e-01 -5.187420000000000364e-01 4.613059999999999938e-01 3.452120000000000188e-01 +1.403715338362139940e+09 -3.634428000000000214e+00 -2.665048000000000084e+00 6.518929999999999447e-01 6.326490000000000169e-01 -5.179449999999999887e-01 4.635750000000000148e-01 3.414479999999999738e-01 +1.403715338412139893e+09 -3.646109000000000044e+00 -2.683771999999999824e+00 6.542130000000000445e-01 6.346030000000000282e-01 -5.151679999999999593e-01 4.664200000000000013e-01 3.381319999999999881e-01 +1.403715338462140083e+09 -3.658647000000000205e+00 -2.702567999999999859e+00 6.564269999999999827e-01 6.374229999999999619e-01 -5.115870000000000140e-01 4.691670000000000007e-01 3.344449999999999923e-01 +1.403715338512140036e+09 -3.671456000000000053e+00 -2.721512000000000153e+00 6.591970000000000329e-01 6.411919999999999842e-01 -5.073339999999999517e-01 4.717720000000000247e-01 3.300259999999999860e-01 +1.403715338562139988e+09 -3.684953999999999841e+00 -2.741217999999999932e+00 6.625720000000000498e-01 6.457359999999999767e-01 -5.009390000000000231e-01 4.744220000000000104e-01 3.271229999999999971e-01 +1.403715338612139940e+09 -3.698771999999999949e+00 -2.760288000000000075e+00 6.665489999999999471e-01 6.508659999999999446e-01 -4.936470000000000025e-01 4.770209999999999728e-01 3.242479999999999807e-01 +1.403715338662139893e+09 -3.712794999999999845e+00 -2.779590999999999923e+00 6.708680000000000199e-01 6.562959999999999905e-01 -4.856099999999999861e-01 4.800099999999999922e-01 3.210120000000000196e-01 +1.403715338712140083e+09 -3.727323999999999860e+00 -2.798718000000000039e+00 6.752320000000000544e-01 6.619270000000000431e-01 -4.774360000000000270e-01 4.827500000000000124e-01 3.175859999999999794e-01 +1.403715338762140036e+09 -3.743097999999999814e+00 -2.819110999999999922e+00 6.797590000000000021e-01 6.673360000000000403e-01 -4.702459999999999973e-01 4.853459999999999996e-01 3.130020000000000024e-01 +1.403715338812139988e+09 -3.758516000000000190e+00 -2.837797999999999821e+00 6.834829999999999517e-01 6.728969999999999674e-01 -4.634510000000000018e-01 4.862870000000000248e-01 3.097550000000000026e-01 +1.403715338862139940e+09 -3.774287000000000170e+00 -2.856802000000000064e+00 6.873369999999999758e-01 6.768960000000000532e-01 -4.580400000000000027e-01 4.878970000000000251e-01 3.065399999999999792e-01 +1.403715338912139893e+09 -3.790058000000000149e+00 -2.876095999999999986e+00 6.906790000000000429e-01 6.806309999999999860e-01 -4.538809999999999789e-01 4.886420000000000208e-01 3.032520000000000215e-01 +1.403715338962140083e+09 -3.806334000000000106e+00 -2.894924000000000053e+00 6.935999999999999943e-01 6.847109999999999586e-01 -4.495540000000000092e-01 4.881510000000000016e-01 3.012980000000000103e-01 +1.403715339012140036e+09 -3.822382000000000168e+00 -2.913815000000000044e+00 6.956750000000000433e-01 6.881399999999999739e-01 -4.466640000000000055e-01 4.874910000000000077e-01 2.988430000000000253e-01 +1.403715339062139988e+09 -3.838470000000000049e+00 -2.932840000000000114e+00 6.971840000000000259e-01 6.912209999999999743e-01 -4.443900000000000072e-01 4.865450000000000053e-01 2.966590000000000060e-01 +1.403715339112139940e+09 -3.854575999999999780e+00 -2.952468999999999788e+00 6.981070000000000331e-01 6.941249999999999920e-01 -4.415399999999999880e-01 4.852179999999999827e-01 2.963060000000000138e-01 +1.403715339162139893e+09 -3.870775000000000077e+00 -2.971499999999999808e+00 6.986590000000000300e-01 6.965529999999999777e-01 -4.383569999999999967e-01 4.842139999999999778e-01 2.969749999999999890e-01 +1.403715339212140083e+09 -3.885934000000000221e+00 -2.991448999999999803e+00 6.985249999999999515e-01 6.987809999999999855e-01 -4.354469999999999730e-01 4.827750000000000097e-01 2.983609999999999873e-01 +1.403715339262140036e+09 -3.900281000000000109e+00 -3.011550999999999867e+00 6.978389999999999871e-01 6.996590000000000309e-01 -4.336610000000000187e-01 4.828959999999999919e-01 2.987090000000000023e-01 +1.403715339312139988e+09 -3.914255999999999958e+00 -3.032369000000000092e+00 6.977849999999999886e-01 6.987839999999999607e-01 -4.331200000000000050e-01 4.851329999999999809e-01 2.979160000000000141e-01 +1.403715339362139940e+09 -3.927487000000000172e+00 -3.053119999999999834e+00 6.969570000000000487e-01 6.973460000000000214e-01 -4.327710000000000168e-01 4.876809999999999756e-01 2.976329999999999809e-01 +1.403715339412139893e+09 -3.940507000000000204e+00 -3.073765999999999998e+00 6.954599999999999671e-01 6.958349999999999813e-01 -4.333139999999999770e-01 4.898779999999999801e-01 2.967710000000000070e-01 +1.403715339462140083e+09 -3.953295999999999921e+00 -3.094111999999999973e+00 6.934609999999999941e-01 6.945590000000000375e-01 -4.340800000000000214e-01 4.912150000000000127e-01 2.964280000000000248e-01 +1.403715339512140036e+09 -3.965923000000000087e+00 -3.114342000000000166e+00 6.908490000000000464e-01 6.928699999999999859e-01 -4.346340000000000203e-01 4.926769999999999761e-01 2.971429999999999905e-01 +1.403715339562139988e+09 -3.978508000000000155e+00 -3.133989000000000136e+00 6.867020000000000346e-01 6.917550000000000088e-01 -4.362800000000000011e-01 4.931829999999999825e-01 2.964890000000000025e-01 +1.403715339612139940e+09 -3.990590000000000082e+00 -3.153700999999999866e+00 6.820150000000000379e-01 6.922859999999999570e-01 -4.382699999999999929e-01 4.909439999999999915e-01 2.960280000000000133e-01 +1.403715339662139893e+09 -4.002494000000000440e+00 -3.173179000000000194e+00 6.769730000000000469e-01 6.929779999999999829e-01 -4.390519999999999978e-01 4.880220000000000113e-01 2.980769999999999809e-01 +1.403715339712140083e+09 -4.014052000000000398e+00 -3.192702999999999847e+00 6.716830000000000300e-01 6.945109999999999895e-01 -4.385169999999999901e-01 4.839450000000000141e-01 3.019169999999999909e-01 +1.403715339762140036e+09 -4.025101000000000262e+00 -3.212439999999999962e+00 6.662670000000000536e-01 6.951950000000000074e-01 -4.368150000000000088e-01 4.807390000000000274e-01 3.078730000000000078e-01 +1.403715339812139988e+09 -4.035103000000000328e+00 -3.232086999999999932e+00 6.603999999999999870e-01 6.961410000000000098e-01 -4.347559999999999758e-01 4.770829999999999793e-01 3.142710000000000226e-01 +1.403715339862139940e+09 -4.044277000000000122e+00 -3.251107999999999887e+00 6.543799999999999617e-01 6.967919999999999670e-01 -4.323509999999999853e-01 4.743740000000000179e-01 3.201910000000000034e-01 +1.403715339912139893e+09 -4.051657999999999760e+00 -3.269979999999999887e+00 6.483299999999999619e-01 6.980429999999999691e-01 -4.289020000000000055e-01 4.726440000000000086e-01 3.246339999999999781e-01 +1.403715339962140083e+09 -4.056961000000000261e+00 -3.288142000000000120e+00 6.420360000000000511e-01 7.005360000000000475e-01 -4.246909999999999852e-01 4.710179999999999922e-01 3.271519999999999984e-01 +1.403715340012140036e+09 -4.060402999999999984e+00 -3.305426000000000197e+00 6.364610000000000545e-01 7.038079999999999892e-01 -4.189970000000000083e-01 4.698439999999999839e-01 3.291549999999999754e-01 +1.403715340062139988e+09 -4.061067000000000426e+00 -3.321830999999999978e+00 6.316319999999999713e-01 7.073190000000000310e-01 -4.134689999999999754e-01 4.703430000000000111e-01 3.279030000000000000e-01 +1.403715340112139940e+09 -4.059479999999999755e+00 -3.337035999999999891e+00 6.282109999999999639e-01 7.108320000000000194e-01 -4.080940000000000123e-01 4.724470000000000058e-01 3.239920000000000022e-01 +1.403715340162139893e+09 -4.055737999999999843e+00 -3.350734000000000101e+00 6.267979999999999663e-01 7.139140000000000486e-01 -4.020020000000000260e-01 4.763310000000000044e-01 3.191069999999999740e-01 +1.403715340212140083e+09 -4.049904999999999866e+00 -3.362785999999999831e+00 6.269209999999999505e-01 7.170029999999999459e-01 -3.966470000000000273e-01 4.817199999999999815e-01 3.106840000000000157e-01 +1.403715340262140036e+09 -4.041400999999999577e+00 -3.374125999999999959e+00 6.288690000000000113e-01 7.199389999999999956e-01 -3.908800000000000052e-01 4.881329999999999836e-01 3.010430000000000050e-01 +1.403715340312139988e+09 -4.030568999999999846e+00 -3.384691000000000116e+00 6.329059999999999686e-01 7.236770000000000147e-01 -3.836899999999999755e-01 4.946150000000000269e-01 2.905690000000000217e-01 +1.403715340362139940e+09 -4.018220999999999599e+00 -3.394552000000000014e+00 6.388430000000000497e-01 7.275249999999999773e-01 -3.762650000000000161e-01 5.017909999999999870e-01 2.780980000000000119e-01 +1.403715340412139893e+09 -4.005143999999999593e+00 -3.403735999999999873e+00 6.463170000000000304e-01 7.323790000000000022e-01 -3.671869999999999856e-01 5.076310000000000544e-01 2.666560000000000041e-01 +1.403715340462140083e+09 -3.991411999999999960e+00 -3.412189999999999834e+00 6.547610000000000374e-01 7.376829999999999776e-01 -3.584089999999999776e-01 5.116220000000000212e-01 2.561419999999999808e-01 +1.403715340512140036e+09 -3.977805000000000035e+00 -3.420303000000000093e+00 6.632799999999999807e-01 7.424110000000000431e-01 -3.507100000000000217e-01 5.146810000000000551e-01 2.468430000000000069e-01 +1.403715340562139988e+09 -3.963709000000000149e+00 -3.428834999999999855e+00 6.707279999999999909e-01 7.467270000000000296e-01 -3.454590000000000161e-01 5.167669999999999764e-01 2.366640000000000132e-01 +1.403715340612139940e+09 -3.949842999999999993e+00 -3.437431000000000125e+00 6.775489999999999569e-01 7.499000000000000110e-01 -3.401230000000000087e-01 5.191249999999999476e-01 2.290739999999999998e-01 +1.403715340662139893e+09 -3.935938000000000159e+00 -3.446489000000000136e+00 6.833749999999999547e-01 7.525389999999999580e-01 -3.358599999999999919e-01 5.208909999999999929e-01 2.226120000000000043e-01 +1.403715340712140083e+09 -3.922041999999999806e+00 -3.455967999999999929e+00 6.884590000000000432e-01 7.546770000000000422e-01 -3.325179999999999803e-01 5.219970000000000443e-01 2.177459999999999951e-01 +1.403715340762140036e+09 -3.908100000000000129e+00 -3.465523000000000131e+00 6.927299999999999569e-01 7.566060000000000008e-01 -3.303699999999999970e-01 5.222010000000000263e-01 2.137969999999999871e-01 +1.403715340812139988e+09 -3.894247000000000014e+00 -3.475506000000000206e+00 6.971150000000000402e-01 7.579430000000000334e-01 -3.288289999999999824e-01 5.223989999999999467e-01 2.109379999999999866e-01 +1.403715340862139940e+09 -3.880335000000000090e+00 -3.486216999999999899e+00 7.011789999999999967e-01 7.577949999999999964e-01 -3.301810000000000023e-01 5.235039999999999694e-01 2.065710000000000046e-01 +1.403715340912139893e+09 -3.866366000000000192e+00 -3.497250000000000192e+00 7.049220000000000486e-01 7.570750000000000535e-01 -3.324400000000000133e-01 5.247889999999999500e-01 2.022809999999999886e-01 +1.403715340962140083e+09 -3.852472999999999814e+00 -3.509345000000000159e+00 7.088119999999999976e-01 7.566540000000000488e-01 -3.343119999999999981e-01 5.250890000000000279e-01 1.999799999999999911e-01 +1.403715341012140036e+09 -3.838556000000000079e+00 -3.522782999999999998e+00 7.128219999999999557e-01 7.560900000000000398e-01 -3.369349999999999845e-01 5.250169999999999559e-01 1.978880000000000083e-01 +1.403715341062139988e+09 -3.824917000000000122e+00 -3.537618000000000151e+00 7.172889999999999544e-01 7.550099999999999589e-01 -3.384030000000000094e-01 5.252919999999999812e-01 1.987760000000000082e-01 +1.403715341112139940e+09 -3.811625999999999959e+00 -3.553835999999999995e+00 7.217510000000000314e-01 7.539970000000000283e-01 -3.381330000000000169e-01 5.253299999999999637e-01 2.029340000000000033e-01 +1.403715341162139893e+09 -3.798500999999999905e+00 -3.570867999999999931e+00 7.261630000000000029e-01 7.532670000000000199e-01 -3.363570000000000171e-01 5.249439999999999662e-01 2.094910000000000105e-01 +1.403715341212140083e+09 -3.785700999999999983e+00 -3.588807000000000080e+00 7.310170000000000279e-01 7.495849999999999458e-01 -3.370560000000000223e-01 5.281689999999999996e-01 2.134320000000000106e-01 +1.403715341262140036e+09 -3.773118999999999890e+00 -3.607763999999999971e+00 7.359489999999999643e-01 7.464030000000000387e-01 -3.384150000000000214e-01 5.304240000000000066e-01 2.168110000000000037e-01 +1.403715341312139988e+09 -3.761106999999999978e+00 -3.627136000000000138e+00 7.408050000000000468e-01 7.435960000000000347e-01 -3.390230000000000188e-01 5.320089999999999542e-01 2.215759999999999952e-01 +1.403715341362139940e+09 -3.750278999999999918e+00 -3.645814999999999806e+00 7.458799999999999875e-01 7.408930000000000238e-01 -3.390029999999999988e-01 5.333949999999999525e-01 2.272540000000000115e-01 +1.403715341412139893e+09 -3.739618000000000109e+00 -3.664247000000000032e+00 7.510689999999999866e-01 7.383309999999999595e-01 -3.399969999999999937e-01 5.344529999999999559e-01 2.315810000000000091e-01 +1.403715341462140083e+09 -3.729333000000000009e+00 -3.682371999999999979e+00 7.560120000000000173e-01 7.376829999999999776e-01 -3.403089999999999726e-01 5.330249999999999710e-01 2.364290000000000003e-01 +1.403715341512140036e+09 -3.719545000000000101e+00 -3.700307000000000013e+00 7.611390000000000100e-01 7.372870000000000257e-01 -3.418459999999999832e-01 5.313029999999999697e-01 2.393039999999999889e-01 +1.403715341562139988e+09 -3.710109000000000101e+00 -3.717872999999999983e+00 7.661919999999999842e-01 7.376730000000000231e-01 -3.413869999999999960e-01 5.287239999999999718e-01 2.444270000000000054e-01 +1.403715341612139940e+09 -3.700833999999999957e+00 -3.735103000000000062e+00 7.711479999999999446e-01 7.369649999999999812e-01 -3.398479999999999834e-01 5.281630000000000491e-01 2.498589999999999978e-01 +1.403715341662139893e+09 -3.691514000000000184e+00 -3.751751000000000058e+00 7.759249999999999758e-01 7.359620000000000051e-01 -3.379849999999999799e-01 5.278909999999999991e-01 2.558480000000000198e-01 +1.403715341712140083e+09 -3.682050999999999963e+00 -3.767365999999999993e+00 7.806269999999999598e-01 7.353250000000000064e-01 -3.353360000000000229e-01 5.273079999999999989e-01 2.622840000000000171e-01 +1.403715341762140036e+09 -3.672051000000000176e+00 -3.781972000000000111e+00 7.843769999999999909e-01 7.361980000000000190e-01 -3.341029999999999833e-01 5.248979999999999757e-01 2.662140000000000062e-01 +1.403715341812139988e+09 -3.661767999999999912e+00 -3.794722999999999846e+00 7.874060000000000503e-01 7.373150000000000537e-01 -3.331230000000000024e-01 5.224929999999999852e-01 2.690670000000000006e-01 +1.403715341862139940e+09 -3.650573000000000068e+00 -3.806038000000000032e+00 7.903679999999999595e-01 7.386209999999999720e-01 -3.313530000000000086e-01 5.200529999999999875e-01 2.723760000000000070e-01 +1.403715341912139893e+09 -3.638005000000000155e+00 -3.815272999999999914e+00 7.928720000000000212e-01 7.391619999999999857e-01 -3.336740000000000261e-01 5.197800000000000198e-01 2.685699999999999754e-01 +1.403715341962140083e+09 -3.625078999999999940e+00 -3.823153000000000024e+00 7.951749999999999652e-01 7.392480000000000162e-01 -3.368749999999999800e-01 5.205450000000000355e-01 2.627920000000000256e-01 +1.403715342012140036e+09 -3.612236999999999920e+00 -3.829413000000000178e+00 7.971420000000000172e-01 7.395920000000000272e-01 -3.406939999999999968e-01 5.209559999999999746e-01 2.559989999999999766e-01 +1.403715342062139988e+09 -3.598828000000000138e+00 -3.834664000000000073e+00 7.989300000000000290e-01 7.408930000000000238e-01 -3.437600000000000100e-01 5.201480000000000548e-01 2.497040000000000093e-01 +1.403715342112139940e+09 -3.585548999999999875e+00 -3.838789999999999925e+00 8.007900000000000018e-01 7.428280000000000438e-01 -3.458470000000000155e-01 5.184959999999999569e-01 2.444560000000000066e-01 +1.403715342162139893e+09 -3.572191999999999812e+00 -3.843014999999999848e+00 8.027039999999999731e-01 7.442069999999999519e-01 -3.494309999999999916e-01 5.174800000000000511e-01 2.372070000000000012e-01 +1.403715342212140083e+09 -3.558863000000000110e+00 -3.847532999999999870e+00 8.046079999999999899e-01 7.455669999999999797e-01 -3.509140000000000037e-01 5.166859999999999786e-01 2.324330000000000007e-01 +1.403715342262140036e+09 -3.544928000000000079e+00 -3.853072000000000052e+00 8.061490000000000045e-01 7.463419999999999499e-01 -3.517370000000000219e-01 5.167589999999999684e-01 2.285040000000000127e-01 +1.403715342312139988e+09 -3.530299999999999994e+00 -3.860219999999999985e+00 8.071589999999999598e-01 7.468850000000000211e-01 -3.514269999999999894e-01 5.176269999999999483e-01 2.252220000000000055e-01 +1.403715342362139940e+09 -3.515667999999999793e+00 -3.867386000000000212e+00 8.076069999999999638e-01 7.488320000000000531e-01 -3.488479999999999914e-01 5.176640000000000130e-01 2.226670000000000038e-01 +1.403715342412139893e+09 -3.500932000000000155e+00 -3.874947000000000141e+00 8.080190000000000428e-01 7.515690000000000426e-01 -3.437549999999999772e-01 5.178679999999999950e-01 2.208829999999999960e-01 +1.403715342462140083e+09 -3.485902999999999974e+00 -3.883077999999999808e+00 8.078670000000000018e-01 7.553999999999999604e-01 -3.388039999999999941e-01 5.174459999999999615e-01 2.164089999999999903e-01 +1.403715342512140036e+09 -3.470651000000000153e+00 -3.891931000000000029e+00 8.077659999999999840e-01 7.597779999999999534e-01 -3.313650000000000206e-01 5.170740000000000336e-01 2.134669999999999901e-01 +1.403715342562139988e+09 -3.455138999999999960e+00 -3.901514000000000149e+00 8.077429999999999888e-01 7.643560000000000354e-01 -3.218730000000000202e-01 5.167850000000000499e-01 2.123460000000000070e-01 +1.403715342612139940e+09 -3.439011999999999958e+00 -3.912028999999999979e+00 8.081589999999999607e-01 7.686439999999999939e-01 -3.101099999999999968e-01 5.171670000000000433e-01 2.134389999999999898e-01 +1.403715342662139893e+09 -3.422060999999999797e+00 -3.922454999999999803e+00 8.088130000000000042e-01 7.719169999999999643e-01 -2.967719999999999803e-01 5.190740000000000354e-01 2.159449999999999981e-01 +1.403715342712140083e+09 -3.403576999999999853e+00 -3.932900000000000063e+00 8.092909999999999826e-01 7.748329999999999940e-01 -2.845090000000000119e-01 5.214569999999999483e-01 2.162650000000000128e-01 +1.403715342762140036e+09 -3.384374999999999911e+00 -3.942559999999999842e+00 8.092709999999999626e-01 7.773560000000000469e-01 -2.754940000000000166e-01 5.238000000000000433e-01 2.132020000000000026e-01 +1.403715342812139988e+09 -3.364326999999999845e+00 -3.951944999999999819e+00 8.087499999999999689e-01 7.788779999999999593e-01 -2.706200000000000272e-01 5.269749999999999712e-01 2.059419999999999862e-01 +1.403715342862139940e+09 -3.343372000000000011e+00 -3.960306000000000104e+00 8.092150000000000176e-01 7.791989999999999750e-01 -2.663579999999999837e-01 5.309949999999999948e-01 1.998659999999999881e-01 +1.403715342912139893e+09 -3.321560999999999986e+00 -3.968484000000000123e+00 8.094149999999999956e-01 7.795830000000000259e-01 -2.639150000000000107e-01 5.340230000000000254e-01 1.934400000000000008e-01 +1.403715342962140083e+09 -3.298957999999999835e+00 -3.976964000000000166e+00 8.096740000000000048e-01 7.788059999999999983e-01 -2.614879999999999982e-01 5.379880000000000217e-01 1.888209999999999888e-01 +1.403715343012140036e+09 -3.275793999999999873e+00 -3.985557000000000016e+00 8.094850000000000101e-01 7.778939999999999744e-01 -2.594650000000000012e-01 5.414740000000000109e-01 1.853769999999999862e-01 +1.403715343062139988e+09 -3.252222999999999864e+00 -3.994152999999999842e+00 8.083280000000000465e-01 7.771339999999999915e-01 -2.583690000000000153e-01 5.443320000000000380e-01 1.816899999999999904e-01 +1.403715343112139940e+09 -3.228544999999999998e+00 -4.002809000000000061e+00 8.070100000000000051e-01 7.772609999999999797e-01 -2.559850000000000181e-01 5.455809999999999826e-01 1.807739999999999903e-01 +1.403715343162139893e+09 -3.204963999999999924e+00 -4.011472000000000371e+00 8.050549999999999651e-01 7.777589999999999781e-01 -2.546979999999999800e-01 5.461540000000000283e-01 1.787030000000000007e-01 +1.403715343212140083e+09 -3.181474999999999831e+00 -4.019834000000000351e+00 8.033670000000000533e-01 7.773499999999999854e-01 -2.533050000000000024e-01 5.478450000000000264e-01 1.772809999999999941e-01 +1.403715343262140036e+09 -3.158065999999999818e+00 -4.028355999999999604e+00 8.002559999999999674e-01 7.787110000000000420e-01 -2.524680000000000257e-01 5.467579999999999663e-01 1.758540000000000103e-01 +1.403715343312139988e+09 -3.134930999999999912e+00 -4.036966999999999750e+00 7.969389999999999530e-01 7.800160000000000426e-01 -2.522019999999999817e-01 5.454520000000000479e-01 1.745049999999999935e-01 +1.403715343362139940e+09 -3.112414999999999932e+00 -4.045780999999999850e+00 7.944919999999999760e-01 7.817460000000000520e-01 -2.525350000000000095e-01 5.432540000000000147e-01 1.731330000000000091e-01 +1.403715343412139893e+09 -3.089608999999999828e+00 -4.054153999999999591e+00 7.907450000000000312e-01 7.839639999999999942e-01 -2.518500000000000183e-01 5.401839999999999975e-01 1.737039999999999973e-01 +1.403715343462140083e+09 -3.066638000000000197e+00 -4.062662000000000440e+00 7.872169999999999446e-01 7.851630000000000553e-01 -2.512699999999999934e-01 5.382980000000000542e-01 1.749749999999999917e-01 +1.403715343512140036e+09 -3.043117000000000072e+00 -4.071185999999999972e+00 7.835349999999999815e-01 7.855180000000000495e-01 -2.520819999999999728e-01 5.374069999999999681e-01 1.749590000000000034e-01 +1.403715343562139988e+09 -3.019028000000000045e+00 -4.080268000000000228e+00 7.802050000000000374e-01 7.858960000000000390e-01 -2.522010000000000085e-01 5.363790000000000502e-01 1.762360000000000038e-01 +1.403715343612139940e+09 -2.994136999999999826e+00 -4.088941000000000159e+00 7.769209999999999727e-01 7.857819999999999805e-01 -2.528150000000000119e-01 5.359620000000000495e-01 1.771340000000000137e-01 +1.403715343662139893e+09 -2.968745000000000189e+00 -4.097877000000000436e+00 7.739000000000000323e-01 7.854809999999999848e-01 -2.526900000000000257e-01 5.357629999999999892e-01 1.792350000000000054e-01 +1.403715343712140083e+09 -2.942595999999999989e+00 -4.107027999999999679e+00 7.715659999999999741e-01 7.848760000000000181e-01 -2.522420000000000218e-01 5.359930000000000527e-01 1.818120000000000014e-01 +1.403715343762140036e+09 -2.915780999999999956e+00 -4.116253000000000384e+00 7.700439999999999507e-01 7.837250000000000050e-01 -2.508429999999999827e-01 5.368870000000000031e-01 1.860239999999999949e-01 +1.403715343812139988e+09 -2.887310999999999961e+00 -4.125784999999999592e+00 7.693269999999999831e-01 7.814360000000000195e-01 -2.500399999999999845e-01 5.394799999999999596e-01 1.892089999999999883e-01 +1.403715343912139893e+09 -2.830763999999999836e+00 -4.142295999999999978e+00 7.671940000000000426e-01 7.793849999999999945e-01 -2.502110000000000167e-01 5.417260000000000408e-01 1.910119999999999874e-01 +1.403715343962140083e+09 -2.801337000000000188e+00 -4.149643000000000193e+00 7.665560000000000151e-01 7.784750000000000281e-01 -2.497340000000000115e-01 5.438330000000000108e-01 1.893549999999999955e-01 +1.403715344012140036e+09 -2.771697000000000077e+00 -4.155882000000000076e+00 7.661229999999999984e-01 7.786619999999999653e-01 -2.478740000000000110e-01 5.450420000000000265e-01 1.875469999999999915e-01 +1.403715344062139988e+09 -2.741591999999999807e+00 -4.161261999999999794e+00 7.657580000000000497e-01 7.783849999999999936e-01 -2.444359999999999866e-01 5.479479999999999906e-01 1.847179999999999933e-01 +1.403715344112139940e+09 -2.711637000000000075e+00 -4.165517000000000358e+00 7.657460000000000377e-01 7.787159999999999638e-01 -2.397739999999999871e-01 5.508110000000000506e-01 1.808770000000000100e-01 +1.403715344162139893e+09 -2.680984000000000034e+00 -4.169277000000000122e+00 7.651780000000000248e-01 7.796159999999999757e-01 -2.338719999999999966e-01 5.535740000000000105e-01 1.762330000000000008e-01 +1.403715344212140083e+09 -2.649932999999999872e+00 -4.172500999999999571e+00 7.640909999999999647e-01 7.813219999999999610e-01 -2.256239999999999912e-01 5.553860000000000463e-01 1.737150000000000083e-01 +1.403715344262140036e+09 -2.619409000000000098e+00 -4.174940999999999569e+00 7.634279999999999955e-01 7.822080000000000144e-01 -2.166339999999999932e-01 5.578819999999999890e-01 1.731699999999999906e-01 +1.403715344312139988e+09 -2.589532999999999863e+00 -4.176473999999999798e+00 7.627380000000000271e-01 7.827659999999999618e-01 -2.070349999999999968e-01 5.603949999999999765e-01 1.742720000000000102e-01 +1.403715344362139940e+09 -2.560000000000000053e+00 -4.176903000000000254e+00 7.619399999999999507e-01 7.826239999999999863e-01 -1.985609999999999875e-01 5.633789999999999631e-01 1.751469999999999971e-01 +1.403715344412139893e+09 -2.530590999999999813e+00 -4.175975000000000215e+00 7.608430000000000470e-01 7.818589999999999707e-01 -1.902719999999999967e-01 5.669060000000000210e-01 1.763830000000000120e-01 +1.403715344462140083e+09 -2.501689999999999969e+00 -4.173564999999999969e+00 7.592119999999999980e-01 7.815069999999999517e-01 -1.839280000000000082e-01 5.695099999999999607e-01 1.762839999999999963e-01 +1.403715344512140036e+09 -2.473651999999999962e+00 -4.169019999999999726e+00 7.575460000000000527e-01 7.812769999999999992e-01 -1.774789999999999979e-01 5.715040000000000120e-01 1.774560000000000026e-01 +1.403715344562139988e+09 -2.445937999999999946e+00 -4.162543999999999578e+00 7.552689999999999682e-01 7.815870000000000317e-01 -1.731340000000000101e-01 5.727640000000000509e-01 1.763170000000000015e-01 +1.403715344612139940e+09 -2.418857000000000035e+00 -4.153458999999999790e+00 7.518439999999999568e-01 7.833560000000000523e-01 -1.705780000000000074e-01 5.719030000000000502e-01 1.737370000000000025e-01 +1.403715344662139893e+09 -2.392116999999999827e+00 -4.142089000000000354e+00 7.476319999999999633e-01 7.869159999999999489e-01 -1.677480000000000082e-01 5.681589999999999696e-01 1.726800000000000002e-01 +1.403715344712140083e+09 -2.365508000000000166e+00 -4.128326999999999636e+00 7.430130000000000345e-01 7.903250000000000552e-01 -1.662170000000000036e-01 5.644439999999999458e-01 1.707680000000000031e-01 +1.403715344762140036e+09 -2.338915000000000077e+00 -4.112217000000000233e+00 7.384429999999999605e-01 7.936530000000000529e-01 -1.652170000000000027e-01 5.606379999999999697e-01 1.688320000000000098e-01 +1.403715344812139988e+09 -2.312005000000000088e+00 -4.093994000000000355e+00 7.342429999999999790e-01 7.956760000000000499e-01 -1.642139999999999989e-01 5.585309999999999997e-01 1.672589999999999910e-01 +1.403715344862139940e+09 -2.285163999999999973e+00 -4.074107999999999841e+00 7.301250000000000240e-01 7.970350000000000490e-01 -1.634929999999999994e-01 5.571450000000000014e-01 1.661189999999999889e-01 +1.403715344912139893e+09 -2.258040999999999965e+00 -4.052586999999999939e+00 7.257919999999999927e-01 7.980540000000000411e-01 -1.631549999999999945e-01 5.562399999999999567e-01 1.645840000000000081e-01 +1.403715344962140083e+09 -2.230157000000000167e+00 -4.029461999999999655e+00 7.216669999999999474e-01 7.975989999999999469e-01 -1.639019999999999921e-01 5.574259999999999771e-01 1.620129999999999904e-01 +1.403715345012140036e+09 -2.201916999999999902e+00 -4.004300999999999888e+00 7.177989999999999648e-01 7.953959999999999919e-01 -1.670619999999999883e-01 5.612089999999999579e-01 1.564609999999999890e-01 +1.403715345062139988e+09 -2.173385999999999818e+00 -3.977898000000000156e+00 7.144740000000000535e-01 7.928640000000000132e-01 -1.697670000000000012e-01 5.652190000000000270e-01 1.518990000000000062e-01 +1.403715345112139940e+09 -2.145246000000000208e+00 -3.950054000000000176e+00 7.117390000000000105e-01 7.903059999999999530e-01 -1.721030000000000060e-01 5.690589999999999815e-01 1.482209999999999916e-01 +1.403715345162139893e+09 -2.117519000000000151e+00 -3.921473999999999904e+00 7.083970000000000544e-01 7.890580000000000371e-01 -1.742289999999999950e-01 5.709030000000000493e-01 1.452660000000000062e-01 +1.403715345212140083e+09 -2.090695999999999888e+00 -3.892260999999999971e+00 7.049109999999999543e-01 7.888690000000000424e-01 -1.764040000000000052e-01 5.711850000000000538e-01 1.425279999999999880e-01 +1.403715345262140036e+09 -2.064646999999999899e+00 -3.862388000000000154e+00 7.011950000000000127e-01 7.896060000000000301e-01 -1.770180000000000087e-01 5.701279999999999681e-01 1.419169999999999876e-01 +1.403715345312139988e+09 -2.039128999999999969e+00 -3.831679999999999975e+00 6.968429999999999902e-01 7.896980000000000111e-01 -1.785380000000000023e-01 5.699269999999999614e-01 1.403050000000000130e-01 +1.403715345362139940e+09 -2.014199000000000073e+00 -3.800119000000000025e+00 6.925839999999999774e-01 7.901340000000000030e-01 -1.791719999999999979e-01 5.692850000000000410e-01 1.396419999999999884e-01 +1.403715345412139893e+09 -1.989471999999999907e+00 -3.767806000000000211e+00 6.882559999999999789e-01 7.906379999999999519e-01 -1.797960000000000114e-01 5.685670000000000446e-01 1.389130000000000087e-01 +1.403715345462140083e+09 -1.966018999999999961e+00 -3.734754999999999825e+00 6.840349999999999486e-01 7.908880000000000354e-01 -1.805140000000000078e-01 5.683129999999999571e-01 1.375909999999999911e-01 +1.403715345512140036e+09 -1.942752000000000034e+00 -3.701308000000000042e+00 6.795489999999999586e-01 7.911690000000000111e-01 -1.799189999999999956e-01 5.679269999999999596e-01 1.383449999999999958e-01 +1.403715345562139988e+09 -1.920668999999999960e+00 -3.667140999999999984e+00 6.758070000000000466e-01 7.907870000000000177e-01 -1.800339999999999996e-01 5.685919999999999863e-01 1.376489999999999936e-01 +1.403715345612139940e+09 -1.898787000000000003e+00 -3.632981000000000016e+00 6.717290000000000205e-01 7.906250000000000222e-01 -1.804050000000000098e-01 5.689659999999999718e-01 1.365449999999999997e-01 +1.403715345662139893e+09 -1.877188999999999997e+00 -3.598342000000000152e+00 6.674590000000000245e-01 7.904660000000000020e-01 -1.804600000000000093e-01 5.693489999999999940e-01 1.357879999999999920e-01 +1.403715345712140083e+09 -1.856468999999999925e+00 -3.563379999999999992e+00 6.631179999999999852e-01 7.903839999999999755e-01 -1.808349999999999957e-01 5.695930000000000160e-01 1.347440000000000027e-01 +1.403715345762140036e+09 -1.836314000000000002e+00 -3.528392000000000195e+00 6.586959999999999482e-01 7.902000000000000135e-01 -1.812789999999999957e-01 5.699210000000000109e-01 1.338310000000000055e-01 +1.403715345812139988e+09 -1.816715999999999998e+00 -3.493396000000000168e+00 6.540589999999999460e-01 7.903540000000000010e-01 -1.816439999999999999e-01 5.697969999999999979e-01 1.329599999999999949e-01 +1.403715345862139940e+09 -1.797951000000000077e+00 -3.458143999999999885e+00 6.490709999999999535e-01 7.913170000000000481e-01 -1.823210000000000108e-01 5.685339999999999838e-01 1.317000000000000115e-01 +1.403715345912139893e+09 -1.779711999999999961e+00 -3.422871000000000219e+00 6.432400000000000340e-01 7.949110000000000342e-01 -1.831669999999999965e-01 5.634439999999999449e-01 1.307520000000000071e-01 +1.403715345962140083e+09 -1.761457999999999968e+00 -3.387468999999999841e+00 6.367890000000000494e-01 7.998410000000000242e-01 -1.842630000000000101e-01 5.563900000000000512e-01 1.293479999999999908e-01 +1.403715346012140036e+09 -1.743408000000000069e+00 -3.352174999999999905e+00 6.319190000000000085e-01 8.036729999999999707e-01 -1.857399999999999884e-01 5.507360000000000033e-01 1.276690000000000047e-01 +1.403715346062139988e+09 -1.725149000000000044e+00 -3.317368999999999790e+00 6.273919999999999497e-01 8.073519999999999586e-01 -1.878670000000000062e-01 5.451599999999999779e-01 1.252570000000000072e-01 +1.403715346112139940e+09 -1.706156999999999924e+00 -3.283320999999999934e+00 6.240090000000000359e-01 8.095259999999999678e-01 -1.891849999999999921e-01 5.416509999999999936e-01 1.244630000000000042e-01 +1.403715346162139893e+09 -1.685619999999999896e+00 -3.249673000000000034e+00 6.217479999999999674e-01 8.103650000000000020e-01 -1.899309999999999887e-01 5.402259999999999840e-01 1.240590000000000026e-01 +1.403715346212140083e+09 -1.664951000000000070e+00 -3.216512999999999955e+00 6.211050000000000182e-01 8.088159999999999794e-01 -1.904210000000000069e-01 5.423149999999999915e-01 1.243009999999999948e-01 +1.403715346262140036e+09 -1.643100000000000005e+00 -3.184663000000000022e+00 6.206230000000000357e-01 8.064440000000000497e-01 -1.905159999999999909e-01 5.455860000000000154e-01 1.252500000000000002e-01 +1.403715346312139988e+09 -1.620786000000000060e+00 -3.153293000000000124e+00 6.201630000000000198e-01 8.040070000000000272e-01 -1.915000000000000036e-01 5.486870000000000358e-01 1.258710000000000107e-01 +1.403715346362139940e+09 -1.597960000000000047e+00 -3.122465000000000046e+00 6.202309999999999768e-01 8.018220000000000347e-01 -1.918580000000000008e-01 5.515259999999999607e-01 1.268489999999999895e-01 +1.403715346412139893e+09 -1.574859999999999927e+00 -3.092328000000000188e+00 6.208580000000000210e-01 7.991120000000000445e-01 -1.928090000000000082e-01 5.549190000000000511e-01 1.277119999999999922e-01 +1.403715346462140083e+09 -1.551909999999999901e+00 -3.062736999999999821e+00 6.217439999999999634e-01 7.964310000000000000e-01 -1.937820000000000098e-01 5.581439999999999735e-01 1.289240000000000108e-01 +1.403715346512140036e+09 -1.528674000000000088e+00 -3.033787999999999929e+00 6.224990000000000245e-01 7.938039999999999541e-01 -1.955260000000000054e-01 5.612129999999999619e-01 1.291700000000000070e-01 +1.403715346562139988e+09 -1.506027999999999922e+00 -3.004640000000000200e+00 6.237019999999999786e-01 7.919969999999999510e-01 -1.977770000000000084e-01 5.629840000000000400e-01 1.291249999999999898e-01 +1.403715346612139940e+09 -1.484161999999999981e+00 -2.976256999999999930e+00 6.249390000000000223e-01 7.898290000000000033e-01 -2.009819999999999940e-01 5.650159999999999627e-01 1.285799999999999998e-01 +1.403715346662139893e+09 -1.463027999999999995e+00 -2.948191000000000006e+00 6.257500000000000284e-01 7.885079999999999867e-01 -2.038619999999999877e-01 5.657109999999999639e-01 1.290959999999999885e-01 +1.403715346712140083e+09 -1.442908000000000079e+00 -2.920560000000000045e+00 6.271700000000000053e-01 7.865900000000000114e-01 -2.064249999999999974e-01 5.672249999999999792e-01 1.300830000000000042e-01 +1.403715346762140036e+09 -1.423686999999999925e+00 -2.893219999999999903e+00 6.284239999999999826e-01 7.853949999999999543e-01 -2.091320000000000123e-01 5.677609999999999602e-01 1.306319999999999981e-01 +1.403715346812139988e+09 -1.405342000000000091e+00 -2.866427999999999976e+00 6.294100000000000250e-01 7.849289999999999878e-01 -2.118389999999999995e-01 5.672120000000000495e-01 1.314559999999999895e-01 +1.403715346862139940e+09 -1.387745000000000006e+00 -2.840311999999999948e+00 6.304269999999999596e-01 7.854980000000000295e-01 -2.136019999999999863e-01 5.653129999999999544e-01 1.333699999999999886e-01 +1.403715346912139893e+09 -1.370506000000000002e+00 -2.814906000000000130e+00 6.312729999999999730e-01 7.860829999999999762e-01 -2.173460000000000114e-01 5.633230000000000182e-01 1.322909999999999919e-01 +1.403715346962140083e+09 -1.354212999999999889e+00 -2.790026999999999813e+00 6.318620000000000347e-01 7.872149999999999981e-01 -2.212409999999999932e-01 5.605390000000000095e-01 1.309220000000000106e-01 +1.403715347012140036e+09 -1.338084999999999969e+00 -2.765840999999999994e+00 6.323569999999999469e-01 7.883559999999999457e-01 -2.245590000000000086e-01 5.578800000000000425e-01 1.297629999999999895e-01 +1.403715347062139988e+09 -1.323083999999999927e+00 -2.743332999999999799e+00 6.334830000000000183e-01 7.897760000000000336e-01 -2.271299999999999986e-01 5.549699999999999633e-01 1.291279999999999928e-01 +1.403715347112139940e+09 -1.308340000000000058e+00 -2.721900999999999904e+00 6.355070000000000441e-01 7.910289999999999822e-01 -2.259039999999999937e-01 5.531949999999999923e-01 1.312089999999999923e-01 +1.403715347162139893e+09 -1.293989999999999974e+00 -2.701299999999999812e+00 6.374539999999999651e-01 7.927180000000000337e-01 -2.225179999999999936e-01 5.516940000000000177e-01 1.331070000000000031e-01 +1.403715347212140083e+09 -1.279246000000000105e+00 -2.681740000000000013e+00 6.405539999999999567e-01 7.942160000000000331e-01 -2.166150000000000020e-01 5.514459999999999917e-01 1.349309999999999954e-01 +1.403715347262140036e+09 -1.264049999999999896e+00 -2.662752999999999926e+00 6.441919999999999868e-01 7.952820000000000444e-01 -2.096379999999999910e-01 5.525999999999999801e-01 1.349519999999999886e-01 +1.403715347312139988e+09 -1.248320000000000096e+00 -2.644118999999999886e+00 6.484969999999999901e-01 7.964059999999999473e-01 -2.009070000000000022e-01 5.544010000000000327e-01 1.342170000000000030e-01 +1.403715347362139940e+09 -1.232842999999999911e+00 -2.625652999999999793e+00 6.527049999999999796e-01 7.974489999999999634e-01 -1.907800000000000051e-01 5.568180000000000351e-01 1.327830000000000121e-01 +1.403715347412139893e+09 -1.217281000000000057e+00 -2.606911999999999896e+00 6.575299999999999478e-01 7.985400000000000276e-01 -1.787060000000000037e-01 5.594219999999999748e-01 1.320790000000000020e-01 +1.403715347462140083e+09 -1.202063000000000104e+00 -2.587423999999999946e+00 6.626079999999999748e-01 8.001599999999999824e-01 -1.672939999999999983e-01 5.613010000000000499e-01 1.292240000000000055e-01 +1.403715347512140036e+09 -1.186309999999999976e+00 -2.567594000000000154e+00 6.674149999999999805e-01 8.015130000000000310e-01 -1.562449999999999950e-01 5.629830000000000112e-01 1.273330000000000017e-01 +1.403715347562139988e+09 -1.170570000000000110e+00 -2.547232999999999858e+00 6.722949999999999759e-01 8.021409999999999929e-01 -1.466240000000000043e-01 5.650450000000000195e-01 1.256790000000000129e-01 +1.403715347612139940e+09 -1.155799000000000021e+00 -2.525421000000000138e+00 6.777509999999999923e-01 8.025349999999999984e-01 -1.384460000000000135e-01 5.669750000000000068e-01 1.237359999999999988e-01 +1.403715347662139893e+09 -1.140269999999999895e+00 -2.503318999999999850e+00 6.827779999999999960e-01 8.022799999999999931e-01 -1.326610000000000011e-01 5.694259999999999877e-01 1.204230000000000023e-01 +1.403715347712140083e+09 -1.124862000000000029e+00 -2.480532999999999877e+00 6.872110000000000163e-01 8.018119999999999692e-01 -1.304349999999999954e-01 5.718940000000000135e-01 1.141100000000000031e-01 +1.403715347762140036e+09 -1.109698999999999991e+00 -2.456933999999999951e+00 6.911370000000000013e-01 8.018520000000000092e-01 -1.298890000000000045e-01 5.734089999999999465e-01 1.066010000000000013e-01 +1.403715347862139940e+09 -1.080106999999999928e+00 -2.407667000000000002e+00 6.987879999999999647e-01 8.024499999999999966e-01 -1.264170000000000016e-01 5.760199999999999765e-01 9.107400000000000218e-02 +1.403715347912139893e+09 -1.066383999999999999e+00 -2.382594000000000101e+00 7.019480000000000164e-01 8.029209999999999958e-01 -1.235249999999999959e-01 5.773589999999999556e-01 8.194999999999999507e-02 +1.403715347962140083e+09 -1.053514999999999979e+00 -2.357670999999999850e+00 7.052380000000000315e-01 8.033099999999999685e-01 -1.213299999999999934e-01 5.788339999999999597e-01 7.016899999999999527e-02 +1.403715348012140036e+09 -1.041400000000000103e+00 -2.332876999999999867e+00 7.085420000000000051e-01 8.035280000000000200e-01 -1.179830000000000045e-01 5.806059999999999555e-01 5.762300000000000061e-02 +1.403715348062139988e+09 -1.029471000000000025e+00 -2.308861999999999970e+00 7.111319999999999864e-01 8.048279999999999879e-01 -1.122350000000000014e-01 5.809670000000000112e-01 4.617899999999999783e-02 +1.403715348112139940e+09 -1.018868000000000107e+00 -2.286645000000000039e+00 7.142140000000000155e-01 8.056670000000000220e-01 -1.035819999999999935e-01 5.821150000000000491e-01 3.624800000000000244e-02 +1.403715348162139893e+09 -1.008659999999999890e+00 -2.264968999999999788e+00 7.168149999999999800e-01 8.078170000000000073e-01 -9.339699999999999391e-02 5.813779999999999504e-01 2.662600000000000036e-02 +1.403715348212140083e+09 -9.992039999999999811e-01 -2.244476999999999833e+00 7.195420000000000149e-01 8.095329999999999471e-01 -8.181700000000000084e-02 5.810859999999999914e-01 1.736000000000000043e-02 +1.403715348262140036e+09 -9.895009999999999639e-01 -2.225881999999999916e+00 7.214110000000000245e-01 8.123930000000000318e-01 -6.878099999999999492e-02 5.789619999999999767e-01 9.485999999999999641e-03 +1.403715348312139988e+09 -9.805519999999999792e-01 -2.208778000000000130e+00 7.234410000000000007e-01 8.146390000000000020e-01 -5.574699999999999794e-02 5.772770000000000401e-01 2.684999999999999887e-03 +1.403715348362139940e+09 -9.720100000000000406e-01 -2.193299999999999805e+00 7.239139999999999464e-01 -8.169969999999999732e-01 4.448200000000000071e-02 -5.749079999999999746e-01 4.323999999999999719e-03 +1.403715348412139893e+09 -9.635390000000000343e-01 -2.179762999999999895e+00 7.230820000000000025e-01 -8.189840000000000453e-01 3.423799999999999760e-02 -5.727229999999999821e-01 9.015999999999999709e-03 +1.403715348462140083e+09 -9.542690000000000339e-01 -2.166999000000000120e+00 7.194779999999999509e-01 -8.211150000000000393e-01 2.663099999999999842e-02 -5.699760000000000382e-01 1.374099999999999974e-02 +1.403715348512140036e+09 -9.455369999999999608e-01 -2.156747999999999887e+00 7.130049999999999999e-01 -8.224829999999999641e-01 1.993800000000000086e-02 -5.681939999999999769e-01 1.674000000000000141e-02 +1.403715348562139988e+09 -9.356360000000000232e-01 -2.147559999999999913e+00 7.034550000000000525e-01 -8.231840000000000268e-01 1.532299999999999982e-02 -5.672239999999999505e-01 1.974599999999999966e-02 +1.403715348612139940e+09 -9.249260000000000259e-01 -2.140052999999999983e+00 6.912169999999999703e-01 -8.223510000000000542e-01 1.217799999999999959e-02 -5.683789999999999676e-01 2.313199999999999978e-02 +1.403715348662139893e+09 -9.151380000000000070e-01 -2.132782999999999873e+00 6.773740000000000316e-01 -8.206499999999999906e-01 1.141000000000000000e-02 -5.706250000000000488e-01 2.811200000000000157e-02 +1.403715348712140083e+09 -9.047629999999999839e-01 -2.128439999999999888e+00 6.610629999999999562e-01 -8.193009999999999460e-01 1.081400000000000070e-02 -5.723549999999999471e-01 3.224400000000000183e-02 +1.403715348762140036e+09 -8.941540000000000044e-01 -2.125795000000000101e+00 6.440099999999999714e-01 -8.187969999999999970e-01 1.032100000000000031e-02 -5.728379999999999583e-01 3.636999999999999955e-02 +1.403715348812139988e+09 -8.837110000000000243e-01 -2.124251999999999807e+00 6.270989999999999620e-01 -8.180619999999999559e-01 8.222999999999999407e-03 -5.736949999999999550e-01 3.976500000000000173e-02 +1.403715348862139940e+09 -8.732240000000000002e-01 -2.124092999999999787e+00 6.109590000000000298e-01 -8.169140000000000290e-01 4.852999999999999675e-03 -5.751119999999999566e-01 4.328699999999999909e-02 +1.403715348912139893e+09 -8.630619999999999958e-01 -2.125742999999999938e+00 5.952749999999999986e-01 -8.162409999999999943e-01 1.479000000000000063e-03 -5.758440000000000225e-01 4.638699999999999768e-02 +1.403715348962140083e+09 -8.531999999999999584e-01 -2.129528000000000088e+00 5.802730000000000388e-01 -8.162430000000000518e-01 -2.027999999999999855e-03 -5.756329999999999503e-01 4.887600000000000278e-02 +1.403715349012140036e+09 -8.431340000000000501e-01 -2.135111000000000203e+00 5.662899999999999601e-01 -8.153939999999999522e-01 -6.468999999999999924e-03 -5.767529999999999601e-01 4.947300000000000308e-02 +1.403715349062139988e+09 -8.328170000000000295e-01 -2.142510000000000137e+00 5.526889999999999858e-01 -8.146959999999999757e-01 -1.095499999999999946e-02 -5.776750000000000496e-01 4.941099999999999659e-02 +1.403715349112139940e+09 -8.226750000000000451e-01 -2.151577000000000073e+00 5.398380000000000400e-01 -8.136949999999999461e-01 -1.706999999999999837e-02 -5.790389999999999704e-01 4.818700000000000067e-02 +1.403715349162139893e+09 -8.129659999999999664e-01 -2.161564999999999959e+00 5.269660000000000455e-01 -8.125189999999999912e-01 -2.223899999999999835e-02 -5.804859999999999465e-01 4.851899999999999963e-02 +1.403715349212140083e+09 -8.035480000000000400e-01 -2.173191999999999791e+00 5.151799999999999713e-01 -8.108100000000000307e-01 -2.719999999999999848e-02 -5.826529999999999765e-01 4.861399999999999749e-02 +1.403715349262140036e+09 -7.942289999999999628e-01 -2.185554999999999914e+00 5.033499999999999641e-01 -8.091669999999999696e-01 -3.113199999999999995e-02 -5.846440000000000525e-01 4.971500000000000224e-02 +1.403715349312139988e+09 -7.859660000000000535e-01 -2.199584000000000206e+00 4.926229999999999776e-01 -8.069720000000000226e-01 -3.348600000000000187e-02 -5.873479999999999812e-01 5.192900000000000293e-02 +1.403715349362139940e+09 -7.778969999999999496e-01 -2.214472000000000218e+00 4.814149999999999818e-01 -8.057400000000000118e-01 -3.682699999999999863e-02 -5.888360000000000261e-01 5.195600000000000218e-02 +1.403715349412139893e+09 -7.704069999999999530e-01 -2.230177999999999994e+00 4.697990000000000221e-01 -8.040960000000000329e-01 -4.006699999999999845e-02 -5.909870000000000401e-01 5.057799999999999796e-02 +1.403715349462140083e+09 -7.640540000000000109e-01 -2.246840000000000170e+00 4.580020000000000202e-01 -8.034810000000000008e-01 -4.250099999999999711e-02 -5.918149999999999800e-01 4.864999999999999880e-02 +1.403715349512140036e+09 -7.586300000000000265e-01 -2.263698999999999906e+00 4.460470000000000268e-01 -8.029209999999999958e-01 -4.498599999999999821e-02 -5.926069999999999949e-01 4.594899999999999679e-02 +1.403715349562139988e+09 -7.542079999999999895e-01 -2.280812000000000062e+00 4.331579999999999875e-01 -8.039539999999999464e-01 -4.791600000000000026e-02 -5.911129999999999995e-01 4.413299999999999862e-02 +1.403715349612139940e+09 -7.506500000000000394e-01 -2.297871000000000219e+00 4.198589999999999822e-01 -8.049030000000000351e-01 -5.155699999999999866e-02 -5.895319999999999450e-01 4.387400000000000327e-02 +1.403715349662139893e+09 -7.482560000000000322e-01 -2.314868000000000148e+00 4.068749999999999867e-01 -8.058009999999999895e-01 -5.533899999999999930e-02 -5.878309999999999924e-01 4.557300000000000240e-02 +1.403715349712140083e+09 -7.469390000000000196e-01 -2.331529999999999880e+00 3.940210000000000101e-01 -8.071289999999999853e-01 -5.964599999999999763e-02 -5.852960000000000385e-01 4.913200000000000206e-02 +1.403715349762140036e+09 -7.455789999999999917e-01 -2.348009999999999931e+00 3.821030000000000260e-01 -8.078750000000000098e-01 -6.479500000000000537e-02 -5.833059999999999912e-01 5.378299999999999748e-02 +1.403715349812139988e+09 -7.456429999999999447e-01 -2.364326000000000150e+00 3.710649999999999782e-01 -8.087980000000000169e-01 -6.972299999999999331e-02 -5.807590000000000252e-01 6.085800000000000237e-02 +1.403715349862139940e+09 -7.456960000000000255e-01 -2.380825999999999887e+00 3.605720000000000036e-01 -8.088600000000000234e-01 -7.574899999999999689e-02 -5.791209999999999969e-01 6.801899999999999613e-02 +1.403715349912139893e+09 -7.463830000000000187e-01 -2.397571000000000119e+00 3.509789999999999854e-01 -8.084249999999999492e-01 -8.354499999999999427e-02 -5.779039999999999733e-01 7.413999999999999757e-02 +1.403715349962140083e+09 -7.472929999999999851e-01 -2.414175000000000182e+00 3.412680000000000158e-01 -8.080330000000000013e-01 -9.183499999999999996e-02 -5.763070000000000137e-01 8.074299999999999533e-02 +1.403715350012140036e+09 -7.485899999999999777e-01 -2.431621999999999950e+00 3.320179999999999798e-01 -8.076489999999999503e-01 -1.007900000000000046e-01 -5.746409999999999574e-01 8.562899999999999678e-02 +1.403715350062139988e+09 -7.500689999999999857e-01 -2.449854000000000198e+00 3.232820000000000138e-01 -8.069910000000000139e-01 -1.089500000000000052e-01 -5.735219999999999763e-01 8.926599999999999813e-02 +1.403715350112139940e+09 -7.518500000000000183e-01 -2.468551999999999857e+00 3.135930000000000106e-01 -8.087159999999999904e-01 -1.168789999999999968e-01 -5.692720000000000002e-01 9.081799999999999595e-02 +1.403715350162139893e+09 -7.538300000000000001e-01 -2.487779999999999880e+00 3.040109999999999757e-01 -8.106210000000000360e-01 -1.225389999999999951e-01 -5.649790000000000090e-01 9.314799999999999469e-02 +1.403715350212140083e+09 -7.553109999999999546e-01 -2.507251999999999814e+00 2.946550000000000002e-01 -8.125229999999999952e-01 -1.281859999999999944e-01 -5.609819999999999807e-01 9.313100000000000545e-02 +1.403715350262140036e+09 -7.567859999999999587e-01 -2.526743999999999879e+00 2.849249999999999838e-01 -8.157079999999999886e-01 -1.340899999999999870e-01 -5.553339999999999943e-01 9.079900000000000471e-02 +1.403715350312139988e+09 -7.576840000000000241e-01 -2.545700000000000074e+00 2.751419999999999977e-01 -8.181939999999999769e-01 -1.393220000000000014e-01 -5.508739999999999748e-01 8.767300000000000093e-02 +1.403715350362139940e+09 -7.583900000000000086e-01 -2.563781999999999783e+00 2.652370000000000005e-01 -8.205510000000000304e-01 -1.431020000000000070e-01 -5.468410000000000215e-01 8.474900000000000488e-02 +1.403715350412139893e+09 -7.577159999999999451e-01 -2.580694999999999961e+00 2.553750000000000187e-01 -8.222190000000000332e-01 -1.469370000000000120e-01 -5.439810000000000478e-01 8.031399999999999650e-02 +1.403715350462140083e+09 -7.563760000000000483e-01 -2.595978999999999814e+00 2.460759999999999892e-01 -8.233709999999999640e-01 -1.498520000000000130e-01 -5.420420000000000238e-01 7.613100000000000422e-02 +1.403715350512140036e+09 -7.534809999999999564e-01 -2.609287000000000134e+00 2.366590000000000082e-01 -8.237649999999999695e-01 -1.520819999999999950e-01 -5.413719999999999644e-01 7.209500000000000630e-02 +1.403715350562139988e+09 -7.492900000000000116e-01 -2.620715999999999823e+00 2.273799999999999988e-01 -8.243270000000000319e-01 -1.529600000000000126e-01 -5.406279999999999974e-01 6.935199999999999698e-02 +1.403715350612139940e+09 -7.437899999999999512e-01 -2.629872000000000209e+00 2.182949999999999890e-01 -8.244439999999999547e-01 -1.519139999999999935e-01 -5.408340000000000369e-01 6.864499999999999769e-02 +1.403715350662139893e+09 -7.369839999999999725e-01 -2.636859999999999982e+00 2.096189999999999998e-01 -8.245529999999999804e-01 -1.499830000000000052e-01 -5.411139999999999839e-01 6.937699999999999423e-02 +1.403715350712140083e+09 -7.291180000000000438e-01 -2.641900000000000137e+00 2.012790000000000135e-01 -8.245299999999999851e-01 -1.471059999999999868e-01 -5.416370000000000351e-01 7.168800000000000172e-02 +1.403715350762140036e+09 -7.198379999999999779e-01 -2.645310999999999968e+00 1.931680000000000064e-01 -8.246059999999999501e-01 -1.443349999999999911e-01 -5.419359999999999733e-01 7.414999999999999369e-02 +1.403715350812139988e+09 -7.093300000000000161e-01 -2.647263000000000144e+00 1.859899999999999887e-01 -8.239330000000000265e-01 -1.425150000000000028e-01 -5.431550000000000544e-01 7.619499999999999884e-02 +1.403715350862139940e+09 -6.977020000000000444e-01 -2.647861999999999938e+00 1.798460000000000059e-01 -8.224160000000000359e-01 -1.428030000000000133e-01 -5.454489999999999617e-01 7.566199999999999315e-02 +1.403715350912139893e+09 -6.852970000000000450e-01 -2.647149999999999892e+00 1.742470000000000130e-01 -8.209750000000000103e-01 -1.445909999999999973e-01 -5.474269999999999969e-01 7.360999999999999488e-02 +1.403715350962140083e+09 -6.722820000000000462e-01 -2.645194000000000045e+00 1.697480000000000100e-01 -8.192249999999999810e-01 -1.461899999999999866e-01 -5.498499999999999499e-01 7.186499999999999833e-02 +1.403715351012140036e+09 -6.587659999999999627e-01 -2.641201000000000132e+00 1.651970000000000105e-01 -8.182770000000000321e-01 -1.474989999999999912e-01 -5.510389999999999455e-01 7.087400000000000644e-02 +1.403715351062139988e+09 -6.449730000000000185e-01 -2.635261999999999993e+00 1.612659999999999927e-01 -8.178520000000000234e-01 -1.486159999999999981e-01 -5.514029999999999765e-01 7.061099999999999322e-02 +1.403715351112139940e+09 -6.307730000000000281e-01 -2.627457000000000154e+00 1.582310000000000105e-01 -8.173059999999999770e-01 -1.492130000000000123e-01 -5.520850000000000479e-01 7.034500000000000475e-02 +1.403715351162139893e+09 -6.161349999999999882e-01 -2.617680000000000007e+00 1.554460000000000008e-01 -8.174740000000000339e-01 -1.486040000000000139e-01 -5.517630000000000035e-01 7.218900000000000317e-02 +1.403715351212140083e+09 -6.009839999999999627e-01 -2.606440000000000090e+00 1.526959999999999984e-01 -8.178750000000000187e-01 -1.480750000000000122e-01 -5.510429999999999495e-01 7.420499999999999319e-02 +1.403715351262140036e+09 -5.852619999999999489e-01 -2.593623000000000012e+00 1.505700000000000094e-01 -8.180560000000000054e-01 -1.478309999999999902e-01 -5.506560000000000343e-01 7.554900000000000504e-02 +1.403715351312139988e+09 -5.687790000000000346e-01 -2.578920000000000101e+00 1.498470000000000080e-01 -8.158400000000000096e-01 -1.465220000000000133e-01 -5.538710000000000022e-01 7.851299999999999946e-02 +1.403715351362139940e+09 -5.521019999999999817e-01 -2.562924000000000202e+00 1.493760000000000088e-01 -8.137649999999999606e-01 -1.460879999999999956e-01 -5.568710000000000049e-01 7.962199999999999833e-02 +1.403715351412139893e+09 -5.355520000000000280e-01 -2.545685000000000198e+00 1.496079999999999910e-01 -8.114649999999999919e-01 -1.451459999999999972e-01 -5.602409999999999890e-01 8.116199999999999803e-02 +1.403715351462140083e+09 -5.187089999999999756e-01 -2.527403000000000066e+00 1.497890000000000055e-01 -8.096489999999999521e-01 -1.452070000000000027e-01 -5.628840000000000510e-01 8.090700000000000669e-02 +1.403715351512140036e+09 -5.019249999999999545e-01 -2.507890999999999870e+00 1.501210000000000044e-01 -8.083259999999999890e-01 -1.450279999999999903e-01 -5.648729999999999585e-01 8.058999999999999497e-02 +1.403715351562139988e+09 -4.849709999999999854e-01 -2.487115999999999882e+00 1.514780000000000015e-01 -8.051070000000000171e-01 -1.446270000000000056e-01 -5.695590000000000375e-01 8.054500000000000548e-02 +1.403715351612139940e+09 -4.691520000000000135e-01 -2.465324999999999989e+00 1.537409999999999888e-01 -8.003580000000000139e-01 -1.443240000000000078e-01 -5.763329999999999842e-01 8.023800000000000376e-02 +1.403715351662139893e+09 -4.540440000000000031e-01 -2.442286000000000179e+00 1.557560000000000056e-01 -7.979410000000000114e-01 -1.449100000000000110e-01 -5.795150000000000023e-01 8.033200000000000063e-02 +1.403715351712140083e+09 -4.397670000000000190e-01 -2.417994999999999894e+00 1.577459999999999973e-01 -7.973649999999999904e-01 -1.469270000000000020e-01 -5.797560000000000491e-01 8.064599999999999547e-02 +1.403715351762140036e+09 -4.267230000000000190e-01 -2.392250000000000210e+00 1.598930000000000073e-01 -7.980530000000000124e-01 -1.496750000000000025e-01 -5.778680000000000483e-01 8.232599999999999640e-02 +1.403715351812139988e+09 -4.146549999999999958e-01 -2.365088000000000079e+00 1.622929999999999928e-01 -7.984539999999999971e-01 -1.521560000000000135e-01 -5.759189999999999587e-01 8.738999999999999546e-02 +1.403715351862139940e+09 -4.032410000000000161e-01 -2.336844000000000143e+00 1.648469999999999935e-01 -7.991639999999999855e-01 -1.551349999999999951e-01 -5.730720000000000258e-01 9.412099999999999633e-02 +1.403715351912139893e+09 -3.925690000000000013e-01 -2.307833000000000023e+00 1.674589999999999967e-01 -7.993639999999999635e-01 -1.590940000000000132e-01 -5.704639999999999711e-01 1.013730000000000048e-01 +1.403715351962140083e+09 -3.824520000000000142e-01 -2.278340000000000032e+00 1.707200000000000106e-01 -7.997410000000000352e-01 -1.628139999999999865e-01 -5.671789999999999887e-01 1.105150000000000021e-01 +1.403715352012140036e+09 -3.728480000000000127e-01 -2.248653000000000013e+00 1.750079999999999969e-01 -7.995849999999999902e-01 -1.677319999999999922e-01 -5.641610000000000236e-01 1.193800000000000000e-01 +1.403715352062139988e+09 -3.640610000000000235e-01 -2.219219999999999970e+00 1.799979999999999913e-01 -7.993869999999999587e-01 -1.732180000000000109e-01 -5.609189999999999454e-01 1.278539999999999954e-01 +1.403715352112139940e+09 -3.551949999999999830e-01 -2.190265999999999824e+00 1.862939999999999874e-01 -7.987800000000000455e-01 -1.793690000000000007e-01 -5.584740000000000260e-01 1.337339999999999918e-01 +1.403715352162139893e+09 -3.465389999999999859e-01 -2.161671999999999816e+00 1.925560000000000049e-01 -7.979850000000000554e-01 -1.837699999999999889e-01 -5.565299999999999692e-01 1.404390000000000083e-01 +1.403715352212140083e+09 -3.392220000000000235e-01 -2.134145000000000181e+00 1.991310000000000024e-01 -7.970580000000000442e-01 -1.869899999999999896e-01 -5.551679999999999948e-01 1.467040000000000011e-01 +1.403715352262140036e+09 -3.303429999999999978e-01 -2.107021000000000033e+00 2.049199999999999910e-01 -7.969429999999999570e-01 -1.902770000000000017e-01 -5.532070000000000043e-01 1.504580000000000084e-01 +1.403715352312139988e+09 -3.209620000000000251e-01 -2.080080999999999847e+00 2.100730000000000097e-01 -7.974639999999999507e-01 -1.932949999999999946e-01 -5.506330000000000391e-01 1.532660000000000133e-01 +1.403715352362139940e+09 -3.113850000000000229e-01 -2.053862000000000076e+00 2.150610000000000022e-01 -7.974040000000000017e-01 -1.955500000000000016e-01 -5.492569999999999952e-01 1.556410000000000016e-01 +1.403715352412139893e+09 -3.013700000000000268e-01 -2.027932999999999986e+00 2.191659999999999997e-01 -7.975950000000000539e-01 -1.946930000000000049e-01 -5.477600000000000247e-01 1.609210000000000085e-01 +1.403715352462140083e+09 -2.910619999999999874e-01 -2.002810999999999897e+00 2.227669999999999928e-01 -7.980650000000000244e-01 -1.911619999999999986e-01 -5.458309999999999551e-01 1.691680000000000128e-01 +1.403715352512140036e+09 -2.801500000000000101e-01 -1.978560000000000096e+00 2.263519999999999976e-01 -7.975510000000000099e-01 -1.881569999999999909e-01 -5.454299999999999704e-01 1.761119999999999908e-01 +1.403715352562139988e+09 -2.681089999999999862e-01 -1.955993000000000093e+00 2.295520000000000060e-01 -7.965600000000000458e-01 -1.882220000000000004e-01 -5.461049999999999516e-01 1.784209999999999963e-01 +1.403715352612139940e+09 -2.553429999999999866e-01 -1.934928999999999899e+00 2.325570000000000137e-01 -7.948659999999999615e-01 -1.914319999999999911e-01 -5.483500000000000041e-01 1.756520000000000026e-01 +1.403715352662139893e+09 -2.422910000000000064e-01 -1.915103000000000000e+00 2.347170000000000090e-01 -7.935600000000000431e-01 -1.946690000000000087e-01 -5.500789999999999846e-01 1.725669999999999982e-01 +1.403715352712140083e+09 -2.287879999999999914e-01 -1.896206000000000058e+00 2.371820000000000039e-01 -7.914449999999999541e-01 -1.968399999999999872e-01 -5.531059999999999865e-01 1.701270000000000004e-01 +1.403715352762140036e+09 -2.154500000000000026e-01 -1.878387999999999947e+00 2.398550000000000126e-01 -7.888389999999999569e-01 -1.998250000000000026e-01 -5.568999999999999506e-01 1.663310000000000066e-01 +1.403715352812139988e+09 -2.020889999999999909e-01 -1.861029000000000044e+00 2.420960000000000056e-01 -7.860179999999999945e-01 -2.015460000000000029e-01 -5.608760000000000412e-01 1.642339999999999911e-01 +1.403715352862139940e+09 -1.892900000000000138e-01 -1.844769000000000103e+00 2.437960000000000127e-01 -7.839739999999999487e-01 -2.034809999999999952e-01 -5.636750000000000371e-01 1.620219999999999994e-01 +1.403715352912139893e+09 -1.772179999999999866e-01 -1.829331999999999958e+00 2.453980000000000050e-01 -7.829690000000000261e-01 -2.054850000000000010e-01 -5.651359999999999717e-01 1.592399999999999927e-01 +1.403715352962140083e+09 -1.661749999999999894e-01 -1.814557999999999893e+00 2.471659999999999968e-01 -7.822489999999999721e-01 -2.051419999999999910e-01 -5.660100000000000131e-01 1.601110000000000033e-01 +1.403715353012140036e+09 -1.557860000000000078e-01 -1.800262999999999947e+00 2.491659999999999986e-01 -7.820099999999999829e-01 -2.036550000000000027e-01 -5.661249999999999893e-01 1.627500000000000058e-01 +1.403715353062139988e+09 -1.461179999999999979e-01 -1.787007999999999930e+00 2.512599999999999834e-01 -7.819880000000000164e-01 -2.037349999999999994e-01 -5.659859999999999891e-01 1.632379999999999942e-01 +1.403715353112139940e+09 -1.370649999999999924e-01 -1.774491999999999958e+00 2.542880000000000140e-01 -7.823379999999999779e-01 -2.050230000000000108e-01 -5.652160000000000517e-01 1.626140000000000085e-01 +1.403715353162139893e+09 -1.286609999999999976e-01 -1.762726999999999933e+00 2.589380000000000015e-01 -7.830350000000000366e-01 -2.064930000000000099e-01 -5.638659999999999783e-01 1.620830000000000048e-01 +1.403715353212140083e+09 -1.209279999999999938e-01 -1.751600999999999964e+00 2.662979999999999792e-01 -7.832529999999999770e-01 -2.078869999999999885e-01 -5.631570000000000187e-01 1.617159999999999986e-01 +1.403715353262140036e+09 -1.139880000000000060e-01 -1.741220999999999908e+00 2.765059999999999740e-01 -7.832580000000000098e-01 -2.092189999999999883e-01 -5.625339999999999785e-01 1.621440000000000103e-01 +1.403715353312139988e+09 -1.077879999999999949e-01 -1.731546000000000030e+00 2.893490000000000228e-01 -7.836720000000000352e-01 -2.104250000000000009e-01 -5.613339999999999996e-01 1.627379999999999938e-01 +1.403715353362139940e+09 -1.022750000000000048e-01 -1.722568000000000099e+00 3.034450000000000203e-01 -7.841829999999999634e-01 -2.121460000000000012e-01 -5.598520000000000163e-01 1.631460000000000132e-01 +1.403715353412139893e+09 -9.646399999999999419e-02 -1.713462999999999958e+00 3.162389999999999923e-01 -7.842729999999999979e-01 -2.150479999999999892e-01 -5.588480000000000114e-01 1.623560000000000003e-01 +1.403715353462140083e+09 -9.126700000000000090e-02 -1.704685000000000006e+00 3.261220000000000230e-01 -7.838429999999999565e-01 -2.175030000000000019e-01 -5.585529999999999662e-01 1.621769999999999878e-01 +1.403715353512140036e+09 -8.627300000000000246e-02 -1.696131000000000055e+00 3.323189999999999755e-01 -7.839549999999999574e-01 -2.195229999999999959e-01 -5.576100000000000501e-01 1.621569999999999956e-01 +1.403715353562139988e+09 -8.177199999999999747e-02 -1.687985999999999986e+00 3.346270000000000078e-01 -7.839040000000000452e-01 -2.215999999999999914e-01 -5.570110000000000339e-01 1.616390000000000049e-01 +1.403715353612139940e+09 -7.751500000000000057e-02 -1.679791000000000034e+00 3.332910000000000039e-01 -7.838279999999999692e-01 -2.230939999999999868e-01 -5.563150000000000039e-01 1.623439999999999883e-01 +1.403715353662139893e+09 -7.369699999999999862e-02 -1.671874000000000082e+00 3.294119999999999826e-01 -7.831700000000000328e-01 -2.253799999999999970e-01 -5.564820000000000322e-01 1.617879999999999874e-01 +1.403715353712140083e+09 -6.986699999999999855e-02 -1.663712999999999997e+00 3.238639999999999852e-01 -7.826220000000000399e-01 -2.273260000000000003e-01 -5.565780000000000172e-01 1.613920000000000077e-01 +1.403715353762140036e+09 -6.699800000000000200e-02 -1.655758999999999981e+00 3.172440000000000260e-01 -7.819909999999999917e-01 -2.291849999999999998e-01 -5.566879999999999606e-01 1.614389999999999992e-01 +1.403715353812139988e+09 -6.460699999999999776e-02 -1.647496999999999989e+00 3.099270000000000080e-01 -7.810059999999999780e-01 -2.312510000000000121e-01 -5.573169999999999513e-01 1.610939999999999872e-01 +1.403715353912139893e+09 -6.144999999999999768e-02 -1.630878000000000050e+00 2.939880000000000271e-01 -7.797290000000000054e-01 -2.334630000000000039e-01 -5.578020000000000200e-01 1.624029999999999918e-01 +1.403715353962140083e+09 -6.049800000000000316e-02 -1.622462000000000071e+00 2.848990000000000133e-01 -7.798659999999999481e-01 -2.344380000000000075e-01 -5.570319999999999716e-01 1.629800000000000137e-01 +1.403715354012140036e+09 -6.007500000000000340e-02 -1.614050999999999902e+00 2.751489999999999769e-01 -7.801289999999999614e-01 -2.351159999999999917e-01 -5.560969999999999525e-01 1.639359999999999984e-01 +1.403715354062139988e+09 -5.981399999999999911e-02 -1.605196999999999985e+00 2.648119999999999918e-01 -7.819279999999999564e-01 -2.343040000000000123e-01 -5.530659999999999465e-01 1.667559999999999876e-01 +1.403715354112139940e+09 -6.011999999999999983e-02 -1.596678999999999959e+00 2.547539999999999805e-01 -7.838669999999999805e-01 -2.309920000000000029e-01 -5.497229999999999617e-01 1.732029999999999959e-01 +1.403715354162139893e+09 -6.046200000000000185e-02 -1.588418000000000108e+00 2.446929999999999938e-01 -7.856969999999999787e-01 -2.275749999999999995e-01 -5.465109999999999690e-01 1.794880000000000086e-01 +1.403715354212140083e+09 -6.060100000000000209e-02 -1.580881999999999898e+00 2.345909999999999940e-01 -7.873759999999999648e-01 -2.251329999999999998e-01 -5.434780000000000166e-01 1.843500000000000139e-01 +1.403715354262140036e+09 -5.984899999999999942e-02 -1.574246999999999952e+00 2.249039999999999928e-01 -7.887579999999999592e-01 -2.245769999999999988e-01 -5.410620000000000429e-01 1.862199999999999966e-01 +1.403715354312139988e+09 -5.866799999999999793e-02 -1.568427000000000016e+00 2.160620000000000041e-01 -7.890519999999999756e-01 -2.257339999999999902e-01 -5.403569999999999762e-01 1.856200000000000072e-01 +1.403715354362139940e+09 -5.707999999999999879e-02 -1.563795999999999964e+00 2.074020000000000030e-01 -7.895280000000000076e-01 -2.283679999999999877e-01 -5.396149999999999558e-01 1.825080000000000036e-01 +1.403715354412139893e+09 -5.438400000000000178e-02 -1.559175999999999895e+00 1.990030000000000132e-01 -7.896990000000000398e-01 -2.318159999999999943e-01 -5.393639999999999546e-01 1.781089999999999895e-01 +1.403715354462140083e+09 -5.084600000000000231e-02 -1.554750000000000076e+00 1.910030000000000061e-01 -7.896990000000000398e-01 -2.350559999999999872e-01 -5.392479999999999496e-01 1.741719999999999935e-01 +1.403715354512140036e+09 -4.683999999999999969e-02 -1.550448999999999966e+00 1.832300000000000040e-01 -7.893540000000000001e-01 -2.376179999999999959e-01 -5.396170000000000133e-01 1.710899999999999921e-01 +1.403715354562139988e+09 -4.253799999999999942e-02 -1.545944999999999903e+00 1.760279999999999900e-01 -7.891280000000000516e-01 -2.386659999999999893e-01 -5.398789999999999978e-01 1.698429999999999940e-01 +1.403715354612139940e+09 -3.800699999999999912e-02 -1.541339999999999932e+00 1.710639999999999938e-01 -7.885870000000000379e-01 -2.385220000000000118e-01 -5.406750000000000167e-01 1.700250000000000095e-01 +1.403715354662139893e+09 -3.291499999999999981e-02 -1.536470000000000002e+00 1.683219999999999994e-01 -7.885199999999999987e-01 -2.383359999999999923e-01 -5.409100000000000019e-01 1.698459999999999970e-01 +1.403715354712140083e+09 -2.702999999999999847e-02 -1.531633999999999940e+00 1.686650000000000094e-01 -7.884860000000000202e-01 -2.377150000000000096e-01 -5.411240000000000494e-01 1.701940000000000119e-01 +1.403715354762140036e+09 -2.064300000000000163e-02 -1.526739999999999986e+00 1.724299999999999999e-01 -7.884839999999999627e-01 -2.371300000000000074e-01 -5.413740000000000219e-01 1.702279999999999904e-01 +1.403715354812139988e+09 -1.384999999999999946e-02 -1.521733000000000002e+00 1.790730000000000099e-01 -7.890369999999999884e-01 -2.363590000000000135e-01 -5.406579999999999719e-01 1.710089999999999943e-01 +1.403715354862139940e+09 -7.169000000000000025e-03 -1.517052999999999985e+00 1.884830000000000116e-01 -7.887680000000000247e-01 -2.364410000000000123e-01 -5.411740000000000439e-01 1.705039999999999889e-01 +1.403715354912139893e+09 -2.300000000000000070e-04 -1.511970999999999954e+00 2.006640000000000090e-01 -7.887300000000000422e-01 -2.344489999999999907e-01 -5.409819999999999629e-01 1.740019999999999900e-01 +1.403715354962140083e+09 7.008000000000000340e-03 -1.507586000000000093e+00 2.145140000000000102e-01 -7.883869999999999489e-01 -2.330319999999999891e-01 -5.410719999999999974e-01 1.771540000000000059e-01 +1.403715355012140036e+09 1.460299999999999966e-02 -1.503258999999999901e+00 2.297919999999999963e-01 -7.874160000000000048e-01 -2.320250000000000090e-01 -5.419209999999999861e-01 1.801699999999999968e-01 +1.403715355062139988e+09 2.291199999999999834e-02 -1.499414000000000025e+00 2.445180000000000131e-01 -7.868540000000000534e-01 -2.326920000000000099e-01 -5.422630000000000505e-01 1.807380000000000098e-01 +1.403715355112139940e+09 3.148000000000000104e-02 -1.496062999999999921e+00 2.582990000000000008e-01 -7.864919999999999689e-01 -2.350740000000000052e-01 -5.419610000000000261e-01 1.801339999999999886e-01 +1.403715355162139893e+09 4.010400000000000076e-02 -1.492801999999999962e+00 2.714590000000000058e-01 -7.855199999999999960e-01 -2.388369999999999937e-01 -5.414400000000000324e-01 1.809929999999999872e-01 +1.403715355212140083e+09 4.899200000000000083e-02 -1.489503999999999939e+00 2.838169999999999860e-01 -7.849209999999999798e-01 -2.435140000000000082e-01 -5.393350000000000088e-01 1.836250000000000104e-01 +1.403715355262140036e+09 5.792100000000000026e-02 -1.486439000000000066e+00 2.957929999999999726e-01 -7.830110000000000126e-01 -2.500569999999999737e-01 -5.381960000000000077e-01 1.863059999999999994e-01 +1.403715355312139988e+09 6.709099999999999786e-02 -1.483316000000000079e+00 3.067259999999999986e-01 -7.810000000000000275e-01 -2.586519999999999930e-01 -5.361879999999999979e-01 1.887860000000000094e-01 +1.403715355362139940e+09 7.632799999999999307e-02 -1.479980999999999991e+00 3.172039999999999860e-01 -7.784849999999999826e-01 -2.677149999999999808e-01 -5.340840000000000032e-01 1.924690000000000012e-01 +1.403715355412139893e+09 8.572100000000000553e-02 -1.476606000000000085e+00 3.279199999999999893e-01 -7.749479999999999702e-01 -2.765159999999999840e-01 -5.326670000000000016e-01 1.981459999999999888e-01 +1.403715355462140083e+09 9.490400000000000225e-02 -1.472860999999999976e+00 3.385349999999999748e-01 -7.712849999999999984e-01 -2.851739999999999831e-01 -5.306039999999999646e-01 2.055609999999999937e-01 +1.403715355512140036e+09 1.043000000000000038e-01 -1.469303000000000026e+00 3.492830000000000101e-01 -7.666800000000000281e-01 -2.939959999999999796e-01 -5.294489999999999474e-01 2.131919999999999926e-01 +1.403715355562139988e+09 1.138239999999999946e-01 -1.465648000000000062e+00 3.597099999999999742e-01 -7.622820000000000151e-01 -3.032989999999999853e-01 -5.276129999999999987e-01 2.203650000000000053e-01 +1.403715355612139940e+09 1.229530000000000067e-01 -1.462296999999999958e+00 3.695840000000000236e-01 -7.582020000000000426e-01 -3.126349999999999962e-01 -5.249380000000000157e-01 2.276600000000000013e-01 +1.403715355662139893e+09 1.323030000000000039e-01 -1.459680000000000089e+00 3.785899999999999821e-01 -7.539770000000000083e-01 -3.224090000000000011e-01 -5.229390000000000427e-01 2.326070000000000082e-01 +1.403715355712140083e+09 1.419999999999999873e-01 -1.457343999999999973e+00 3.871419999999999861e-01 -7.502429999999999932e-01 -3.307999999999999829e-01 -5.210700000000000331e-01 2.370500000000000107e-01 +1.403715355762140036e+09 1.517159999999999898e-01 -1.455248000000000097e+00 3.950540000000000163e-01 -7.471139999999999448e-01 -3.381100000000000216e-01 -5.194130000000000136e-01 2.402360000000000051e-01 +1.403715355812139988e+09 1.613189999999999902e-01 -1.453424000000000049e+00 4.024829999999999797e-01 -7.450179999999999580e-01 -3.442509999999999737e-01 -5.175840000000000440e-01 2.419640000000000124e-01 +1.403715355862139940e+09 1.708870000000000111e-01 -1.451472000000000095e+00 4.098809999999999953e-01 -7.437439999999999607e-01 -3.490309999999999802e-01 -5.155790000000000095e-01 2.433099999999999985e-01 +1.403715355912139893e+09 1.805259999999999920e-01 -1.449244999999999894e+00 4.174379999999999757e-01 -7.424269999999999481e-01 -3.529329999999999967e-01 -5.143760000000000554e-01 2.442479999999999929e-01 +1.403715355962140083e+09 1.911670000000000036e-01 -1.446647999999999934e+00 4.246240000000000014e-01 -7.415310000000000512e-01 -3.565769999999999773e-01 -5.135070000000000467e-01 2.435049999999999992e-01 +1.403715356012140036e+09 2.009309999999999985e-01 -1.444210999999999911e+00 4.318290000000000184e-01 -7.404920000000000391e-01 -3.592799999999999883e-01 -5.137350000000000527e-01 2.422100000000000086e-01 +1.403715356062139988e+09 2.105899999999999994e-01 -1.441078000000000081e+00 4.390169999999999906e-01 -7.398120000000000251e-01 -3.622170000000000112e-01 -5.141520000000000534e-01 2.390059999999999962e-01 +1.403715356162139893e+09 2.281529999999999947e-01 -1.433939999999999992e+00 4.528229999999999755e-01 -7.393410000000000259e-01 -3.661780000000000035e-01 -5.162879999999999692e-01 2.296410000000000118e-01 +1.403715356212140083e+09 2.355379999999999974e-01 -1.429068000000000005e+00 4.593829999999999858e-01 -7.392480000000000162e-01 -3.659549999999999748e-01 -5.183050000000000157e-01 2.257210000000000050e-01 +1.403715356262140036e+09 2.423589999999999911e-01 -1.422944999999999904e+00 4.656440000000000023e-01 -7.397259999999999946e-01 -3.647380000000000067e-01 -5.198559999999999848e-01 2.225350000000000106e-01 +1.403715356312139988e+09 2.480799999999999950e-01 -1.415893999999999986e+00 4.709960000000000258e-01 -7.411659999999999915e-01 -3.632650000000000046e-01 -5.202799999999999647e-01 2.191359999999999975e-01 +1.403715356362139940e+09 2.531329999999999969e-01 -1.407577999999999996e+00 4.753049999999999775e-01 -7.440689999999999804e-01 -3.609109999999999818e-01 -5.188160000000000549e-01 2.166420000000000012e-01 +1.403715356412139893e+09 2.574699999999999767e-01 -1.397890999999999995e+00 4.788129999999999886e-01 -7.473049999999999971e-01 -3.583250000000000046e-01 -5.167079999999999451e-01 2.148269999999999902e-01 +1.403715356462140083e+09 2.611620000000000053e-01 -1.386798999999999893e+00 4.815889999999999893e-01 -7.507260000000000044e-01 -3.543930000000000136e-01 -5.144699999999999829e-01 2.147950000000000137e-01 +1.403715356512140036e+09 2.644360000000000044e-01 -1.374405000000000099e+00 4.833640000000000159e-01 -7.546659999999999480e-01 -3.481589999999999963e-01 -5.114279999999999937e-01 2.184170000000000000e-01 +1.403715356562139988e+09 2.678849999999999842e-01 -1.360756000000000077e+00 4.846719999999999917e-01 -7.570219999999999727e-01 -3.435449999999999893e-01 -5.096100000000000074e-01 2.217929999999999902e-01 +1.403715356612139940e+09 2.713490000000000069e-01 -1.345472000000000001e+00 4.859499999999999931e-01 -7.584020000000000206e-01 -3.406460000000000043e-01 -5.078939999999999566e-01 2.254569999999999907e-01 +1.403715356662139893e+09 2.753340000000000232e-01 -1.329442000000000013e+00 4.868040000000000145e-01 -7.583800000000000541e-01 -3.393320000000000225e-01 -5.068540000000000267e-01 2.298090000000000133e-01 +1.403715356712140083e+09 2.798019999999999952e-01 -1.312361000000000111e+00 4.875320000000000209e-01 -7.576840000000000241e-01 -3.404750000000000276e-01 -5.053919999999999524e-01 2.336030000000000051e-01 +1.403715356762140036e+09 2.847529999999999784e-01 -1.294883999999999924e+00 4.882380000000000053e-01 -7.561360000000000303e-01 -3.428320000000000256e-01 -5.039979999999999460e-01 2.381399999999999906e-01 +1.403715356812139988e+09 2.903470000000000217e-01 -1.276391000000000053e+00 4.882190000000000141e-01 -7.535159999999999636e-01 -3.465799999999999992e-01 -5.027570000000000094e-01 2.435809999999999920e-01 +1.403715356862139940e+09 2.965530000000000110e-01 -1.257643000000000066e+00 4.876940000000000164e-01 -7.510869999999999491e-01 -3.529289999999999927e-01 -4.998369999999999758e-01 2.479349999999999887e-01 +1.403715356912139893e+09 3.036630000000000162e-01 -1.238593000000000055e+00 4.873179999999999734e-01 -7.482609999999999539e-01 -3.591010000000000035e-01 -4.963529999999999887e-01 2.545299999999999785e-01 +1.403715356962140083e+09 3.117349999999999843e-01 -1.218693999999999944e+00 4.890410000000000035e-01 -7.441849999999999854e-01 -3.659140000000000170e-01 -4.932050000000000045e-01 2.627639999999999976e-01 +1.403715357012140036e+09 3.206140000000000101e-01 -1.198598999999999970e+00 4.925519999999999898e-01 -7.383180000000000298e-01 -3.746820000000000150e-01 -4.915390000000000037e-01 2.699819999999999998e-01 +1.403715357062139988e+09 3.303670000000000218e-01 -1.178503999999999996e+00 4.969999999999999973e-01 -7.326930000000000387e-01 -3.839779999999999860e-01 -4.884049999999999780e-01 2.778169999999999806e-01 +1.403715357112139940e+09 3.403820000000000179e-01 -1.158376000000000072e+00 5.026359999999999717e-01 -7.260050000000000114e-01 -3.933719999999999994e-01 -4.865300000000000180e-01 2.854180000000000050e-01 +1.403715357162139893e+09 3.509579999999999922e-01 -1.138663999999999898e+00 5.084349999999999703e-01 -7.195489999999999942e-01 -4.033720000000000083e-01 -4.841659999999999853e-01 2.917589999999999906e-01 +1.403715357212140083e+09 3.623700000000000254e-01 -1.119345000000000034e+00 5.150280000000000413e-01 -7.135249999999999648e-01 -4.129090000000000260e-01 -4.818720000000000225e-01 2.969620000000000037e-01 +1.403715357262140036e+09 3.748540000000000205e-01 -1.100225999999999926e+00 5.222510000000000208e-01 -7.071650000000000436e-01 -4.213359999999999883e-01 -4.816590000000000038e-01 3.006630000000000136e-01 +1.403715357312139988e+09 3.884090000000000042e-01 -1.081153000000000031e+00 5.298920000000000297e-01 -7.018140000000000489e-01 -4.287920000000000065e-01 -4.819559999999999955e-01 3.021800000000000042e-01 +1.403715357362139940e+09 4.020719999999999850e-01 -1.062235000000000040e+00 5.385440000000000227e-01 -6.973880000000000079e-01 -4.350499999999999923e-01 -4.824620000000000020e-01 3.026760000000000006e-01 +1.403715357412139893e+09 4.159809999999999897e-01 -1.043533999999999962e+00 5.471669999999999590e-01 -6.944190000000000085e-01 -4.393469999999999875e-01 -4.821650000000000102e-01 3.037670000000000092e-01 +1.403715357462140083e+09 4.297369999999999801e-01 -1.025382999999999933e+00 5.554409999999999625e-01 -6.915390000000000148e-01 -4.434449999999999781e-01 -4.827489999999999837e-01 3.034549999999999748e-01 +1.403715357512140036e+09 4.423670000000000102e-01 -1.008569000000000049e+00 5.629429999999999712e-01 -6.903939999999999522e-01 -4.470029999999999837e-01 -4.816179999999999906e-01 3.026360000000000161e-01 +1.403715357562139988e+09 4.557769999999999877e-01 -9.904220000000000246e-01 5.691969999999999530e-01 -6.897170000000000245e-01 -4.499949999999999783e-01 -4.804399999999999782e-01 3.016150000000000220e-01 +1.403715357612139940e+09 4.687310000000000088e-01 -9.720860000000000056e-01 5.753289999999999793e-01 -6.890260000000000273e-01 -4.529139999999999833e-01 -4.795130000000000225e-01 3.002980000000000094e-01 +1.403715357662139893e+09 4.813060000000000116e-01 -9.532680000000000042e-01 5.813770000000000326e-01 -6.876520000000000410e-01 -4.551089999999999858e-01 -4.800650000000000195e-01 2.992460000000000120e-01 +1.403715357712140083e+09 4.934189999999999965e-01 -9.340509999999999646e-01 5.880779999999999896e-01 -6.849509999999999765e-01 -4.563679999999999959e-01 -4.827850000000000197e-01 2.991469999999999962e-01 +1.403715357762140036e+09 5.046969999999999512e-01 -9.147129999999999983e-01 5.937789999999999457e-01 -6.830929999999999502e-01 -4.581640000000000157e-01 -4.845849999999999880e-01 2.977380000000000027e-01 +1.403715357812139988e+09 5.149449999999999861e-01 -8.949730000000000185e-01 5.986160000000000370e-01 -6.804620000000000113e-01 -4.606219999999999759e-01 -4.874479999999999924e-01 2.952850000000000197e-01 +1.403715357862139940e+09 5.234109999999999596e-01 -8.749780000000000335e-01 6.028999999999999915e-01 -6.784109999999999863e-01 -4.634409999999999918e-01 -4.897580000000000267e-01 2.917500000000000093e-01 +1.403715357912139893e+09 5.308119999999999505e-01 -8.539320000000000244e-01 6.058480000000000532e-01 -6.774529999999999719e-01 -4.653530000000000166e-01 -4.907779999999999920e-01 2.892069999999999919e-01 +1.403715357962140083e+09 5.365220000000000544e-01 -8.320840000000000458e-01 6.080590000000000162e-01 -6.778269999999999573e-01 -4.666469999999999785e-01 -4.902590000000000003e-01 2.871190000000000131e-01 +1.403715358012140036e+09 5.413400000000000434e-01 -8.089600000000000124e-01 6.094530000000000225e-01 -6.784050000000000358e-01 -4.678450000000000109e-01 -4.893080000000000207e-01 2.854200000000000070e-01 +1.403715358062139988e+09 5.447410000000000307e-01 -7.847539999999999516e-01 6.101299999999999502e-01 -6.791500000000000314e-01 -4.687859999999999805e-01 -4.883350000000000191e-01 2.837680000000000202e-01 +1.403715358112139940e+09 5.467530000000000445e-01 -7.589089999999999447e-01 6.094359999999999777e-01 -6.806630000000000180e-01 -4.679849999999999843e-01 -4.865180000000000060e-01 2.845849999999999769e-01 +1.403715358162139893e+09 5.476619999999999822e-01 -7.321290000000000298e-01 6.087580000000000213e-01 -6.823900000000000521e-01 -4.658079999999999998e-01 -4.846909999999999830e-01 2.871239999999999903e-01 +1.403715358212140083e+09 5.476659999999999862e-01 -7.040910000000000224e-01 6.070670000000000233e-01 -6.856889999999999930e-01 -4.631060000000000176e-01 -4.808029999999999804e-01 2.901599999999999735e-01 +1.403715358262140036e+09 5.469450000000000145e-01 -6.749990000000000157e-01 6.057000000000000162e-01 -6.876980000000000315e-01 -4.608280000000000154e-01 -4.783540000000000014e-01 2.930650000000000199e-01 +1.403715358312139988e+09 5.462200000000000388e-01 -6.443320000000000158e-01 6.031859999999999999e-01 -6.894959999999999978e-01 -4.600480000000000125e-01 -4.759229999999999849e-01 2.940209999999999768e-01 +1.403715358362139940e+09 5.454369999999999497e-01 -6.128200000000000314e-01 6.011429999999999829e-01 -6.897569999999999535e-01 -4.612959999999999838e-01 -4.745690000000000186e-01 2.936420000000000141e-01 +1.403715358412139893e+09 5.441200000000000481e-01 -5.801899999999999835e-01 5.993490000000000206e-01 -6.875480000000000480e-01 -4.647540000000000004e-01 -4.752460000000000018e-01 2.922730000000000050e-01 +1.403715358462140083e+09 5.420319999999999583e-01 -5.467389999999999750e-01 5.971670000000000034e-01 -6.840389999999999526e-01 -4.685579999999999745e-01 -4.762120000000000242e-01 2.928589999999999804e-01 +1.403715358512140036e+09 5.392850000000000144e-01 -5.116910000000000069e-01 5.950100000000000389e-01 -6.788129999999999997e-01 -4.726159999999999806e-01 -4.784419999999999784e-01 2.948560000000000070e-01 +1.403715358562139988e+09 5.356530000000000458e-01 -4.759929999999999994e-01 5.924409999999999954e-01 -6.737199999999999855e-01 -4.764950000000000019e-01 -4.800929999999999920e-01 2.975970000000000004e-01 +1.403715358612139940e+09 5.310540000000000260e-01 -4.396189999999999820e-01 5.892030000000000323e-01 -6.690040000000000431e-01 -4.797770000000000090e-01 -4.811050000000000049e-01 3.013049999999999895e-01 +1.403715358662139893e+09 5.254529999999999479e-01 -4.021379999999999955e-01 5.861359999999999904e-01 -6.649009999999999643e-01 -4.812939999999999996e-01 -4.811819999999999986e-01 3.077770000000000228e-01 +1.403715358712140083e+09 5.188000000000000389e-01 -3.638730000000000020e-01 5.832629999999999759e-01 -6.620200000000000529e-01 -4.802339999999999942e-01 -4.792750000000000066e-01 3.184359999999999968e-01 +1.403715358762140036e+09 5.114030000000000520e-01 -3.260120000000000240e-01 5.806510000000000282e-01 -6.594999999999999751e-01 -4.796290000000000275e-01 -4.767480000000000051e-01 3.282200000000000117e-01 +1.403715358812139988e+09 5.035399999999999876e-01 -2.884559999999999902e-01 5.780229999999999535e-01 -6.568739999999999579e-01 -4.796130000000000115e-01 -4.747480000000000033e-01 3.363079999999999958e-01 +1.403715358862139940e+09 4.957929999999999837e-01 -2.515100000000000113e-01 5.750929999999999653e-01 -6.545710000000000139e-01 -4.799140000000000073e-01 -4.724740000000000051e-01 3.434940000000000215e-01 +1.403715358912139893e+09 4.876389999999999891e-01 -2.157560000000000033e-01 5.722220000000000084e-01 -6.516110000000000513e-01 -4.803799999999999737e-01 -4.719099999999999961e-01 3.491980000000000084e-01 +1.403715358962140083e+09 4.792930000000000246e-01 -1.807600000000000040e-01 5.687079999999999913e-01 -6.493820000000000148e-01 -4.818060000000000120e-01 -4.707589999999999830e-01 3.529200000000000115e-01 +1.403715359012140036e+09 4.711710000000000065e-01 -1.466719999999999968e-01 5.644789999999999530e-01 -6.487540000000000529e-01 -4.832330000000000236e-01 -4.677649999999999864e-01 3.560900000000000176e-01 +1.403715359062139988e+09 4.631950000000000234e-01 -1.137159999999999976e-01 5.596860000000000168e-01 -6.485429999999999806e-01 -4.855439999999999756e-01 -4.648149999999999782e-01 3.571900000000000075e-01 +1.403715359112139940e+09 4.554429999999999867e-01 -8.218399999999999317e-02 5.553050000000000486e-01 -6.476699999999999680e-01 -4.871380000000000154e-01 -4.635949999999999793e-01 3.581889999999999796e-01 +1.403715359162139893e+09 4.482760000000000078e-01 -5.214499999999999691e-02 5.509450000000000180e-01 -6.461449999999999694e-01 -4.881630000000000136e-01 -4.637350000000000083e-01 3.593640000000000168e-01 +1.403715359212140083e+09 4.408659999999999801e-01 -2.293399999999999953e-02 5.468769999999999465e-01 -6.445889999999999675e-01 -4.882690000000000086e-01 -4.646159999999999735e-01 3.608750000000000013e-01 +1.403715359262140036e+09 4.331519999999999815e-01 4.877000000000000259e-03 5.432879999999999932e-01 -6.430740000000000345e-01 -4.887199999999999878e-01 -4.661210000000000075e-01 3.610280000000000156e-01 +1.403715359312139988e+09 4.257850000000000246e-01 3.081400000000000111e-02 5.395699999999999941e-01 -6.420540000000000136e-01 -4.897790000000000199e-01 -4.675770000000000204e-01 3.595209999999999795e-01 +1.403715359362139940e+09 4.178720000000000212e-01 5.546399999999999941e-02 5.354689999999999728e-01 -6.415499999999999536e-01 -4.910959999999999770e-01 -4.686080000000000245e-01 3.572739999999999805e-01 +1.403715359412139893e+09 4.092939999999999912e-01 7.889699999999999491e-02 5.321719999999999784e-01 -6.405110000000000525e-01 -4.927549999999999986e-01 -4.710320000000000062e-01 3.536480000000000179e-01 +1.403715359462140083e+09 4.002780000000000227e-01 1.017190000000000039e-01 5.293670000000000320e-01 -6.393469999999999986e-01 -4.943580000000000196e-01 -4.737279999999999824e-01 3.498959999999999848e-01 +1.403715359512140036e+09 3.903570000000000095e-01 1.236020000000000035e-01 5.273550000000000182e-01 -6.383929999999999882e-01 -4.953929999999999723e-01 -4.761000000000000232e-01 3.469430000000000014e-01 +1.403715359562139988e+09 3.794640000000000235e-01 1.447180000000000133e-01 5.262480000000000491e-01 -6.377239999999999576e-01 -4.952739999999999920e-01 -4.783040000000000069e-01 3.453069999999999751e-01 +1.403715359612139940e+09 3.673770000000000091e-01 1.651390000000000080e-01 5.258289999999999909e-01 -6.376570000000000293e-01 -4.943250000000000144e-01 -4.792690000000000006e-01 3.454539999999999833e-01 +1.403715359662139893e+09 3.539829999999999921e-01 1.843269999999999909e-01 5.255389999999999784e-01 -6.387350000000000527e-01 -4.931530000000000080e-01 -4.786250000000000226e-01 3.460300000000000042e-01 +1.403715359712140083e+09 3.398289999999999922e-01 2.024880000000000013e-01 5.258789999999999853e-01 -6.404940000000000078e-01 -4.917110000000000092e-01 -4.770619999999999861e-01 3.469869999999999899e-01 +1.403715359762140036e+09 3.246760000000000201e-01 2.199760000000000049e-01 5.265379999999999505e-01 -6.425819999999999865e-01 -4.905760000000000121e-01 -4.749079999999999968e-01 3.476870000000000238e-01 +1.403715359812139988e+09 3.087190000000000212e-01 2.364199999999999913e-01 5.278990000000000071e-01 -6.440150000000000041e-01 -4.888970000000000260e-01 -4.736859999999999959e-01 3.490650000000000142e-01 +1.403715359862139940e+09 2.921340000000000048e-01 2.521970000000000045e-01 5.294539999999999802e-01 -6.455009999999999915e-01 -4.885709999999999775e-01 -4.719999999999999751e-01 3.490579999999999794e-01 +1.403715359912139893e+09 2.752330000000000054e-01 2.668980000000000241e-01 5.311860000000000470e-01 -6.481200000000000294e-01 -4.880740000000000078e-01 -4.686489999999999823e-01 3.494169999999999776e-01 +1.403715359962140083e+09 2.580609999999999848e-01 2.811420000000000030e-01 5.328009999999999691e-01 -6.510880000000000001e-01 -4.865880000000000205e-01 -4.646140000000000270e-01 3.513549999999999729e-01 +1.403715360012140036e+09 2.406739999999999990e-01 2.945070000000000188e-01 5.349329999999999918e-01 -6.527020000000000044e-01 -4.869280000000000275e-01 -4.622820000000000262e-01 3.509650000000000269e-01 +1.403715360062139988e+09 2.235149999999999915e-01 3.077989999999999893e-01 5.370700000000000474e-01 -6.536809999999999565e-01 -4.877190000000000136e-01 -4.607800000000000229e-01 3.500190000000000246e-01 +1.403715360112139940e+09 2.063149999999999984e-01 3.206950000000000078e-01 5.391380000000000061e-01 -6.540799999999999947e-01 -4.886389999999999900e-01 -4.598889999999999922e-01 3.491600000000000259e-01 +1.403715360162139893e+09 1.891859999999999931e-01 3.333740000000000037e-01 5.413489999999999691e-01 -6.540280000000000538e-01 -4.896690000000000209e-01 -4.595670000000000033e-01 3.482379999999999920e-01 +1.403715360212140083e+09 1.721860000000000057e-01 3.458820000000000228e-01 5.434499999999999886e-01 -6.540270000000000250e-01 -4.903910000000000213e-01 -4.592919999999999781e-01 3.475860000000000061e-01 +1.403715360262140036e+09 1.553259999999999919e-01 3.575189999999999757e-01 5.457920000000000549e-01 -6.545370000000000354e-01 -4.902199999999999891e-01 -4.591040000000000121e-01 3.471139999999999781e-01 +1.403715360312139988e+09 1.385379999999999945e-01 3.685430000000000095e-01 5.478410000000000224e-01 -6.561759999999999815e-01 -4.882029999999999981e-01 -4.588209999999999789e-01 3.472379999999999911e-01 +1.403715360362139940e+09 1.222189999999999943e-01 3.794210000000000083e-01 5.498210000000000042e-01 -6.598249999999999948e-01 -4.834439999999999849e-01 -4.573220000000000063e-01 3.489539999999999864e-01 +1.403715360412139893e+09 1.063599999999999962e-01 3.897439999999999793e-01 5.520119999999999472e-01 -6.647539999999999560e-01 -4.764900000000000246e-01 -4.554030000000000022e-01 3.516630000000000034e-01 +1.403715360462140083e+09 9.132400000000000240e-02 3.995659999999999767e-01 5.542000000000000259e-01 -6.704989999999999561e-01 -4.685340000000000060e-01 -4.538340000000000152e-01 3.534709999999999797e-01 +1.403715360512140036e+09 7.751099999999999657e-02 4.086339999999999972e-01 5.562989999999999879e-01 -6.765729999999999800e-01 -4.597339999999999760e-01 -4.531189999999999940e-01 3.543689999999999896e-01 +1.403715360562139988e+09 6.544800000000000617e-02 4.169709999999999805e-01 5.584280000000000355e-01 -6.823559999999999626e-01 -4.509600000000000275e-01 -4.539449999999999874e-01 3.534939999999999749e-01 +1.403715360612139940e+09 5.509900000000000214e-02 4.248270000000000102e-01 5.612850000000000339e-01 -6.878400000000000070e-01 -4.428779999999999939e-01 -4.564929999999999821e-01 3.497859999999999858e-01 +1.403715360662139893e+09 4.674999999999999989e-02 4.316809999999999814e-01 5.650429999999999620e-01 -6.923979999999999579e-01 -4.351610000000000200e-01 -4.612789999999999946e-01 3.441529999999999867e-01 +1.403715360712140083e+09 4.025800000000000212e-02 4.372460000000000235e-01 5.694420000000000037e-01 -6.970939999999999914e-01 -4.274990000000000179e-01 -4.663820000000000188e-01 3.373320000000000207e-01 +1.403715360762140036e+09 3.552400000000000002e-02 4.417829999999999813e-01 5.741249999999999964e-01 -7.012610000000000232e-01 -4.213500000000000023e-01 -4.728749999999999898e-01 3.272410000000000041e-01 +1.403715360812139988e+09 3.187199999999999755e-02 4.454299999999999926e-01 5.784380000000000077e-01 -7.058320000000000149e-01 -4.146500000000000186e-01 -4.793490000000000251e-01 3.163730000000000153e-01 +1.403715360862139940e+09 2.919599999999999973e-02 4.480739999999999723e-01 5.829309999999999770e-01 -7.102950000000000097e-01 -4.076339999999999963e-01 -4.860090000000000243e-01 3.051400000000000223e-01 +1.403715360912139893e+09 2.766700000000000062e-02 4.506780000000000230e-01 5.876409999999999689e-01 -7.144899999999999585e-01 -3.997950000000000115e-01 -4.930019999999999958e-01 2.943069999999999853e-01 +1.403715360962140083e+09 2.661399999999999877e-02 4.527229999999999865e-01 5.922220000000000262e-01 -7.196190000000000087e-01 -3.912160000000000082e-01 -4.985479999999999912e-01 2.838109999999999800e-01 +1.403715361012140036e+09 2.578300000000000036e-02 4.545870000000000188e-01 5.967970000000000219e-01 -7.248499999999999943e-01 -3.818349999999999800e-01 -5.035969999999999613e-01 2.741970000000000240e-01 +1.403715361062139988e+09 2.499600000000000086e-02 4.564300000000000024e-01 6.011170000000000124e-01 -7.302650000000000530e-01 -3.720040000000000013e-01 -5.081569999999999698e-01 2.647669999999999746e-01 +1.403715361112139940e+09 2.428200000000000150e-02 4.575850000000000195e-01 6.055650000000000199e-01 -7.360809999999999853e-01 -3.614820000000000255e-01 -5.118129999999999624e-01 2.560529999999999751e-01 +1.403715361162139893e+09 2.327900000000000108e-02 4.590859999999999941e-01 6.105089999999999684e-01 -7.418000000000000149e-01 -3.508910000000000085e-01 -5.151080000000000103e-01 2.475300000000000000e-01 +1.403715361212140083e+09 2.252600000000000088e-02 4.605250000000000177e-01 6.153499999999999526e-01 -7.472739999999999938e-01 -3.405750000000000166e-01 -5.185300000000000464e-01 2.381520000000000026e-01 +1.403715361262140036e+09 2.168399999999999841e-02 4.627160000000000162e-01 6.201649999999999663e-01 -7.523440000000000127e-01 -3.301499999999999990e-01 -5.219390000000000418e-01 2.292589999999999906e-01 +1.403715361312139988e+09 2.028500000000000095e-02 4.648450000000000082e-01 6.244070000000000453e-01 -7.571250000000000480e-01 -3.200999999999999956e-01 -5.252970000000000139e-01 2.199119999999999964e-01 +1.403715361362139940e+09 1.897799999999999834e-02 4.668849999999999945e-01 6.288540000000000241e-01 -7.612999999999999767e-01 -3.098500000000000143e-01 -5.292419999999999902e-01 2.105190000000000117e-01 +1.403715361412139893e+09 1.751600000000000032e-02 4.701210000000000111e-01 6.322219999999999507e-01 -7.656380000000000408e-01 -2.994490000000000207e-01 -5.324740000000000029e-01 2.014950000000000074e-01 +1.403715361462140083e+09 1.553700000000000046e-02 4.731119999999999770e-01 6.345269999999999522e-01 -7.695689999999999475e-01 -2.891159999999999841e-01 -5.354830000000000423e-01 1.934750000000000081e-01 +1.403715361512140036e+09 1.334199999999999969e-02 4.772669999999999968e-01 6.366870000000000029e-01 -7.726490000000000302e-01 -2.800610000000000044e-01 -5.383489999999999664e-01 1.864399999999999946e-01 +1.403715361562139988e+09 1.072099999999999963e-02 4.821389999999999842e-01 6.378359999999999586e-01 -7.755189999999999584e-01 -2.725910000000000277e-01 -5.402500000000000080e-01 1.799860000000000071e-01 +1.403715361612139940e+09 7.738000000000000086e-03 4.879649999999999821e-01 6.387410000000000032e-01 -7.778629999999999711e-01 -2.670919999999999961e-01 -5.418469999999999676e-01 1.731840000000000046e-01 +1.403715361662139893e+09 4.545000000000000429e-03 4.947409999999999863e-01 6.389599999999999724e-01 -7.799599999999999866e-01 -2.619449999999999834e-01 -5.428699999999999637e-01 1.683439999999999936e-01 +1.403715361712140083e+09 1.317000000000000028e-03 5.026920000000000277e-01 6.382449999999999513e-01 -7.828519999999999923e-01 -2.561359999999999748e-01 -5.426919999999999522e-01 1.643870000000000053e-01 +1.403715361762140036e+09 -2.037000000000000182e-03 5.112550000000000150e-01 6.365089999999999915e-01 -7.865729999999999666e-01 -2.496359999999999968e-01 -5.414980000000000349e-01 1.605129999999999890e-01 +1.403715361812139988e+09 -4.916000000000000231e-03 5.206699999999999662e-01 6.344859999999999944e-01 -7.905079999999999885e-01 -2.427269999999999983e-01 -5.399990000000000068e-01 1.567840000000000067e-01 +1.403715361862139940e+09 -7.426999999999999574e-03 5.308220000000000161e-01 6.317469999999999475e-01 -7.945379999999999665e-01 -2.352549999999999919e-01 -5.386410000000000364e-01 1.524149999999999949e-01 +1.403715361912139893e+09 -9.343999999999999875e-03 5.414630000000000276e-01 6.284969999999999724e-01 -7.979249999999999954e-01 -2.275969999999999938e-01 -5.386009999999999964e-01 1.463710000000000011e-01 +1.403715361962140083e+09 -1.068000000000000026e-02 5.530840000000000201e-01 6.254619999999999624e-01 -8.002479999999999594e-01 -2.184500000000000053e-01 -5.402379999999999960e-01 1.415099999999999969e-01 +1.403715362012140036e+09 -1.126100000000000018e-02 5.652000000000000357e-01 6.223020000000000218e-01 -8.024520000000000541e-01 -2.086749999999999994e-01 -5.422240000000000393e-01 1.360850000000000115e-01 +1.403715362062139988e+09 -1.169000000000000074e-02 5.780370000000000230e-01 6.179869999999999530e-01 -8.044820000000000304e-01 -1.992539999999999867e-01 -5.444870000000000543e-01 1.290000000000000036e-01 +1.403715362112139940e+09 -1.109399999999999969e-02 5.910840000000000538e-01 6.137820000000000498e-01 -8.064930000000000154e-01 -1.888150000000000106e-01 -5.468849999999999545e-01 1.217960000000000015e-01 +1.403715362162139893e+09 -1.013599999999999918e-02 6.051790000000000225e-01 6.085819999999999563e-01 -8.088530000000000442e-01 -1.786089999999999900e-01 -5.487109999999999488e-01 1.130140000000000033e-01 +1.403715362212140083e+09 -8.647000000000000172e-03 6.197489999999999943e-01 6.031919999999999504e-01 -8.108610000000000539e-01 -1.675729999999999997e-01 -5.510310000000000485e-01 1.038710000000000050e-01 +1.403715362262140036e+09 -6.218999999999999702e-03 6.348930000000000407e-01 5.978109999999999813e-01 -8.124139999999999695e-01 -1.560400000000000120e-01 -5.538170000000000037e-01 9.446000000000000230e-02 +1.403715362312139988e+09 -3.475999999999999923e-03 6.510449999999999848e-01 5.914869999999999850e-01 -8.144829999999999570e-01 -1.444390000000000118e-01 -5.555309999999999970e-01 8.450199999999999378e-02 +1.403715362362139940e+09 -4.440000000000000045e-04 6.680970000000000519e-01 5.847449999999999593e-01 -8.163930000000000353e-01 -1.321849999999999969e-01 -5.571739999999999471e-01 7.474000000000000088e-02 +1.403715362412139893e+09 2.452999999999999885e-03 6.858119999999999772e-01 5.780039999999999623e-01 -8.180490000000000261e-01 -1.195429999999999965e-01 -5.587959999999999594e-01 6.521100000000000507e-02 +1.403715362462140083e+09 5.049999999999999802e-03 7.053599999999999870e-01 5.709089999999999998e-01 -8.194339999999999957e-01 -1.061850000000000016e-01 -5.604430000000000245e-01 5.617599999999999677e-02 +1.403715362512140036e+09 7.875000000000000056e-03 7.248010000000000286e-01 5.640549999999999731e-01 -8.204759999999999831e-01 -9.277799999999999936e-02 -5.621490000000000098e-01 4.691499999999999837e-02 +1.403715362562139988e+09 1.092399999999999968e-02 7.450219999999999620e-01 5.571909999999999918e-01 -8.219859999999999944e-01 -8.011600000000000665e-02 -5.626339999999999675e-01 3.691900000000000043e-02 +1.403715362612139940e+09 1.475100000000000022e-02 7.662980000000000347e-01 5.515529999999999600e-01 -8.229980000000000073e-01 -6.685599999999999876e-02 -5.633799999999999919e-01 2.841899999999999982e-02 +1.403715362662139893e+09 1.917100000000000054e-02 7.887330000000000174e-01 5.465860000000000163e-01 -8.236620000000000053e-01 -5.382200000000000178e-02 -5.641659999999999453e-01 2.004299999999999832e-02 +1.403715362712140083e+09 2.425100000000000172e-02 8.123839999999999950e-01 5.425940000000000207e-01 -8.241140000000000132e-01 -4.022599999999999787e-02 -5.648499999999999632e-01 1.272700000000000047e-02 +1.403715362762140036e+09 2.974399999999999961e-02 8.367660000000000098e-01 5.389289999999999914e-01 -8.245080000000000187e-01 -2.510199999999999931e-02 -5.652359999999999607e-01 8.073999999999999580e-03 +1.403715362812139988e+09 3.559600000000000264e-02 8.618209999999999482e-01 5.364759999999999529e-01 -8.246529999999999694e-01 -8.727999999999999647e-03 -5.655430000000000179e-01 5.588000000000000085e-03 +1.403715362862139940e+09 4.161499999999999921e-02 8.873140000000000471e-01 5.339000000000000412e-01 -8.239750000000000130e-01 9.766999999999999640e-03 -5.665019999999999500e-01 6.734000000000000402e-03 +1.403715362912139893e+09 4.780399999999999927e-02 9.123909999999999521e-01 5.324550000000000116e-01 -8.210840000000000360e-01 2.934300000000000103e-02 -5.699629999999999974e-01 1.007699999999999915e-02 +1.403715362962140083e+09 5.428600000000000092e-02 9.366339999999999666e-01 5.315999999999999615e-01 -8.171840000000000215e-01 4.645799999999999930e-02 -5.743970000000000464e-01 1.092699999999999921e-02 +1.403715363012140036e+09 6.093200000000000005e-02 9.592730000000000423e-01 5.312989999999999657e-01 -8.135869999999999491e-01 6.221999999999999753e-02 -5.779879999999999463e-01 1.162200000000000039e-02 +1.403715363062139988e+09 6.722599999999999409e-02 9.797099999999999698e-01 5.315069999999999517e-01 -8.110349999999999504e-01 7.602000000000000424e-02 -5.799410000000000398e-01 1.053699999999999949e-02 +1.403715363112139940e+09 7.311299999999999744e-02 9.983159999999999812e-01 5.322850000000000081e-01 -8.092970000000000441e-01 8.780000000000000304e-02 -5.807499999999999885e-01 7.629999999999999630e-03 +1.403715363162139893e+09 7.829999999999999460e-02 1.014397999999999911e+00 5.333059999999999468e-01 -8.093479999999999563e-01 9.791500000000000203e-02 -5.790999999999999481e-01 3.317000000000000070e-03 +1.403715363212140083e+09 8.288800000000000334e-02 1.027873000000000037e+00 5.351519999999999611e-01 8.091979999999999729e-01 -1.071730000000000044e-01 5.776750000000000496e-01 2.063999999999999863e-03 +1.403715363262140036e+09 8.693800000000000139e-02 1.038545999999999969e+00 5.376769999999999605e-01 8.088189999999999547e-01 -1.155859999999999943e-01 5.765259999999999829e-01 8.342999999999999722e-03 +1.403715363312139988e+09 9.083600000000000008e-02 1.047117999999999993e+00 5.405839999999999534e-01 8.084409999999999652e-01 -1.239890000000000020e-01 5.751939999999999831e-01 1.421799999999999974e-02 +1.403715363362139940e+09 9.364200000000000301e-02 1.052615000000000078e+00 5.443280000000000340e-01 8.075400000000000356e-01 -1.321980000000000099e-01 5.744369999999999754e-01 2.062200000000000144e-02 +1.403715363412139893e+09 9.598199999999999787e-02 1.055727000000000082e+00 5.487189999999999568e-01 8.061040000000000427e-01 -1.398929999999999896e-01 5.743570000000000064e-01 2.719999999999999848e-02 +1.403715363462140083e+09 9.761300000000000532e-02 1.056253000000000108e+00 5.537450000000000427e-01 8.046590000000000131e-01 -1.476049999999999862e-01 5.740570000000000395e-01 3.456800000000000150e-02 +1.403715363512140036e+09 9.863700000000000245e-02 1.054666000000000103e+00 5.592939999999999579e-01 8.031639999999999890e-01 -1.550570000000000004e-01 5.736599999999999477e-01 4.241899999999999837e-02 +1.403715363562139988e+09 9.885900000000000243e-02 1.050964999999999927e+00 5.651540000000000452e-01 8.020979999999999777e-01 -1.608050000000000035e-01 5.726900000000000324e-01 5.297700000000000325e-02 +1.403715363612139940e+09 9.863299999999999845e-02 1.045407999999999893e+00 5.710960000000000480e-01 8.013050000000000450e-01 -1.648910000000000098e-01 5.712540000000000395e-01 6.626300000000000245e-02 +1.403715363662139893e+09 9.778399999999999592e-02 1.038906000000000107e+00 5.767170000000000352e-01 8.002249999999999641e-01 -1.702160000000000062e-01 5.697520000000000362e-01 7.778000000000000191e-02 +1.403715363712140083e+09 9.664100000000000468e-02 1.031022000000000105e+00 5.827820000000000222e-01 7.984820000000000251e-01 -1.761399999999999910e-01 5.686980000000000368e-01 8.935500000000000387e-02 +1.403715363762140036e+09 9.446899999999999742e-02 1.022698000000000107e+00 5.884110000000000174e-01 7.961749999999999661e-01 -1.838700000000000057e-01 5.678180000000000449e-01 9.939900000000000124e-02 +1.403715363812139988e+09 9.176399999999999835e-02 1.014073000000000002e+00 5.937729999999999952e-01 7.934830000000000494e-01 -1.926259999999999917e-01 5.668849999999999723e-01 1.091870000000000063e-01 +1.403715363862139940e+09 8.813100000000000100e-02 1.004154999999999909e+00 5.981480000000000130e-01 7.905720000000000525e-01 -2.031169999999999920e-01 5.655510000000000259e-01 1.178590000000000054e-01 +1.403715363912139893e+09 8.278900000000000148e-02 9.938280000000000447e-01 6.019290000000000473e-01 7.870009999999999506e-01 -2.135440000000000116e-01 5.645740000000000203e-01 1.276069999999999982e-01 +1.403715363962140083e+09 7.759800000000000031e-02 9.824939999999999785e-01 6.065420000000000256e-01 7.825280000000000014e-01 -2.242129999999999956e-01 5.640370000000000106e-01 1.387140000000000040e-01 +1.403715364012140036e+09 7.182499999999999996e-02 9.713420000000000387e-01 6.110100000000000531e-01 7.782620000000000093e-01 -2.365629999999999955e-01 5.624970000000000248e-01 1.481329999999999869e-01 +1.403715364062139988e+09 6.590200000000000224e-02 9.600560000000000205e-01 6.156850000000000378e-01 7.737070000000000336e-01 -2.482769999999999977e-01 5.609800000000000342e-01 1.582320000000000115e-01 +1.403715364112139940e+09 5.988600000000000173e-02 9.490169999999999995e-01 6.206899999999999640e-01 7.692360000000000309e-01 -2.594480000000000119e-01 5.596780000000000088e-01 1.665040000000000131e-01 +1.403715364162139893e+09 5.306199999999999806e-02 9.386149999999999771e-01 6.255870000000000042e-01 7.650350000000000206e-01 -2.690379999999999994e-01 5.585430000000000117e-01 1.742670000000000052e-01 +1.403715364212140083e+09 4.644800000000000317e-02 9.281650000000000178e-01 6.300989999999999647e-01 7.624499999999999611e-01 -2.773320000000000229e-01 5.561209999999999765e-01 1.802410000000000123e-01 +1.403715364262140036e+09 3.998499999999999971e-02 9.180749999999999744e-01 6.351350000000000051e-01 7.603309999999999791e-01 -2.852190000000000003e-01 5.538790000000000102e-01 1.837519999999999987e-01 +1.403715364312139988e+09 3.312699999999999673e-02 9.082750000000000545e-01 6.407129999999999770e-01 7.589399999999999480e-01 -2.924169999999999825e-01 5.515569999999999640e-01 1.851690000000000003e-01 +1.403715364362139940e+09 2.630899999999999905e-02 8.985149999999999526e-01 6.466640000000000166e-01 7.584239999999999871e-01 -2.984709999999999863e-01 5.490150000000000308e-01 1.851770000000000083e-01 +1.403715364412139893e+09 1.918900000000000119e-02 8.890320000000000444e-01 6.530679999999999819e-01 7.577420000000000266e-01 -3.037279999999999980e-01 5.474649999999999794e-01 1.840040000000000009e-01 +1.403715364462140083e+09 1.192400000000000057e-02 8.790869999999999518e-01 6.601399999999999491e-01 7.569390000000000285e-01 -3.069629999999999859e-01 5.467520000000000158e-01 1.840610000000000024e-01 +1.403715364512140036e+09 3.700999999999999863e-03 8.684570000000000345e-01 6.670300000000000118e-01 7.565969999999999640e-01 -3.097650000000000126e-01 5.462320000000000508e-01 1.823110000000000008e-01 +1.403715364562139988e+09 -4.908000000000000036e-03 8.576380000000000114e-01 6.744830000000000547e-01 7.561090000000000311e-01 -3.110669999999999824e-01 5.465069999999999650e-01 1.812910000000000077e-01 +1.403715364612139940e+09 -1.418600000000000069e-02 8.459280000000000133e-01 6.823559999999999626e-01 7.560029999999999806e-01 -3.114899999999999891e-01 5.464719999999999578e-01 1.811159999999999992e-01 +1.403715364662139893e+09 -2.441499999999999920e-02 8.331239999999999757e-01 6.915310000000000068e-01 7.550259999999999749e-01 -3.121559999999999890e-01 5.471660000000000412e-01 1.819449999999999956e-01 +1.403715364712140083e+09 -3.567100000000000132e-02 8.200110000000000454e-01 7.006299999999999750e-01 7.539350000000000218e-01 -3.115749999999999909e-01 5.475250000000000394e-01 1.863309999999999966e-01 +1.403715364762140036e+09 -4.826300000000000034e-02 8.065529999999999644e-01 7.099130000000000162e-01 7.538759999999999906e-01 -3.105700000000000127e-01 5.457870000000000221e-01 1.932169999999999999e-01 +1.403715364812139988e+09 -6.140199999999999825e-02 7.929829999999999934e-01 7.186040000000000205e-01 7.548059999999999770e-01 -3.100049999999999750e-01 5.420059999999999878e-01 2.009819999999999940e-01 +1.403715364862139940e+09 -7.491100000000000536e-02 7.790479999999999627e-01 7.268310000000000048e-01 7.557019999999999849e-01 -3.107500000000000262e-01 5.376490000000000435e-01 2.080460000000000087e-01 +1.403715364912139893e+09 -8.834899999999999698e-02 7.648350000000000426e-01 7.348190000000000000e-01 7.559489999999999821e-01 -3.131200000000000094e-01 5.337469999999999715e-01 2.135670000000000068e-01 +1.403715364962140083e+09 -1.019899999999999973e-01 7.504760000000000320e-01 7.428700000000000303e-01 7.561400000000000343e-01 -3.158639999999999781e-01 5.292860000000000342e-01 2.198589999999999989e-01 +1.403715365012140036e+09 -1.150499999999999995e-01 7.362340000000000551e-01 7.506389999999999452e-01 7.550369999999999582e-01 -3.207849999999999868e-01 5.263510000000000133e-01 2.235409999999999897e-01 +1.403715365062139988e+09 -1.277379999999999904e-01 7.221349999999999714e-01 7.585039999999999560e-01 7.542159999999999975e-01 -3.252659999999999996e-01 5.226239999999999775e-01 2.285260000000000069e-01 +1.403715365112139940e+09 -1.411320000000000074e-01 7.081680000000000197e-01 7.669070000000000054e-01 7.516589999999999661e-01 -3.302999999999999825e-01 5.209770000000000234e-01 2.334390000000000076e-01 +1.403715365162139893e+09 -1.525060000000000027e-01 6.947010000000000129e-01 7.753130000000000299e-01 7.474669999999999925e-01 -3.355279999999999929e-01 5.213020000000000431e-01 2.386610000000000120e-01 +1.403715365262140036e+09 -1.735949999999999993e-01 6.700099999999999945e-01 7.916699999999999848e-01 7.402849999999999708e-01 -3.450889999999999791e-01 5.206159999999999677e-01 2.486970000000000014e-01 +1.403715365312139988e+09 -1.839729999999999976e-01 6.592510000000000314e-01 7.998110000000000497e-01 7.375559999999999894e-01 -3.488390000000000102e-01 5.198239999999999528e-01 2.531889999999999974e-01 +1.403715365362139940e+09 -1.929039999999999921e-01 6.491050000000000431e-01 8.066339999999999621e-01 7.349599999999999467e-01 -3.530079999999999885e-01 5.191200000000000259e-01 2.563860000000000028e-01 +1.403715365412139893e+09 -2.014090000000000047e-01 6.397819999999999618e-01 8.132679999999999909e-01 7.313899999999999846e-01 -3.586619999999999808e-01 5.190759999999999819e-01 2.588230000000000253e-01 +1.403715365462140083e+09 -2.100599999999999967e-01 6.310219999999999718e-01 8.193970000000000420e-01 7.283389999999999587e-01 -3.644430000000000169e-01 5.175260000000000415e-01 2.624299999999999966e-01 +1.403715365512140036e+09 -2.183420000000000083e-01 6.231219999999999537e-01 8.253099999999999881e-01 7.242699999999999694e-01 -3.711209999999999787e-01 5.166450000000000209e-01 2.660449999999999759e-01 +1.403715365562139988e+09 -2.265929999999999889e-01 6.158179999999999765e-01 8.308219999999999494e-01 7.204420000000000268e-01 -3.781970000000000054e-01 5.143830000000000346e-01 2.708119999999999972e-01 +1.403715365612139940e+09 -2.364539999999999975e-01 6.105779999999999541e-01 8.369159999999999933e-01 7.149630000000000152e-01 -3.877320000000000211e-01 5.132050000000000223e-01 2.740659999999999763e-01 +1.403715365662139893e+09 -2.449369999999999881e-01 6.047010000000000440e-01 8.420509999999999939e-01 7.085879999999999956e-01 -3.985040000000000249e-01 5.123809999999999754e-01 2.767009999999999748e-01 +1.403715365712140083e+09 -2.536229999999999873e-01 5.992680000000000229e-01 8.468759999999999621e-01 7.019229999999999636e-01 -4.097410000000000219e-01 5.110989999999999700e-01 2.796319999999999917e-01 +1.403715365762140036e+09 -2.645140000000000269e-01 5.942819999999999769e-01 8.521170000000000133e-01 6.951929999999999499e-01 -4.211489999999999956e-01 5.091379999999999795e-01 2.830539999999999723e-01 +1.403715365812139988e+09 -2.747299999999999742e-01 5.897029999999999772e-01 8.562549999999999883e-01 6.889619999999999633e-01 -4.319129999999999914e-01 5.063379999999999548e-01 2.870610000000000106e-01 +1.403715365862139940e+09 -2.854510000000000103e-01 5.857740000000000169e-01 8.603990000000000249e-01 6.832099999999999840e-01 -4.409480000000000066e-01 5.036640000000000006e-01 2.917370000000000241e-01 +1.403715365912139893e+09 -2.972969999999999779e-01 5.830170000000000075e-01 8.644600000000000062e-01 6.782690000000000108e-01 -4.492380000000000262e-01 5.005020000000000024e-01 2.960320000000000173e-01 +1.403715365962140083e+09 -3.093150000000000066e-01 5.797590000000000243e-01 8.680170000000000385e-01 6.738349999999999618e-01 -4.568639999999999923e-01 4.978299999999999947e-01 2.989760000000000195e-01 +1.403715366012140036e+09 -3.219699999999999784e-01 5.766930000000000112e-01 8.711780000000000079e-01 6.684980000000000366e-01 -4.642140000000000155e-01 4.976229999999999820e-01 2.999780000000000224e-01 +1.403715366062139988e+09 -3.356350000000000167e-01 5.742439999999999767e-01 8.733699999999999797e-01 6.643029999999999768e-01 -4.708669999999999800e-01 4.967840000000000034e-01 3.003179999999999739e-01 +1.403715366112139940e+09 -3.501070000000000015e-01 5.717830000000000412e-01 8.755420000000000424e-01 6.599059999999999926e-01 -4.770909999999999873e-01 4.971309999999999896e-01 2.996130000000000182e-01 +1.403715366162139893e+09 -3.660349999999999993e-01 5.693669999999999565e-01 8.777169999999999694e-01 6.568249999999999922e-01 -4.808580000000000076e-01 4.967530000000000001e-01 3.009850000000000025e-01 +1.403715366212140083e+09 -3.857979999999999743e-01 5.691530000000000200e-01 8.800559999999999494e-01 6.544539999999999802e-01 -4.835380000000000233e-01 4.965609999999999746e-01 3.021739999999999982e-01 +1.403715366262140036e+09 -4.047970000000000179e-01 5.669650000000000523e-01 8.816159999999999553e-01 6.527290000000000036e-01 -4.851730000000000209e-01 4.963230000000000142e-01 3.036710000000000242e-01 +1.403715366312139988e+09 -4.251389999999999891e-01 5.645139999999999603e-01 8.833490000000000508e-01 6.525400000000000089e-01 -4.854379999999999806e-01 4.948989999999999778e-01 3.059669999999999890e-01 +1.403715366362139940e+09 -4.469339999999999979e-01 5.618140000000000356e-01 8.850059999999999594e-01 6.524950000000000472e-01 -4.852199999999999847e-01 4.938560000000000172e-01 3.080899999999999750e-01 +1.403715366412139893e+09 -4.700529999999999986e-01 5.593179999999999819e-01 8.859780000000000433e-01 6.546380000000000532e-01 -4.844370000000000065e-01 4.906650000000000178e-01 3.098670000000000035e-01 +1.403715366462140083e+09 -4.946840000000000126e-01 5.571709999999999718e-01 8.872889999999999944e-01 6.574320000000000164e-01 -4.821880000000000055e-01 4.866969999999999907e-01 3.136929999999999996e-01 +1.403715366512140036e+09 -5.203179999999999472e-01 5.549589999999999801e-01 8.883750000000000258e-01 6.604499999999999815e-01 -4.797199999999999798e-01 4.828720000000000234e-01 3.170310000000000072e-01 +1.403715366562139988e+09 -5.460709999999999731e-01 5.529619999999999536e-01 8.893069999999999586e-01 6.630629999999999580e-01 -4.779769999999999852e-01 4.801320000000000032e-01 3.183690000000000131e-01 +1.403715366612139940e+09 -5.722540000000000404e-01 5.507940000000000058e-01 8.896969999999999601e-01 6.660129999999999661e-01 -4.766560000000000241e-01 4.769809999999999883e-01 3.189270000000000160e-01 +1.403715366662139893e+09 -5.981910000000000283e-01 5.484250000000000513e-01 8.896849999999999481e-01 6.685499999999999776e-01 -4.752899999999999903e-01 4.746230000000000171e-01 3.191760000000000153e-01 +1.403715366712140083e+09 -6.240090000000000359e-01 5.456870000000000331e-01 8.892919999999999714e-01 6.712709999999999511e-01 -4.741639999999999744e-01 4.724559999999999871e-01 3.183529999999999971e-01 +1.403715366762140036e+09 -6.497519999999999962e-01 5.428009999999999780e-01 8.889449999999999852e-01 6.735539999999999861e-01 -4.736949999999999772e-01 4.706940000000000013e-01 3.168380000000000085e-01 +1.403715366812139988e+09 -6.767499999999999627e-01 5.403900000000000370e-01 8.886330000000000062e-01 6.763930000000000220e-01 -4.732480000000000020e-01 4.681440000000000046e-01 3.152309999999999834e-01 +1.403715366862139940e+09 -7.020669999999999966e-01 5.367880000000000429e-01 8.889759999999999884e-01 6.787900000000000045e-01 -4.727489999999999748e-01 4.664599999999999858e-01 3.133159999999999834e-01 +1.403715366912139893e+09 -7.267630000000000479e-01 5.324510000000000076e-01 8.900320000000000453e-01 6.803780000000000383e-01 -4.721090000000000009e-01 4.657939999999999858e-01 3.118239999999999901e-01 +1.403715366962140083e+09 -7.510980000000000434e-01 5.274480000000000279e-01 8.916009999999999769e-01 6.814160000000000217e-01 -4.725570000000000048e-01 4.657339999999999813e-01 3.089560000000000084e-01 +1.403715367012140036e+09 -7.748369999999999980e-01 5.215389999999999748e-01 8.937749999999999861e-01 6.822740000000000471e-01 -4.724249999999999838e-01 4.660529999999999951e-01 3.067739999999999911e-01 +1.403715367062139988e+09 -7.979619999999999491e-01 5.146619999999999528e-01 8.967169999999999863e-01 6.826109999999999678e-01 -4.724650000000000238e-01 4.669329999999999870e-01 3.046179999999999999e-01 +1.403715367112139940e+09 -8.213070000000000093e-01 5.065790000000000015e-01 9.001719999999999722e-01 6.832169999999999632e-01 -4.720260000000000011e-01 4.675509999999999944e-01 3.029890000000000083e-01 +1.403715367162139893e+09 -8.435080000000000355e-01 4.977409999999999890e-01 9.034569999999999546e-01 6.840840000000000254e-01 -4.718459999999999877e-01 4.678620000000000001e-01 3.008259999999999823e-01 +1.403715367212140083e+09 -8.654749999999999943e-01 4.876599999999999824e-01 9.072400000000000464e-01 6.846919999999999673e-01 -4.705820000000000003e-01 4.685610000000000053e-01 3.003330000000000166e-01 +1.403715367262140036e+09 -8.870829999999999549e-01 4.766870000000000274e-01 9.107480000000000020e-01 6.846680000000000543e-01 -4.708760000000000168e-01 4.700070000000000081e-01 2.976539999999999742e-01 +1.403715367312139988e+09 -9.109620000000000495e-01 4.661100000000000243e-01 9.150620000000000420e-01 6.857250000000000290e-01 -4.707169999999999965e-01 4.696890000000000231e-01 2.959709999999999841e-01 +1.403715367362139940e+09 -9.322380000000000111e-01 4.529489999999999905e-01 9.179549999999999654e-01 6.866719999999999491e-01 -4.710550000000000015e-01 4.694499999999999784e-01 2.936079999999999801e-01 +1.403715367412139893e+09 -9.541100000000000136e-01 4.386660000000000004e-01 9.210709999999999731e-01 6.873909999999999743e-01 -4.709369999999999945e-01 4.695259999999999989e-01 2.919869999999999965e-01 +1.403715367462140083e+09 -9.752739999999999743e-01 4.231840000000000046e-01 9.238699999999999690e-01 6.880260000000000264e-01 -4.703720000000000123e-01 4.697930000000000161e-01 2.909709999999999797e-01 +1.403715367512140036e+09 -9.965079999999999494e-01 4.063999999999999835e-01 9.267980000000000107e-01 6.891610000000000236e-01 -4.701429999999999776e-01 4.691569999999999907e-01 2.896790000000000198e-01 +1.403715367562139988e+09 -1.017698999999999909e+00 3.881450000000000178e-01 9.296560000000000379e-01 6.900439999999999907e-01 -4.693459999999999854e-01 4.691409999999999747e-01 2.888939999999999841e-01 +1.403715367612139940e+09 -1.038648999999999933e+00 3.685660000000000047e-01 9.327550000000000008e-01 6.902549999999999519e-01 -4.684309999999999863e-01 4.699849999999999861e-01 2.885030000000000094e-01 +1.403715367662139893e+09 -1.059525000000000050e+00 3.478040000000000020e-01 9.355649999999999800e-01 6.903939999999999522e-01 -4.678840000000000221e-01 4.709050000000000180e-01 2.875590000000000090e-01 +1.403715367712140083e+09 -1.079690000000000039e+00 3.255770000000000053e-01 9.389840000000000408e-01 6.906160000000000077e-01 -4.663240000000000163e-01 4.716339999999999977e-01 2.883620000000000072e-01 +1.403715367762140036e+09 -1.100146000000000068e+00 3.021699999999999942e-01 9.427759999999999474e-01 6.908100000000000351e-01 -4.653340000000000254e-01 4.723390000000000088e-01 2.883439999999999892e-01 +1.403715367812139988e+09 -1.120117000000000029e+00 2.774900000000000144e-01 9.469490000000000407e-01 6.911890000000000533e-01 -4.637350000000000083e-01 4.726920000000000011e-01 2.894309999999999938e-01 +1.403715367862139940e+09 -1.140630000000000033e+00 2.520149999999999890e-01 9.508189999999999698e-01 6.913000000000000256e-01 -4.615690000000000071e-01 4.733510000000000217e-01 2.915429999999999966e-01 +1.403715367912139893e+09 -1.161388000000000087e+00 2.256789999999999907e-01 9.550680000000000280e-01 6.908849999999999714e-01 -4.588180000000000036e-01 4.744320000000000204e-01 2.950909999999999922e-01 +1.403715367962140083e+09 -1.181599999999999984e+00 1.983870000000000078e-01 9.592600000000000016e-01 6.888360000000000039e-01 -4.567370000000000041e-01 4.775909999999999878e-01 2.979979999999999851e-01 +1.403715368012140036e+09 -1.201430999999999916e+00 1.702130000000000032e-01 9.634359999999999591e-01 6.867469999999999963e-01 -4.555069999999999952e-01 4.804640000000000022e-01 3.000780000000000114e-01 +1.403715368062139988e+09 -1.221370000000000067e+00 1.419350000000000056e-01 9.663340000000000263e-01 6.842599999999999794e-01 -4.550170000000000048e-01 4.837670000000000026e-01 3.011909999999999865e-01 +1.403715368112139940e+09 -1.241085999999999911e+00 1.137169999999999986e-01 9.683760000000000145e-01 6.824580000000000091e-01 -4.547470000000000123e-01 4.859339999999999771e-01 3.022009999999999974e-01 +1.403715368162139893e+09 -1.261249000000000065e+00 8.543299999999999506e-02 9.696280000000000454e-01 6.806889999999999885e-01 -4.550179999999999780e-01 4.878600000000000159e-01 3.026780000000000026e-01 +1.403715368212140083e+09 -1.281611000000000056e+00 5.753699999999999787e-02 9.702830000000000066e-01 6.793200000000000349e-01 -4.558420000000000250e-01 4.892389999999999795e-01 3.022869999999999724e-01 +1.403715368262140036e+09 -1.302370000000000028e+00 2.983900000000000094e-02 9.706029999999999935e-01 6.775799999999999601e-01 -4.577039999999999997e-01 4.911179999999999990e-01 3.003250000000000086e-01 +1.403715368312139988e+09 -1.323099999999999943e+00 2.665999999999999967e-03 9.710130000000000150e-01 6.760380000000000278e-01 -4.597879999999999745e-01 4.926170000000000271e-01 2.981539999999999746e-01 +1.403715368362139940e+09 -1.344924999999999926e+00 -2.479200000000000154e-02 9.708280000000000243e-01 6.735700000000000021e-01 -4.624519999999999742e-01 4.953409999999999758e-01 2.950909999999999922e-01 +1.403715368412139893e+09 -1.367706000000000088e+00 -5.229500000000000121e-02 9.704580000000000428e-01 6.715929999999999955e-01 -4.644869999999999832e-01 4.974509999999999765e-01 2.928439999999999932e-01 +1.403715368462140083e+09 -1.391442999999999985e+00 -8.018100000000000227e-02 9.701279999999999903e-01 6.690610000000000168e-01 -4.657009999999999761e-01 5.002659999999999885e-01 2.919140000000000068e-01 +1.403715368512140036e+09 -1.416452000000000044e+00 -1.082400000000000029e-01 9.701070000000000526e-01 6.674080000000000013e-01 -4.662680000000000158e-01 5.017570000000000086e-01 2.922330000000000205e-01 +1.403715368562139988e+09 -1.442714999999999970e+00 -1.360939999999999928e-01 9.693629999999999747e-01 6.671080000000000343e-01 -4.651939999999999964e-01 5.014610000000000456e-01 2.951239999999999974e-01 +1.403715368612139940e+09 -1.469892999999999894e+00 -1.636789999999999912e-01 9.683619999999999450e-01 6.682569999999999899e-01 -4.629280000000000062e-01 4.991559999999999886e-01 2.999560000000000004e-01 +1.403715368662139893e+09 -1.498618000000000006e+00 -1.907810000000000061e-01 9.671830000000000149e-01 6.700800000000000090e-01 -4.606790000000000052e-01 4.959330000000000127e-01 3.046599999999999864e-01 +1.403715368712140083e+09 -1.528016999999999959e+00 -2.174870000000000136e-01 9.656949999999999701e-01 6.712930000000000286e-01 -4.596259999999999790e-01 4.935579999999999967e-01 3.074259999999999771e-01 +1.403715368762140036e+09 -1.558159999999999989e+00 -2.440970000000000084e-01 9.644160000000000510e-01 6.724480000000000457e-01 -4.584989999999999899e-01 4.910289999999999933e-01 3.106180000000000052e-01 +1.403715368812139988e+09 -1.588777000000000106e+00 -2.700429999999999775e-01 9.633260000000000156e-01 6.732099999999999751e-01 -4.575969999999999760e-01 4.891229999999999745e-01 3.132900000000000129e-01 +1.403715368862139940e+09 -1.619372999999999951e+00 -2.955139999999999989e-01 9.619919999999999582e-01 6.738250000000000073e-01 -4.579980000000000162e-01 4.873850000000000127e-01 3.140910000000000091e-01 +1.403715368912139893e+09 -1.649296000000000095e+00 -3.201530000000000209e-01 9.606339999999999879e-01 6.749960000000000404e-01 -4.576029999999999820e-01 4.860320000000000196e-01 3.142499999999999738e-01 +1.403715368962140083e+09 -1.679389999999999938e+00 -3.444050000000000167e-01 9.591990000000000238e-01 6.771570000000000089e-01 -4.566720000000000224e-01 4.848290000000000100e-01 3.128090000000000037e-01 +1.403715369012140036e+09 -1.709384000000000015e+00 -3.678910000000000236e-01 9.573739999999999473e-01 6.802550000000000541e-01 -4.552510000000000168e-01 4.838580000000000103e-01 3.096459999999999768e-01 +1.403715369062139988e+09 -1.739192000000000071e+00 -3.911020000000000052e-01 9.557569999999999677e-01 6.842810000000000281e-01 -4.528400000000000203e-01 4.831550000000000011e-01 3.053799999999999848e-01 +1.403715369112139940e+09 -1.768423999999999996e+00 -4.146799999999999931e-01 9.545050000000000479e-01 6.888180000000000414e-01 -4.488659999999999872e-01 4.833410000000000206e-01 3.007159999999999833e-01 +1.403715369162139893e+09 -1.797288999999999914e+00 -4.381470000000000087e-01 9.531190000000000495e-01 6.939380000000000548e-01 -4.433819999999999983e-01 4.839260000000000228e-01 2.961050000000000071e-01 +1.403715369212140083e+09 -1.825868000000000047e+00 -4.618030000000000190e-01 9.516940000000000399e-01 6.992760000000000087e-01 -4.369890000000000163e-01 4.852670000000000039e-01 2.908080000000000109e-01 +1.403715369262140036e+09 -1.853520000000000056e+00 -4.859240000000000226e-01 9.509980000000000100e-01 7.049400000000000110e-01 -4.287119999999999820e-01 4.870479999999999809e-01 2.864419999999999744e-01 +1.403715369312139988e+09 -1.880797000000000052e+00 -5.098880000000000079e-01 9.502389999999999448e-01 7.110180000000000389e-01 -4.204030000000000267e-01 4.888950000000000240e-01 2.805270000000000263e-01 +1.403715369362139940e+09 -1.907189999999999941e+00 -5.339540000000000397e-01 9.497510000000000119e-01 7.166449999999999765e-01 -4.111790000000000167e-01 4.918699999999999739e-01 2.746199999999999752e-01 +1.403715369412139893e+09 -1.933011000000000035e+00 -5.582120000000000415e-01 9.490380000000000482e-01 7.228599999999999470e-01 -4.014130000000000198e-01 4.943290000000000184e-01 2.682919999999999749e-01 +1.403715369462140083e+09 -1.958069999999999977e+00 -5.825099999999999723e-01 9.483909999999999840e-01 7.287259999999999849e-01 -3.916310000000000069e-01 4.973130000000000051e-01 2.612740000000000062e-01 +1.403715369512140036e+09 -1.982877000000000001e+00 -6.071539999999999715e-01 9.478779999999999983e-01 7.344399999999999817e-01 -3.814569999999999905e-01 5.005779999999999674e-01 2.539879999999999916e-01 +1.403715369562139988e+09 -2.007264000000000159e+00 -6.319460000000000077e-01 9.475099999999999634e-01 7.399229999999999974e-01 -3.711369999999999947e-01 5.039470000000000338e-01 2.465920000000000056e-01 +1.403715369612139940e+09 -2.031233999999999984e+00 -6.567290000000000072e-01 9.470899999999999874e-01 7.453149999999999498e-01 -3.603759999999999741e-01 5.073149999999999604e-01 2.393039999999999889e-01 +1.403715369662139893e+09 -2.054767000000000010e+00 -6.817910000000000359e-01 9.468839999999999479e-01 7.503990000000000382e-01 -3.501319999999999988e-01 5.100829999999999531e-01 2.326439999999999897e-01 +1.403715369712140083e+09 -2.077837999999999852e+00 -7.075989999999999780e-01 9.465940000000000465e-01 7.545450000000000212e-01 -3.409309999999999841e-01 5.126910000000000078e-01 2.271029999999999993e-01 +1.403715369762140036e+09 -2.100160999999999945e+00 -7.337209999999999566e-01 9.464390000000000303e-01 7.585349999999999593e-01 -3.321799999999999753e-01 5.143710000000000226e-01 2.229440000000000033e-01 +1.403715369862139940e+09 -2.142221000000000153e+00 -7.869030000000000191e-01 9.444869999999999655e-01 7.649129999999999541e-01 -3.187030000000000141e-01 5.158380000000000187e-01 2.173670000000000047e-01 +1.403715369912139893e+09 -2.162033000000000094e+00 -8.142380000000000173e-01 9.429490000000000371e-01 7.682160000000000100e-01 -3.136120000000000019e-01 5.146539999999999448e-01 2.159230000000000038e-01 +1.403715369962140083e+09 -2.180924999999999780e+00 -8.415550000000000530e-01 9.409690000000000554e-01 7.715490000000000403e-01 -3.096970000000000001e-01 5.125840000000000396e-01 2.146099999999999952e-01 +1.403715370012140036e+09 -2.198596000000000217e+00 -8.690160000000000107e-01 9.386959999999999749e-01 7.744229999999999725e-01 -3.058489999999999820e-01 5.103269999999999751e-01 2.151550000000000129e-01 +1.403715370062139988e+09 -2.214573999999999820e+00 -8.963579999999999881e-01 9.362559999999999771e-01 7.767749999999999932e-01 -3.019910000000000094e-01 5.082360000000000211e-01 2.170680000000000109e-01 +1.403715370112139940e+09 -2.228596000000000021e+00 -9.236969999999999903e-01 9.340049999999999741e-01 7.777089999999999836e-01 -2.990550000000000153e-01 5.076929999999999499e-01 2.190499999999999947e-01 +1.403715370162139893e+09 -2.240324999999999900e+00 -9.507900000000000240e-01 9.321420000000000261e-01 7.767939999999999845e-01 -2.959519999999999929e-01 5.097059999999999924e-01 2.218160000000000132e-01 +1.403715370212140083e+09 -2.250039000000000122e+00 -9.775850000000000373e-01 9.305250000000000465e-01 7.736439999999999984e-01 -2.968330000000000135e-01 5.145629999999999926e-01 2.204309999999999881e-01 +1.403715370262140036e+09 -2.258052999999999866e+00 -1.003703999999999930e+00 9.293620000000000214e-01 7.700529999999999875e-01 -2.987830000000000208e-01 5.196380000000000443e-01 2.184580000000000133e-01 +1.403715370312139988e+09 -2.264692000000000149e+00 -1.029417000000000026e+00 9.281329999999999858e-01 7.670150000000000023e-01 -3.009689999999999865e-01 5.237260000000000248e-01 2.163710000000000078e-01 +1.403715370362139940e+09 -2.270345999999999975e+00 -1.054416999999999938e+00 9.268790000000000084e-01 7.639209999999999612e-01 -3.043150000000000022e-01 5.275600000000000289e-01 2.132999999999999896e-01 +1.403715370412139893e+09 -2.275332000000000132e+00 -1.079174999999999995e+00 9.256320000000000103e-01 7.609799999999999898e-01 -3.081729999999999747e-01 5.309829999999999828e-01 2.097509999999999930e-01 +1.403715370462140083e+09 -2.276632000000000211e+00 -1.103239000000000081e+00 9.258410000000000251e-01 7.589320000000000510e-01 -3.115299999999999736e-01 5.329289999999999861e-01 2.072620000000000018e-01 +1.403715370512140036e+09 -2.281698000000000004e+00 -1.127780000000000005e+00 9.248359999999999914e-01 7.569540000000000157e-01 -3.145359999999999823e-01 5.345440000000000191e-01 2.057920000000000027e-01 +1.403715370562139988e+09 -2.285848000000000102e+00 -1.152573999999999987e+00 9.246280000000000054e-01 7.557540000000000369e-01 -3.169770000000000088e-01 5.352360000000000451e-01 2.046550000000000036e-01 +1.403715370612139940e+09 -2.291164999999999896e+00 -1.177464000000000066e+00 9.242460000000000120e-01 7.544640000000000235e-01 -3.183949999999999836e-01 5.360759999999999970e-01 2.050150000000000028e-01 +1.403715370662139893e+09 -2.296825000000000117e+00 -1.202501999999999960e+00 9.236910000000000398e-01 7.539400000000000546e-01 -3.202450000000000019e-01 5.358289999999999997e-01 2.047039999999999971e-01 +1.403715370712140083e+09 -2.302592999999999890e+00 -1.227770000000000028e+00 9.233069999999999888e-01 7.535939999999999861e-01 -3.209879999999999955e-01 5.355799999999999450e-01 2.054690000000000127e-01 +1.403715370762140036e+09 -2.308260999999999896e+00 -1.253223999999999894e+00 9.232770000000000143e-01 7.538099999999999801e-01 -3.203329999999999789e-01 5.346499999999999586e-01 2.081030000000000102e-01 +1.403715370812139988e+09 -2.314080000000000137e+00 -1.278683000000000014e+00 9.232470000000000399e-01 7.546500000000000430e-01 -3.194270000000000165e-01 5.329129999999999701e-01 2.108879999999999921e-01 +1.403715370862139940e+09 -2.320101999999999887e+00 -1.304003999999999941e+00 9.230310000000000459e-01 7.558009999999999451e-01 -3.188860000000000028e-01 5.306340000000000501e-01 2.133180000000000076e-01 +1.403715370912139893e+09 -2.326137000000000121e+00 -1.329296999999999951e+00 9.225379999999999692e-01 7.565720000000000223e-01 -3.189690000000000025e-01 5.289490000000000025e-01 2.146399999999999975e-01 +1.403715370962140083e+09 -2.332024999999999793e+00 -1.354422000000000015e+00 9.212749999999999551e-01 7.582820000000000116e-01 -3.199589999999999934e-01 5.257830000000000004e-01 2.149119999999999919e-01 +1.403715371012140036e+09 -2.337711999999999790e+00 -1.379747999999999974e+00 9.192110000000000003e-01 7.610050000000000425e-01 -3.215439999999999965e-01 5.211379999999999901e-01 2.142330000000000068e-01 +1.403715371062139988e+09 -2.343024000000000218e+00 -1.404776999999999942e+00 9.170460000000000278e-01 7.648740000000000538e-01 -3.237320000000000197e-01 5.146380000000000399e-01 2.128700000000000037e-01 +1.403715371112139940e+09 -2.347678999999999849e+00 -1.430377000000000010e+00 9.141010000000000524e-01 7.686690000000000467e-01 -3.253539999999999766e-01 5.082670000000000243e-01 2.120329999999999993e-01 +1.403715371162139893e+09 -2.351453999999999933e+00 -1.456623000000000001e+00 9.112580000000000124e-01 7.717910000000000048e-01 -3.268860000000000099e-01 5.030080000000000107e-01 2.108710000000000029e-01 +1.403715371212140083e+09 -2.353358000000000061e+00 -1.483751999999999960e+00 9.082200000000000273e-01 7.744640000000000413e-01 -3.276769999999999960e-01 4.985160000000000147e-01 2.105110000000000037e-01 +1.403715371262140036e+09 -2.353636999999999979e+00 -1.512067000000000050e+00 9.052780000000000271e-01 7.758990000000000054e-01 -3.281129999999999880e-01 4.959629999999999872e-01 2.105779999999999874e-01 +1.403715371312139988e+09 -2.352217000000000002e+00 -1.541554000000000091e+00 9.023120000000000029e-01 7.764870000000000383e-01 -3.278610000000000135e-01 4.949990000000000223e-01 2.110720000000000096e-01 +1.403715371362139940e+09 -2.349285000000000068e+00 -1.571982999999999908e+00 8.994159999999999933e-01 7.765800000000000480e-01 -3.277349999999999985e-01 4.948589999999999933e-01 2.112519999999999953e-01 +1.403715371412139893e+09 -2.344901999999999820e+00 -1.603366000000000069e+00 8.968049999999999633e-01 7.758650000000000269e-01 -3.270770000000000066e-01 4.961659999999999959e-01 2.118329999999999935e-01 +1.403715371462140083e+09 -2.339018999999999959e+00 -1.635712000000000055e+00 8.947829999999999950e-01 7.727899999999999769e-01 -3.269639999999999769e-01 5.011120000000000019e-01 2.116079999999999905e-01 +1.403715371512140036e+09 -2.331770000000000120e+00 -1.668878000000000084e+00 8.929949999999999832e-01 7.680909999999999682e-01 -3.277680000000000038e-01 5.083379999999999566e-01 2.102320000000000022e-01 +1.403715371562139988e+09 -2.323728000000000016e+00 -1.702801000000000009e+00 8.912949999999999484e-01 7.632980000000000320e-01 -3.287829999999999919e-01 5.158289999999999820e-01 2.078399999999999970e-01 +1.403715371612139940e+09 -2.315195999999999810e+00 -1.737627999999999950e+00 8.892409999999999481e-01 7.590820000000000345e-01 -3.295069999999999943e-01 5.223470000000000057e-01 2.058480000000000032e-01 +1.403715371662139893e+09 -2.307020000000000071e+00 -1.772567000000000004e+00 8.874269999999999659e-01 7.551309999999999967e-01 -3.307510000000000172e-01 5.282660000000000133e-01 2.032619999999999982e-01 +1.403715371712140083e+09 -2.298779000000000128e+00 -1.808648999999999951e+00 8.847140000000000004e-01 7.520980000000000443e-01 -3.324829999999999730e-01 5.328469999999999596e-01 1.996930000000000094e-01 +1.403715371762140036e+09 -2.291593000000000213e+00 -1.845474000000000059e+00 8.821520000000000472e-01 7.503450000000000397e-01 -3.333149999999999724e-01 5.357300000000000395e-01 1.971710000000000129e-01 +1.403715371812139988e+09 -2.284904000000000046e+00 -1.883153999999999995e+00 8.792039999999999855e-01 7.495270000000000543e-01 -3.330429999999999779e-01 5.372689999999999966e-01 1.965560000000000085e-01 +1.403715371862139940e+09 -2.279085999999999945e+00 -1.921098999999999890e+00 8.755180000000000184e-01 7.517260000000000053e-01 -3.309500000000000219e-01 5.349140000000000006e-01 1.981080000000000063e-01 +1.403715371912139893e+09 -2.274275999999999964e+00 -1.959443999999999964e+00 8.717380000000000129e-01 7.542200000000000015e-01 -3.278429999999999955e-01 5.320920000000000094e-01 2.013669999999999904e-01 +1.403715371962140083e+09 -2.269734000000000140e+00 -1.998264999999999958e+00 8.678109999999999991e-01 7.566720000000000113e-01 -3.245000000000000107e-01 5.292639999999999567e-01 2.050029999999999908e-01 +1.403715372012140036e+09 -2.265540000000000109e+00 -2.037506000000000039e+00 8.642159999999999842e-01 7.586559999999999970e-01 -3.223900000000000099e-01 5.269789999999999752e-01 2.068810000000000093e-01 +1.403715372062139988e+09 -2.260809000000000069e+00 -2.076728999999999825e+00 8.609320000000000306e-01 7.588270000000000293e-01 -3.203429999999999889e-01 5.271989999999999732e-01 2.088629999999999931e-01 +1.403715372112139940e+09 -2.255583000000000116e+00 -2.116035000000000110e+00 8.581389999999999851e-01 7.584549999999999903e-01 -3.193219999999999947e-01 5.280709999999999571e-01 2.095730000000000093e-01 +1.403715372162139893e+09 -2.250081999999999915e+00 -2.155438999999999883e+00 8.556190000000000184e-01 7.580810000000000048e-01 -3.182639999999999914e-01 5.292540000000000022e-01 2.095499999999999863e-01 +1.403715372212140083e+09 -2.244705999999999868e+00 -2.194250999999999951e+00 8.535669999999999646e-01 7.576289999999999969e-01 -3.169620000000000215e-01 5.315210000000000212e-01 2.074090000000000100e-01 +1.403715372262140036e+09 -2.238040999999999947e+00 -2.232718999999999898e+00 8.525530000000000053e-01 7.584689999999999488e-01 -3.138310000000000266e-01 5.326030000000000486e-01 2.063250000000000084e-01 +1.403715372312139988e+09 -2.231767000000000056e+00 -2.272057000000000215e+00 8.524819999999999620e-01 7.597040000000000459e-01 -3.098339999999999983e-01 5.340139999999999887e-01 2.041610000000000091e-01 +1.403715372362139940e+09 -2.225334000000000145e+00 -2.311404000000000014e+00 8.531940000000000079e-01 7.615429999999999700e-01 -3.048420000000000019e-01 5.353679999999999550e-01 2.012579999999999925e-01 +1.403715372412139893e+09 -2.218405000000000182e+00 -2.350753000000000092e+00 8.552140000000000297e-01 7.634710000000000107e-01 -2.979060000000000041e-01 5.374320000000000208e-01 1.988270000000000037e-01 +1.403715372462140083e+09 -2.211818000000000062e+00 -2.389702000000000215e+00 8.582260000000000444e-01 7.652160000000000073e-01 -2.922660000000000258e-01 5.391939999999999511e-01 1.956900000000000028e-01 +1.403715372512140036e+09 -2.205258000000000163e+00 -2.428294000000000175e+00 8.621600000000000374e-01 7.670820000000000416e-01 -2.867060000000000164e-01 5.403729999999999922e-01 1.933420000000000138e-01 +1.403715372562139988e+09 -2.199043000000000081e+00 -2.466861000000000193e+00 8.672790000000000221e-01 7.681350000000000122e-01 -2.814260000000000095e-01 5.423320000000000363e-01 1.914270000000000138e-01 +1.403715372612139940e+09 -2.192928999999999906e+00 -2.504312999999999789e+00 8.728380000000000027e-01 7.690970000000000306e-01 -2.771830000000000127e-01 5.438920000000000421e-01 1.893170000000000130e-01 +1.403715372662139893e+09 -2.186713000000000129e+00 -2.541824000000000083e+00 8.789609999999999923e-01 7.700989999999999780e-01 -2.733400000000000274e-01 5.449239999999999640e-01 1.878589999999999982e-01 +1.403715372712140083e+09 -2.180486000000000146e+00 -2.579013999999999918e+00 8.848799999999999999e-01 7.707680000000000087e-01 -2.708289999999999864e-01 5.459439999999999849e-01 1.857800000000000007e-01 +1.403715372762140036e+09 -2.174234000000000222e+00 -2.615339000000000080e+00 8.899169999999999581e-01 7.717460000000000431e-01 -2.683539999999999814e-01 5.460660000000000514e-01 1.849500000000000033e-01 +1.403715372812139988e+09 -2.168734999999999857e+00 -2.651806000000000108e+00 8.949139999999999873e-01 7.719770000000000243e-01 -2.667720000000000091e-01 5.469289999999999985e-01 1.837229999999999974e-01 +1.403715372862139940e+09 -2.163336000000000148e+00 -2.688388000000000222e+00 8.997089999999999810e-01 7.724189999999999667e-01 -2.659590000000000010e-01 5.471930000000000405e-01 1.822479999999999933e-01 +1.403715372912139893e+09 -2.157207999999999792e+00 -2.724873999999999796e+00 9.037509999999999710e-01 7.723780000000000090e-01 -2.660759999999999792e-01 5.478979999999999961e-01 1.801200000000000023e-01 +1.403715372962140083e+09 -2.151247999999999827e+00 -2.761073999999999806e+00 9.075999999999999623e-01 7.719230000000000258e-01 -2.667849999999999944e-01 5.489389999999999548e-01 1.778409999999999991e-01 +1.403715373012140036e+09 -2.145220999999999822e+00 -2.797006000000000103e+00 9.112909999999999622e-01 7.718140000000000001e-01 -2.676799999999999735e-01 5.493350000000000177e-01 1.757319999999999993e-01 +1.403715373062139988e+09 -2.139428000000000107e+00 -2.832777000000000100e+00 9.145539999999999781e-01 7.714079999999999826e-01 -2.685859999999999914e-01 5.500030000000000197e-01 1.740369999999999973e-01 +1.403715373112139940e+09 -2.134980999999999796e+00 -2.868469000000000158e+00 9.179190000000000405e-01 7.709209999999999674e-01 -2.696200000000000263e-01 5.505619999999999958e-01 1.728220000000000034e-01 +1.403715373162139893e+09 -2.130079999999999973e+00 -2.904193999999999942e+00 9.206619999999999804e-01 7.705999999999999517e-01 -2.703829999999999845e-01 5.508760000000000323e-01 1.720579999999999887e-01 +1.403715373212140083e+09 -2.125601000000000074e+00 -2.940249999999999808e+00 9.233780000000000321e-01 7.702139999999999542e-01 -2.710730000000000084e-01 5.511179999999999968e-01 1.719249999999999945e-01 +1.403715373262140036e+09 -2.121551999999999882e+00 -2.976132999999999917e+00 9.264550000000000285e-01 7.703449999999999465e-01 -2.712970000000000104e-01 5.505349999999999966e-01 1.728510000000000046e-01 +1.403715373312139988e+09 -2.117853000000000208e+00 -3.011966999999999839e+00 9.299399999999999888e-01 7.705009999999999915e-01 -2.699889999999999790e-01 5.499119999999999564e-01 1.761560000000000070e-01 +1.403715373362139940e+09 -2.114250999999999880e+00 -3.047493999999999925e+00 9.333690000000000042e-01 7.703710000000000280e-01 -2.699059999999999793e-01 5.495600000000000485e-01 1.779390000000000138e-01 +1.403715373412139893e+09 -2.111134999999999984e+00 -3.082660999999999873e+00 9.367879999999999541e-01 7.702170000000000405e-01 -2.699520000000000253e-01 5.493329999999999602e-01 1.792330000000000034e-01 +1.403715373462140083e+09 -2.107368999999999826e+00 -3.117434999999999956e+00 9.400770000000000515e-01 7.700989999999999780e-01 -2.695449999999999791e-01 5.491570000000000062e-01 1.808869999999999922e-01 +1.403715373512140036e+09 -2.103721999999999870e+00 -3.151975999999999889e+00 9.427379999999999649e-01 7.704779999999999962e-01 -2.684159999999999879e-01 5.489389999999999548e-01 1.816109999999999947e-01 +1.403715373562139988e+09 -2.099769999999999914e+00 -3.186312000000000033e+00 9.452779999999999516e-01 7.713560000000000416e-01 -2.648949999999999916e-01 5.488610000000000433e-01 1.832799999999999985e-01 +1.403715373612139940e+09 -2.095444999999999780e+00 -3.220032999999999923e+00 9.474050000000000527e-01 7.736739999999999728e-01 -2.590689999999999937e-01 5.476170000000000204e-01 1.855439999999999867e-01 +1.403715373662139893e+09 -2.090628999999999849e+00 -3.253074999999999939e+00 9.492559999999999887e-01 7.759369999999999878e-01 -2.520720000000000183e-01 5.474059999999999482e-01 1.863519999999999899e-01 +1.403715373712140083e+09 -2.085201000000000082e+00 -3.285063000000000066e+00 9.506280000000000285e-01 7.784839999999999538e-01 -2.431490000000000040e-01 5.477009999999999934e-01 1.867209999999999981e-01 +1.403715373762140036e+09 -2.079839999999999911e+00 -3.315132999999999885e+00 9.524500000000000188e-01 7.811050000000000493e-01 -2.344120000000000092e-01 5.485299999999999621e-01 1.845009999999999983e-01 +1.403715373812139988e+09 -2.073500999999999816e+00 -3.343904000000000210e+00 9.536139999999999617e-01 7.834860000000000158e-01 -2.258499999999999952e-01 5.503500000000000059e-01 1.795980000000000076e-01 +1.403715373862139940e+09 -2.066275000000000084e+00 -3.371516000000000179e+00 9.547130000000000338e-01 7.861620000000000275e-01 -2.173279999999999934e-01 5.522810000000000219e-01 1.723500000000000032e-01 +1.403715373912139893e+09 -2.058403999999999900e+00 -3.397851999999999872e+00 9.559969999999999857e-01 7.888039999999999496e-01 -2.084179999999999922e-01 5.545020000000000504e-01 1.639410000000000034e-01 +1.403715373962140083e+09 -2.050183999999999784e+00 -3.423086000000000073e+00 9.573049999999999615e-01 7.912230000000000096e-01 -1.992039999999999922e-01 5.571239999999999526e-01 1.545819999999999972e-01 +1.403715374012140036e+09 -2.041720000000000201e+00 -3.446683999999999859e+00 9.580779999999999852e-01 7.939680000000000071e-01 -1.888620000000000021e-01 5.592289999999999761e-01 1.456349999999999867e-01 +1.403715374062139988e+09 -2.032399999999999984e+00 -3.468920999999999921e+00 9.584599999999999786e-01 7.965529999999999555e-01 -1.782880000000000020e-01 5.614209999999999479e-01 1.360989999999999978e-01 +1.403715374112139940e+09 -2.022972999999999910e+00 -3.490047000000000121e+00 9.590579999999999661e-01 7.988960000000000505e-01 -1.673219999999999985e-01 5.637240000000000029e-01 1.264230000000000076e-01 +1.403715374162139893e+09 -2.013306000000000040e+00 -3.510132000000000030e+00 9.598710000000000298e-01 8.015759999999999552e-01 -1.552739999999999954e-01 5.651300000000000212e-01 1.182980000000000004e-01 +1.403715374212140083e+09 -2.003019999999999801e+00 -3.530227000000000004e+00 9.611420000000000519e-01 8.040720000000000089e-01 -1.438039999999999874e-01 5.664919999999999956e-01 1.089780000000000054e-01 +1.403715374262140036e+09 -1.993335000000000079e+00 -3.548532999999999937e+00 9.622349999999999515e-01 8.062709999999999599e-01 -1.321809999999999929e-01 5.678520000000000234e-01 9.999299999999999855e-02 +1.403715374312139988e+09 -1.983484000000000025e+00 -3.565767000000000131e+00 9.632849999999999469e-01 8.089389999999999636e-01 -1.213339999999999974e-01 5.680979999999999919e-01 9.033800000000000163e-02 +1.403715374362139940e+09 -1.973465000000000025e+00 -3.584087999999999941e+00 9.644730000000000247e-01 8.115189999999999904e-01 -1.102100000000000024e-01 5.678630000000000067e-01 8.259700000000000375e-02 +1.403715374412139893e+09 -1.963796000000000097e+00 -3.601592000000000127e+00 9.660609999999999475e-01 8.143010000000000526e-01 -1.004550000000000026e-01 5.666419999999999790e-01 7.575700000000000489e-02 +1.403715374462140083e+09 -1.953845000000000054e+00 -3.618599999999999817e+00 9.674350000000000449e-01 8.168910000000000338e-01 -9.222199999999999842e-02 5.650509999999999700e-01 7.001000000000000278e-02 +1.403715374512140036e+09 -1.943567999999999962e+00 -3.635267999999999944e+00 9.682469999999999688e-01 8.204770000000000119e-01 -8.565100000000000491e-02 5.614209999999999479e-01 6.548400000000000054e-02 +1.403715374562139988e+09 -1.932846999999999982e+00 -3.652482000000000006e+00 9.695599999999999774e-01 8.231950000000000101e-01 -8.044600000000000362e-02 5.586119999999999974e-01 6.189399999999999763e-02 +1.403715374612139940e+09 -1.921208999999999945e+00 -3.667812000000000072e+00 9.701070000000000526e-01 8.259100000000000330e-01 -7.615199999999999747e-02 5.554559999999999498e-01 5.951200000000000240e-02 +1.403715374662139893e+09 -1.908743999999999996e+00 -3.683720999999999801e+00 9.710010000000000030e-01 8.277390000000000025e-01 -7.372599999999999987e-02 5.533019999999999605e-01 5.717900000000000066e-02 +1.403715374712140083e+09 -1.895067000000000057e+00 -3.699189000000000060e+00 9.716409999999999769e-01 8.290680000000000271e-01 -7.157700000000000173e-02 5.517039999999999722e-01 5.608099999999999891e-02 +1.403715374762140036e+09 -1.880406999999999940e+00 -3.714665000000000106e+00 9.720499999999999696e-01 8.299370000000000358e-01 -7.014499999999999902e-02 5.505959999999999743e-01 5.592799999999999855e-02 +1.403715374812139988e+09 -1.864522000000000013e+00 -3.729845000000000077e+00 9.724310000000000453e-01 8.303770000000000318e-01 -6.918299999999999450e-02 5.500159999999999494e-01 5.630799999999999694e-02 +1.403715374862139940e+09 -1.846837999999999980e+00 -3.744298000000000126e+00 9.727170000000000538e-01 8.304920000000000080e-01 -6.918399999999999550e-02 5.498039999999999594e-01 5.666800000000000309e-02 +1.403715374912139893e+09 -1.827849000000000057e+00 -3.757911000000000001e+00 9.731880000000000530e-01 8.300170000000000048e-01 -6.865400000000000669e-02 5.504000000000000004e-01 5.847000000000000114e-02 +1.403715374962140083e+09 -1.807778000000000107e+00 -3.770932999999999868e+00 9.739370000000000527e-01 8.276670000000000416e-01 -6.849399999999999933e-02 5.537710000000000132e-01 6.011699999999999683e-02 +1.403715375012140036e+09 -1.786596000000000073e+00 -3.783141000000000087e+00 9.745009999999999506e-01 8.254289999999999683e-01 -6.896700000000000053e-02 5.568760000000000376e-01 6.164200000000000235e-02 +1.403715375062139988e+09 -1.763695999999999930e+00 -3.793320000000000025e+00 9.744000000000000439e-01 8.232169999999999765e-01 -6.889800000000000091e-02 5.598330000000000251e-01 6.444800000000000528e-02 +1.403715375112139940e+09 -1.740552000000000099e+00 -3.803504000000000218e+00 9.745420000000000194e-01 8.217630000000000212e-01 -6.988800000000000567e-02 5.616409999999999458e-01 6.618999999999999884e-02 +1.403715375162139893e+09 -1.716768000000000072e+00 -3.812403999999999904e+00 9.744939999999999714e-01 8.202420000000000266e-01 -7.145999999999999575e-02 5.635000000000000009e-01 6.756099999999999606e-02 +1.403715375212140083e+09 -1.692479000000000067e+00 -3.820212000000000163e+00 9.746510000000000451e-01 8.189119999999999733e-01 -7.348300000000000665e-02 5.650230000000000530e-01 6.878700000000000092e-02 +1.403715375262140036e+09 -1.668029999999999902e+00 -3.827078999999999898e+00 9.744939999999999714e-01 8.183979999999999588e-01 -7.619599999999999984e-02 5.653810000000000224e-01 6.902300000000000102e-02 +1.403715375312139988e+09 -1.643334000000000072e+00 -3.832694000000000045e+00 9.738440000000000429e-01 8.179509999999999836e-01 -7.861100000000000032e-02 5.655590000000000339e-01 7.013900000000000690e-02 +1.403715375362139940e+09 -1.618581000000000047e+00 -3.837747999999999937e+00 9.731109999999999483e-01 8.170899999999999830e-01 -8.256800000000000250e-02 5.663820000000000521e-01 6.898300000000000265e-02 +1.403715375412139893e+09 -1.593075999999999937e+00 -3.842420999999999864e+00 9.720959999999999601e-01 8.177100000000000479e-01 -8.433400000000000618e-02 5.649389999999999690e-01 7.129199999999999426e-02 +1.403715375462140083e+09 -1.567050999999999972e+00 -3.845781000000000116e+00 9.709710000000000285e-01 8.170600000000000085e-01 -8.764800000000000368e-02 5.654209999999999514e-01 7.092700000000000393e-02 +1.403715375512140036e+09 -1.540945999999999927e+00 -3.848484000000000016e+00 9.692570000000000352e-01 8.170760000000000245e-01 -9.020000000000000240e-02 5.649520000000000097e-01 7.127100000000000102e-02 +1.403715375562139988e+09 -1.514590000000000103e+00 -3.850538999999999934e+00 9.668750000000000400e-01 8.169560000000000155e-01 -9.368200000000000138e-02 5.646640000000000548e-01 7.042900000000000549e-02 +1.403715375612139940e+09 -1.488137000000000043e+00 -3.852117999999999931e+00 9.639109999999999623e-01 8.166790000000000438e-01 -9.643599999999999395e-02 5.646039999999999948e-01 7.041200000000000236e-02 +1.403715375662139893e+09 -1.461972999999999967e+00 -3.853305000000000202e+00 9.608349999999999946e-01 8.160420000000000451e-01 -9.865100000000000258e-02 5.651140000000000052e-01 7.063500000000000334e-02 +1.403715375712140083e+09 -1.434919000000000056e+00 -3.854487999999999914e+00 9.577219999999999622e-01 8.151140000000000052e-01 -9.989000000000000656e-02 5.660539999999999461e-01 7.206899999999999418e-02 +1.403715375762140036e+09 -1.407651999999999903e+00 -3.855334000000000039e+00 9.543599999999999861e-01 8.142540000000000333e-01 -1.011100000000000054e-01 5.670009999999999772e-01 7.264400000000000024e-02 +1.403715375812139988e+09 -1.380201999999999929e+00 -3.856081000000000092e+00 9.510119999999999685e-01 8.135069999999999801e-01 -1.020169999999999966e-01 5.677849999999999842e-01 7.362000000000000488e-02 +1.403715375862139940e+09 -1.352797000000000027e+00 -3.856109000000000009e+00 9.480359999999999898e-01 8.125719999999999610e-01 -1.017330000000000040e-01 5.688889999999999780e-01 7.578600000000000614e-02 +1.403715375912139893e+09 -1.325264999999999915e+00 -3.855745999999999896e+00 9.447740000000000027e-01 8.122899999999999565e-01 -1.006920000000000037e-01 5.691159999999999553e-01 7.843899999999999484e-02 +1.403715375962140083e+09 -1.298084999999999933e+00 -3.854623000000000133e+00 9.418680000000000385e-01 8.112080000000000402e-01 -1.001839999999999953e-01 5.705419999999999936e-01 7.991700000000000192e-02 +1.403715376012140036e+09 -1.271908999999999956e+00 -3.852632999999999974e+00 9.388290000000000246e-01 8.105850000000000000e-01 -9.915100000000000302e-02 5.713749999999999662e-01 8.155199999999999949e-02 +1.403715376062139988e+09 -1.245983999999999980e+00 -3.849849999999999994e+00 9.349690000000000500e-01 8.099650000000000460e-01 -9.980500000000000482e-02 5.722650000000000237e-01 8.067399999999999571e-02 +1.403715376112139940e+09 -1.220172000000000034e+00 -3.846435000000000048e+00 9.307560000000000278e-01 8.094729999999999981e-01 -1.007399999999999962e-01 5.730889999999999596e-01 7.856799999999999895e-02 +1.403715376162139893e+09 -1.194679999999999964e+00 -3.842426999999999815e+00 9.262850000000000250e-01 8.088210000000000122e-01 -1.020139999999999936e-01 5.741929999999999534e-01 7.552100000000000479e-02 +1.403715376212140083e+09 -1.169232000000000049e+00 -3.838206000000000007e+00 9.217060000000000253e-01 8.080779999999999630e-01 -1.036750000000000033e-01 5.753390000000000448e-01 7.243600000000000039e-02 +1.403715376262140036e+09 -1.144155000000000033e+00 -3.833607999999999905e+00 9.165010000000000101e-01 8.074679999999999636e-01 -1.049299999999999955e-01 5.763129999999999642e-01 6.962500000000000633e-02 +1.403715376312139988e+09 -1.119235999999999898e+00 -3.828943999999999903e+00 9.126039999999999708e-01 8.040110000000000312e-01 -1.041939999999999950e-01 5.812640000000000029e-01 6.958599999999999508e-02 +1.403715376362139940e+09 -1.095075999999999938e+00 -3.824454999999999938e+00 9.085119999999999862e-01 7.991350000000000398e-01 -1.035179999999999989e-01 5.880689999999999529e-01 6.958399999999999308e-02 +1.403715376412139893e+09 -1.072055999999999898e+00 -3.819605999999999835e+00 9.042559999999999487e-01 7.956210000000000226e-01 -1.009140000000000037e-01 5.929569999999999563e-01 7.214500000000000079e-02 +1.403715376462140083e+09 -1.050872999999999946e+00 -3.814239000000000157e+00 8.988690000000000291e-01 7.959070000000000311e-01 -9.809099999999999764e-02 5.926550000000000429e-01 7.530499999999999694e-02 +1.403715376512140036e+09 -1.030999999999999917e+00 -3.808222000000000218e+00 8.927819999999999645e-01 7.983170000000000543e-01 -9.566199999999999704e-02 5.895150000000000112e-01 7.752399999999999569e-02 +1.403715376562139988e+09 -1.012207999999999997e+00 -3.801527000000000100e+00 8.864130000000000065e-01 8.014719999999999622e-01 -9.366199999999999526e-02 5.854030000000000067e-01 7.857300000000000395e-02 +1.403715376612139940e+09 -9.943589999999999929e-01 -3.793969000000000147e+00 8.799339999999999939e-01 8.040549999999999642e-01 -9.196400000000000408e-02 5.820349999999999691e-01 7.920499999999999763e-02 +1.403715376662139893e+09 -9.772760000000000336e-01 -3.785833999999999921e+00 8.732560000000000322e-01 8.068490000000000384e-01 -9.072700000000000209e-02 5.784070000000000045e-01 7.879400000000000293e-02 +1.403715376712140083e+09 -9.603720000000000034e-01 -3.776740999999999904e+00 8.672800000000000509e-01 8.079009999999999803e-01 -8.975600000000000245e-02 5.771950000000000136e-01 7.800799999999999401e-02 +1.403715376762140036e+09 -9.443179999999999907e-01 -3.766840000000000188e+00 8.615169999999999773e-01 8.082599999999999785e-01 -8.787999999999999978e-02 5.769309999999999716e-01 7.838599999999999735e-02 +1.403715376812139988e+09 -9.287149999999999572e-01 -3.756159999999999943e+00 8.559560000000000501e-01 8.073810000000000153e-01 -8.627999999999999559e-02 5.784160000000000412e-01 7.827199999999999436e-02 +1.403715376862139940e+09 -9.136699999999999822e-01 -3.744682000000000066e+00 8.511379999999999502e-01 8.054839999999999778e-01 -8.514199999999999546e-02 5.813779999999999504e-01 7.711199999999999999e-02 +1.403715376912139893e+09 -8.995030000000000525e-01 -3.732142000000000071e+00 8.470670000000000144e-01 8.018070000000000475e-01 -8.359500000000000264e-02 5.867769999999999930e-01 7.622700000000000309e-02 +1.403715376962140083e+09 -8.859939999999999483e-01 -3.718783999999999867e+00 8.437200000000000255e-01 7.972960000000000047e-01 -8.100400000000000655e-02 5.931859999999999911e-01 7.673800000000000066e-02 +1.403715377012140036e+09 -8.740430000000000144e-01 -3.704161000000000037e+00 8.396649999999999947e-01 7.943590000000000373e-01 -8.035899999999999987e-02 5.975369999999999848e-01 7.407500000000000195e-02 +1.403715377062139988e+09 -8.635239999999999583e-01 -3.688604000000000216e+00 8.349520000000000275e-01 7.945109999999999673e-01 -7.841299999999999659e-02 5.977090000000000458e-01 7.312399999999999456e-02 +1.403715377112139940e+09 -8.545749999999999735e-01 -3.672090999999999994e+00 8.292789999999999884e-01 7.977319999999999967e-01 -7.684199999999999364e-02 5.937019999999999520e-01 7.236399999999999777e-02 +1.403715377162139893e+09 -8.469680000000000542e-01 -3.654872999999999816e+00 8.240579999999999572e-01 8.009150000000000436e-01 -7.451000000000000678e-02 5.896719999999999740e-01 7.259300000000000475e-02 +1.403715377212140083e+09 -8.398630000000000262e-01 -3.636468999999999951e+00 8.188060000000000338e-01 8.038330000000000197e-01 -7.259400000000000575e-02 5.859320000000000084e-01 7.256300000000000250e-02 +1.403715377262140036e+09 -8.336980000000000501e-01 -3.617002999999999968e+00 8.138609999999999456e-01 8.058210000000000095e-01 -7.113600000000000478e-02 5.835050000000000514e-01 7.150900000000000312e-02 +1.403715377312139988e+09 -8.283890000000000420e-01 -3.596429999999999794e+00 8.094569999999999821e-01 8.069060000000000121e-01 -7.065899999999999959e-02 5.823190000000000310e-01 6.938300000000000023e-02 +1.403715377362139940e+09 -8.240730000000000555e-01 -3.575095999999999830e+00 8.056229999999999780e-01 8.069800000000000306e-01 -6.999600000000000266e-02 5.824669999999999570e-01 6.794600000000000639e-02 +1.403715377412139893e+09 -8.202279999999999571e-01 -3.553007000000000026e+00 8.021620000000000417e-01 8.059009999999999785e-01 -6.980500000000000593e-02 5.842730000000000423e-01 6.538599999999999968e-02 +1.403715377462140083e+09 -8.170250000000000012e-01 -3.530394999999999950e+00 7.986490000000000533e-01 8.049779999999999713e-01 -6.895500000000000240e-02 5.857400000000000384e-01 6.452800000000000202e-02 +1.403715377512140036e+09 -8.149499999999999522e-01 -3.506437000000000026e+00 7.946750000000000203e-01 8.044559999999999489e-01 -6.834999999999999409e-02 5.866580000000000128e-01 6.333300000000000041e-02 +1.403715377562139988e+09 -8.129250000000000087e-01 -3.482511000000000134e+00 7.910829999999999806e-01 8.043730000000000047e-01 -6.839599999999999846e-02 5.869389999999999885e-01 6.171499999999999903e-02 +1.403715377612139940e+09 -8.123449999999999838e-01 -3.457885999999999793e+00 7.870169999999999666e-01 8.048279999999999879e-01 -6.812200000000000200e-02 5.864150000000000196e-01 6.106199999999999822e-02 +1.403715377662139893e+09 -8.126100000000000545e-01 -3.432573000000000096e+00 7.827849999999999531e-01 8.062179999999999902e-01 -6.787899999999999490e-02 5.846050000000000413e-01 6.033899999999999680e-02 +1.403715377712140083e+09 -8.130509999999999682e-01 -3.406693000000000193e+00 7.785849999999999715e-01 8.075630000000000308e-01 -6.809999999999999387e-02 5.827870000000000550e-01 5.969900000000000206e-02 +1.403715377762140036e+09 -8.143439999999999568e-01 -3.380015999999999909e+00 7.743929999999999980e-01 8.080500000000000460e-01 -6.795900000000000551e-02 5.821479999999999988e-01 5.950400000000000134e-02 +1.403715377812139988e+09 -8.163000000000000256e-01 -3.352554000000000034e+00 7.703989999999999450e-01 8.086710000000000287e-01 -6.806900000000000450e-02 5.813129999999999686e-01 5.910300000000000276e-02 +1.403715377862139940e+09 -8.188149999999999595e-01 -3.324364999999999792e+00 7.665619999999999656e-01 8.092219999999999969e-01 -6.825799999999999923e-02 5.805660000000000265e-01 5.868000000000000299e-02 +1.403715377912139893e+09 -8.214120000000000310e-01 -3.295580999999999872e+00 7.623529999999999474e-01 8.094569999999999821e-01 -6.821699999999999986e-02 5.802650000000000308e-01 5.845800000000000302e-02 +1.403715377962140083e+09 -8.246750000000000469e-01 -3.266433000000000142e+00 7.578030000000000044e-01 8.093930000000000291e-01 -6.832599999999999785e-02 5.804040000000000310e-01 5.783400000000000346e-02 +1.403715378012140036e+09 -8.284690000000000110e-01 -3.236410999999999927e+00 7.532590000000000119e-01 8.093559999999999643e-01 -6.960700000000000220e-02 5.805010000000000447e-01 5.583300000000000068e-02 +1.403715378062139988e+09 -8.327379999999999782e-01 -3.205705000000000027e+00 7.486300000000000177e-01 8.088189999999999547e-01 -7.120899999999999452e-02 5.813369999999999926e-01 5.280300000000000271e-02 +1.403715378112139940e+09 -8.376360000000000472e-01 -3.174935000000000063e+00 7.439489999999999714e-01 8.085210000000000452e-01 -7.264800000000000424e-02 5.818250000000000366e-01 4.995399999999999840e-02 +1.403715378162139893e+09 -8.429050000000000153e-01 -3.144022000000000094e+00 7.391440000000000232e-01 8.079849999999999532e-01 -7.408900000000000208e-02 5.826480000000000548e-01 4.682399999999999757e-02 +1.403715378212140083e+09 -8.485740000000000505e-01 -3.113414999999999822e+00 7.352379999999999471e-01 8.072620000000000351e-01 -7.598900000000000099e-02 5.836599999999999566e-01 4.352199999999999819e-02 +1.403715378262140036e+09 -8.546540000000000248e-01 -3.083263999999999783e+00 7.302119999999999722e-01 8.082669999999999577e-01 -7.766299999999999593e-02 5.822770000000000445e-01 4.032700000000000173e-02 +1.403715378312139988e+09 -8.611259999999999470e-01 -3.053573000000000093e+00 7.249379999999999713e-01 8.094630000000000436e-01 -7.981699999999999906e-02 5.805639999999999690e-01 3.667800000000000227e-02 +1.403715378362139940e+09 -8.682159999999999878e-01 -3.024774999999999991e+00 7.192030000000000367e-01 8.113970000000000349e-01 -8.173600000000000310e-02 5.777759999999999563e-01 3.358699999999999880e-02 +1.403715378412139893e+09 -8.755509999999999682e-01 -2.996795000000000098e+00 7.134909999999999863e-01 8.140319999999999778e-01 -8.268799999999999761e-02 5.740140000000000242e-01 3.198700000000000154e-02 +1.403715378462140083e+09 -8.835560000000000080e-01 -2.969951000000000008e+00 7.084890000000000354e-01 8.160140000000000171e-01 -8.244100000000000039e-02 5.711850000000000538e-01 3.275900000000000339e-02 +1.403715378512140036e+09 -8.913729999999999709e-01 -2.944139999999999979e+00 7.039069999999999494e-01 8.180119999999999614e-01 -8.088399999999999757e-02 5.684069999999999956e-01 3.505400000000000182e-02 +1.403715378562139988e+09 -8.991440000000000543e-01 -2.919414999999999871e+00 7.001880000000000326e-01 8.193519999999999692e-01 -7.857100000000000195e-02 5.665689999999999893e-01 3.857700000000000018e-02 +1.403715378612139940e+09 -9.065950000000000397e-01 -2.895289000000000001e+00 6.971920000000000339e-01 8.203179999999999916e-01 -7.750899999999999457e-02 5.651939999999999742e-01 4.033400000000000180e-02 +1.403715378662139893e+09 -9.134020000000000472e-01 -2.871576000000000128e+00 6.943409999999999860e-01 8.216620000000000035e-01 -7.633800000000000308e-02 5.632639999999999869e-01 4.216400000000000009e-02 +1.403715378712140083e+09 -9.199150000000000382e-01 -2.848440000000000083e+00 6.919260000000000410e-01 8.230129999999999946e-01 -7.542300000000000393e-02 5.613139999999999796e-01 4.343199999999999839e-02 +1.403715378762140036e+09 -9.261599999999999833e-01 -2.826077999999999868e+00 6.901399999999999757e-01 8.245719999999999716e-01 -7.513100000000000334e-02 5.590209999999999901e-01 4.394300000000000289e-02 +1.403715378812139988e+09 -9.320019999999999971e-01 -2.804209999999999869e+00 6.889779999999999793e-01 8.265850000000000142e-01 -7.523000000000000520e-02 5.560410000000000075e-01 4.377299999999999941e-02 +1.403715378862139940e+09 -9.370270000000000543e-01 -2.782916000000000167e+00 6.880500000000000504e-01 8.281269999999999465e-01 -7.563499999999999390e-02 5.537349999999999772e-01 4.316099999999999798e-02 +1.403715378962140083e+09 -9.440359999999999863e-01 -2.741728999999999861e+00 6.888069999999999471e-01 8.297940000000000316e-01 -7.639300000000000257e-02 5.512179999999999858e-01 4.200799999999999673e-02 +1.403715379012140036e+09 -9.454519999999999591e-01 -2.722097000000000211e+00 6.903650000000000064e-01 8.298100000000000476e-01 -7.669700000000000129e-02 5.511810000000000320e-01 4.162199999999999928e-02 +1.403715379062139988e+09 -9.457590000000000163e-01 -2.703262000000000054e+00 6.924580000000000179e-01 8.295759999999999801e-01 -7.613100000000000422e-02 5.515170000000000350e-01 4.284799999999999720e-02 +1.403715379112139940e+09 -9.451600000000000001e-01 -2.684787000000000035e+00 6.951370000000000049e-01 8.287590000000000234e-01 -7.487699999999999911e-02 5.528049999999999908e-01 4.424899999999999667e-02 +1.403715379162139893e+09 -9.434350000000000236e-01 -2.666967999999999783e+00 6.984820000000000473e-01 8.270539999999999559e-01 -7.237000000000000377e-02 5.553599999999999648e-01 4.816499999999999948e-02 +1.403715379212140083e+09 -9.408940000000000081e-01 -2.649379000000000151e+00 7.018619999999999859e-01 8.261249999999999982e-01 -7.004900000000000015e-02 5.567170000000000174e-01 5.173799999999999927e-02 +1.403715379262140036e+09 -9.379739999999999744e-01 -2.631689999999999863e+00 7.053209999999999757e-01 8.253629999999999578e-01 -6.776400000000000479e-02 5.578020000000000200e-01 5.514299999999999757e-02 +1.403715379312139988e+09 -9.341850000000000431e-01 -2.614116000000000106e+00 7.091739999999999711e-01 8.248900000000000121e-01 -6.601200000000000123e-02 5.584139999999999660e-01 5.807999999999999968e-02 +1.403715379362139940e+09 -9.294820000000000304e-01 -2.596009000000000011e+00 7.132070000000000354e-01 8.242930000000000534e-01 -6.409700000000000120e-02 5.592399999999999594e-01 6.069999999999999701e-02 +1.403715379412139893e+09 -9.241070000000000118e-01 -2.577393999999999963e+00 7.171539999999999582e-01 8.242180000000000062e-01 -6.280499999999999972e-02 5.592510000000000536e-01 6.291599999999999970e-02 +1.403715379462140083e+09 -9.180589999999999584e-01 -2.558016999999999985e+00 7.208440000000000403e-01 8.248269999999999769e-01 -6.176100000000000340e-02 5.582840000000000025e-01 6.453000000000000402e-02 +1.403715379512140036e+09 -9.112639999999999629e-01 -2.538062000000000040e+00 7.245780000000000554e-01 8.253810000000000313e-01 -6.087499999999999856e-02 5.573860000000000481e-01 6.603900000000000048e-02 +1.403715379562139988e+09 -9.037150000000000460e-01 -2.517236000000000029e+00 7.284789999999999877e-01 8.261939999999999840e-01 -6.112999999999999684e-02 5.561770000000000325e-01 6.583500000000000463e-02 +1.403715379612139940e+09 -8.950700000000000323e-01 -2.495623999999999842e+00 7.323499999999999455e-01 8.269579999999999709e-01 -6.051900000000000335e-02 5.550239999999999618e-01 6.653699999999999892e-02 +1.403715379662139893e+09 -8.855870000000000131e-01 -2.473193999999999892e+00 7.358900000000000441e-01 8.284089999999999510e-01 -6.054699999999999666e-02 5.528170000000000028e-01 6.682599999999999651e-02 +1.403715379712140083e+09 -8.748230000000000173e-01 -2.449896999999999991e+00 7.400170000000000359e-01 8.282100000000000017e-01 -5.970000000000000306e-02 5.530950000000000033e-01 6.774600000000000066e-02 +1.403715379762140036e+09 -8.631550000000000056e-01 -2.425657000000000174e+00 7.441429999999999989e-01 8.279980000000000118e-01 -5.944499999999999784e-02 5.533930000000000238e-01 6.813500000000000112e-02 +1.403715379812139988e+09 -8.503950000000000120e-01 -2.400558000000000192e+00 7.487599999999999811e-01 8.264770000000000172e-01 -5.875799999999999773e-02 5.556689999999999685e-01 6.866800000000000681e-02 +1.403715379862139940e+09 -8.366740000000000288e-01 -2.374697999999999976e+00 7.535739999999999661e-01 8.244620000000000282e-01 -5.754999999999999699e-02 5.586149999999999727e-01 6.999199999999999866e-02 +1.403715379912139893e+09 -8.219459999999999544e-01 -2.347770000000000135e+00 7.582360000000000211e-01 8.219950000000000312e-01 -5.658300000000000135e-02 5.622310000000000363e-01 7.084400000000000419e-02 +1.403715379962140083e+09 -8.065569999999999684e-01 -2.320063999999999904e+00 7.626990000000000158e-01 8.201129999999999809e-01 -5.611800000000000122e-02 5.649199999999999777e-01 7.162999999999999923e-02 +1.403715380012140036e+09 -7.908429999999999627e-01 -2.291230999999999796e+00 7.669190000000000174e-01 8.188809999999999700e-01 -5.526999999999999968e-02 5.665909999999999558e-01 7.316400000000000681e-02 +1.403715380062139988e+09 -7.748479999999999812e-01 -2.261160999999999976e+00 7.708709999999999729e-01 8.170749999999999957e-01 -5.611399999999999721e-02 5.692059999999999897e-01 7.241699999999999526e-02 +1.403715380112139940e+09 -7.593560000000000310e-01 -2.229764999999999997e+00 7.740789999999999615e-01 8.155999999999999917e-01 -5.897800000000000264e-02 5.714590000000000503e-01 6.894200000000000328e-02 +1.403715380162139893e+09 -7.440320000000000267e-01 -2.197637999999999980e+00 7.774860000000000104e-01 8.140709999999999891e-01 -6.281399999999999484e-02 5.738189999999999680e-01 6.383400000000000185e-02 +1.403715380212140083e+09 -7.286409999999999831e-01 -2.164759999999999796e+00 7.806610000000000493e-01 8.130960000000000409e-01 -6.509299999999999808e-02 5.752789999999999848e-01 6.076299999999999757e-02 +1.403715380262140036e+09 -7.141330000000000178e-01 -2.131444000000000116e+00 7.835419999999999607e-01 8.128170000000000117e-01 -6.777800000000000491e-02 5.757390000000000008e-01 5.708699999999999886e-02 +1.403715380312139988e+09 -6.998980000000000201e-01 -2.098104000000000191e+00 7.859990000000000032e-01 8.130579999999999474e-01 -6.998699999999999366e-02 5.753840000000000066e-01 5.451999999999999902e-02 +1.403715380362139940e+09 -6.861159999999999481e-01 -2.064760000000000151e+00 7.883379999999999832e-01 8.136710000000000331e-01 -7.200499999999999956e-02 5.743730000000000224e-01 5.338299999999999990e-02 +1.403715380412139893e+09 -6.719659999999999522e-01 -2.031848999999999794e+00 7.906750000000000167e-01 8.147750000000000270e-01 -7.281700000000000672e-02 5.726930000000000076e-01 5.350300000000000195e-02 +1.403715380462140083e+09 -6.577330000000000121e-01 -1.998963999999999963e+00 7.932890000000000219e-01 8.150279999999999747e-01 -7.221199999999999841e-02 5.722709999999999742e-01 5.495699999999999891e-02 +1.403715380512140036e+09 -6.442830000000000501e-01 -1.965870999999999924e+00 7.962080000000000268e-01 8.149570000000000425e-01 -7.127999999999999614e-02 5.723530000000000006e-01 5.635099999999999831e-02 +1.403715380562139988e+09 -6.312480000000000313e-01 -1.932716000000000101e+00 7.985879999999999646e-01 8.150699999999999612e-01 -7.014299999999999702e-02 5.722159999999999469e-01 5.752299999999999774e-02 +1.403715380612139940e+09 -6.186749999999999750e-01 -1.899296000000000095e+00 8.014080000000000092e-01 8.153470000000000439e-01 -6.910299999999999776e-02 5.718969999999999887e-01 5.802800000000000319e-02 +1.403715380662139893e+09 -6.063129999999999908e-01 -1.865436000000000094e+00 8.045309999999999961e-01 8.153820000000000512e-01 -6.855999999999999595e-02 5.719100000000000295e-01 5.805500000000000244e-02 +1.403715380712140083e+09 -5.943030000000000257e-01 -1.831002000000000018e+00 8.078600000000000225e-01 8.150619999999999532e-01 -6.818799999999999861e-02 5.724390000000000311e-01 5.777299999999999797e-02 +1.403715380762140036e+09 -5.828109999999999680e-01 -1.795879000000000003e+00 8.112829999999999764e-01 8.146640000000000548e-01 -6.761599999999999555e-02 5.730450000000000266e-01 5.804600000000000037e-02 +1.403715380812139988e+09 -5.713519999999999710e-01 -1.760777999999999954e+00 8.151960000000000317e-01 8.141969999999999485e-01 -6.722000000000000197e-02 5.737740000000000062e-01 5.786700000000000177e-02 +1.403715380862139940e+09 -5.602030000000000065e-01 -1.725659999999999972e+00 8.186409999999999521e-01 8.136480000000000379e-01 -6.672200000000000353e-02 5.745930000000000204e-01 5.802899999999999725e-02 +1.403715380912139893e+09 -5.492890000000000272e-01 -1.690492000000000106e+00 8.212000000000000410e-01 8.134940000000000504e-01 -6.614399999999999447e-02 5.748189999999999689e-01 5.861700000000000244e-02 +1.403715380962140083e+09 -5.384280000000000177e-01 -1.655038999999999927e+00 8.237160000000000037e-01 8.131399999999999739e-01 -6.561799999999999577e-02 5.753289999999999793e-01 5.911199999999999788e-02 +1.403715381012140036e+09 -5.276410000000000267e-01 -1.619367000000000001e+00 8.264209999999999612e-01 8.131709999999999772e-01 -6.493699999999999473e-02 5.752580000000000471e-01 6.011899999999999883e-02 +1.403715381062139988e+09 -5.176870000000000083e-01 -1.583387000000000100e+00 8.291749999999999954e-01 8.125860000000000305e-01 -6.535000000000000531e-02 5.759750000000000147e-01 6.071100000000000108e-02 +1.403715381112139940e+09 -5.075720000000000232e-01 -1.547139000000000042e+00 8.320779999999999843e-01 8.125839999999999730e-01 -6.705899999999999361e-02 5.758969999999999922e-01 5.961000000000000326e-02 +1.403715381162139893e+09 -4.980069999999999775e-01 -1.510394000000000014e+00 8.348499999999999810e-01 8.119570000000000398e-01 -6.947899999999999909e-02 5.766510000000000247e-01 5.807099999999999762e-02 +1.403715381212140083e+09 -4.892969999999999819e-01 -1.473910999999999971e+00 8.369090000000000140e-01 8.112850000000000339e-01 -7.166100000000000247e-02 5.774460000000000148e-01 5.689299999999999913e-02 +1.403715381262140036e+09 -4.810380000000000211e-01 -1.437543999999999933e+00 8.386649999999999938e-01 8.105050000000000310e-01 -7.396400000000000197e-02 5.783449999999999980e-01 5.592300000000000049e-02 +1.403715381312139988e+09 -4.734909999999999952e-01 -1.401359999999999939e+00 8.401359999999999939e-01 8.098030000000000506e-01 -7.571899999999999464e-02 5.791389999999999594e-01 5.553999999999999909e-02 +1.403715381362139940e+09 -4.662729999999999930e-01 -1.365798999999999985e+00 8.411389999999999700e-01 8.094839999999999813e-01 -7.846400000000000596e-02 5.793199999999999461e-01 5.447099999999999859e-02 +1.403715381412139893e+09 -4.592840000000000256e-01 -1.330711999999999895e+00 8.419259999999999522e-01 8.085510000000000197e-01 -8.118300000000000516e-02 5.803160000000000540e-01 5.373599999999999904e-02 +1.403715381462140083e+09 -4.527360000000000273e-01 -1.296145000000000103e+00 8.423239999999999617e-01 8.078440000000000065e-01 -8.324099999999999555e-02 5.809720000000000439e-01 5.413300000000000056e-02 +1.403715381512140036e+09 -4.470979999999999954e-01 -1.261984999999999912e+00 8.426749999999999519e-01 8.059079999999999577e-01 -8.493000000000000549e-02 5.833409999999999984e-01 5.489100000000000229e-02 +1.403715381562139988e+09 -4.425279999999999769e-01 -1.228096999999999994e+00 8.421089999999999964e-01 8.055590000000000250e-01 -8.425399999999999556e-02 5.836019999999999541e-01 5.817699999999999955e-02 +1.403715381612139940e+09 -4.386729999999999796e-01 -1.194512999999999936e+00 8.409219999999999473e-01 8.057600000000000318e-01 -8.406600000000000183e-02 5.830990000000000339e-01 6.066200000000000064e-02 +1.403715381662139893e+09 -4.356189999999999785e-01 -1.160935000000000050e+00 8.387620000000000076e-01 8.071789999999999798e-01 -8.332499999999999629e-02 5.809220000000000494e-01 6.363499999999999712e-02 +1.403715381712140083e+09 -4.329689999999999928e-01 -1.127151000000000014e+00 8.360929999999999751e-01 8.098880000000000523e-01 -8.252400000000000013e-02 5.769459999999999589e-01 6.636000000000000232e-02 +1.403715381762140036e+09 -4.306869999999999865e-01 -1.093364000000000003e+00 8.337599999999999456e-01 8.126090000000000257e-01 -8.160399999999999598e-02 5.729980000000000073e-01 6.840899999999999759e-02 +1.403715381812139988e+09 -4.286470000000000002e-01 -1.059417999999999971e+00 8.317930000000000046e-01 8.154299999999999882e-01 -8.079200000000000270e-02 5.689089999999999980e-01 6.991999999999999604e-02 +1.403715381862139940e+09 -4.266610000000000125e-01 -1.025131000000000014e+00 8.291150000000000464e-01 8.186790000000000456e-01 -8.062700000000000422e-02 5.640730000000000466e-01 7.131400000000000239e-02 +1.403715381912139893e+09 -4.241420000000000190e-01 -9.908820000000000405e-01 8.261830000000000007e-01 8.213749999999999662e-01 -8.167599999999999860e-02 5.596940000000000248e-01 7.358299999999999563e-02 +1.403715381962140083e+09 -4.218080000000000163e-01 -9.560560000000000169e-01 8.232890000000000486e-01 8.232810000000000406e-01 -8.408000000000000196e-02 5.560220000000000162e-01 7.731999999999999984e-02 +1.403715382012140036e+09 -4.182600000000000207e-01 -9.214869999999999450e-01 8.208159999999999901e-01 8.240220000000000322e-01 -8.909400000000000652e-02 5.537269999999999692e-01 8.022600000000000564e-02 +1.403715382062139988e+09 -4.136529999999999929e-01 -8.870860000000000412e-01 8.185360000000000413e-01 8.244129999999999514e-01 -9.533999999999999420e-02 5.515309999999999935e-01 8.407000000000000584e-02 +1.403715382112139940e+09 -4.079999999999999738e-01 -8.524019999999999930e-01 8.163179999999999881e-01 8.238539999999999752e-01 -1.033339999999999953e-01 5.504369999999999541e-01 8.721099999999999686e-02 +1.403715382162139893e+09 -4.017229999999999968e-01 -8.176839999999999664e-01 8.146440000000000348e-01 8.227459999999999773e-01 -1.123419999999999974e-01 5.497910000000000297e-01 9.054299999999999848e-02 +1.403715382212140083e+09 -3.943889999999999896e-01 -7.831709999999999505e-01 8.136700000000000044e-01 8.211289999999999978e-01 -1.223520000000000024e-01 5.494930000000000092e-01 9.398600000000000010e-02 +1.403715382262140036e+09 -3.860169999999999990e-01 -7.488569999999999949e-01 8.130819999999999714e-01 8.193219999999999947e-01 -1.320030000000000092e-01 5.490810000000000413e-01 9.898300000000000154e-02 +1.403715382312139988e+09 -3.764060000000000183e-01 -7.152089999999999836e-01 8.126079999999999970e-01 8.171950000000000047e-01 -1.423800000000000066e-01 5.487689999999999513e-01 1.037890000000000063e-01 +1.403715382362139940e+09 -3.660669999999999757e-01 -6.823590000000000488e-01 8.122589999999999533e-01 8.149429999999999730e-01 -1.523609999999999964e-01 5.482770000000000143e-01 1.097599999999999965e-01 +1.403715382412139893e+09 -3.546619999999999773e-01 -6.492109999999999825e-01 8.116179999999999506e-01 8.120249999999999968e-01 -1.625729999999999953e-01 5.483379999999999921e-01 1.162369999999999931e-01 +1.403715382462140083e+09 -3.424740000000000006e-01 -6.160820000000000185e-01 8.108790000000000164e-01 8.101399999999999713e-01 -1.722450000000000092e-01 5.469519999999999937e-01 1.218560000000000060e-01 +1.403715382512140036e+09 -3.291390000000000149e-01 -5.832629999999999759e-01 8.101730000000000320e-01 8.079180000000000250e-01 -1.811649999999999927e-01 5.462639999999999718e-01 1.266599999999999948e-01 +1.403715382562139988e+09 -3.141610000000000236e-01 -5.512590000000000545e-01 8.097750000000000226e-01 8.061329999999999885e-01 -1.893930000000000058e-01 5.451310000000000322e-01 1.308140000000000136e-01 +1.403715382612139940e+09 -2.994709999999999872e-01 -5.190890000000000226e-01 8.087959999999999594e-01 8.041580000000000394e-01 -1.976529999999999954e-01 5.443249999999999478e-01 1.340699999999999947e-01 +1.403715382662139893e+09 -2.839709999999999734e-01 -4.875849999999999906e-01 8.076179999999999470e-01 8.025849999999999929e-01 -2.052930000000000033e-01 5.426440000000000152e-01 1.387420000000000042e-01 +1.403715382712140083e+09 -2.677620000000000000e-01 -4.566379999999999884e-01 8.061620000000000452e-01 8.004360000000000364e-01 -2.136389999999999956e-01 5.416159999999999863e-01 1.425200000000000078e-01 +1.403715382762140036e+09 -2.505859999999999754e-01 -4.262770000000000170e-01 8.043799999999999839e-01 7.992430000000000367e-01 -2.209460000000000035e-01 5.389800000000000146e-01 1.479659999999999864e-01 +1.403715382812139988e+09 -2.327480000000000104e-01 -3.964889999999999803e-01 8.025999999999999801e-01 7.969749999999999890e-01 -2.279539999999999900e-01 5.378220000000000223e-01 1.536740000000000050e-01 +1.403715382862139940e+09 -2.143220000000000125e-01 -3.672340000000000049e-01 8.005670000000000286e-01 7.949509999999999632e-01 -2.356090000000000129e-01 5.360460000000000225e-01 1.587290000000000090e-01 +1.403715382912139893e+09 -1.951180000000000136e-01 -3.393959999999999755e-01 7.984390000000000098e-01 7.927859999999999907e-01 -2.427600000000000036e-01 5.344449999999999479e-01 1.640959999999999919e-01 +1.403715382962140083e+09 -1.753820000000000101e-01 -3.114509999999999779e-01 7.961629999999999541e-01 7.907969999999999722e-01 -2.506200000000000094e-01 5.324689999999999701e-01 1.682430000000000037e-01 +1.403715383012140036e+09 -1.549979999999999969e-01 -2.843910000000000049e-01 7.939420000000000366e-01 7.884349999999999969e-01 -2.585029999999999828e-01 5.310049999999999493e-01 1.719870000000000010e-01 +1.403715383062139988e+09 -1.337309999999999888e-01 -2.572550000000000114e-01 7.912949999999999706e-01 7.865560000000000329e-01 -2.661979999999999902e-01 5.293419999999999792e-01 1.739690000000000125e-01 +1.403715383112139940e+09 -1.118429999999999980e-01 -2.314080000000000026e-01 7.884550000000000169e-01 7.847650000000000459e-01 -2.729929999999999857e-01 5.283020000000000493e-01 1.746860000000000079e-01 +1.403715383162139893e+09 -8.913100000000000189e-02 -2.071070000000000133e-01 7.850519999999999721e-01 7.834630000000000205e-01 -2.780210000000000181e-01 5.273489999999999567e-01 1.754799999999999971e-01 +1.403715383212140083e+09 -6.545800000000000229e-02 -1.827989999999999893e-01 7.818819999999999659e-01 7.827349999999999586e-01 -2.831770000000000120e-01 5.259249999999999758e-01 1.747569999999999957e-01 +1.403715383262140036e+09 -4.073800000000000338e-02 -1.596670000000000034e-01 7.784520000000000328e-01 7.822670000000000456e-01 -2.854749999999999788e-01 5.249500000000000277e-01 1.760420000000000040e-01 +1.403715383312139988e+09 -1.544200000000000086e-02 -1.378359999999999863e-01 7.745959999999999512e-01 7.815199999999999925e-01 -2.883209999999999940e-01 5.246990000000000265e-01 1.754650000000000098e-01 +1.403715383362139940e+09 1.045699999999999928e-02 -1.173479999999999940e-01 7.710090000000000554e-01 7.805060000000000331e-01 -2.906380000000000075e-01 5.252649999999999819e-01 1.744610000000000050e-01 +1.403715383412139893e+09 3.665399999999999908e-02 -9.837100000000000011e-02 7.673699999999999966e-01 7.796459999999999502e-01 -2.914680000000000049e-01 5.260329999999999728e-01 1.746109999999999884e-01 +1.403715383462140083e+09 6.315999999999999392e-02 -8.102099999999999580e-02 7.640810000000000102e-01 7.783099999999999463e-01 -2.925209999999999755e-01 5.274269999999999792e-01 1.746030000000000082e-01 +1.403715383512140036e+09 9.015399999999999803e-02 -6.522699999999999332e-02 7.614929999999999755e-01 7.757420000000000426e-01 -2.941650000000000098e-01 5.299629999999999619e-01 1.755889999999999951e-01 +1.403715383562139988e+09 1.175169999999999965e-01 -5.066899999999999876e-02 7.588160000000000460e-01 7.731519999999999504e-01 -2.957469999999999821e-01 5.319460000000000299e-01 1.783349999999999935e-01 +1.403715383612139940e+09 1.447450000000000125e-01 -3.749000000000000249e-02 7.559430000000000316e-01 7.698049999999999615e-01 -2.979100000000000081e-01 5.341059999999999697e-01 1.827030000000000043e-01 +1.403715383662139893e+09 1.718409999999999938e-01 -2.523099999999999996e-02 7.531099999999999461e-01 7.669010000000000549e-01 -3.020470000000000099e-01 5.344659999999999966e-01 1.870189999999999908e-01 +1.403715383712140083e+09 1.979730000000000101e-01 -1.480700000000000072e-02 7.494699999999999696e-01 7.637939999999999729e-01 -3.073400000000000021e-01 5.341240000000000432e-01 1.920240000000000002e-01 +1.403715383762140036e+09 2.234440000000000037e-01 -6.276999999999999594e-03 7.452229999999999688e-01 7.599110000000000031e-01 -3.139919999999999933e-01 5.336750000000000105e-01 1.978260000000000018e-01 +1.403715383812139988e+09 2.486889999999999934e-01 2.589999999999999854e-03 7.411240000000000050e-01 7.557650000000000201e-01 -3.220180000000000264e-01 5.325170000000000181e-01 2.038359999999999894e-01 +1.403715383862139940e+09 2.734869999999999801e-01 1.087499999999999925e-02 7.369830000000000547e-01 7.518230000000000190e-01 -3.309309999999999752e-01 5.300489999999999924e-01 2.104630000000000112e-01 +1.403715383912139893e+09 2.973540000000000072e-01 1.840200000000000169e-02 7.326430000000000442e-01 7.469959999999999933e-01 -3.409780000000000033e-01 5.276570000000000427e-01 2.175070000000000059e-01 +1.403715383962140083e+09 3.207470000000000043e-01 2.550200000000000036e-02 7.283819999999999739e-01 7.423429999999999751e-01 -3.510909999999999864e-01 5.239639999999999853e-01 2.261050000000000004e-01 +1.403715384012140036e+09 3.437979999999999925e-01 3.217300000000000021e-02 7.244829999999999881e-01 7.366949999999999887e-01 -3.620999999999999774e-01 5.210029999999999939e-01 2.339229999999999920e-01 +1.403715384062139988e+09 3.655240000000000156e-01 3.845099999999999907e-02 7.203779999999999628e-01 7.314490000000000158e-01 -3.732110000000000150e-01 5.169249999999999678e-01 2.418329999999999924e-01 +1.403715384112139940e+09 3.863070000000000115e-01 4.456999999999999851e-02 7.167740000000000222e-01 7.254899999999999682e-01 -3.844819999999999904e-01 5.132200000000000095e-01 2.498869999999999980e-01 +1.403715384162139893e+09 4.063399999999999790e-01 5.027999999999999831e-02 7.133439999999999781e-01 7.193270000000000497e-01 -3.954989999999999895e-01 5.096720000000000139e-01 2.576510000000000189e-01 +1.403715384212140083e+09 4.259629999999999805e-01 5.521000000000000213e-02 7.107869999999999466e-01 7.133899999999999686e-01 -4.067120000000000180e-01 5.056300000000000239e-01 2.645719999999999739e-01 +1.403715384262140036e+09 4.453690000000000149e-01 6.052199999999999941e-02 7.087930000000000064e-01 7.067560000000000509e-01 -4.177790000000000115e-01 5.023509999999999920e-01 2.712919999999999776e-01 +1.403715384312139988e+09 4.640699999999999825e-01 6.475799999999999612e-02 7.072739999999999583e-01 6.999269999999999659e-01 -4.290669999999999762e-01 4.990979999999999861e-01 2.773180000000000089e-01 +1.403715384362139940e+09 4.817219999999999835e-01 6.821599999999999886e-02 7.059060000000000334e-01 6.929020000000000179e-01 -4.398730000000000140e-01 4.958420000000000050e-01 2.837930000000000175e-01 +1.403715384412139893e+09 4.988670000000000049e-01 7.152000000000000024e-02 7.049079999999999790e-01 6.862080000000000402e-01 -4.500370000000000203e-01 4.922119999999999829e-01 2.903649999999999842e-01 +1.403715384462140083e+09 5.155060000000000198e-01 7.465800000000000214e-02 7.039680000000000382e-01 6.796470000000000011e-01 -4.605890000000000262e-01 4.882440000000000113e-01 2.958970000000000211e-01 +1.403715384512140036e+09 5.307969999999999633e-01 7.712700000000000111e-02 7.029029999999999445e-01 6.733360000000000456e-01 -4.713169999999999860e-01 4.838509999999999756e-01 3.006119999999999903e-01 +1.403715384562139988e+09 5.454130000000000367e-01 7.869700000000000306e-02 7.019809999999999661e-01 6.681500000000000217e-01 -4.814390000000000058e-01 4.778350000000000097e-01 3.057210000000000205e-01 +1.403715384612139940e+09 5.594270000000000076e-01 7.926800000000000512e-02 7.016679999999999584e-01 6.623080000000000078e-01 -4.917569999999999997e-01 4.725770000000000248e-01 3.101519999999999833e-01 +1.403715384662139893e+09 5.722110000000000252e-01 7.924200000000000688e-02 7.012399999999999745e-01 6.568180000000000129e-01 -5.016549999999999621e-01 4.666250000000000120e-01 3.149500000000000077e-01 +1.403715384712140083e+09 5.841659999999999631e-01 7.811999999999999500e-02 7.012890000000000512e-01 6.519260000000000055e-01 -5.104699999999999793e-01 4.599509999999999987e-01 3.207160000000000011e-01 +1.403715384762140036e+09 5.953359999999999763e-01 7.605599999999999861e-02 7.019589999999999996e-01 6.457030000000000269e-01 -5.193529999999999536e-01 4.553329999999999878e-01 3.255950000000000233e-01 +1.403715384812139988e+09 6.052429999999999755e-01 7.286800000000000221e-02 7.024249999999999661e-01 6.399040000000000283e-01 -5.277939999999999854e-01 4.501809999999999978e-01 3.305950000000000277e-01 +1.403715384862139940e+09 6.152490000000000459e-01 6.936000000000000498e-02 7.036170000000000480e-01 6.340660000000000185e-01 -5.358239999999999670e-01 4.454810000000000159e-01 3.352600000000000025e-01 +1.403715384912139893e+09 6.242539999999999756e-01 6.393300000000000372e-02 7.049889999999999768e-01 6.278930000000000344e-01 -5.428770000000000540e-01 4.422050000000000147e-01 3.398370000000000002e-01 +1.403715384962140083e+09 6.325389999999999624e-01 5.753899999999999987e-02 7.066639999999999588e-01 6.221670000000000256e-01 -5.479399999999999826e-01 4.405660000000000132e-01 3.443430000000000102e-01 +1.403715385012140036e+09 6.402099999999999458e-01 4.998899999999999871e-02 7.084209999999999674e-01 6.179689999999999905e-01 -5.511580000000000368e-01 4.385109999999999841e-01 3.493530000000000246e-01 +1.403715385062139988e+09 6.469350000000000378e-01 4.119300000000000045e-02 7.095839999999999925e-01 6.151109999999999634e-01 -5.534660000000000135e-01 4.356889999999999930e-01 3.542429999999999746e-01 +1.403715385112139940e+09 6.526429999999999731e-01 3.173000000000000126e-02 7.117120000000000113e-01 6.125960000000000294e-01 -5.553120000000000278e-01 4.322779999999999956e-01 3.598469999999999724e-01 +1.403715385162139893e+09 6.575450000000000461e-01 2.146899999999999850e-02 7.138219999999999565e-01 6.097930000000000295e-01 -5.575269999999999948e-01 4.286789999999999767e-01 3.654450000000000198e-01 +1.403715385212140083e+09 6.618990000000000151e-01 1.070499999999999924e-02 7.160809999999999675e-01 6.069160000000000110e-01 -5.599250000000000060e-01 4.249310000000000032e-01 3.709049999999999847e-01 +1.403715385262140036e+09 6.660359999999999614e-01 -7.429999999999999539e-04 7.186040000000000205e-01 6.045730000000000270e-01 -5.620849999999999458e-01 4.215220000000000078e-01 3.753290000000000237e-01 +1.403715385312139988e+09 6.703569999999999807e-01 -1.289599999999999948e-02 7.210739999999999927e-01 6.026230000000000198e-01 -5.644700000000000273e-01 4.185260000000000091e-01 3.782260000000000066e-01 +1.403715385362139940e+09 6.747189999999999577e-01 -2.593900000000000025e-02 7.234800000000000120e-01 6.003969999999999585e-01 -5.664569999999999883e-01 4.172469999999999790e-01 3.802030000000000132e-01 +1.403715385412139893e+09 6.790910000000000002e-01 -3.935899999999999815e-02 7.262260000000000382e-01 5.993000000000000549e-01 -5.682859999999999578e-01 4.152770000000000072e-01 3.813599999999999768e-01 +1.403715385462140083e+09 6.832829999999999737e-01 -5.310600000000000043e-02 7.293950000000000156e-01 5.971109999999999474e-01 -5.699899999999999967e-01 4.158939999999999859e-01 3.815779999999999728e-01 +1.403715385512140036e+09 6.870990000000000153e-01 -6.761999999999999955e-02 7.327590000000000492e-01 5.944720000000000004e-01 -5.711450000000000138e-01 4.182710000000000039e-01 3.813739999999999908e-01 +1.403715385562139988e+09 6.911199999999999566e-01 -8.229300000000000503e-02 7.365040000000000475e-01 5.912640000000000118e-01 -5.730849999999999556e-01 4.216659999999999853e-01 3.797079999999999900e-01 +1.403715385612139940e+09 6.947470000000000034e-01 -9.757200000000000595e-02 7.408200000000000340e-01 5.879560000000000342e-01 -5.751060000000000061e-01 4.261289999999999800e-01 3.767949999999999910e-01 +1.403715385662139893e+09 6.974399999999999489e-01 -1.131859999999999949e-01 7.450569999999999693e-01 5.859830000000000316e-01 -5.776559999999999473e-01 4.289240000000000275e-01 3.727750000000000230e-01 +1.403715385712140083e+09 6.991490000000000204e-01 -1.290880000000000083e-01 7.496829999999999883e-01 5.843610000000000193e-01 -5.788870000000000404e-01 4.318830000000000169e-01 3.699850000000000083e-01 +1.403715385762140036e+09 6.994460000000000122e-01 -1.454560000000000020e-01 7.544939999999999980e-01 5.833559999999999857e-01 -5.788769999999999749e-01 4.342480000000000229e-01 3.688159999999999772e-01 +1.403715385812139988e+09 6.980779999999999763e-01 -1.621900000000000008e-01 7.601649999999999796e-01 5.817600000000000549e-01 -5.784160000000000412e-01 4.374939999999999940e-01 3.682239999999999958e-01 +1.403715385862139940e+09 6.949549999999999894e-01 -1.792199999999999904e-01 7.664490000000000469e-01 5.808449999999999447e-01 -5.771290000000000031e-01 4.398429999999999840e-01 3.688899999999999957e-01 +1.403715385912139893e+09 6.901819999999999622e-01 -1.965619999999999867e-01 7.733839999999999604e-01 5.801290000000000058e-01 -5.746820000000000261e-01 4.418679999999999830e-01 3.714089999999999892e-01 +1.403715385962140083e+09 6.839680000000000204e-01 -2.139830000000000065e-01 7.806849999999999623e-01 5.804599999999999760e-01 -5.704470000000000374e-01 4.423989999999999867e-01 3.767480000000000273e-01 +1.403715386012140036e+09 6.765560000000000462e-01 -2.307130000000000014e-01 7.875739999999999963e-01 5.815529999999999866e-01 -5.660990000000000189e-01 4.415589999999999793e-01 3.825620000000000132e-01 +1.403715386062139988e+09 6.682550000000000434e-01 -2.467139999999999889e-01 7.942040000000000211e-01 5.829849999999999755e-01 -5.628210000000000157e-01 4.400410000000000155e-01 3.869440000000000102e-01 +1.403715386112139940e+09 6.592320000000000402e-01 -2.622070000000000234e-01 8.005780000000000118e-01 5.843129999999999713e-01 -5.603770000000000140e-01 4.385490000000000221e-01 3.901680000000000148e-01 +1.403715386162139893e+09 6.495330000000000270e-01 -2.759969999999999923e-01 8.064270000000000049e-01 5.856440000000000534e-01 -5.591490000000000071e-01 4.365290000000000004e-01 3.921939999999999871e-01 +1.403715386212140083e+09 6.396619999999999528e-01 -2.888370000000000104e-01 8.115229999999999944e-01 5.871530000000000360e-01 -5.586360000000000214e-01 4.341059999999999919e-01 3.933570000000000122e-01 +1.403715386262140036e+09 6.300799999999999734e-01 -3.017400000000000082e-01 8.156719999999999526e-01 5.880779999999999896e-01 -5.591920000000000224e-01 4.322489999999999943e-01 3.932289999999999952e-01 +1.403715386312139988e+09 6.199980000000000491e-01 -3.132079999999999864e-01 8.193690000000000140e-01 5.879079999999999862e-01 -5.603059999999999707e-01 4.317170000000000174e-01 3.924830000000000263e-01 +1.403715386362139940e+09 6.095739999999999492e-01 -3.241479999999999917e-01 8.229220000000000423e-01 5.871669999999999945e-01 -5.605010000000000270e-01 4.321550000000000114e-01 3.928300000000000125e-01 +1.403715386412139893e+09 5.989400000000000279e-01 -3.340190000000000103e-01 8.260079999999999645e-01 5.857609999999999761e-01 -5.602819999999999467e-01 4.333839999999999915e-01 3.938869999999999871e-01 +1.403715386462140083e+09 5.881999999999999451e-01 -3.432529999999999748e-01 8.283629999999999605e-01 5.842009999999999703e-01 -5.600850000000000550e-01 4.347500000000000253e-01 3.949759999999999938e-01 +1.403715386512140036e+09 5.772739999999999538e-01 -3.517460000000000031e-01 8.299919999999999520e-01 5.823850000000000415e-01 -5.598680000000000323e-01 4.366990000000000038e-01 3.958149999999999724e-01 +1.403715386562139988e+09 5.661479999999999846e-01 -3.592239999999999878e-01 8.307689999999999797e-01 5.801520000000000010e-01 -5.607240000000000002e-01 4.393650000000000055e-01 3.949309999999999765e-01 +1.403715386612139940e+09 5.546630000000000171e-01 -3.654549999999999743e-01 8.307250000000000467e-01 5.788290000000000379e-01 -5.614209999999999479e-01 4.409370000000000234e-01 3.941299999999999804e-01 +1.403715386662139893e+09 5.425889999999999880e-01 -3.705579999999999985e-01 8.301479999999999970e-01 5.760699999999999710e-01 -5.627729999999999677e-01 4.445230000000000015e-01 3.922100000000000031e-01 +1.403715386712140083e+09 5.297600000000000087e-01 -3.745419999999999860e-01 8.288039999999999852e-01 5.744500000000000162e-01 -5.641659999999999453e-01 4.468269999999999742e-01 3.899610000000000021e-01 +1.403715386762140036e+09 5.161120000000000152e-01 -3.769719999999999738e-01 8.270220000000000349e-01 5.735670000000000490e-01 -5.661960000000000326e-01 4.480799999999999783e-01 3.868690000000000184e-01 +1.403715386812139988e+09 5.010790000000000521e-01 -3.783619999999999761e-01 8.238790000000000280e-01 5.736780000000000213e-01 -5.703529999999999989e-01 4.480859999999999843e-01 3.805399999999999894e-01 +1.403715386862139940e+09 4.841750000000000220e-01 -3.787220000000000031e-01 8.207710000000000283e-01 5.735879999999999868e-01 -5.742159999999999487e-01 4.486740000000000173e-01 3.741180000000000061e-01 +1.403715386912139893e+09 4.656790000000000096e-01 -3.787130000000000218e-01 8.175339999999999829e-01 5.734970000000000345e-01 -5.778879999999999573e-01 4.488469999999999960e-01 3.683509999999999840e-01 +1.403715386962140083e+09 4.452499999999999791e-01 -3.785789999999999988e-01 8.142310000000000381e-01 5.737379999999999702e-01 -5.805609999999999937e-01 4.487079999999999957e-01 3.639149999999999885e-01 +1.403715387012140036e+09 4.226420000000000177e-01 -3.783830000000000249e-01 8.105459999999999887e-01 5.742340000000000222e-01 -5.824589999999999490e-01 4.481160000000000143e-01 3.608169999999999988e-01 +1.403715387062139988e+09 3.977169999999999872e-01 -3.782869999999999844e-01 8.066020000000000412e-01 5.754749999999999588e-01 -5.828579999999999872e-01 4.466069999999999762e-01 3.600659999999999972e-01 +1.403715387112139940e+09 3.707170000000000187e-01 -3.786959999999999771e-01 8.028260000000000396e-01 5.775909999999999656e-01 -5.813540000000000374e-01 4.443659999999999832e-01 3.618770000000000042e-01 +1.403715387162139893e+09 3.419929999999999914e-01 -3.794259999999999855e-01 7.985740000000000061e-01 5.802939999999999765e-01 -5.792990000000000084e-01 4.411359999999999726e-01 3.647869999999999724e-01 +1.403715387212140083e+09 3.118690000000000073e-01 -3.802130000000000232e-01 7.941129999999999578e-01 5.833899999999999642e-01 -5.760859999999999870e-01 4.379709999999999992e-01 3.687309999999999754e-01 +1.403715387262140036e+09 2.804090000000000193e-01 -3.810080000000000133e-01 7.893609999999999793e-01 5.857430000000000136e-01 -5.738050000000000095e-01 4.356550000000000145e-01 3.712909999999999822e-01 +1.403715387312139988e+09 2.477499999999999980e-01 -3.817699999999999982e-01 7.845020000000000326e-01 5.875669999999999504e-01 -5.712679999999999980e-01 4.340959999999999819e-01 3.741380000000000261e-01 +1.403715387362139940e+09 2.148180000000000089e-01 -3.831950000000000078e-01 7.791599999999999637e-01 5.890410000000000368e-01 -5.691950000000000065e-01 4.331459999999999755e-01 3.760740000000000194e-01 +1.403715387412139893e+09 1.813859999999999917e-01 -3.845790000000000042e-01 7.736650000000000471e-01 5.906700000000000284e-01 -5.673319999999999474e-01 4.319250000000000034e-01 3.777369999999999894e-01 +1.403715387462140083e+09 1.477380000000000082e-01 -3.858170000000000210e-01 7.679160000000000430e-01 5.921669999999999989e-01 -5.661599999999999966e-01 4.309160000000000212e-01 3.783030000000000004e-01 +1.403715387512140036e+09 1.133149999999999991e-01 -3.872769999999999824e-01 7.624800000000000466e-01 5.946690000000000031e-01 -5.658119999999999816e-01 4.286519999999999775e-01 3.774680000000000257e-01 +1.403715387562139988e+09 7.854600000000000470e-02 -3.888989999999999947e-01 7.583480000000000221e-01 5.966770000000000129e-01 -5.659950000000000259e-01 4.269129999999999869e-01 3.759939999999999949e-01 +1.403715387612139940e+09 4.324100000000000166e-02 -3.897880000000000233e-01 7.558989999999999876e-01 5.983789999999999942e-01 -5.673519999999999675e-01 4.256059999999999843e-01 3.727119999999999878e-01 +1.403715387662139893e+09 7.856000000000000136e-03 -3.918630000000000169e-01 7.565410000000000190e-01 6.003249999999999975e-01 -5.682930000000000481e-01 4.240050000000000208e-01 3.699640000000000151e-01 +1.403715387712140083e+09 -2.759299999999999947e-02 -3.944130000000000136e-01 7.603630000000000111e-01 6.025829999999999798e-01 -5.682409999999999961e-01 4.225200000000000067e-01 3.680660000000000043e-01 +1.403715387762140036e+09 -6.319099999999999717e-02 -3.980739999999999834e-01 7.675600000000000200e-01 6.045160000000000533e-01 -5.682709999999999706e-01 4.216900000000000093e-01 3.657949999999999813e-01 +1.403715387812139988e+09 -9.922300000000000564e-02 -4.027649999999999841e-01 7.774590000000000112e-01 6.060560000000000391e-01 -5.678279999999999994e-01 4.214559999999999973e-01 3.642009999999999970e-01 +1.403715387862139940e+09 -1.356920000000000071e-01 -4.083970000000000100e-01 7.888969999999999594e-01 6.074410000000000087e-01 -5.677349999999999897e-01 4.213120000000000198e-01 3.622009999999999952e-01 +1.403715387912139893e+09 -1.729670000000000096e-01 -4.146569999999999978e-01 7.996689999999999632e-01 6.084469999999999601e-01 -5.673559999999999715e-01 4.216989999999999905e-01 3.606500000000000261e-01 +1.403715387962140083e+09 -2.098349999999999937e-01 -4.228580000000000116e-01 8.075790000000000468e-01 6.094180000000000152e-01 -5.666790000000000438e-01 4.219990000000000130e-01 3.597250000000000170e-01 +1.403715388012140036e+09 -2.468839999999999923e-01 -4.321490000000000054e-01 8.122989999999999933e-01 6.097439999999999527e-01 -5.660699999999999621e-01 4.229640000000000066e-01 3.589970000000000105e-01 +1.403715388062139988e+09 -2.845349999999999824e-01 -4.421350000000000002e-01 8.139119999999999688e-01 6.106390000000000429e-01 -5.646759999999999557e-01 4.232799999999999896e-01 3.592980000000000063e-01 +1.403715388112139940e+09 -3.221120000000000094e-01 -4.527820000000000178e-01 8.121979999999999755e-01 6.106899999999999551e-01 -5.634240000000000359e-01 4.243489999999999762e-01 3.599149999999999849e-01 +1.403715388162139893e+09 -3.597420000000000062e-01 -4.642970000000000153e-01 8.071220000000000061e-01 6.107169999999999543e-01 -5.619750000000000023e-01 4.256130000000000191e-01 3.606420000000000181e-01 +1.403715388212140083e+09 -3.979610000000000092e-01 -4.757069999999999910e-01 7.992120000000000335e-01 6.103840000000000376e-01 -5.598659999999999748e-01 4.271940000000000182e-01 3.626110000000000166e-01 +1.403715388262140036e+09 -4.356269999999999865e-01 -4.886559999999999793e-01 7.887729999999999464e-01 6.097470000000000390e-01 -5.575609999999999733e-01 4.291499999999999759e-01 3.649169999999999914e-01 +1.403715388312139988e+09 -4.741299999999999959e-01 -5.019019999999999593e-01 7.769369999999999887e-01 6.094960000000000377e-01 -5.553559999999999608e-01 4.305510000000000170e-01 3.670430000000000081e-01 +1.403715388362139940e+09 -5.124100000000000321e-01 -5.162870000000000514e-01 7.645279999999999854e-01 6.093340000000000423e-01 -5.533059999999999645e-01 4.313930000000000264e-01 3.694120000000000181e-01 +1.403715388412139893e+09 -5.507239999999999913e-01 -5.307640000000000136e-01 7.517979999999999663e-01 6.092130000000000045e-01 -5.521779999999999466e-01 4.322460000000000191e-01 3.703000000000000180e-01 +1.403715388462140083e+09 -5.891150000000000553e-01 -5.455160000000000009e-01 7.391560000000000352e-01 6.094150000000000400e-01 -5.506210000000000271e-01 4.322759999999999936e-01 3.722469999999999946e-01 +1.403715388512140036e+09 -6.275030000000000330e-01 -5.600730000000000430e-01 7.257169999999999455e-01 6.095479999999999787e-01 -5.503489999999999771e-01 4.321260000000000101e-01 3.726039999999999908e-01 +1.403715388562139988e+09 -6.650490000000000013e-01 -5.753979999999999650e-01 7.126909999999999634e-01 6.090160000000000018e-01 -5.502050000000000551e-01 4.332010000000000027e-01 3.724399999999999933e-01 +1.403715388612139940e+09 -7.027470000000000105e-01 -5.905390000000000361e-01 6.998680000000000456e-01 6.086049999999999516e-01 -5.501399999999999624e-01 4.337509999999999977e-01 3.725680000000000103e-01 +1.403715388662139893e+09 -7.403760000000000341e-01 -6.051339999999999497e-01 6.870150000000000423e-01 6.083739999999999704e-01 -5.496149999999999647e-01 4.343449999999999811e-01 3.730269999999999975e-01 +1.403715388712140083e+09 -7.778169999999999806e-01 -6.202480000000000215e-01 6.749880000000000324e-01 6.080499999999999794e-01 -5.490030000000000188e-01 4.352329999999999810e-01 3.734210000000000029e-01 +1.403715388762140036e+09 -8.150990000000000180e-01 -6.354499999999999593e-01 6.637030000000000429e-01 6.082579999999999654e-01 -5.484120000000000106e-01 4.351829999999999865e-01 3.740080000000000071e-01 +1.403715388812139988e+09 -8.524680000000000035e-01 -6.506070000000000464e-01 6.530580000000000274e-01 6.082539999999999614e-01 -5.481390000000000429e-01 4.355069999999999775e-01 3.740379999999999816e-01 +1.403715388862139940e+09 -8.894910000000000316e-01 -6.660469999999999446e-01 6.434220000000000494e-01 6.087360000000000548e-01 -5.474379999999999802e-01 4.355870000000000020e-01 3.741880000000000206e-01 +1.403715388912139893e+09 -9.268340000000000467e-01 -6.812799999999999967e-01 6.357840000000000158e-01 6.094249999999999945e-01 -5.458969999999999656e-01 4.351760000000000073e-01 3.757920000000000149e-01 +1.403715388962140083e+09 -9.633030000000000204e-01 -6.968330000000000357e-01 6.303490000000000482e-01 6.096749999999999670e-01 -5.449049999999999727e-01 4.357059999999999822e-01 3.762110000000000176e-01 +1.403715389012140036e+09 -9.998120000000000340e-01 -7.125500000000000167e-01 6.276559999999999917e-01 6.102400000000000047e-01 -5.439089999999999758e-01 4.356979999999999742e-01 3.767460000000000253e-01 +1.403715389062139988e+09 -1.036350000000000104e+00 -7.283500000000000529e-01 6.287989999999999968e-01 6.105239999999999556e-01 -5.427239999999999842e-01 4.363360000000000016e-01 3.772559999999999802e-01 +1.403715389112139940e+09 -1.072630999999999890e+00 -7.440290000000000514e-01 6.324680000000000302e-01 6.113680000000000225e-01 -5.416459999999999608e-01 4.360890000000000044e-01 3.777229999999999754e-01 +1.403715389162139893e+09 -1.108141999999999960e+00 -7.597080000000000499e-01 6.384699999999999820e-01 6.124129999999999852e-01 -5.403900000000000370e-01 4.356430000000000025e-01 3.783440000000000136e-01 +1.403715389212140083e+09 -1.143342000000000080e+00 -7.752160000000000162e-01 6.449129999999999585e-01 6.132239999999999913e-01 -5.390369999999999884e-01 4.354890000000000150e-01 3.791370000000000018e-01 +1.403715389262140036e+09 -1.178104999999999958e+00 -7.903590000000000337e-01 6.512139999999999596e-01 6.146760000000000002e-01 -5.372379999999999933e-01 4.344450000000000256e-01 3.805350000000000121e-01 +1.403715389312139988e+09 -1.212198000000000109e+00 -8.050199999999999578e-01 6.571099999999999719e-01 6.157500000000000195e-01 -5.359580000000000455e-01 4.337940000000000129e-01 3.813449999999999895e-01 +1.403715389362139940e+09 -1.245552999999999910e+00 -8.193930000000000380e-01 6.625889999999999835e-01 6.170010000000000217e-01 -5.345450000000000479e-01 4.332520000000000260e-01 3.819199999999999817e-01 +1.403715389412139893e+09 -1.278262000000000009e+00 -8.337379999999999791e-01 6.677959999999999452e-01 6.180060000000000553e-01 -5.333010000000000250e-01 4.326550000000000118e-01 3.827110000000000234e-01 +1.403715389462140083e+09 -1.310021000000000102e+00 -8.480699999999999905e-01 6.719340000000000312e-01 6.187350000000000350e-01 -5.327769999999999451e-01 4.324330000000000118e-01 3.825129999999999919e-01 +1.403715389512140036e+09 -1.341453000000000007e+00 -8.623490000000000322e-01 6.758750000000000036e-01 6.190379999999999772e-01 -5.326400000000000023e-01 4.328020000000000200e-01 3.817969999999999975e-01 +1.403715389562139988e+09 -1.371923000000000004e+00 -8.767439999999999678e-01 6.795170000000000377e-01 6.185599999999999987e-01 -5.331200000000000383e-01 4.339899999999999869e-01 3.805509999999999726e-01 +1.403715389612139940e+09 -1.401532000000000000e+00 -8.910200000000000342e-01 6.829619999999999580e-01 6.177810000000000246e-01 -5.335659999999999847e-01 4.364600000000000146e-01 3.783610000000000029e-01 +1.403715389662139893e+09 -1.430517000000000039e+00 -9.049270000000000369e-01 6.858229999999999604e-01 6.181100000000000483e-01 -5.331150000000000055e-01 4.389540000000000108e-01 3.755640000000000089e-01 +1.403715389712140083e+09 -1.458947999999999912e+00 -9.192869999999999653e-01 6.884989999999999721e-01 6.193370000000000264e-01 -5.317129999999999912e-01 4.416490000000000138e-01 3.723560000000000203e-01 +1.403715389762140036e+09 -1.486561999999999939e+00 -9.336119999999999974e-01 6.904510000000000369e-01 6.214460000000000539e-01 -5.294750000000000290e-01 4.444469999999999810e-01 3.686860000000000137e-01 +1.403715389812139988e+09 -1.513595999999999941e+00 -9.481230000000000491e-01 6.919880000000000475e-01 6.244220000000000326e-01 -5.258800000000000141e-01 4.476550000000000251e-01 3.649009999999999754e-01 +1.403715389862139940e+09 -1.540410999999999975e+00 -9.621250000000000080e-01 6.927929999999999922e-01 6.287390000000000478e-01 -5.222020000000000550e-01 4.498659999999999881e-01 3.600180000000000047e-01 +1.403715389912139893e+09 -1.568227000000000038e+00 -9.753079999999999528e-01 6.937100000000000488e-01 6.343189999999999662e-01 -5.179240000000000510e-01 4.511510000000000242e-01 3.547629999999999950e-01 +1.403715389962140083e+09 -1.594721999999999973e+00 -9.896390000000000464e-01 6.931739999999999569e-01 6.403919999999999613e-01 -5.134379999999999500e-01 4.520060000000000189e-01 3.492439999999999989e-01 +1.403715390012140036e+09 -1.621102000000000043e+00 -1.004262999999999906e+00 6.920079999999999565e-01 6.475109999999999477e-01 -5.085389999999999633e-01 4.517570000000000197e-01 3.435610000000000053e-01 +1.403715390062139988e+09 -1.647227999999999914e+00 -1.019296999999999898e+00 6.900150000000000450e-01 6.546830000000000149e-01 -5.032029999999999559e-01 4.516870000000000052e-01 3.378700000000000037e-01 +1.403715390112139940e+09 -1.672806999999999933e+00 -1.035317999999999961e+00 6.878379999999999495e-01 6.617579999999999574e-01 -4.971740000000000048e-01 4.520440000000000014e-01 3.324909999999999810e-01 +1.403715390162139893e+09 -1.697748999999999953e+00 -1.052375000000000060e+00 6.852930000000000410e-01 6.690519999999999801e-01 -4.902279999999999971e-01 4.522419999999999773e-01 3.279070000000000040e-01 +1.403715390212140083e+09 -1.721797999999999940e+00 -1.070510999999999990e+00 6.821190000000000309e-01 6.760490000000000110e-01 -4.828069999999999862e-01 4.530310000000000170e-01 3.234480000000000133e-01 +1.403715390262140036e+09 -1.745177999999999896e+00 -1.089698000000000055e+00 6.774419999999999886e-01 6.832420000000000160e-01 -4.754479999999999817e-01 4.533619999999999872e-01 3.187360000000000193e-01 +1.403715390312139988e+09 -1.767555999999999905e+00 -1.109971999999999959e+00 6.740730000000000333e-01 6.890079999999999538e-01 -4.668780000000000152e-01 4.559270000000000267e-01 3.153150000000000119e-01 +1.403715390362139940e+09 -1.788354999999999917e+00 -1.131324999999999914e+00 6.700129999999999697e-01 6.945949999999999624e-01 -4.584269999999999734e-01 4.587350000000000039e-01 3.113589999999999969e-01 +1.403715390412139893e+09 -1.808211000000000013e+00 -1.153478999999999921e+00 6.663019999999999499e-01 7.003099999999999881e-01 -4.490950000000000220e-01 4.611689999999999956e-01 3.085510000000000197e-01 +1.403715390462140083e+09 -1.826569000000000109e+00 -1.176881000000000066e+00 6.627330000000000165e-01 7.062230000000000452e-01 -4.388400000000000079e-01 4.633129999999999749e-01 3.066110000000000224e-01 +1.403715390512140036e+09 -1.844027000000000083e+00 -1.200634999999999897e+00 6.591569999999999929e-01 7.117710000000000425e-01 -4.290300000000000225e-01 4.657510000000000261e-01 3.039600000000000080e-01 +1.403715390562139988e+09 -1.859359999999999902e+00 -1.224876000000000076e+00 6.559249999999999803e-01 7.169710000000000250e-01 -4.186590000000000034e-01 4.685139999999999860e-01 3.019479999999999942e-01 +1.403715390612139940e+09 -1.873448000000000002e+00 -1.249079999999999968e+00 6.529009999999999536e-01 7.215610000000000079e-01 -4.082200000000000273e-01 4.719289999999999874e-01 2.999839999999999729e-01 +1.403715390662139893e+09 -1.885661000000000032e+00 -1.273487999999999953e+00 6.494590000000000085e-01 7.257169999999999455e-01 -3.993260000000000143e-01 4.755800000000000027e-01 2.961360000000000103e-01 +1.403715390712140083e+09 -1.896330999999999989e+00 -1.297520000000000007e+00 6.458709999999999729e-01 7.291239999999999943e-01 -3.923929999999999918e-01 4.800200000000000022e-01 2.898040000000000060e-01 +1.403715390762140036e+09 -1.905402999999999958e+00 -1.321344999999999992e+00 6.423119999999999941e-01 7.316540000000000266e-01 -3.880330000000000168e-01 4.853069999999999884e-01 2.803399999999999781e-01 +1.403715390812139988e+09 -1.912541000000000047e+00 -1.346619000000000010e+00 6.378260000000000041e-01 7.347820000000000462e-01 -3.834719999999999795e-01 4.887520000000000198e-01 2.723340000000000205e-01 +1.403715390862139940e+09 -1.918520999999999921e+00 -1.371723999999999943e+00 6.340379999999999905e-01 7.371440000000000214e-01 -3.803730000000000167e-01 4.916079999999999894e-01 2.650609999999999911e-01 +1.403715390912139893e+09 -1.924193999999999960e+00 -1.397157999999999900e+00 6.306869999999999976e-01 7.395979999999999777e-01 -3.772610000000000130e-01 4.929509999999999725e-01 2.601330000000000031e-01 +1.403715390962140083e+09 -1.928088999999999942e+00 -1.423100000000000032e+00 6.270489999999999675e-01 7.414349999999999552e-01 -3.754529999999999812e-01 4.941380000000000217e-01 2.552200000000000024e-01 +1.403715391012140036e+09 -1.930962000000000067e+00 -1.449646999999999908e+00 6.232509999999999994e-01 7.432339999999999502e-01 -3.739739999999999731e-01 4.949060000000000126e-01 2.506300000000000194e-01 +1.403715391062139988e+09 -1.932725999999999944e+00 -1.476809999999999956e+00 6.192020000000000302e-01 7.449130000000000473e-01 -3.720720000000000138e-01 4.963500000000000134e-01 2.455680000000000085e-01 +1.403715391112139940e+09 -1.934007000000000032e+00 -1.504564000000000012e+00 6.147909999999999764e-01 7.466949999999999976e-01 -3.698589999999999933e-01 4.980539999999999967e-01 2.399850000000000039e-01 +1.403715391162139893e+09 -1.933532999999999946e+00 -1.533349999999999991e+00 6.114429999999999588e-01 7.476530000000000120e-01 -3.674120000000000164e-01 5.013849999999999696e-01 2.337450000000000083e-01 +1.403715391212140083e+09 -1.932283999999999891e+00 -1.563339000000000034e+00 6.084140000000000104e-01 7.488230000000000164e-01 -3.642830000000000235e-01 5.044060000000000210e-01 2.283350000000000102e-01 +1.403715391262140036e+09 -1.930606000000000044e+00 -1.594573999999999936e+00 6.059360000000000301e-01 7.486620000000000497e-01 -3.615479999999999805e-01 5.085950000000000193e-01 2.238729999999999887e-01 +1.403715391312139988e+09 -1.928879999999999928e+00 -1.626978999999999953e+00 6.038959999999999884e-01 7.484030000000000404e-01 -3.591520000000000268e-01 5.120470000000000299e-01 2.207030000000000103e-01 +1.403715391362139940e+09 -1.927270000000000039e+00 -1.660716999999999999e+00 6.018350000000000088e-01 7.485330000000000039e-01 -3.565650000000000208e-01 5.143510000000000026e-01 2.190950000000000120e-01 +1.403715391412139893e+09 -1.926268000000000091e+00 -1.695588000000000095e+00 5.997780000000000333e-01 7.489510000000000334e-01 -3.542509999999999826e-01 5.156960000000000433e-01 2.182580000000000076e-01 +1.403715391462140083e+09 -1.924755999999999911e+00 -1.731349000000000027e+00 5.971769999999999579e-01 7.494979999999999976e-01 -3.533180000000000209e-01 5.160519999999999552e-01 2.170479999999999909e-01 +1.403715391512140036e+09 -1.923351999999999951e+00 -1.768934999999999924e+00 5.947900000000000409e-01 7.500909999999999522e-01 -3.523830000000000018e-01 5.159930000000000350e-01 2.166599999999999915e-01 +1.403715391562139988e+09 -1.921532000000000018e+00 -1.806993999999999989e+00 5.921480000000000077e-01 7.499909999999999632e-01 -3.519109999999999738e-01 5.169869999999999743e-01 2.154000000000000081e-01 +1.403715391612139940e+09 -1.919502999999999959e+00 -1.845792000000000099e+00 5.896369999999999667e-01 7.499000000000000110e-01 -3.520800000000000041e-01 5.185480000000000089e-01 2.116550000000000098e-01 +1.403715391662139893e+09 -1.917586999999999930e+00 -1.885850999999999944e+00 5.880049999999999999e-01 7.498310000000000253e-01 -3.510190000000000254e-01 5.206359999999999877e-01 2.085120000000000029e-01 +1.403715391712140083e+09 -1.915594000000000019e+00 -1.927424999999999944e+00 5.888069999999999693e-01 7.503370000000000317e-01 -3.480509999999999993e-01 5.226830000000000087e-01 2.065400000000000014e-01 +1.403715391762140036e+09 -1.913639000000000090e+00 -1.969892999999999894e+00 5.924580000000000402e-01 7.511989999999999501e-01 -3.439139999999999975e-01 5.249730000000000230e-01 2.045160000000000033e-01 +1.403715391812139988e+09 -1.911753000000000036e+00 -2.013685000000000169e+00 5.989999999999999769e-01 7.531179999999999541e-01 -3.375819999999999932e-01 5.264450000000000518e-01 2.042259999999999909e-01 +1.403715391862139940e+09 -1.909330999999999889e+00 -2.058570000000000011e+00 6.083800000000000319e-01 7.561949999999999505e-01 -3.297479999999999856e-01 5.267889999999999517e-01 2.047660000000000036e-01 +1.403715391912139893e+09 -1.907615999999999978e+00 -2.103838999999999793e+00 6.201379999999999670e-01 7.591959999999999820e-01 -3.225990000000000246e-01 5.270139999999999825e-01 2.044680000000000109e-01 +1.403715391962140083e+09 -1.905459000000000014e+00 -2.149722999999999828e+00 6.335530000000000328e-01 7.625309999999999588e-01 -3.165589999999999793e-01 5.260930000000000328e-01 2.038699999999999957e-01 +1.403715392012140036e+09 -1.903067999999999982e+00 -2.196053000000000033e+00 6.467920000000000336e-01 7.665929999999999689e-01 -3.126519999999999855e-01 5.232419999999999849e-01 2.019940000000000069e-01 +1.403715392062139988e+09 -1.900341000000000058e+00 -2.243021999999999849e+00 6.600599999999999801e-01 7.695180000000000353e-01 -3.090490000000000181e-01 5.217319999999999736e-01 2.003149999999999931e-01 +1.403715392112139940e+09 -1.897331000000000101e+00 -2.290386999999999951e+00 6.727800000000000447e-01 7.717249999999999943e-01 -3.070370000000000044e-01 5.204530000000000545e-01 1.982349999999999945e-01 +1.403715392162139893e+09 -1.892811999999999939e+00 -2.338341999999999921e+00 6.856830000000000425e-01 7.734100000000000419e-01 -3.049049999999999816e-01 5.197869999999999990e-01 1.967009999999999870e-01 +1.403715392212140083e+09 -1.887591000000000019e+00 -2.386890999999999874e+00 6.985299999999999843e-01 7.742700000000000138e-01 -3.022150000000000114e-01 5.208279999999999577e-01 1.947049999999999892e-01 +1.403715392262140036e+09 -1.881229999999999958e+00 -2.435477999999999810e+00 7.117210000000000480e-01 7.748300000000000187e-01 -2.978520000000000056e-01 5.231459999999999999e-01 1.929800000000000126e-01 +1.403715392312139988e+09 -1.873747000000000051e+00 -2.484271000000000118e+00 7.243519999999999959e-01 7.752480000000000482e-01 -2.927060000000000217e-01 5.264520000000000310e-01 1.901629999999999987e-01 +1.403715392362139940e+09 -1.864883000000000068e+00 -2.533815999999999846e+00 7.374549999999999716e-01 7.749200000000000532e-01 -2.849960000000000271e-01 5.317969999999999642e-01 1.883289999999999964e-01 +1.403715392412139893e+09 -1.856403999999999943e+00 -2.583445999999999909e+00 7.511889999999999956e-01 7.725079999999999725e-01 -2.765500000000000180e-01 5.405680000000000485e-01 1.858460000000000112e-01 +1.403715392462140083e+09 -1.847013999999999934e+00 -2.632683000000000106e+00 7.646079999999999544e-01 7.691989999999999661e-01 -2.668380000000000196e-01 5.507459999999999578e-01 1.838710000000000067e-01 +1.403715392512140036e+09 -1.838120999999999894e+00 -2.681280999999999803e+00 7.775290000000000257e-01 7.676330000000000098e-01 -2.562530000000000086e-01 5.585620000000000029e-01 1.818879999999999941e-01 +1.403715392562139988e+09 -1.829700000000000104e+00 -2.728702000000000183e+00 7.886239999999999917e-01 7.684170000000000167e-01 -2.464109999999999912e-01 5.630830000000000002e-01 1.781989999999999963e-01 +1.403715392662139893e+09 -1.813034000000000034e+00 -2.821194000000000202e+00 8.078269999999999618e-01 7.736450000000000271e-01 -2.272849999999999870e-01 5.670060000000000100e-01 1.682809999999999861e-01 +1.403715392712140083e+09 -1.805590999999999946e+00 -2.866417000000000215e+00 8.166579999999999950e-01 7.754689999999999639e-01 -2.176039999999999919e-01 5.699549999999999894e-01 1.626239999999999908e-01 +1.403715392762140036e+09 -1.798847000000000085e+00 -2.910344999999999960e+00 8.242660000000000542e-01 7.781630000000000491e-01 -2.080589999999999939e-01 5.715219999999999745e-01 1.566420000000000035e-01 +1.403715392812139988e+09 -1.792315000000000103e+00 -2.953342999999999829e+00 8.303789999999999782e-01 7.830909999999999815e-01 -1.984579999999999955e-01 5.699480000000000102e-01 1.501409999999999967e-01 +1.403715392862139940e+09 -1.786316000000000015e+00 -2.995032999999999834e+00 8.361769999999999481e-01 7.890660000000000451e-01 -1.893789999999999918e-01 5.667140000000000510e-01 1.426360000000000128e-01 +1.403715392912139893e+09 -1.780567000000000011e+00 -3.036512000000000100e+00 8.412420000000000453e-01 7.944489999999999608e-01 -1.795769999999999866e-01 5.641599999999999948e-01 1.353729999999999933e-01 +1.403715392962140083e+09 -1.775539999999999896e+00 -3.076691999999999982e+00 8.462889999999999580e-01 7.998589999999999867e-01 -1.689209999999999878e-01 5.613890000000000269e-01 1.285850000000000048e-01 +1.403715393012140036e+09 -1.769373000000000085e+00 -3.115498999999999796e+00 8.515080000000000426e-01 8.041190000000000282e-01 -1.580090000000000106e-01 5.600079999999999503e-01 1.217270000000000019e-01 +1.403715393062139988e+09 -1.763190999999999953e+00 -3.153013000000000066e+00 8.561520000000000241e-01 8.075069999999999748e-01 -1.478210000000000079e-01 5.596550000000000136e-01 1.134379999999999972e-01 +1.403715393112139940e+09 -1.756372999999999962e+00 -3.189557999999999893e+00 8.601220000000000532e-01 8.103759999999999852e-01 -1.357399999999999995e-01 5.598530000000000451e-01 1.069110000000000060e-01 +1.403715393162139893e+09 -1.749322999999999961e+00 -3.225105000000000111e+00 8.631900000000000128e-01 8.123879999999999990e-01 -1.221249999999999974e-01 5.610070000000000334e-01 1.018970000000000015e-01 +1.403715393212140083e+09 -1.741508000000000056e+00 -3.259001000000000037e+00 8.655169999999999808e-01 8.139100000000000223e-01 -1.077300000000000063e-01 5.626179999999999515e-01 9.698700000000000376e-02 +1.403715393262140036e+09 -1.733672000000000102e+00 -3.291506000000000043e+00 8.675439999999999818e-01 8.143120000000000358e-01 -9.386200000000000099e-02 5.655459999999999932e-01 9.079399999999999971e-02 +1.403715393312139988e+09 -1.725398999999999905e+00 -3.322146000000000043e+00 8.697810000000000263e-01 8.143169999999999575e-01 -7.970399999999999707e-02 5.687069999999999625e-01 8.429999999999999993e-02 +1.403715393362139940e+09 -1.716776999999999997e+00 -3.350963999999999832e+00 8.716580000000000439e-01 8.144519999999999538e-01 -6.575000000000000289e-02 5.712970000000000548e-01 7.723700000000000010e-02 +1.403715393412139893e+09 -1.708018000000000036e+00 -3.378112999999999921e+00 8.732349999999999834e-01 8.146970000000000045e-01 -5.124000000000000082e-02 5.732650000000000245e-01 7.079199999999999382e-02 +1.403715393462140083e+09 -1.699202000000000101e+00 -3.403156000000000070e+00 8.742929999999999868e-01 8.148579999999999712e-01 -3.658499999999999946e-02 5.749030000000000529e-01 6.444800000000000528e-02 +1.403715393512140036e+09 -1.690777999999999892e+00 -3.426690999999999931e+00 8.742159999999999931e-01 8.142380000000000173e-01 -2.233699999999999922e-02 5.772540000000000449e-01 5.739799999999999763e-02 +1.403715393562139988e+09 -1.683032000000000084e+00 -3.447665000000000202e+00 8.742959999999999621e-01 8.135139999999999594e-01 -7.697999999999999982e-03 5.792800000000000171e-01 5.068899999999999795e-02 +1.403715393612139940e+09 -1.675531000000000104e+00 -3.466277999999999970e+00 8.741259999999999586e-01 8.129039999999999599e-01 5.955000000000000224e-03 5.808410000000000517e-01 4.214999999999999997e-02 +1.403715393662139893e+09 -1.668633000000000033e+00 -3.482310000000000016e+00 8.735880000000000312e-01 8.126240000000000130e-01 1.744000000000000064e-02 5.817240000000000189e-01 3.057500000000000148e-02 +1.403715393712140083e+09 -1.661704000000000070e+00 -3.496328999999999798e+00 8.724290000000000100e-01 8.134059999999999624e-01 2.792100000000000137e-02 5.807620000000000005e-01 1.748699999999999907e-02 +1.403715393762140036e+09 -1.655370999999999926e+00 -3.508243999999999918e+00 8.708470000000000377e-01 8.144940000000000513e-01 3.774099999999999677e-02 5.789320000000000022e-01 3.749999999999999861e-03 +1.403715393812139988e+09 -1.650166000000000022e+00 -3.519141999999999992e+00 8.695140000000000091e-01 -8.158579999999999721e-01 -4.804599999999999843e-02 -5.761800000000000255e-01 9.155999999999999209e-03 +1.403715393862139940e+09 -1.644133999999999984e+00 -3.528221999999999969e+00 8.679029999999999800e-01 -8.168429999999999858e-01 -5.794599999999999751e-02 -5.735170000000000545e-01 2.211099999999999871e-02 +1.403715393912139893e+09 -1.638716000000000061e+00 -3.536881000000000164e+00 8.668400000000000549e-01 -8.169380000000000530e-01 -6.975199999999999456e-02 -5.715930000000000177e-01 3.207900000000000335e-02 +1.403715393962140083e+09 -1.633497999999999895e+00 -3.544264000000000081e+00 8.651229999999999754e-01 -8.170169999999999932e-01 -8.032999999999999863e-02 -5.693390000000000395e-01 4.340299999999999714e-02 +1.403715394012140036e+09 -1.628975000000000062e+00 -3.551149000000000111e+00 8.634789999999999965e-01 -8.160180000000000211e-01 -9.111900000000000555e-02 -5.681929999999999481e-01 5.448399999999999771e-02 +1.403715394062139988e+09 -1.624117999999999951e+00 -3.557123999999999953e+00 8.618540000000000090e-01 -8.146499999999999853e-01 -1.026090000000000058e-01 -5.671169999999999822e-01 6.476800000000000612e-02 +1.403715394112139940e+09 -1.619370999999999894e+00 -3.562597999999999931e+00 8.599229999999999929e-01 -8.132479999999999709e-01 -1.147159999999999985e-01 -5.655909999999999549e-01 7.465800000000000214e-02 +1.403715394162139893e+09 -1.615243999999999902e+00 -3.567187000000000108e+00 8.589759999999999618e-01 -8.109300000000000397e-01 -1.282119999999999926e-01 -5.648499999999999632e-01 8.305999999999999495e-02 +1.403715394212140083e+09 -1.610875999999999975e+00 -3.570978000000000208e+00 8.572739999999999805e-01 -8.087530000000000552e-01 -1.415530000000000121e-01 -5.633519999999999639e-01 9.228300000000000392e-02 +1.403715394262140036e+09 -1.606956999999999969e+00 -3.574206000000000216e+00 8.556009999999999449e-01 -8.062449999999999894e-01 -1.551889999999999936e-01 -5.617870000000000363e-01 1.013990000000000030e-01 +1.403715394312139988e+09 -1.602780000000000094e+00 -3.576503999999999905e+00 8.540769999999999751e-01 -8.028140000000000276e-01 -1.682250000000000134e-01 -5.610450000000000159e-01 1.114379999999999954e-01 +1.403715394362139940e+09 -1.598799999999999999e+00 -3.578108999999999984e+00 8.528909999999999547e-01 -7.982359999999999456e-01 -1.826909999999999923e-01 -5.613550000000000484e-01 1.196809999999999957e-01 +1.403715394412139893e+09 -1.594899000000000067e+00 -3.579137999999999931e+00 8.522290000000000143e-01 -7.934039999999999981e-01 -1.970079999999999887e-01 -5.614599999999999591e-01 1.282979999999999954e-01 +1.403715394462140083e+09 -1.591388999999999943e+00 -3.579588000000000214e+00 8.522530000000000383e-01 -7.875119999999999898e-01 -2.114669999999999883e-01 -5.626060000000000505e-01 1.363119999999999887e-01 +1.403715394512140036e+09 -1.589164000000000021e+00 -3.580067000000000110e+00 8.523979999999999890e-01 -7.819049999999999612e-01 -2.258570000000000022e-01 -5.628739999999999855e-01 1.441749999999999976e-01 +1.403715394562139988e+09 -1.588564000000000087e+00 -3.579544999999999977e+00 8.516470000000000429e-01 -7.768359999999999710e-01 -2.397940000000000071e-01 -5.618210000000000148e-01 1.529099999999999904e-01 +1.403715394612139940e+09 -1.588772999999999991e+00 -3.578586000000000045e+00 8.509430000000000049e-01 -7.722320000000000295e-01 -2.529000000000000137e-01 -5.595970000000000111e-01 1.629400000000000015e-01 +1.403715394662139893e+09 -1.590519999999999934e+00 -3.577166000000000068e+00 8.500839999999999508e-01 -7.681350000000000122e-01 -2.655719999999999748e-01 -5.560380000000000322e-01 1.739630000000000065e-01 +1.403715394712140083e+09 -1.593501000000000056e+00 -3.575145000000000017e+00 8.490720000000000489e-01 -7.644149999999999556e-01 -2.785460000000000158e-01 -5.514000000000000012e-01 1.844989999999999963e-01 +1.403715394762140036e+09 -1.597582999999999975e+00 -3.573341000000000101e+00 8.473199999999999621e-01 -7.612780000000000102e-01 -2.918780000000000263e-01 -5.452550000000000452e-01 1.948320000000000052e-01 +1.403715394812139988e+09 -1.602527000000000035e+00 -3.570880999999999972e+00 8.462030000000000385e-01 -7.578690000000000149e-01 -3.055260000000000198e-01 -5.388420000000000432e-01 2.047849999999999948e-01 +1.403715394862139940e+09 -1.608440000000000092e+00 -3.568092000000000041e+00 8.450609999999999511e-01 -7.536709999999999798e-01 -3.196180000000000132e-01 -5.325590000000000046e-01 2.149540000000000062e-01 +1.403715394912139893e+09 -1.614716000000000040e+00 -3.565281000000000144e+00 8.442859999999999809e-01 -7.489270000000000094e-01 -3.345639999999999725e-01 -5.259880000000000111e-01 2.247490000000000043e-01 +1.403715394962140083e+09 -1.621002999999999972e+00 -3.561732000000000120e+00 8.439670000000000227e-01 -7.431999999999999718e-01 -3.496279999999999943e-01 -5.197770000000000445e-01 2.350440000000000029e-01 +1.403715395012140036e+09 -1.627834000000000003e+00 -3.557615999999999890e+00 8.433420000000000361e-01 -7.368230000000000057e-01 -3.653750000000000053e-01 -5.136570000000000302e-01 2.444359999999999866e-01 +1.403715395062139988e+09 -1.635040000000000049e+00 -3.552900000000000169e+00 8.426850000000000174e-01 -7.297339999999999938e-01 -3.808190000000000186e-01 -5.076479999999999881e-01 2.544779999999999820e-01 +1.403715395112139940e+09 -1.642444999999999933e+00 -3.547334999999999905e+00 8.418240000000000167e-01 -7.222420000000000506e-01 -3.956390000000000184e-01 -5.018709999999999560e-01 2.645020000000000149e-01 +1.403715395162139893e+09 -1.650363999999999942e+00 -3.541320999999999941e+00 8.404989999999999961e-01 -7.148240000000000149e-01 -4.100070000000000103e-01 -4.960740000000000149e-01 2.735540000000000194e-01 +1.403715395212140083e+09 -1.658052999999999999e+00 -3.534521999999999942e+00 8.389579999999999815e-01 -7.084359999999999546e-01 -4.227759999999999851e-01 -4.890639999999999987e-01 2.831879999999999953e-01 +1.403715395262140036e+09 -1.666423999999999905e+00 -3.527785000000000171e+00 8.376209999999999489e-01 -7.012310000000000487e-01 -4.353339999999999987e-01 -4.835349999999999926e-01 2.914680000000000049e-01 +1.403715395312139988e+09 -1.674852000000000007e+00 -3.519855999999999874e+00 8.352760000000000185e-01 -6.938499999999999668e-01 -4.473249999999999726e-01 -4.786170000000000146e-01 2.989950000000000108e-01 +1.403715395362139940e+09 -1.683740000000000014e+00 -3.512345999999999968e+00 8.324960000000000138e-01 -6.869319999999999871e-01 -4.584790000000000254e-01 -4.736620000000000275e-01 3.058839999999999892e-01 +1.403715395412139893e+09 -1.692798000000000025e+00 -3.504494000000000220e+00 8.289990000000000414e-01 -6.804710000000000480e-01 -4.687890000000000112e-01 -4.684209999999999763e-01 3.126950000000000007e-01 +1.403715395462140083e+09 -1.703618999999999994e+00 -3.497675000000000090e+00 8.248189999999999689e-01 -6.746609999999999552e-01 -4.783709999999999907e-01 -4.626140000000000252e-01 3.193469999999999920e-01 +1.403715395512140036e+09 -1.713591000000000086e+00 -3.489433000000000007e+00 8.196999999999999842e-01 -6.688089999999999868e-01 -4.872909999999999742e-01 -4.572539999999999938e-01 3.258220000000000005e-01 +1.403715395562139988e+09 -1.723012999999999906e+00 -3.479751999999999956e+00 8.141140000000000043e-01 -6.631420000000000092e-01 -4.954779999999999740e-01 -4.519859999999999989e-01 3.323439999999999728e-01 +1.403715395612139940e+09 -1.732882999999999951e+00 -3.469987000000000155e+00 8.078020000000000200e-01 -6.579319999999999613e-01 -5.023940000000000072e-01 -4.470100000000000184e-01 3.389789999999999748e-01 +1.403715395662139893e+09 -1.742648999999999893e+00 -3.459299999999999820e+00 8.009450000000000180e-01 -6.522809999999999997e-01 -5.094870000000000232e-01 -4.430230000000000001e-01 3.445039999999999769e-01 +1.403715395712140083e+09 -1.752483999999999931e+00 -3.448106999999999811e+00 7.932350000000000234e-01 -6.468209999999999793e-01 -5.173790000000000333e-01 -4.390220000000000233e-01 3.481389999999999763e-01 +1.403715395762140036e+09 -1.762207000000000079e+00 -3.436233000000000093e+00 7.851000000000000201e-01 -6.406969999999999610e-01 -5.244140000000000468e-01 -4.361119999999999997e-01 3.525670000000000193e-01 +1.403715395812139988e+09 -1.772059000000000051e+00 -3.423902000000000001e+00 7.766429999999999723e-01 -6.347960000000000269e-01 -5.313550000000000217e-01 -4.339459999999999984e-01 3.555099999999999927e-01 +1.403715395862139940e+09 -1.782229999999999981e+00 -3.411083999999999783e+00 7.679489999999999927e-01 -6.310339999999999838e-01 -5.357600000000000140e-01 -4.302000000000000268e-01 3.601190000000000224e-01 +1.403715395912139893e+09 -1.793651000000000106e+00 -3.400053999999999910e+00 7.593750000000000222e-01 -6.284410000000000274e-01 -5.387049999999999894e-01 -4.264990000000000170e-01 3.646329999999999849e-01 +1.403715395962140083e+09 -1.803867000000000109e+00 -3.386696000000000151e+00 7.508270000000000222e-01 -6.274509999999999810e-01 -5.397750000000000048e-01 -4.222969999999999779e-01 3.696119999999999961e-01 +1.403715396012140036e+09 -1.814135999999999971e+00 -3.372958000000000123e+00 7.425049999999999706e-01 -6.272389999999999910e-01 -5.396300000000000541e-01 -4.180650000000000199e-01 3.749560000000000115e-01 +1.403715396062139988e+09 -1.824194000000000093e+00 -3.359071999999999836e+00 7.348569999999999824e-01 -6.280069999999999819e-01 -5.375210000000000266e-01 -4.139860000000000206e-01 3.811749999999999861e-01 +1.403715396112139940e+09 -1.833156000000000008e+00 -3.345028000000000112e+00 7.276110000000000078e-01 -6.289390000000000258e-01 -5.353029999999999733e-01 -4.108979999999999855e-01 3.860700000000000243e-01 +1.403715396162139893e+09 -1.840616999999999948e+00 -3.330754999999999910e+00 7.212460000000000537e-01 -6.294210000000000083e-01 -5.327849999999999531e-01 -4.095610000000000084e-01 3.901660000000000128e-01 +1.403715396212140083e+09 -1.846610000000000085e+00 -3.316218999999999806e+00 7.152610000000000356e-01 -6.295089999999999852e-01 -5.311460000000000070e-01 -4.096929999999999739e-01 3.921149999999999913e-01 +1.403715396262140036e+09 -1.851177000000000072e+00 -3.301543000000000117e+00 7.099170000000000202e-01 -6.284969999999999724e-01 -5.309249999999999803e-01 -4.122830000000000106e-01 3.913220000000000032e-01 +1.403715396312139988e+09 -1.854476000000000013e+00 -3.286582999999999810e+00 7.047590000000000243e-01 -6.267850000000000366e-01 -5.324600000000000444e-01 -4.162489999999999801e-01 3.877680000000000016e-01 +1.403715396362139940e+09 -1.856857999999999898e+00 -3.271484000000000059e+00 6.999469999999999859e-01 -6.241290000000000449e-01 -5.343909999999999494e-01 -4.215720000000000023e-01 3.836220000000000185e-01 +1.403715396412139893e+09 -1.858865999999999907e+00 -3.256644999999999790e+00 6.950629999999999864e-01 -6.222809999999999730e-01 -5.357210000000000027e-01 -4.253040000000000154e-01 3.806379999999999764e-01 +1.403715396462140083e+09 -1.860568999999999917e+00 -3.241912000000000127e+00 6.898079999999999767e-01 -6.205199999999999605e-01 -5.379610000000000225e-01 -4.285889999999999977e-01 3.766479999999999828e-01 +1.403715396512140036e+09 -1.863501000000000074e+00 -3.228260000000000129e+00 6.859499999999999487e-01 -6.178010000000000446e-01 -5.404499999999999860e-01 -4.311909999999999910e-01 3.745809999999999973e-01 +1.403715396562139988e+09 -1.865691999999999906e+00 -3.213649999999999896e+00 6.810549999999999660e-01 -6.151389999999999914e-01 -5.424419999999999797e-01 -4.325990000000000113e-01 3.744580000000000131e-01 +1.403715396612139940e+09 -1.868584000000000023e+00 -3.200638000000000094e+00 6.770159999999999512e-01 -6.121250000000000302e-01 -5.454299999999999704e-01 -4.329749999999999988e-01 3.746240000000000125e-01 +1.403715396662139893e+09 -1.871930000000000094e+00 -3.186205999999999872e+00 6.717419999999999503e-01 -6.082509999999999861e-01 -5.483749999999999458e-01 -4.327989999999999893e-01 3.768290000000000251e-01 +1.403715396712140083e+09 -1.875845999999999902e+00 -3.172360999999999986e+00 6.656279999999999974e-01 -6.049470000000000125e-01 -5.513080000000000203e-01 -4.313949999999999729e-01 3.794690000000000007e-01 +1.403715396762140036e+09 -1.880398000000000014e+00 -3.158668000000000031e+00 6.587159999999999682e-01 -6.032250000000000112e-01 -5.540819999999999634e-01 -4.279749999999999943e-01 3.820339999999999847e-01 +1.403715396812139988e+09 -1.885351999999999917e+00 -3.145182999999999840e+00 6.516480000000000050e-01 -6.020699999999999941e-01 -5.565360000000000307e-01 -4.238089999999999913e-01 3.849230000000000151e-01 +1.403715396862139940e+09 -1.890481999999999996e+00 -3.131733999999999796e+00 6.443060000000000453e-01 -6.012819999999999832e-01 -5.596470000000000056e-01 -4.194930000000000048e-01 3.863679999999999892e-01 +1.403715396912139893e+09 -1.895726999999999940e+00 -3.118411000000000044e+00 6.366260000000000252e-01 -6.007400000000000517e-01 -5.625559999999999450e-01 -4.154709999999999792e-01 3.873329999999999829e-01 +1.403715396962140083e+09 -1.900883000000000100e+00 -3.104915999999999787e+00 6.279630000000000489e-01 -6.010910000000000419e-01 -5.668619999999999770e-01 -4.106489999999999863e-01 3.856470000000000176e-01 +1.403715397012140036e+09 -1.905783999999999923e+00 -3.091025999999999829e+00 6.187150000000000150e-01 -6.024040000000000505e-01 -5.702129999999999699e-01 -4.052020000000000066e-01 3.844190000000000107e-01 +1.403715397112139940e+09 -1.915783999999999931e+00 -3.061297000000000157e+00 5.996550000000000491e-01 -6.040529999999999511e-01 -5.760359999999999925e-01 -3.966640000000000166e-01 3.820470000000000255e-01 +1.403715397162139893e+09 -1.919540000000000024e+00 -3.043838000000000044e+00 5.894279999999999520e-01 -6.053659999999999597e-01 -5.770690000000000541e-01 -3.923070000000000168e-01 3.829080000000000261e-01 +1.403715397212140083e+09 -1.923925000000000107e+00 -3.025828000000000184e+00 5.793810000000000349e-01 -6.072959999999999470e-01 -5.765379999999999949e-01 -3.876120000000000121e-01 3.854259999999999908e-01 +1.403715397262140036e+09 -1.927956000000000003e+00 -3.005206999999999962e+00 5.685839999999999783e-01 -6.097559999999999647e-01 -5.750969999999999693e-01 -3.823420000000000152e-01 3.889429999999999832e-01 +1.403715397312139988e+09 -1.931187999999999905e+00 -2.984424000000000188e+00 5.593500000000000139e-01 -6.117179999999999840e-01 -5.725409999999999666e-01 -3.786089999999999733e-01 3.932590000000000252e-01 +1.403715397362139940e+09 -1.933200999999999947e+00 -2.962277999999999967e+00 5.498380000000000489e-01 -6.131490000000000551e-01 -5.704460000000000086e-01 -3.757739999999999969e-01 3.967789999999999928e-01 +1.403715397412139893e+09 -1.933885999999999994e+00 -2.938868999999999954e+00 5.407089999999999952e-01 -6.141649999999999610e-01 -5.689419999999999478e-01 -3.738620000000000276e-01 3.991660000000000208e-01 +1.403715397462140083e+09 -1.933014000000000010e+00 -2.914191000000000198e+00 5.318349999999999467e-01 -6.149620000000000086e-01 -5.682509999999999506e-01 -3.719239999999999768e-01 4.007310000000000039e-01 +1.403715397512140036e+09 -1.930558999999999914e+00 -2.888345999999999858e+00 5.236020000000000119e-01 -6.153149999999999453e-01 -5.679220000000000379e-01 -3.711439999999999739e-01 4.013780000000000125e-01 +1.403715397562139988e+09 -1.926444999999999963e+00 -2.861177000000000081e+00 5.157530000000000170e-01 -6.150189999999999824e-01 -5.671810000000000462e-01 -3.710450000000000137e-01 4.029679999999999929e-01 +1.403715397612139940e+09 -1.920492000000000088e+00 -2.832638000000000211e+00 5.089580000000000215e-01 -6.144309999999999494e-01 -5.661009999999999653e-01 -3.715720000000000134e-01 4.048950000000000049e-01 +1.403715397662139893e+09 -1.913006999999999902e+00 -2.803157999999999817e+00 5.036789999999999878e-01 -6.126329999999999831e-01 -5.651019999999999932e-01 -3.741519999999999846e-01 4.066350000000000242e-01 +1.403715397712140083e+09 -1.904050999999999938e+00 -2.772794000000000203e+00 4.995149999999999868e-01 -6.097029999999999950e-01 -5.636759999999999549e-01 -3.782900000000000151e-01 4.091790000000000149e-01 +1.403715397762140036e+09 -1.893729999999999913e+00 -2.741963999999999846e+00 4.962980000000000169e-01 -6.070470000000000033e-01 -5.629180000000000295e-01 -3.825899999999999856e-01 4.101750000000000118e-01 +1.403715397812139988e+09 -1.882339999999999902e+00 -2.711145000000000138e+00 4.939259999999999762e-01 -6.047909999999999675e-01 -5.617280000000000051e-01 -3.863869999999999805e-01 4.115750000000000242e-01 +1.403715397862139940e+09 -1.869783999999999891e+00 -2.680137000000000214e+00 4.921490000000000031e-01 -6.028599999999999515e-01 -5.611690000000000289e-01 -3.897590000000000221e-01 4.119920000000000249e-01 +1.403715397912139893e+09 -1.856176999999999966e+00 -2.648664999999999825e+00 4.909850000000000048e-01 -6.004359999999999697e-01 -5.612449999999999939e-01 -3.941379999999999884e-01 4.112609999999999877e-01 +1.403715397962140083e+09 -1.841777999999999915e+00 -2.617459999999999898e+00 4.908890000000000198e-01 -5.969060000000000477e-01 -5.601369999999999960e-01 -4.001509999999999789e-01 4.121029999999999971e-01 +1.403715398012140036e+09 -1.826888000000000067e+00 -2.586523000000000128e+00 4.905360000000000276e-01 -5.930950000000000388e-01 -5.587959999999999594e-01 -4.067890000000000117e-01 4.129269999999999885e-01 +1.403715398062139988e+09 -1.811668999999999974e+00 -2.556477999999999806e+00 4.898379999999999956e-01 -5.896820000000000395e-01 -5.571819999999999551e-01 -4.128430000000000155e-01 4.139860000000000206e-01 +1.403715398112139940e+09 -1.796322999999999892e+00 -2.527271999999999963e+00 4.883170000000000011e-01 -5.869609999999999550e-01 -5.556740000000000013e-01 -4.178410000000000180e-01 4.148649999999999838e-01 +1.403715398162139893e+09 -1.780945000000000000e+00 -2.499282000000000004e+00 4.861630000000000118e-01 -5.846759999999999735e-01 -5.543350000000000222e-01 -4.222629999999999995e-01 4.154039999999999955e-01 +1.403715398212140083e+09 -1.765697999999999990e+00 -2.472936999999999941e+00 4.829379999999999784e-01 -5.837970000000000104e-01 -5.537469999999999892e-01 -4.248560000000000114e-01 4.147810000000000108e-01 +1.403715398262140036e+09 -1.750559999999999894e+00 -2.448472999999999900e+00 4.786159999999999859e-01 -5.844230000000000258e-01 -5.536699999999999955e-01 -4.255530000000000146e-01 4.132850000000000135e-01 +1.403715398312139988e+09 -1.735589000000000048e+00 -2.425626999999999978e+00 4.735489999999999977e-01 -5.856000000000000094e-01 -5.543879999999999919e-01 -4.256849999999999801e-01 4.105099999999999860e-01 +1.403715398362139940e+09 -1.720898999999999957e+00 -2.404379000000000044e+00 4.680920000000000081e-01 -5.867040000000000033e-01 -5.547959999999999559e-01 -4.261110000000000175e-01 4.079329999999999901e-01 +1.403715398412139893e+09 -1.706498000000000070e+00 -2.384152999999999967e+00 4.625889999999999724e-01 -5.887170000000000458e-01 -5.539809999999999457e-01 -4.250559999999999894e-01 4.072410000000000196e-01 +1.403715398462140083e+09 -1.692237999999999909e+00 -2.365108000000000210e+00 4.566740000000000244e-01 -5.898139999999999494e-01 -5.546119999999999939e-01 -4.254990000000000161e-01 4.043220000000000147e-01 +1.403715398512140036e+09 -1.678190000000000071e+00 -2.346966000000000108e+00 4.506200000000000205e-01 -5.907620000000000093e-01 -5.547999999999999599e-01 -4.263419999999999987e-01 4.017839999999999745e-01 +1.403715398562139988e+09 -1.665037000000000100e+00 -2.330061999999999856e+00 4.453579999999999761e-01 -5.910269999999999690e-01 -5.548959999999999448e-01 -4.279459999999999931e-01 3.995500000000000163e-01 +1.403715398612139940e+09 -1.652549000000000046e+00 -2.314043999999999990e+00 4.410140000000000171e-01 -5.904500000000000304e-01 -5.533850000000000158e-01 -4.306860000000000133e-01 3.995529999999999915e-01 +1.403715398662139893e+09 -1.640697999999999990e+00 -2.299091000000000218e+00 4.371680000000000010e-01 -5.885150000000000103e-01 -5.526630000000000154e-01 -4.352559999999999762e-01 3.984539999999999749e-01 +1.403715398712140083e+09 -1.629491000000000023e+00 -2.285340000000000149e+00 4.337529999999999997e-01 -5.853620000000000489e-01 -5.523139999999999716e-01 -4.413079999999999781e-01 3.969230000000000258e-01 +1.403715398762140036e+09 -1.619429999999999925e+00 -2.272978000000000165e+00 4.306429999999999980e-01 -5.821920000000000428e-01 -5.522399999999999531e-01 -4.475520000000000054e-01 3.946919999999999873e-01 +1.403715398812139988e+09 -1.610826000000000091e+00 -2.262281000000000208e+00 4.275519999999999876e-01 -5.798389999999999933e-01 -5.524440000000000461e-01 -4.521640000000000104e-01 3.926069999999999838e-01 +1.403715398862139940e+09 -1.604008000000000100e+00 -2.253092000000000095e+00 4.244510000000000227e-01 -5.780459999999999487e-01 -5.530000000000000471e-01 -4.555170000000000052e-01 3.905870000000000175e-01 +1.403715398912139893e+09 -1.599134999999999973e+00 -2.245436999999999905e+00 4.214970000000000105e-01 -5.768149999999999666e-01 -5.533160000000000300e-01 -4.577439999999999842e-01 3.893550000000000066e-01 +1.403715398962140083e+09 -1.596233000000000013e+00 -2.239195000000000046e+00 4.187569999999999903e-01 -5.763740000000000530e-01 -5.533810000000000118e-01 -4.584119999999999862e-01 3.891290000000000027e-01 +1.403715399012140036e+09 -1.595167999999999919e+00 -2.234748000000000179e+00 4.166679999999999828e-01 -5.755519999999999525e-01 -5.534670000000000423e-01 -4.592780000000000196e-01 3.892030000000000212e-01 +1.403715399062139988e+09 -1.595997000000000110e+00 -2.232105999999999923e+00 4.147219999999999795e-01 -5.759410000000000363e-01 -5.535229999999999873e-01 -4.580969999999999764e-01 3.899369999999999781e-01 +1.403715399112139940e+09 -1.598468000000000000e+00 -2.231129000000000140e+00 4.124800000000000133e-01 -5.772880000000000233e-01 -5.539920000000000400e-01 -4.550969999999999738e-01 3.907919999999999727e-01 +1.403715399162139893e+09 -1.602961000000000080e+00 -2.231343999999999994e+00 4.102649999999999908e-01 -5.787809999999999899e-01 -5.534900000000000375e-01 -4.516990000000000172e-01 3.932280000000000220e-01 +1.403715399212140083e+09 -1.608991999999999978e+00 -2.233305000000000096e+00 4.086549999999999905e-01 -5.794249999999999678e-01 -5.535790000000000433e-01 -4.493260000000000032e-01 3.948710000000000275e-01 +1.403715399262140036e+09 -1.616343000000000085e+00 -2.237195999999999962e+00 4.075909999999999811e-01 -5.796369999999999578e-01 -5.531449999999999978e-01 -4.476530000000000231e-01 3.970620000000000260e-01 +1.403715399312139988e+09 -1.624474999999999891e+00 -2.242614000000000107e+00 4.063809999999999922e-01 -5.798689999999999678e-01 -5.546140000000000514e-01 -4.460749999999999993e-01 3.964500000000000246e-01 +1.403715399362139940e+09 -1.633966000000000030e+00 -2.249721000000000082e+00 4.051400000000000001e-01 -5.807120000000000060e-01 -5.564860000000000362e-01 -4.441240000000000188e-01 3.947800000000000198e-01 +1.403715399412139893e+09 -1.644808000000000048e+00 -2.257931000000000132e+00 4.036259999999999848e-01 -5.818010000000000126e-01 -5.593310000000000226e-01 -4.417599999999999860e-01 3.917959999999999776e-01 +1.403715399462140083e+09 -1.656851000000000074e+00 -2.267262999999999806e+00 4.024929999999999897e-01 -5.823789999999999800e-01 -5.615099999999999536e-01 -4.403079999999999772e-01 3.894480000000000164e-01 +1.403715399512140036e+09 -1.670047000000000059e+00 -2.277595999999999954e+00 4.017379999999999840e-01 -5.819910000000000361e-01 -5.634949999999999681e-01 -4.408119999999999816e-01 3.865810000000000080e-01 +1.403715399562139988e+09 -1.684668999999999972e+00 -2.288972999999999924e+00 4.002569999999999739e-01 -5.844209999999999683e-01 -5.663169999999999593e-01 -4.376019999999999910e-01 3.824159999999999782e-01 +1.403715399612139940e+09 -1.700795999999999975e+00 -2.300915999999999961e+00 3.981879999999999864e-01 -5.900069999999999482e-01 -5.677299999999999569e-01 -4.303420000000000023e-01 3.799730000000000052e-01 +1.403715399662139893e+09 -1.718150999999999984e+00 -2.313112999999999975e+00 3.965090000000000003e-01 -5.953289999999999971e-01 -5.688680000000000403e-01 -4.235809999999999853e-01 3.775589999999999780e-01 +1.403715399712140083e+09 -1.736599000000000004e+00 -2.324873999999999885e+00 3.952680000000000082e-01 -6.002579999999999583e-01 -5.695679999999999632e-01 -4.175610000000000155e-01 3.753989999999999827e-01 +1.403715399762140036e+09 -1.755725999999999898e+00 -2.335808000000000106e+00 3.953010000000000135e-01 -6.039090000000000291e-01 -5.700250000000000039e-01 -4.135800000000000032e-01 3.732519999999999727e-01 +1.403715399812139988e+09 -1.775320999999999927e+00 -2.345877000000000212e+00 3.960580000000000211e-01 -6.066350000000000353e-01 -5.699990000000000334e-01 -4.109920000000000240e-01 3.717269999999999741e-01 +1.403715399862139940e+09 -1.795481000000000105e+00 -2.355138000000000176e+00 3.973590000000000177e-01 -6.084310000000000551e-01 -5.701869999999999994e-01 -4.093930000000000069e-01 3.702630000000000088e-01 +1.403715399912139893e+09 -1.816117999999999899e+00 -2.363249999999999851e+00 3.995299999999999963e-01 -6.098479999999999457e-01 -5.704669999999999463e-01 -4.084760000000000058e-01 3.685109999999999775e-01 +1.403715399962140083e+09 -1.836951999999999918e+00 -2.370048999999999850e+00 4.021179999999999755e-01 -6.114410000000000123e-01 -5.701140000000000096e-01 -4.087410000000000210e-01 3.661150000000000237e-01 +1.403715400012140036e+09 -1.858244000000000007e+00 -2.375366999999999784e+00 4.052100000000000146e-01 -6.128400000000000514e-01 -5.687179999999999458e-01 -4.110509999999999997e-01 3.633509999999999796e-01 +1.403715400062139988e+09 -1.880076000000000080e+00 -2.378981000000000012e+00 4.089130000000000265e-01 -6.142849999999999699e-01 -5.660950000000000149e-01 -4.146090000000000053e-01 3.609569999999999723e-01 +1.403715400112139940e+09 -1.902511999999999981e+00 -2.380777000000000143e+00 4.127100000000000213e-01 -6.160120000000000040e-01 -5.628170000000000117e-01 -4.190289999999999848e-01 3.580229999999999801e-01 +1.403715400162139893e+09 -1.925419999999999909e+00 -2.381302999999999948e+00 4.164439999999999809e-01 -6.191050000000000164e-01 -5.582989999999999897e-01 -4.230979999999999741e-01 3.549640000000000017e-01 +1.403715400212140083e+09 -1.948974999999999902e+00 -2.380355000000000221e+00 4.203890000000000127e-01 -6.223079999999999723e-01 -5.534419999999999895e-01 -4.281789999999999763e-01 3.508530000000000260e-01 +1.403715400262140036e+09 -1.973333999999999921e+00 -2.377273999999999887e+00 4.246770000000000267e-01 -6.250869999999999482e-01 -5.499039999999999484e-01 -4.344210000000000016e-01 3.437290000000000068e-01 +1.403715400312139988e+09 -1.998701000000000061e+00 -2.373690999999999995e+00 4.287090000000000067e-01 -6.289930000000000243e-01 -5.451899999999999524e-01 -4.400339999999999807e-01 3.369050000000000100e-01 +1.403715400362139940e+09 -2.025351999999999819e+00 -2.368970000000000020e+00 4.324080000000000146e-01 -6.330980000000000496e-01 -5.398570000000000313e-01 -4.460640000000000160e-01 3.298010000000000108e-01 +1.403715400412139893e+09 -2.053183000000000202e+00 -2.363145999999999969e+00 4.355740000000000167e-01 -6.387190000000000367e-01 -5.335239999999999982e-01 -4.506820000000000270e-01 3.229170000000000096e-01 +1.403715400462140083e+09 -2.082361000000000129e+00 -2.355977000000000210e+00 4.386109999999999731e-01 -6.455079999999999707e-01 -5.248770000000000380e-01 -4.543940000000000201e-01 3.183540000000000258e-01 +1.403715400512140036e+09 -2.112579999999999902e+00 -2.347636000000000056e+00 4.418139999999999845e-01 -6.536030000000000451e-01 -5.149599999999999733e-01 -4.568760000000000043e-01 3.144580000000000153e-01 +1.403715400562139988e+09 -2.144181000000000115e+00 -2.338118000000000141e+00 4.443599999999999772e-01 -6.623219999999999663e-01 -5.045819999999999750e-01 -4.589929999999999843e-01 3.099230000000000040e-01 +1.403715400612139940e+09 -2.176733000000000029e+00 -2.326932999999999918e+00 4.460160000000000236e-01 -6.717319999999999958e-01 -4.927560000000000273e-01 -4.608450000000000046e-01 3.059239999999999737e-01 +1.403715400662139893e+09 -2.209805999999999937e+00 -2.314820000000000100e+00 4.471640000000000059e-01 -6.815170000000000394e-01 -4.809419999999999806e-01 -4.624519999999999742e-01 3.006119999999999903e-01 +1.403715400712140083e+09 -2.243139999999999912e+00 -2.301098000000000088e+00 4.478710000000000191e-01 -6.908879999999999466e-01 -4.687520000000000020e-01 -4.648860000000000214e-01 2.946630000000000082e-01 +1.403715400762140036e+09 -2.276618000000000031e+00 -2.286084999999999923e+00 4.481859999999999733e-01 -7.005249999999999533e-01 -4.559699999999999864e-01 -4.667410000000000170e-01 2.889800000000000146e-01 +1.403715400812139988e+09 -2.310109999999999886e+00 -2.269829999999999792e+00 4.483699999999999908e-01 -7.095770000000000133e-01 -4.418529999999999958e-01 -4.691040000000000210e-01 2.849700000000000011e-01 +1.403715400862139940e+09 -2.343570000000000153e+00 -2.252543999999999880e+00 4.482999999999999763e-01 -7.182330000000000103e-01 -4.272190000000000154e-01 -4.715809999999999724e-01 2.814880000000000160e-01 +1.403715400912139893e+09 -2.376288000000000178e+00 -2.234039999999999804e+00 4.471519999999999939e-01 -7.267839999999999856e-01 -4.146250000000000213e-01 -4.722049999999999859e-01 2.772970000000000157e-01 +1.403715400962140083e+09 -2.408316999999999819e+00 -2.214214999999999822e+00 4.455799999999999761e-01 -7.343499999999999472e-01 -4.036310000000000175e-01 -4.720739999999999936e-01 2.737840000000000273e-01 +1.403715401012140036e+09 -2.439064999999999817e+00 -2.193541999999999881e+00 4.441860000000000253e-01 -7.410369999999999457e-01 -3.939329999999999776e-01 -4.717189999999999994e-01 2.704860000000000042e-01 +1.403715401062139988e+09 -2.468633000000000077e+00 -2.172306999999999988e+00 4.433599999999999763e-01 -7.464250000000000052e-01 -3.873389999999999889e-01 -4.714070000000000205e-01 2.656939999999999857e-01 +1.403715401112139940e+09 -2.496242000000000072e+00 -2.150310000000000166e+00 4.431490000000000151e-01 -7.501109999999999722e-01 -3.817130000000000245e-01 -4.721409999999999774e-01 2.621299999999999741e-01 +1.403715401162139893e+09 -2.522234999999999783e+00 -2.127279999999999838e+00 4.434529999999999861e-01 -7.529310000000000169e-01 -3.780609999999999804e-01 -4.733060000000000045e-01 2.571910000000000029e-01 +1.403715401212140083e+09 -2.546546000000000198e+00 -2.102799999999999780e+00 4.444810000000000150e-01 -7.545680000000000165e-01 -3.764029999999999876e-01 -4.749820000000000153e-01 2.516749999999999821e-01 +1.403715401262140036e+09 -2.569148999999999905e+00 -2.076710999999999974e+00 4.459799999999999875e-01 -7.554220000000000379e-01 -3.759970000000000256e-01 -4.767859999999999876e-01 2.462499999999999967e-01 +1.403715401312139988e+09 -2.590373000000000037e+00 -2.048801000000000094e+00 4.476829999999999976e-01 -7.559949999999999726e-01 -3.753839999999999955e-01 -4.786889999999999756e-01 2.416939999999999922e-01 +1.403715401362139940e+09 -2.610920999999999825e+00 -2.019274999999999931e+00 4.496209999999999929e-01 -7.556270000000000486e-01 -3.738119999999999776e-01 -4.812270000000000159e-01 2.402360000000000051e-01 +1.403715401412139893e+09 -2.629465000000000163e+00 -1.987403000000000031e+00 4.529690000000000105e-01 -7.549770000000000092e-01 -3.721960000000000268e-01 -4.835920000000000218e-01 2.400370000000000004e-01 +1.403715401462140083e+09 -2.646736000000000200e+00 -1.954134000000000038e+00 4.563860000000000139e-01 -7.538759999999999906e-01 -3.711139999999999994e-01 -4.862110000000000043e-01 2.398839999999999861e-01 +1.403715401512140036e+09 -2.662249000000000088e+00 -1.919737999999999944e+00 4.604349999999999832e-01 -7.525119999999999587e-01 -3.692079999999999806e-01 -4.888339999999999907e-01 2.417690000000000117e-01 +1.403715401562139988e+09 -2.676629999999999843e+00 -1.884719999999999951e+00 4.649119999999999919e-01 -7.517530000000000046e-01 -3.667659999999999809e-01 -4.905340000000000256e-01 2.443889999999999951e-01 +1.403715401612139940e+09 -2.689788000000000068e+00 -1.848964999999999970e+00 4.703899999999999748e-01 -7.497700000000000475e-01 -3.636229999999999740e-01 -4.936749999999999750e-01 2.488130000000000064e-01 +1.403715401662139893e+09 -2.701693000000000122e+00 -1.812689999999999912e+00 4.759709999999999774e-01 -7.483919999999999462e-01 -3.606699999999999906e-01 -4.964189999999999992e-01 2.517840000000000078e-01 +1.403715401712140083e+09 -2.712571000000000065e+00 -1.775724999999999998e+00 4.819470000000000143e-01 -7.475899999999999768e-01 -3.540479999999999738e-01 -4.995020000000000016e-01 2.574020000000000197e-01 +1.403715401762140036e+09 -2.722211000000000158e+00 -1.738741000000000092e+00 4.871980000000000199e-01 -7.482010000000000050e-01 -3.456130000000000035e-01 -5.015060000000000073e-01 2.631330000000000058e-01 +1.403715401812139988e+09 -2.730170999999999903e+00 -1.702482000000000051e+00 4.922560000000000269e-01 -7.485169999999999879e-01 -3.395110000000000072e-01 -5.044459999999999500e-01 2.645540000000000114e-01 +1.403715401862139940e+09 -2.736994000000000149e+00 -1.667362999999999928e+00 4.971999999999999753e-01 -7.493640000000000301e-01 -3.340890000000000248e-01 -5.068259999999999987e-01 2.645120000000000249e-01 +1.403715401912139893e+09 -2.742865999999999804e+00 -1.633299999999999974e+00 5.014300000000000423e-01 -7.493039999999999701e-01 -3.327269999999999950e-01 -5.094980000000000064e-01 2.612410000000000010e-01 +1.403715401962140083e+09 -2.747036000000000033e+00 -1.600464000000000109e+00 5.049240000000000395e-01 -7.485209999999999919e-01 -3.337459999999999871e-01 -5.125319999999999876e-01 2.562070000000000181e-01 +1.403715402012140036e+09 -2.751222999999999974e+00 -1.568416000000000032e+00 5.083360000000000101e-01 -7.474030000000000395e-01 -3.355529999999999902e-01 -5.153539999999999788e-01 2.514009999999999856e-01 +1.403715402062139988e+09 -2.754774999999999974e+00 -1.536626000000000047e+00 5.120280000000000387e-01 -7.464420000000000499e-01 -3.378470000000000084e-01 -5.172489999999999588e-01 2.472600000000000076e-01 +1.403715402112139940e+09 -2.757562000000000069e+00 -1.505130999999999997e+00 5.156359999999999832e-01 -7.436639999999999917e-01 -3.387220000000000231e-01 -5.211019999999999541e-01 2.463410000000000044e-01 +1.403715402162139893e+09 -2.760078000000000031e+00 -1.474634000000000000e+00 5.196880000000000388e-01 -7.383110000000000506e-01 -3.381129999999999969e-01 -5.286079999999999668e-01 2.472860000000000058e-01 +1.403715402212140083e+09 -2.761563999999999908e+00 -1.445694000000000035e+00 5.227579999999999449e-01 -7.346080000000000387e-01 -3.362689999999999846e-01 -5.344389999999999974e-01 2.482930000000000137e-01 +1.403715402262140036e+09 -2.764857000000000120e+00 -1.417567000000000021e+00 5.254349999999999854e-01 -7.329170000000000407e-01 -3.339739999999999931e-01 -5.383409999999999584e-01 2.479570000000000107e-01 +1.403715402312139988e+09 -2.768412999999999791e+00 -1.390749000000000013e+00 5.268340000000000245e-01 -7.336500000000000243e-01 -3.334829999999999739e-01 -5.396720000000000406e-01 2.435190000000000132e-01 +1.403715402362139940e+09 -2.772161000000000097e+00 -1.365056000000000047e+00 5.277800000000000269e-01 -7.362769999999999593e-01 -3.330219999999999847e-01 -5.395590000000000108e-01 2.363629999999999898e-01 +1.403715402412139893e+09 -2.776051999999999964e+00 -1.340224000000000082e+00 5.289019999999999833e-01 -7.383899999999999908e-01 -3.308960000000000234e-01 -5.412679999999999714e-01 2.287299999999999889e-01 +1.403715402462140083e+09 -2.780670999999999893e+00 -1.316389999999999949e+00 5.293219999999999592e-01 -7.402020000000000266e-01 -3.279009999999999980e-01 -5.443120000000000180e-01 2.197890000000000121e-01 +1.403715402512140036e+09 -2.785826999999999831e+00 -1.292367000000000044e+00 5.303550000000000209e-01 -7.401079999999999881e-01 -3.246749999999999914e-01 -5.497969999999999802e-01 2.110700000000000076e-01 +1.403715402562139988e+09 -2.791262000000000132e+00 -1.267632000000000092e+00 5.318349999999999467e-01 -7.407580000000000275e-01 -3.212180000000000035e-01 -5.533730000000000038e-01 2.046340000000000103e-01 +1.403715402612139940e+09 -2.798719000000000179e+00 -1.242923999999999918e+00 5.331399999999999473e-01 -7.401450000000000529e-01 -3.174500000000000099e-01 -5.580260000000000220e-01 2.000439999999999996e-01 +1.403715402662139893e+09 -2.807942000000000160e+00 -1.217230000000000034e+00 5.351259999999999906e-01 -7.401689999999999658e-01 -3.141689999999999761e-01 -5.612960000000000171e-01 1.959470000000000101e-01 +1.403715402712140083e+09 -2.818922999999999845e+00 -1.192120999999999986e+00 5.358429999999999582e-01 -7.406770000000000298e-01 -3.105160000000000142e-01 -5.634029999999999871e-01 1.937909999999999910e-01 +1.403715402762140036e+09 -2.832059000000000104e+00 -1.166943000000000064e+00 5.358699999999999575e-01 -7.452630000000000088e-01 -3.048170000000000046e-01 -5.599520000000000053e-01 1.952510000000000079e-01 +1.403715402812139988e+09 -2.847821000000000158e+00 -1.143272000000000066e+00 5.355450000000000488e-01 -7.496819999999999595e-01 -2.991059999999999830e-01 -5.561730000000000285e-01 1.979509999999999881e-01 +1.403715402862139940e+09 -2.864104999999999901e+00 -1.118444999999999911e+00 5.356140000000000345e-01 -7.540559999999999485e-01 -2.937830000000000163e-01 -5.519570000000000309e-01 2.010840000000000127e-01 +1.403715402912139893e+09 -2.881086999999999954e+00 -1.093680999999999903e+00 5.353689999999999838e-01 -7.585239999999999760e-01 -2.886600000000000277e-01 -5.473940000000000472e-01 2.041499999999999981e-01 +1.403715402962140083e+09 -2.898397999999999808e+00 -1.068921000000000010e+00 5.350359999999999561e-01 -7.636870000000000047e-01 -2.843459999999999877e-01 -5.416910000000000336e-01 2.061570000000000069e-01 +1.403715403012140036e+09 -2.915595999999999854e+00 -1.044205999999999968e+00 5.348399999999999821e-01 -7.694569999999999466e-01 -2.802939999999999876e-01 -5.346999999999999531e-01 2.084880000000000067e-01 +1.403715403062139988e+09 -2.932351999999999848e+00 -1.020229999999999970e+00 5.349399999999999711e-01 -7.752289999999999459e-01 -2.781629999999999936e-01 -5.275410000000000377e-01 2.081959999999999922e-01 +1.403715403112139940e+09 -2.949132000000000087e+00 -9.958120000000000305e-01 5.349730000000000318e-01 -7.803219999999999601e-01 -2.760630000000000028e-01 -5.210310000000000219e-01 2.083569999999999867e-01 +1.403715403162139893e+09 -2.963548999999999989e+00 -9.728820000000000245e-01 5.357969999999999677e-01 -7.844969999999999999e-01 -2.749730000000000230e-01 -5.153919999999999613e-01 2.081459999999999977e-01 +1.403715403212140083e+09 -2.976392999999999844e+00 -9.500570000000000404e-01 5.377279999999999838e-01 -7.874339999999999673e-01 -2.737080000000000068e-01 -5.115720000000000267e-01 2.081500000000000017e-01 +1.403715403262140036e+09 -2.987478999999999996e+00 -9.274989999999999624e-01 5.395849999999999813e-01 -7.889469999999999539e-01 -2.752100000000000102e-01 -5.094199999999999839e-01 2.057049999999999990e-01 +1.403715403312139988e+09 -2.996542999999999957e+00 -9.044969999999999954e-01 5.418720000000000203e-01 -7.889739999999999531e-01 -2.771089999999999942e-01 -5.093490000000000517e-01 2.032079999999999997e-01 +1.403715403362139940e+09 -3.003833999999999893e+00 -8.817500000000000338e-01 5.445179999999999465e-01 -7.882449999999999735e-01 -2.782839999999999758e-01 -5.109259999999999913e-01 2.004539999999999933e-01 +1.403715403412139893e+09 -3.010172999999999988e+00 -8.590520000000000378e-01 5.472409999999999775e-01 -7.876030000000000530e-01 -2.782129999999999881e-01 -5.131170000000000453e-01 1.974579999999999946e-01 +1.403715403462140083e+09 -3.013606999999999925e+00 -8.361640000000000184e-01 5.502879999999999994e-01 -7.872740000000000293e-01 -2.766250000000000098e-01 -5.156420000000000448e-01 1.943999999999999895e-01 +1.403715403512140036e+09 -3.015302000000000149e+00 -8.131960000000000299e-01 5.531880000000000130e-01 -7.872759999999999758e-01 -2.730350000000000277e-01 -5.187990000000000101e-01 1.910370000000000124e-01 +1.403715403562139988e+09 -3.015835000000000043e+00 -7.904750000000000387e-01 5.556900000000000173e-01 -7.883310000000000040e-01 -2.674940000000000095e-01 -5.212390000000000079e-01 1.878599999999999992e-01 +1.403715403612139940e+09 -3.014606000000000119e+00 -7.676629999999999843e-01 5.573010000000000463e-01 -7.908190000000000497e-01 -2.612619999999999942e-01 -5.222959999999999825e-01 1.831800000000000095e-01 +1.403715403662139893e+09 -3.012392999999999876e+00 -7.449390000000000178e-01 5.587809999999999722e-01 -7.936609999999999498e-01 -2.541539999999999910e-01 -5.233189999999999786e-01 1.778899999999999926e-01 +1.403715403712140083e+09 -3.008528999999999787e+00 -7.222300000000000386e-01 5.598629999999999995e-01 -7.979049999999999754e-01 -2.461119999999999974e-01 -5.225170000000000092e-01 1.724900000000000044e-01 +1.403715403762140036e+09 -3.003321999999999825e+00 -6.993489999999999984e-01 5.608579999999999677e-01 -8.025510000000000144e-01 -2.363780000000000048e-01 -5.213670000000000249e-01 1.679700000000000082e-01 +1.403715403812139988e+09 -2.996107999999999993e+00 -6.761019999999999808e-01 5.622989999999999933e-01 -8.066499999999999782e-01 -2.258580000000000032e-01 -5.211109999999999909e-01 1.635449999999999959e-01 +1.403715403862139940e+09 -2.986873999999999807e+00 -6.530179999999999874e-01 5.644050000000000455e-01 -8.099530000000000340e-01 -2.152840000000000031e-01 -5.219580000000000330e-01 1.587099999999999900e-01 +1.403715403962140083e+09 -2.962858999999999909e+00 -6.066209999999999658e-01 5.687940000000000218e-01 -8.156560000000000477e-01 -1.946670000000000067e-01 -5.245410000000000350e-01 1.471949999999999925e-01 +1.403715404012140036e+09 -2.947878999999999916e+00 -5.836670000000000469e-01 5.716250000000000497e-01 -8.174000000000000155e-01 -1.852280000000000038e-01 -5.271010000000000417e-01 1.403989999999999960e-01 +1.403715404062139988e+09 -2.931477000000000110e+00 -5.609680000000000222e-01 5.754749999999999588e-01 -8.174930000000000252e-01 -1.757070000000000021e-01 -5.320139999999999869e-01 1.333890000000000076e-01 +1.403715404112139940e+09 -2.913618000000000041e+00 -5.385429999999999939e-01 5.795190000000000063e-01 -8.172249999999999792e-01 -1.673910000000000120e-01 -5.370650000000000146e-01 1.252369999999999872e-01 +1.403715404162139893e+09 -2.894735999999999976e+00 -5.157140000000000057e-01 5.840260000000000451e-01 -8.159619999999999651e-01 -1.608549999999999980e-01 -5.433679999999999621e-01 1.143829999999999986e-01 +1.403715404212140083e+09 -2.874572000000000127e+00 -4.931019999999999848e-01 5.878550000000000164e-01 -8.151399999999999757e-01 -1.542219999999999980e-01 -5.485379999999999701e-01 1.042529999999999984e-01 +1.403715404262140036e+09 -2.854306999999999928e+00 -4.698709999999999831e-01 5.914709999999999690e-01 -8.138870000000000271e-01 -1.493059999999999943e-01 -5.535480000000000400e-01 9.423600000000000032e-02 +1.403715404312139988e+09 -2.833337000000000216e+00 -4.460089999999999888e-01 5.940579999999999750e-01 -8.132979999999999654e-01 -1.453629999999999922e-01 -5.569880000000000386e-01 8.473799999999999388e-02 +1.403715404362139940e+09 -2.812311999999999923e+00 -4.207850000000000201e-01 5.960180000000000478e-01 -8.134500000000000064e-01 -1.411870000000000069e-01 -5.587539999999999729e-01 7.848199999999999621e-02 +1.403715404412139893e+09 -2.791341000000000072e+00 -3.952709999999999835e-01 5.974660000000000526e-01 -8.131429999999999492e-01 -1.381650000000000100e-01 -5.607609999999999539e-01 7.249400000000000288e-02 +1.403715404462140083e+09 -2.770493999999999790e+00 -3.682010000000000005e-01 5.989910000000000512e-01 -8.124259999999999815e-01 -1.348830000000000029e-01 -5.630549999999999722e-01 6.884800000000000642e-02 +1.403715404512140036e+09 -2.749922000000000200e+00 -3.399730000000000252e-01 5.999020000000000463e-01 -8.116100000000000536e-01 -1.330919999999999881e-01 -5.651019999999999932e-01 6.508600000000000496e-02 +1.403715404562139988e+09 -2.729347999999999885e+00 -3.103949999999999765e-01 6.001539999999999653e-01 -8.108750000000000124e-01 -1.313439999999999885e-01 -5.668170000000000153e-01 6.284800000000000109e-02 +1.403715404612139940e+09 -2.709632000000000041e+00 -2.803340000000000276e-01 5.991819999999999924e-01 -8.101890000000000480e-01 -1.291710000000000080e-01 -5.683829999999999716e-01 6.204400000000000193e-02 +1.403715404662139893e+09 -2.690214000000000105e+00 -2.489760000000000029e-01 5.974859999999999616e-01 -8.098499999999999588e-01 -1.253799999999999915e-01 -5.693789999999999685e-01 6.505099999999999771e-02 +1.403715404712140083e+09 -2.671143999999999963e+00 -2.165839999999999987e-01 5.957660000000000178e-01 -8.093129999999999491e-01 -1.222469999999999946e-01 -5.705000000000000071e-01 6.780400000000000316e-02 +1.403715404762140036e+09 -2.652276000000000078e+00 -1.839520000000000044e-01 5.935369999999999813e-01 -8.086550000000000127e-01 -1.182529999999999970e-01 -5.717379999999999685e-01 7.217099999999999904e-02 +1.403715404812139988e+09 -2.633617999999999792e+00 -1.511969999999999981e-01 5.908470000000000111e-01 -8.090450000000000141e-01 -1.146059999999999995e-01 -5.716259999999999675e-01 7.452899999999999803e-02 +1.403715404862139940e+09 -2.614939999999999820e+00 -1.184930000000000011e-01 5.880020000000000246e-01 -8.096360000000000223e-01 -1.101590000000000069e-01 -5.716050000000000297e-01 7.498699999999999810e-02 +1.403715404912139893e+09 -2.596630999999999911e+00 -8.577400000000000302e-02 5.848520000000000385e-01 -8.096050000000000191e-01 -1.047639999999999960e-01 -5.726930000000000076e-01 7.474699999999999400e-02 +1.403715404962140083e+09 -2.578336999999999879e+00 -5.284599999999999714e-02 5.815649999999999986e-01 -8.093909999999999716e-01 -9.772799999999999543e-02 -5.743219999999999992e-01 7.408800000000000108e-02 +1.403715405012140036e+09 -2.560261000000000120e+00 -2.090499999999999997e-02 5.776879999999999793e-01 -8.089300000000000379e-01 -8.922499999999999876e-02 -5.765120000000000244e-01 7.284200000000000397e-02 +1.403715405062139988e+09 -2.542867999999999906e+00 1.000299999999999974e-02 5.736869999999999470e-01 -8.088990000000000347e-01 -7.911999999999999589e-02 -5.782829999999999915e-01 7.079399999999999582e-02 +1.403715405112139940e+09 -2.526334999999999997e+00 3.997300000000000159e-02 5.693259999999999987e-01 -8.093479999999999563e-01 -6.686000000000000276e-02 -5.794040000000000301e-01 6.911200000000000676e-02 +1.403715405162139893e+09 -2.510600999999999861e+00 6.849500000000000033e-02 5.645170000000000465e-01 -8.107210000000000250e-01 -5.378499999999999948e-02 -5.793080000000000451e-01 6.512099999999999833e-02 +1.403715405212140083e+09 -2.495518000000000125e+00 9.568300000000000416e-02 5.597959999999999603e-01 -8.123700000000000365e-01 -3.974199999999999955e-02 -5.787099999999999467e-01 5.974899999999999656e-02 +1.403715405262140036e+09 -2.481078999999999812e+00 1.214500000000000024e-01 5.550979999999999803e-01 -8.139420000000000543e-01 -2.517399999999999846e-02 -5.779600000000000293e-01 5.316900000000000098e-02 +1.403715405312139988e+09 -2.466772999999999882e+00 1.455289999999999917e-01 5.503440000000000554e-01 -8.153150000000000119e-01 -1.143500000000000072e-02 -5.772080000000000544e-01 4.428499999999999798e-02 +1.403715405362139940e+09 -2.452631999999999923e+00 1.679299999999999959e-01 5.458030000000000381e-01 -8.165750000000000508e-01 1.918000000000000000e-03 -5.761979999999999880e-01 3.459999999999999881e-02 +1.403715405412139893e+09 -2.439297999999999966e+00 1.888170000000000126e-01 5.415990000000000526e-01 -8.178959999999999564e-01 1.458300000000000048e-02 -5.746869999999999479e-01 2.383800000000000155e-02 +1.403715405462140083e+09 -2.425448999999999966e+00 2.090589999999999948e-01 5.371369999999999756e-01 -8.191580000000000528e-01 2.796699999999999880e-02 -5.727119999999999989e-01 1.410699999999999975e-02 +1.403715405512140036e+09 -2.411885999999999974e+00 2.277109999999999967e-01 5.328049999999999731e-01 -8.197109999999999674e-01 4.152399999999999841e-02 -5.712530000000000108e-01 4.346000000000000037e-03 +1.403715405562139988e+09 -2.398013000000000172e+00 2.450819999999999943e-01 5.284529999999999506e-01 8.199670000000000014e-01 -5.485000000000000292e-02 5.697459999999999747e-01 5.834999999999999909e-03 +1.403715405612139940e+09 -2.384436000000000000e+00 2.614190000000000125e-01 5.242900000000000338e-01 8.202230000000000354e-01 -6.638299999999999756e-02 5.678849999999999731e-01 1.826300000000000145e-02 +1.403715405662139893e+09 -2.370985999999999816e+00 2.765730000000000133e-01 5.200249999999999595e-01 8.210979999999999945e-01 -7.675999999999999490e-02 5.647219999999999462e-01 3.154900000000000065e-02 +1.403715405712140083e+09 -2.357450000000000045e+00 2.914619999999999989e-01 5.157739999999999547e-01 8.217210000000000347e-01 -8.731700000000000572e-02 5.614729999999999999e-01 4.356600000000000056e-02 +1.403715405762140036e+09 -2.343366000000000060e+00 3.056269999999999820e-01 5.115659999999999652e-01 8.218569999999999487e-01 -9.766199999999999881e-02 5.585280000000000244e-01 5.531599999999999712e-02 +1.403715405812139988e+09 -2.329209000000000085e+00 3.194690000000000030e-01 5.070719999999999672e-01 8.222279999999999589e-01 -1.088969999999999938e-01 5.547950000000000381e-01 6.546200000000000629e-02 +1.403715405862139940e+09 -2.314262999999999959e+00 3.329170000000000185e-01 5.028700000000000392e-01 8.221150000000000402e-01 -1.200699999999999962e-01 5.513770000000000060e-01 7.545799999999999730e-02 +1.403715405912139893e+09 -2.298575000000000035e+00 3.461069999999999980e-01 4.984970000000000234e-01 8.202749999999999764e-01 -1.329100000000000004e-01 5.499589999999999756e-01 8.383899999999999686e-02 +1.403715405962140083e+09 -2.282081999999999944e+00 3.589310000000000000e-01 4.943500000000000116e-01 8.167609999999999593e-01 -1.457600000000000007e-01 5.505750000000000366e-01 9.231999999999999929e-02 +1.403715406012140036e+09 -2.264673999999999854e+00 3.713730000000000087e-01 4.900519999999999876e-01 8.119680000000000231e-01 -1.582089999999999885e-01 5.525440000000000351e-01 1.018489999999999951e-01 +1.403715406062139988e+09 -2.247107000000000188e+00 3.836959999999999815e-01 4.850940000000000252e-01 8.069460000000000521e-01 -1.715659999999999963e-01 5.542369999999999797e-01 1.105619999999999936e-01 +1.403715406112139940e+09 -2.229013999999999829e+00 3.955699999999999772e-01 4.791139999999999843e-01 8.023719999999999741e-01 -1.840749999999999886e-01 5.549250000000000016e-01 1.198909999999999976e-01 +1.403715406162139893e+09 -2.210637999999999881e+00 4.074920000000000209e-01 4.720159999999999911e-01 7.979850000000000554e-01 -1.970939999999999914e-01 5.549140000000000184e-01 1.282330000000000136e-01 +1.403715406212140083e+09 -2.192353999999999914e+00 4.193069999999999853e-01 4.648300000000000209e-01 7.936889999999999779e-01 -2.102580000000000005e-01 5.543679999999999719e-01 1.361100000000000088e-01 +1.403715406262140036e+09 -2.174223000000000017e+00 4.306280000000000108e-01 4.570879999999999943e-01 7.899680000000000035e-01 -2.227099999999999913e-01 5.527119999999999811e-01 1.444290000000000018e-01 +1.403715406312139988e+09 -2.156458000000000208e+00 4.420749999999999957e-01 4.494580000000000242e-01 7.864550000000000152e-01 -2.352269999999999917e-01 5.505139999999999478e-01 1.519570000000000087e-01 +1.403715406362139940e+09 -2.138815999999999828e+00 4.533479999999999732e-01 4.406939999999999746e-01 7.833390000000000075e-01 -2.486029999999999907e-01 5.475149999999999739e-01 1.574929999999999941e-01 +1.403715406462140083e+09 -2.101453999999999933e+00 4.738550000000000262e-01 4.222699999999999787e-01 7.769270000000000342e-01 -2.757249999999999979e-01 5.408500000000000529e-01 1.668600000000000083e-01 +1.403715406512140036e+09 -2.083505999999999858e+00 4.830490000000000061e-01 4.129689999999999750e-01 7.738099999999999978e-01 -2.883100000000000107e-01 5.370500000000000274e-01 1.722589999999999955e-01 +1.403715406562139988e+09 -2.065837999999999841e+00 4.915269999999999917e-01 4.034429999999999961e-01 7.702409999999999535e-01 -3.008859999999999868e-01 5.336030000000000495e-01 1.773830000000000129e-01 +1.403715406612139940e+09 -2.048611999999999878e+00 4.988830000000000209e-01 3.938860000000000139e-01 7.661499999999999977e-01 -3.125729999999999897e-01 5.307870000000000088e-01 1.832399999999999862e-01 +1.403715406662139893e+09 -2.031382999999999939e+00 5.050120000000000164e-01 3.845210000000000017e-01 7.618139999999999912e-01 -3.235169999999999990e-01 5.282059999999999533e-01 1.896710000000000063e-01 +1.403715406712140083e+09 -2.014355999999999813e+00 5.099759999999999849e-01 3.750539999999999985e-01 7.573659999999999837e-01 -3.338329999999999909e-01 5.257260000000000266e-01 1.963789999999999980e-01 +1.403715406762140036e+09 -1.997940000000000049e+00 5.133309999999999818e-01 3.654830000000000023e-01 7.527030000000000109e-01 -3.429749999999999743e-01 5.232409999999999561e-01 2.049999999999999878e-01 +1.403715406812139988e+09 -1.981851999999999947e+00 5.153630000000000155e-01 3.560240000000000071e-01 7.476819999999999578e-01 -3.521520000000000206e-01 5.209240000000000537e-01 2.135370000000000046e-01 +1.403715406862139940e+09 -1.966283000000000003e+00 5.163470000000000004e-01 3.470249999999999724e-01 7.428200000000000358e-01 -3.610650000000000248e-01 5.180839999999999890e-01 2.223489999999999911e-01 +1.403715406912139893e+09 -1.950900000000000079e+00 5.162430000000000074e-01 3.382020000000000026e-01 7.382360000000000033e-01 -3.698739999999999806e-01 5.147080000000000544e-01 2.308149999999999924e-01 +1.403715406962140083e+09 -1.935507000000000088e+00 5.153790000000000315e-01 3.298119999999999941e-01 7.332670000000000021e-01 -3.784629999999999939e-01 5.115840000000000387e-01 2.395140000000000047e-01 +1.403715407012140036e+09 -1.920225999999999988e+00 5.139740000000000419e-01 3.217059999999999920e-01 7.286449999999999871e-01 -3.875379999999999936e-01 5.079550000000000454e-01 2.467229999999999979e-01 +1.403715407062139988e+09 -1.904314000000000062e+00 5.123069999999999569e-01 3.140660000000000118e-01 7.240379999999999594e-01 -3.973650000000000237e-01 5.040059999999999540e-01 2.526820000000000177e-01 +1.403715407112139940e+09 -1.890247000000000011e+00 5.088880000000000070e-01 3.064520000000000022e-01 7.197430000000000216e-01 -4.070980000000000154e-01 4.995560000000000000e-01 2.582349999999999923e-01 +1.403715407162139893e+09 -1.876600000000000046e+00 5.051499999999999879e-01 2.991900000000000115e-01 7.162469999999999670e-01 -4.164499999999999869e-01 4.944209999999999994e-01 2.628829999999999778e-01 +1.403715407212140083e+09 -1.862994000000000039e+00 5.008540000000000214e-01 2.922770000000000090e-01 7.147919999999999829e-01 -4.248839999999999839e-01 4.876039999999999819e-01 2.660609999999999919e-01 +1.403715407262140036e+09 -1.849134000000000055e+00 4.955140000000000100e-01 2.861529999999999907e-01 7.141229999999999523e-01 -4.324569999999999803e-01 4.808100000000000152e-01 2.680130000000000012e-01 +1.403715407312139988e+09 -1.834929999999999950e+00 4.890939999999999732e-01 2.802279999999999771e-01 7.146970000000000267e-01 -4.381450000000000067e-01 4.736699999999999799e-01 2.699500000000000233e-01 +1.403715407362139940e+09 -1.819992000000000054e+00 4.807629999999999959e-01 2.753659999999999997e-01 7.145930000000000337e-01 -4.426410000000000067e-01 4.686449999999999783e-01 2.716569999999999818e-01 +1.403715407412139893e+09 -1.804348999999999981e+00 4.699429999999999996e-01 2.708590000000000164e-01 7.140149999999999553e-01 -4.454989999999999783e-01 4.655610000000000026e-01 2.737979999999999858e-01 +1.403715407462140083e+09 -1.787784999999999958e+00 4.575879999999999947e-01 2.674400000000000110e-01 7.121960000000000512e-01 -4.470370000000000177e-01 4.653519999999999879e-01 2.763729999999999798e-01 +1.403715407512140036e+09 -1.770597999999999894e+00 4.435430000000000206e-01 2.647030000000000216e-01 7.110649999999999471e-01 -4.475609999999999866e-01 4.647379999999999844e-01 2.794519999999999782e-01 +1.403715407562139988e+09 -1.752486999999999906e+00 4.279740000000000211e-01 2.622459999999999791e-01 7.091039999999999566e-01 -4.483519999999999728e-01 4.659409999999999941e-01 2.811589999999999923e-01 +1.403715407612139940e+09 -1.733886000000000038e+00 4.110230000000000272e-01 2.603920000000000123e-01 7.075179999999999803e-01 -4.476539999999999964e-01 4.672540000000000027e-01 2.840750000000000219e-01 +1.403715407662139893e+09 -1.714515000000000011e+00 3.924139999999999850e-01 2.587800000000000100e-01 7.065890000000000226e-01 -4.452639999999999931e-01 4.682459999999999956e-01 2.884740000000000082e-01 +1.403715407712140083e+09 -1.694827000000000083e+00 3.732179999999999942e-01 2.587360000000000215e-01 7.060579999999999634e-01 -4.406260000000000177e-01 4.694479999999999764e-01 2.948729999999999962e-01 +1.403715407762140036e+09 -1.674387000000000070e+00 3.529579999999999940e-01 2.594299999999999939e-01 7.060300000000000464e-01 -4.364080000000000181e-01 4.702470000000000261e-01 2.998950000000000227e-01 +1.403715407812139988e+09 -1.653030999999999917e+00 3.315310000000000201e-01 2.590680000000000205e-01 7.065069999999999961e-01 -4.331720000000000015e-01 4.706069999999999975e-01 3.028819999999999846e-01 +1.403715407862139940e+09 -1.630940000000000056e+00 3.103890000000000260e-01 2.591069999999999762e-01 7.066590000000000371e-01 -4.306409999999999960e-01 4.713040000000000007e-01 3.050479999999999858e-01 +1.403715407912139893e+09 -1.608017000000000030e+00 2.890400000000000191e-01 2.590790000000000037e-01 7.058820000000000094e-01 -4.301059999999999883e-01 4.734180000000000055e-01 3.043270000000000142e-01 +1.403715407962140083e+09 -1.584316000000000058e+00 2.675640000000000240e-01 2.602260000000000129e-01 7.060039999999999649e-01 -4.296550000000000091e-01 4.741170000000000107e-01 3.035919999999999730e-01 +1.403715408012140036e+09 -1.560248999999999997e+00 2.451969999999999983e-01 2.635489999999999777e-01 7.043639999999999901e-01 -4.304890000000000105e-01 4.770769999999999733e-01 3.015749999999999820e-01 +1.403715408062139988e+09 -1.535938999999999943e+00 2.236190000000000122e-01 2.693889999999999896e-01 7.041309999999999514e-01 -4.308520000000000127e-01 4.780340000000000145e-01 3.000840000000000174e-01 +1.403715408112139940e+09 -1.511343000000000103e+00 2.019430000000000114e-01 2.784539999999999793e-01 7.033059999999999867e-01 -4.311519999999999797e-01 4.798330000000000095e-01 2.987130000000000063e-01 +1.403715408162139893e+09 -1.486175999999999942e+00 1.798869999999999914e-01 2.909280000000000199e-01 7.026210000000000511e-01 -4.312219999999999942e-01 4.816750000000000198e-01 2.972549999999999915e-01 +1.403715408212140083e+09 -1.461492000000000013e+00 1.576480000000000103e-01 3.066860000000000142e-01 7.016029999999999767e-01 -4.310329999999999995e-01 4.839669999999999805e-01 2.962110000000000021e-01 +1.403715408262140036e+09 -1.436382000000000048e+00 1.352240000000000109e-01 3.227519999999999833e-01 7.013490000000000002e-01 -4.306099999999999928e-01 4.849780000000000202e-01 2.957710000000000061e-01 +1.403715408312139988e+09 -1.410919999999999952e+00 1.134060000000000068e-01 3.382850000000000024e-01 7.010340000000000460e-01 -4.307059999999999778e-01 4.860630000000000228e-01 2.945960000000000245e-01 +1.403715408362139940e+09 -1.385428000000000104e+00 9.096100000000000019e-02 3.518270000000000008e-01 7.004690000000000083e-01 -4.303839999999999888e-01 4.874049999999999772e-01 2.941920000000000091e-01 +1.403715408412139893e+09 -1.359528999999999987e+00 6.808100000000000263e-02 3.625680000000000014e-01 6.994169999999999554e-01 -4.289080000000000115e-01 4.903790000000000093e-01 2.939100000000000046e-01 +1.403715408462140083e+09 -1.333658999999999928e+00 4.599199999999999816e-02 3.703060000000000240e-01 6.987710000000000310e-01 -4.257409999999999806e-01 4.938500000000000112e-01 2.942389999999999728e-01 +1.403715408512140036e+09 -1.306856999999999935e+00 2.610300000000000120e-02 3.766300000000000203e-01 6.979969999999999786e-01 -4.213759999999999728e-01 4.991249999999999853e-01 2.934570000000000234e-01 +1.403715408562139988e+09 -1.281053999999999915e+00 5.349999999999999721e-03 3.798489999999999922e-01 6.985860000000000403e-01 -4.154959999999999765e-01 5.037599999999999856e-01 2.925170000000000270e-01 +1.403715408612139940e+09 -1.255293999999999910e+00 -1.377699999999999932e-02 3.803239999999999954e-01 6.987679999999999447e-01 -4.086210000000000120e-01 5.100780000000000314e-01 2.908149999999999902e-01 +1.403715408662139893e+09 -1.230323000000000055e+00 -3.227700000000000014e-02 3.793460000000000165e-01 7.005759999999999765e-01 -3.996620000000000172e-01 5.152269999999999905e-01 2.898370000000000113e-01 +1.403715408712140083e+09 -1.206121999999999916e+00 -4.988700000000000079e-02 3.770209999999999950e-01 7.028579999999999828e-01 -3.907530000000000170e-01 5.206380000000000452e-01 2.867739999999999734e-01 +1.403715408762140036e+09 -1.182422000000000084e+00 -6.693699999999999650e-02 3.745720000000000161e-01 7.060269999999999602e-01 -3.817079999999999917e-01 5.257720000000000171e-01 2.817609999999999837e-01 +1.403715408812139988e+09 -1.159527999999999892e+00 -8.281499999999999972e-02 3.727869999999999795e-01 7.100119999999999765e-01 -3.716760000000000064e-01 5.304060000000000441e-01 2.764220000000000010e-01 +1.403715408862139940e+09 -1.137165999999999899e+00 -9.718300000000000549e-02 3.717320000000000069e-01 7.148130000000000317e-01 -3.620360000000000245e-01 5.343869999999999454e-01 2.690779999999999839e-01 +1.403715408912139893e+09 -1.115677999999999948e+00 -1.100570000000000020e-01 3.710629999999999762e-01 7.199870000000000436e-01 -3.517509999999999803e-01 5.382249999999999535e-01 2.611589999999999745e-01 +1.403715408962140083e+09 -1.094527000000000028e+00 -1.221730000000000038e-01 3.712139999999999884e-01 7.256869999999999710e-01 -3.407180000000000208e-01 5.414290000000000491e-01 2.532679999999999931e-01 +1.403715409012140036e+09 -1.074384999999999923e+00 -1.326910000000000034e-01 3.718359999999999999e-01 7.307479999999999531e-01 -3.293659999999999921e-01 5.455699999999999994e-01 2.447010000000000018e-01 +1.403715409062139988e+09 -1.054972999999999939e+00 -1.421709999999999918e-01 3.730589999999999740e-01 7.363640000000000185e-01 -3.177659999999999929e-01 5.486999999999999655e-01 2.360540000000000138e-01 +1.403715409112139940e+09 -1.036269000000000107e+00 -1.505579999999999974e-01 3.755379999999999829e-01 7.411429999999999962e-01 -3.073130000000000028e-01 5.525299999999999656e-01 2.257800000000000085e-01 +1.403715409162139893e+09 -1.018869999999999942e+00 -1.582659999999999900e-01 3.782760000000000011e-01 7.450879999999999725e-01 -2.984820000000000251e-01 5.562650000000000095e-01 2.152249999999999996e-01 +1.403715409212140083e+09 -1.003271000000000024e+00 -1.650040000000000118e-01 3.815999999999999948e-01 7.493640000000000301e-01 -2.905670000000000197e-01 5.582420000000000160e-01 2.058899999999999897e-01 +1.403715409262140036e+09 -9.885030000000000205e-01 -1.715679999999999983e-01 3.856760000000000188e-01 7.537890000000000423e-01 -2.843550000000000244e-01 5.584029999999999827e-01 1.978129999999999888e-01 +1.403715409312139988e+09 -9.753209999999999935e-01 -1.767660000000000065e-01 3.894799999999999929e-01 7.569110000000000005e-01 -2.791980000000000017e-01 5.592430000000000456e-01 1.907379999999999909e-01 +1.403715409362139940e+09 -9.637090000000000378e-01 -1.821349999999999913e-01 3.957669999999999799e-01 7.593469999999999942e-01 -2.743769999999999820e-01 5.600340000000000318e-01 1.856649999999999967e-01 +1.403715409412139893e+09 -9.529370000000000340e-01 -1.877969999999999917e-01 4.028169999999999806e-01 7.611959999999999837e-01 -2.699810000000000265e-01 5.606280000000000152e-01 1.827199999999999935e-01 +1.403715409462140083e+09 -9.447010000000000129e-01 -1.921690000000000065e-01 4.112649999999999917e-01 7.625450000000000284e-01 -2.653760000000000008e-01 5.611939999999999706e-01 1.821020000000000139e-01 +1.403715409512140036e+09 -9.369410000000000238e-01 -1.969569999999999932e-01 4.204410000000000092e-01 7.633830000000000338e-01 -2.607119999999999993e-01 5.616259999999999586e-01 1.839890000000000136e-01 +1.403715409562139988e+09 -9.303630000000000511e-01 -2.016310000000000047e-01 4.296150000000000246e-01 7.651149999999999896e-01 -2.579489999999999839e-01 5.593599999999999683e-01 1.875539999999999985e-01 +1.403715409612139940e+09 -9.238640000000000185e-01 -2.060379999999999989e-01 4.388790000000000191e-01 7.669869999999999743e-01 -2.596200000000000174e-01 5.558710000000000040e-01 1.879760000000000042e-01 +1.403715409662139893e+09 -9.185179999999999456e-01 -2.095200000000000118e-01 4.483139999999999903e-01 7.687129999999999797e-01 -2.620219999999999771e-01 5.524059999999999526e-01 1.878110000000000057e-01 +1.403715409712140083e+09 -9.137530000000000374e-01 -2.127159999999999884e-01 4.577959999999999807e-01 7.710960000000000036e-01 -2.654099999999999793e-01 5.477880000000000527e-01 1.868070000000000008e-01 +1.403715409762140036e+09 -9.091500000000000137e-01 -2.161349999999999938e-01 4.674240000000000061e-01 7.736199999999999743e-01 -2.688929999999999931e-01 5.426889999999999770e-01 1.862709999999999921e-01 +1.403715409812139988e+09 -9.045410000000000394e-01 -2.192540000000000044e-01 4.774410000000000043e-01 7.761529999999999818e-01 -2.723920000000000230e-01 5.374269999999999881e-01 1.859079999999999899e-01 +1.403715409862139940e+09 -8.998180000000000067e-01 -2.224250000000000116e-01 4.880399999999999738e-01 7.780169999999999586e-01 -2.758550000000000169e-01 5.328289999999999971e-01 1.862439999999999929e-01 +1.403715409912139893e+09 -8.948580000000000423e-01 -2.256410000000000082e-01 4.986869999999999914e-01 7.802970000000000184e-01 -2.800710000000000144e-01 5.274839999999999529e-01 1.856269999999999865e-01 +1.403715409962140083e+09 -8.888460000000000250e-01 -2.302400000000000002e-01 5.099639999999999729e-01 7.822440000000000504e-01 -2.831830000000000180e-01 5.227779999999999649e-01 1.860229999999999939e-01 +1.403715410012140036e+09 -8.822130000000000249e-01 -2.349259999999999959e-01 5.208110000000000239e-01 7.831639999999999713e-01 -2.866699999999999804e-01 5.194539999999999713e-01 1.861240000000000117e-01 +1.403715410062139988e+09 -8.739249999999999519e-01 -2.407529999999999948e-01 5.320430000000000437e-01 7.830160000000000453e-01 -2.890559999999999796e-01 5.180299999999999905e-01 1.870259999999999978e-01 +1.403715410112139940e+09 -8.648770000000000069e-01 -2.471230000000000093e-01 5.438119999999999621e-01 7.811179999999999790e-01 -2.903540000000000010e-01 5.192940000000000333e-01 1.894280000000000130e-01 +1.403715410162139893e+09 -8.550060000000000437e-01 -2.542800000000000060e-01 5.553460000000000063e-01 7.781630000000000491e-01 -2.901210000000000178e-01 5.225220000000000420e-01 1.930360000000000131e-01 +1.403715410212140083e+09 -8.445880000000000054e-01 -2.616550000000000264e-01 5.644169999999999465e-01 7.750310000000000255e-01 -2.902930000000000232e-01 5.261510000000000353e-01 1.955040000000000111e-01 +1.403715410262140036e+09 -8.336069999999999869e-01 -2.691359999999999864e-01 5.702099999999999946e-01 7.720369999999999733e-01 -2.902520000000000100e-01 5.296370000000000244e-01 1.979819999999999913e-01 +1.403715410312139988e+09 -8.221840000000000259e-01 -2.766870000000000163e-01 5.725390000000000201e-01 7.696460000000000523e-01 -2.900530000000000053e-01 5.323809999999999931e-01 2.002140000000000031e-01 +1.403715410362139940e+09 -8.107389999999999874e-01 -2.841810000000000169e-01 5.717320000000000180e-01 7.679200000000000470e-01 -2.897150000000000003e-01 5.344630000000000214e-01 2.017730000000000079e-01 +1.403715410412139893e+09 -7.986969999999999903e-01 -2.916529999999999956e-01 5.695149999999999935e-01 7.671799999999999731e-01 -2.890050000000000119e-01 5.351949999999999763e-01 2.036590000000000067e-01 +1.403715410462140083e+09 -7.868760000000000199e-01 -2.989990000000000148e-01 5.663460000000000161e-01 7.673529999999999518e-01 -2.877100000000000213e-01 5.348279999999999701e-01 2.057940000000000047e-01 +1.403715410512140036e+09 -7.750259999999999927e-01 -3.065339999999999732e-01 5.634360000000000479e-01 7.682029999999999692e-01 -2.855539999999999745e-01 5.335769999999999680e-01 2.088530000000000109e-01 +1.403715410562139988e+09 -7.635629999999999917e-01 -3.134859999999999869e-01 5.605590000000000295e-01 7.685530000000000417e-01 -2.832069999999999865e-01 5.332280000000000353e-01 2.116319999999999868e-01 +1.403715410612139940e+09 -7.500010000000000288e-01 -3.197369999999999934e-01 5.576060000000000461e-01 7.693520000000000358e-01 -2.816890000000000227e-01 5.325130000000000141e-01 2.125509999999999899e-01 +1.403715410662139893e+09 -7.361290000000000333e-01 -3.256279999999999730e-01 5.548589999999999911e-01 7.694530000000000536e-01 -2.803510000000000169e-01 5.328389999999999516e-01 2.131389999999999951e-01 +1.403715410762140036e+09 -7.064799999999999969e-01 -3.359059999999999824e-01 5.503770000000000051e-01 7.669350000000000334e-01 -2.789590000000000125e-01 5.379340000000000233e-01 2.112310000000000021e-01 +1.403715410812139988e+09 -6.922509999999999497e-01 -3.407589999999999786e-01 5.492240000000000455e-01 7.628019999999999801e-01 -2.778900000000000259e-01 5.446870000000000323e-01 2.103009999999999879e-01 +1.403715410862139940e+09 -6.781920000000000170e-01 -3.452580000000000093e-01 5.488260000000000360e-01 7.596159999999999579e-01 -2.754420000000000202e-01 5.502099999999999769e-01 2.106770000000000032e-01 +1.403715410912139893e+09 -6.645339999999999581e-01 -3.480369999999999853e-01 5.469840000000000257e-01 7.573999999999999622e-01 -2.745360000000000023e-01 5.545069999999999721e-01 2.085599999999999954e-01 +1.403715410962140083e+09 -6.516469999999999763e-01 -3.495789999999999731e-01 5.445229999999999793e-01 7.579550000000000454e-01 -2.729829999999999757e-01 5.549119999999999608e-01 2.075019999999999920e-01 +1.403715411012140036e+09 -6.395349999999999646e-01 -3.495630000000000126e-01 5.407560000000000144e-01 7.599599999999999689e-01 -2.728639999999999954e-01 5.535649999999999737e-01 2.038919999999999899e-01 +1.403715411062139988e+09 -6.282889999999999864e-01 -3.486929999999999752e-01 5.369859999999999634e-01 7.623029999999999529e-01 -2.726040000000000130e-01 5.517330000000000290e-01 2.004279999999999951e-01 +1.403715411112139940e+09 -6.175720000000000098e-01 -3.470599999999999796e-01 5.333290000000000530e-01 7.650350000000000206e-01 -2.722709999999999853e-01 5.493040000000000145e-01 1.971160000000000134e-01 +1.403715411162139893e+09 -6.067090000000000538e-01 -3.447990000000000221e-01 5.298159999999999537e-01 7.668599999999999861e-01 -2.728300000000000169e-01 5.480150000000000299e-01 1.927949999999999942e-01 +1.403715411212140083e+09 -5.964540000000000397e-01 -3.423880000000000257e-01 5.270270000000000232e-01 7.675729999999999498e-01 -2.741609999999999880e-01 5.480399999999999716e-01 1.879349999999999909e-01 +1.403715411262140036e+09 -5.865209999999999591e-01 -3.396819999999999840e-01 5.246579999999999577e-01 7.679559999999999720e-01 -2.748749999999999805e-01 5.485179999999999501e-01 1.838909999999999989e-01 +1.403715411312139988e+09 -5.771169999999999911e-01 -3.369400000000000173e-01 5.228140000000000009e-01 7.670839999999999881e-01 -2.750980000000000092e-01 5.505529999999999591e-01 1.810930000000000040e-01 +1.403715411362139940e+09 -5.683200000000000474e-01 -3.342410000000000103e-01 5.212609999999999744e-01 7.651820000000000288e-01 -2.746290000000000120e-01 5.539939999999999864e-01 1.793500000000000094e-01 +1.403715411412139893e+09 -5.599560000000000093e-01 -3.319130000000000136e-01 5.196159999999999668e-01 7.625760000000000316e-01 -2.742499999999999938e-01 5.583430000000000337e-01 1.775299999999999934e-01 +1.403715411462140083e+09 -5.526699999999999946e-01 -3.297149999999999803e-01 5.179209999999999647e-01 7.597340000000000204e-01 -2.734650000000000136e-01 5.629260000000000375e-01 1.764489999999999947e-01 +1.403715411512140036e+09 -5.463550000000000351e-01 -3.276020000000000043e-01 5.156119999999999592e-01 7.586610000000000298e-01 -2.718559999999999865e-01 5.650519999999999987e-01 1.767569999999999975e-01 +1.403715411562139988e+09 -5.417330000000000201e-01 -3.252050000000000218e-01 5.129350000000000298e-01 7.599829999999999641e-01 -2.702519999999999922e-01 5.639870000000000161e-01 1.769399999999999862e-01 +1.403715411612139940e+09 -5.382649999999999935e-01 -3.227570000000000161e-01 5.103839999999999488e-01 7.620409999999999684e-01 -2.686700000000000199e-01 5.617520000000000291e-01 1.776099999999999901e-01 +1.403715411662139893e+09 -5.356999999999999540e-01 -3.202690000000000259e-01 5.076859999999999706e-01 7.646230000000000526e-01 -2.671970000000000178e-01 5.588109999999999467e-01 1.780130000000000046e-01 +1.403715411712140083e+09 -5.339439999999999742e-01 -3.179139999999999744e-01 5.051400000000000334e-01 7.664490000000000469e-01 -2.658530000000000060e-01 5.568370000000000264e-01 1.783540000000000125e-01 +1.403715411762140036e+09 -5.322519999999999474e-01 -3.155580000000000052e-01 5.022100000000000453e-01 7.680360000000000520e-01 -2.644710000000000116e-01 5.551700000000000523e-01 1.787779999999999925e-01 +1.403715411812139988e+09 -5.317629999999999857e-01 -3.129160000000000275e-01 4.993699999999999806e-01 7.685539999999999594e-01 -2.631709999999999883e-01 5.548459999999999503e-01 1.794759999999999966e-01 +1.403715411862139940e+09 -5.318619999999999459e-01 -3.100280000000000258e-01 4.959450000000000247e-01 7.693750000000000311e-01 -2.624389999999999779e-01 5.541110000000000202e-01 1.793019999999999892e-01 +1.403715411912139893e+09 -5.325159999999999894e-01 -3.068670000000000009e-01 4.928279999999999883e-01 7.696089999999999876e-01 -2.620259999999999811e-01 5.540479999999999849e-01 1.790940000000000032e-01 +1.403715411962140083e+09 -5.336920000000000552e-01 -3.035419999999999785e-01 4.898930000000000229e-01 7.695859999999999923e-01 -2.622320000000000206e-01 5.543369999999999687e-01 1.779969999999999886e-01 +1.403715412012140036e+09 -5.351169999999999538e-01 -3.002020000000000244e-01 4.869319999999999760e-01 7.698329999999999895e-01 -2.623210000000000264e-01 5.541430000000000522e-01 1.773980000000000001e-01 +1.403715412062139988e+09 -5.371310000000000251e-01 -2.967400000000000038e-01 4.838060000000000138e-01 7.701240000000000308e-01 -2.627630000000000243e-01 5.537670000000000092e-01 1.766540000000000055e-01 +1.403715412112139940e+09 -5.395280000000000076e-01 -2.931770000000000209e-01 4.810619999999999896e-01 7.702900000000000302e-01 -2.630689999999999973e-01 5.535339999999999705e-01 1.762039999999999995e-01 +1.403715412162139893e+09 -5.423409999999999620e-01 -2.894559999999999911e-01 4.781650000000000067e-01 7.713799999999999546e-01 -2.632660000000000000e-01 5.518640000000000212e-01 1.763790000000000080e-01 +1.403715412212140083e+09 -5.453059999999999574e-01 -2.855900000000000105e-01 4.752370000000000205e-01 7.721430000000000238e-01 -2.634299999999999975e-01 5.507459999999999578e-01 1.762910000000000033e-01 +1.403715412262140036e+09 -5.486839999999999495e-01 -2.815889999999999782e-01 4.720650000000000124e-01 7.726960000000000495e-01 -2.633730000000000238e-01 5.498769999999999492e-01 1.766689999999999927e-01 +1.403715412312139988e+09 -5.523890000000000189e-01 -2.775719999999999854e-01 4.687060000000000115e-01 7.732050000000000312e-01 -2.634779999999999900e-01 5.490720000000000045e-01 1.767869999999999997e-01 +1.403715412362139940e+09 -5.563219999999999832e-01 -2.735130000000000061e-01 4.656120000000000259e-01 7.736610000000000431e-01 -2.639059999999999739e-01 5.482519999999999616e-01 1.767009999999999970e-01 +1.403715412412139893e+09 -5.602470000000000505e-01 -2.694159999999999888e-01 4.624679999999999902e-01 7.740259999999999918e-01 -2.643220000000000014e-01 5.475970000000000004e-01 1.765079999999999982e-01 +1.403715412462140083e+09 -5.642009999999999525e-01 -2.652680000000000038e-01 4.595000000000000195e-01 7.748289999999999900e-01 -2.653059999999999863e-01 5.462660000000000293e-01 1.756310000000000093e-01 +1.403715412512140036e+09 -5.682310000000000416e-01 -2.611490000000000200e-01 4.567590000000000261e-01 7.756570000000000409e-01 -2.659110000000000085e-01 5.449340000000000295e-01 1.751979999999999926e-01 +1.403715412562139988e+09 -5.721479999999999899e-01 -2.572989999999999999e-01 4.539059999999999762e-01 7.764630000000000143e-01 -2.664549999999999974e-01 5.436860000000000026e-01 1.746759999999999979e-01 +1.403715412612139940e+09 -5.758990000000000498e-01 -2.536280000000000201e-01 4.516669999999999852e-01 7.771630000000000482e-01 -2.662300000000000222e-01 5.425689999999999680e-01 1.753780000000000061e-01 +1.403715412662139893e+09 -5.793559999999999821e-01 -2.502949999999999897e-01 4.496310000000000029e-01 7.776480000000000059e-01 -2.662300000000000222e-01 5.418760000000000243e-01 1.753760000000000041e-01 +1.403715412712140083e+09 -5.826970000000000205e-01 -2.469919999999999893e-01 4.480609999999999871e-01 7.789239999999999498e-01 -2.660939999999999972e-01 5.400500000000000300e-01 1.755490000000000106e-01 +1.403715412762140036e+09 -5.858259999999999579e-01 -2.442360000000000086e-01 4.468610000000000082e-01 7.795760000000000467e-01 -2.660230000000000095e-01 5.390559999999999796e-01 1.758170000000000011e-01 +1.403715412812139988e+09 -5.887630000000000363e-01 -2.414590000000000070e-01 4.457400000000000251e-01 7.802219999999999711e-01 -2.660449999999999759e-01 5.380580000000000362e-01 1.759749999999999925e-01 +1.403715412862139940e+09 -5.912969999999999615e-01 -2.388079999999999925e-01 4.447889999999999899e-01 7.807720000000000216e-01 -2.660009999999999875e-01 5.373050000000000326e-01 1.759060000000000068e-01 +1.403715412912139893e+09 -5.933239999999999625e-01 -2.363429999999999975e-01 4.441599999999999993e-01 7.808880000000000265e-01 -2.658739999999999992e-01 5.370610000000000106e-01 1.763260000000000105e-01 +1.403715412962140083e+09 -5.955819999999999448e-01 -2.335770000000000068e-01 4.441229999999999900e-01 7.803029999999999688e-01 -2.658619999999999872e-01 5.377790000000000070e-01 1.767420000000000102e-01 +1.403715413012140036e+09 -5.968590000000000284e-01 -2.315730000000000011e-01 4.432949999999999946e-01 7.790690000000000115e-01 -2.653909999999999880e-01 5.394280000000000186e-01 1.778639999999999943e-01 +1.403715413062139988e+09 -5.979160000000000030e-01 -2.294080000000000008e-01 4.401089999999999725e-01 7.782759999999999678e-01 -2.648719999999999963e-01 5.403689999999999882e-01 1.792519999999999947e-01 +1.403715413112139940e+09 -5.986650000000000027e-01 -2.272240000000000093e-01 4.346240000000000103e-01 7.775879999999999459e-01 -2.644110000000000071e-01 5.412829999999999586e-01 1.801590000000000136e-01 +1.403715413162139893e+09 -5.991229999999999611e-01 -2.249700000000000033e-01 4.271240000000000037e-01 7.766899999999999915e-01 -2.642439999999999789e-01 5.424520000000000453e-01 1.807560000000000000e-01 +1.403715413212140083e+09 -5.996010000000000506e-01 -2.225910000000000111e-01 4.170309999999999850e-01 7.761400000000000521e-01 -2.636499999999999955e-01 5.432230000000000114e-01 1.816709999999999992e-01 +1.403715413262140036e+09 -6.002030000000000420e-01 -2.199089999999999934e-01 4.044980000000000242e-01 7.754039999999999822e-01 -2.638639999999999874e-01 5.442540000000000155e-01 1.814179999999999959e-01 +1.403715413312139988e+09 -6.009400000000000297e-01 -2.169069999999999887e-01 3.896410000000000151e-01 7.742440000000000433e-01 -2.653630000000000155e-01 5.457859999999999934e-01 1.795710000000000084e-01 +1.403715413362139940e+09 -6.016299999999999981e-01 -2.138660000000000005e-01 3.737469999999999959e-01 7.728500000000000369e-01 -2.674030000000000018e-01 5.477469999999999839e-01 1.765549999999999897e-01 +1.403715413412139893e+09 -6.024119999999999475e-01 -2.110609999999999986e-01 3.583620000000000139e-01 7.716190000000000548e-01 -2.694619999999999793e-01 5.493689999999999962e-01 1.737489999999999868e-01 +1.403715413462140083e+09 -6.034760000000000124e-01 -2.085380000000000011e-01 3.439980000000000260e-01 7.707039999999999447e-01 -2.712109999999999799e-01 5.505449999999999511e-01 1.713490000000000013e-01 +1.403715413512140036e+09 -6.050419999999999687e-01 -2.064469999999999916e-01 3.309570000000000012e-01 7.700630000000000530e-01 -2.719690000000000163e-01 5.514339999999999797e-01 1.701660000000000117e-01 +1.403715413562139988e+09 -6.066899999999999515e-01 -2.052350000000000008e-01 3.190549999999999775e-01 7.701099999999999612e-01 -2.717350000000000043e-01 5.513149999999999995e-01 1.707100000000000006e-01 +1.403715413612139940e+09 -6.093460000000000543e-01 -2.038899999999999879e-01 3.091249999999999831e-01 7.700879999999999947e-01 -2.709139999999999882e-01 5.512310000000000265e-01 1.723790000000000044e-01 +1.403715413662139893e+09 -6.125920000000000254e-01 -2.030510000000000093e-01 3.004069999999999796e-01 7.700090000000000545e-01 -2.693880000000000163e-01 5.513280000000000403e-01 1.747980000000000089e-01 +1.403715413712140083e+09 -6.161149999999999682e-01 -2.022319999999999951e-01 2.925610000000000155e-01 7.700740000000000363e-01 -2.674360000000000070e-01 5.512200000000000433e-01 1.778220000000000078e-01 +1.403715413762140036e+09 -6.199430000000000218e-01 -2.013379999999999892e-01 2.838910000000000045e-01 7.707340000000000302e-01 -2.662610000000000254e-01 5.501399999999999624e-01 1.800559999999999938e-01 +1.403715413812139988e+09 -6.239679999999999671e-01 -2.003929999999999878e-01 2.736109999999999931e-01 7.715440000000000076e-01 -2.656999999999999917e-01 5.488939999999999930e-01 1.812179999999999902e-01 +1.403715413862139940e+09 -6.279409999999999714e-01 -1.991080000000000072e-01 2.618690000000000184e-01 7.723520000000000385e-01 -2.652220000000000133e-01 5.476149999999999629e-01 1.823420000000000041e-01 +1.403715413912139893e+09 -6.324689999999999479e-01 -1.979430000000000078e-01 2.490420000000000134e-01 7.723079999999999945e-01 -2.645379999999999954e-01 5.476769999999999694e-01 1.833289999999999920e-01 +1.403715413962140083e+09 -6.365300000000000402e-01 -1.960189999999999988e-01 2.365210000000000090e-01 7.721700000000000230e-01 -2.631189999999999918e-01 5.479650000000000354e-01 1.850819999999999965e-01 +1.403715414012140036e+09 -6.405509999999999815e-01 -1.935260000000000036e-01 2.254269999999999885e-01 7.722860000000000280e-01 -2.626740000000000186e-01 5.477130000000000054e-01 1.859770000000000034e-01 +1.403715414062139988e+09 -6.447089999999999765e-01 -1.903410000000000102e-01 2.170140000000000124e-01 7.727359999999999784e-01 -2.628630000000000133e-01 5.471139999999999892e-01 1.856039999999999912e-01 +1.403715414112139940e+09 -6.488760000000000083e-01 -1.863200000000000134e-01 2.113680000000000003e-01 7.741320000000000423e-01 -2.633369999999999878e-01 5.449910000000000032e-01 1.853579999999999950e-01 +1.403715414162139893e+09 -6.529779999999999474e-01 -1.814810000000000034e-01 2.079199999999999937e-01 7.764729999999999688e-01 -2.645170000000000021e-01 5.415339999999999598e-01 1.840140000000000109e-01 +1.403715414212140083e+09 -6.560610000000000053e-01 -1.769199999999999939e-01 2.076300000000000090e-01 7.798169999999999824e-01 -2.662979999999999792e-01 5.363630000000000342e-01 1.824459999999999971e-01 +1.403715414262140036e+09 -6.587579999999999547e-01 -1.723260000000000070e-01 2.097320000000000018e-01 7.827619999999999578e-01 -2.676810000000000023e-01 5.318629999999999747e-01 1.809749999999999970e-01 +1.403715414312139988e+09 -6.602569999999999828e-01 -1.682480000000000087e-01 2.134230000000000016e-01 7.856630000000000003e-01 -2.690799999999999859e-01 5.273400000000000309e-01 1.795589999999999964e-01 +1.403715414362139940e+09 -6.604400000000000270e-01 -1.649460000000000093e-01 2.174139999999999961e-01 7.879709999999999770e-01 -2.694710000000000161e-01 5.236680000000000224e-01 1.796089999999999909e-01 +1.403715414412139893e+09 -6.592139999999999667e-01 -1.620699999999999918e-01 2.210779999999999967e-01 7.886630000000000029e-01 -2.691470000000000251e-01 5.225750000000000117e-01 1.802400000000000113e-01 +1.403715414462140083e+09 -6.566990000000000327e-01 -1.596879999999999966e-01 2.234510000000000107e-01 7.884430000000000049e-01 -2.686509999999999732e-01 5.228639999999999954e-01 1.811000000000000110e-01 +1.403715414512140036e+09 -6.518209999999999837e-01 -1.579290000000000138e-01 2.268550000000000011e-01 7.876319999999999988e-01 -2.678820000000000090e-01 5.240010000000000501e-01 1.824780000000000013e-01 +1.403715414562139988e+09 -6.469329999999999803e-01 -1.558620000000000005e-01 2.258390000000000120e-01 7.855969999999999898e-01 -2.668599999999999861e-01 5.270340000000000025e-01 1.840080000000000049e-01 +1.403715414612139940e+09 -6.411379999999999857e-01 -1.536919999999999953e-01 2.234160000000000035e-01 7.832219999999999738e-01 -2.655710000000000015e-01 5.305480000000000196e-01 1.858869999999999967e-01 +1.403715414662139893e+09 -6.347570000000000157e-01 -1.509489999999999998e-01 2.201960000000000028e-01 7.809669999999999668e-01 -2.658690000000000220e-01 5.337560000000000082e-01 1.857640000000000124e-01 +1.403715414712140083e+09 -6.275110000000000410e-01 -1.479409999999999892e-01 2.159520000000000051e-01 7.782360000000000388e-01 -2.667889999999999984e-01 5.374630000000000241e-01 1.852209999999999968e-01 +1.403715414762140036e+09 -6.200029999999999708e-01 -1.446179999999999966e-01 2.108889999999999931e-01 7.757429999999999604e-01 -2.686729999999999952e-01 5.407830000000000137e-01 1.832799999999999985e-01 +1.403715414812139988e+09 -6.126439999999999664e-01 -1.415410000000000001e-01 2.047160000000000091e-01 7.738939999999999708e-01 -2.717240000000000211e-01 5.429720000000000102e-01 1.801000000000000101e-01 +1.403715414862139940e+09 -6.047409999999999730e-01 -1.388230000000000020e-01 1.974499999999999866e-01 7.717420000000000391e-01 -2.758010000000000184e-01 5.454069999999999752e-01 1.757269999999999943e-01 +1.403715414912139893e+09 -5.973690000000000389e-01 -1.365790000000000060e-01 1.887469999999999981e-01 7.692269999999999941e-01 -2.802629999999999844e-01 5.481909999999999838e-01 1.709640000000000049e-01 +1.403715414962140083e+09 -5.905749999999999611e-01 -1.348489999999999966e-01 1.794350000000000112e-01 7.673569999999999558e-01 -2.841699999999999782e-01 5.500249999999999861e-01 1.669829999999999925e-01 +1.403715415012140036e+09 -5.847520000000000495e-01 -1.336070000000000035e-01 1.697089999999999987e-01 7.653309999999999835e-01 -2.879189999999999805e-01 5.519089999999999829e-01 1.636050000000000004e-01 +1.403715415062139988e+09 -5.797080000000000011e-01 -1.330939999999999901e-01 1.593990000000000129e-01 7.637890000000000512e-01 -2.908979999999999899e-01 5.531289999999999818e-01 1.614089999999999969e-01 +1.403715415112139940e+09 -5.775780000000000358e-01 -1.323840000000000017e-01 1.475219999999999865e-01 7.625690000000000524e-01 -2.932080000000000242e-01 5.538680000000000270e-01 1.604579999999999895e-01 +1.403715415162139893e+09 -5.742699999999999472e-01 -1.327899999999999914e-01 1.371449999999999891e-01 7.615680000000000227e-01 -2.953950000000000187e-01 5.541709999999999692e-01 1.601569999999999938e-01 +1.403715415212140083e+09 -5.727320000000000189e-01 -1.336700000000000110e-01 1.273890000000000022e-01 7.604720000000000368e-01 -2.964149999999999840e-01 5.546980000000000244e-01 1.616499999999999881e-01 +1.403715415312139988e+09 -5.730819999999999803e-01 -1.385520000000000085e-01 1.101000000000000034e-01 7.609949999999999770e-01 -2.933749999999999969e-01 5.528229999999999533e-01 1.708919999999999884e-01 +1.403715415362139940e+09 -5.742699999999999472e-01 -1.425629999999999953e-01 1.029319999999999957e-01 7.624889999999999723e-01 -2.901400000000000090e-01 5.501230000000000286e-01 1.783089999999999953e-01 +1.403715415412139893e+09 -5.761960000000000415e-01 -1.467400000000000093e-01 9.751400000000000345e-02 7.632560000000000455e-01 -2.863550000000000262e-01 5.482510000000000439e-01 1.867139999999999911e-01 +1.403715415462140083e+09 -5.776440000000000463e-01 -1.507789999999999964e-01 9.269700000000000162e-02 7.654919999999999503e-01 -2.829900000000000193e-01 5.442590000000000483e-01 1.942170000000000007e-01 +1.403715415512140036e+09 -5.794479999999999631e-01 -1.542330000000000090e-01 8.976900000000000157e-02 7.658719999999999972e-01 -2.800670000000000104e-01 5.429469999999999574e-01 2.005280000000000118e-01 +1.403715415562139988e+09 -5.809969999999999857e-01 -1.568269999999999942e-01 8.686299999999999577e-02 7.663180000000000547e-01 -2.787490000000000245e-01 5.417779999999999818e-01 2.037970000000000059e-01 +1.403715415612139940e+09 -5.823479999999999768e-01 -1.585640000000000105e-01 8.285299999999999609e-02 7.658169999999999700e-01 -2.775420000000000109e-01 5.419239999999999613e-01 2.069120000000000126e-01 +1.403715415662139893e+09 -5.838719999999999466e-01 -1.596190000000000109e-01 7.629700000000000371e-02 7.655539999999999567e-01 -2.771649999999999947e-01 5.415630000000000166e-01 2.093210000000000071e-01 +1.403715415712140083e+09 -5.852770000000000472e-01 -1.598440000000000139e-01 6.715699999999999448e-02 7.656690000000000440e-01 -2.776460000000000039e-01 5.408889999999999532e-01 2.100069999999999992e-01 +1.403715415762140036e+09 -5.860980000000000079e-01 -1.607010000000000105e-01 6.321899999999999742e-02 7.663130000000000219e-01 -2.787680000000000158e-01 5.400030000000000108e-01 2.084449999999999914e-01 +1.403715415812139988e+09 -5.856249999999999512e-01 -1.603100000000000080e-01 6.705600000000000449e-02 7.663510000000000044e-01 -2.778100000000000014e-01 5.399739999999999540e-01 2.096580000000000110e-01 +1.403715415862139940e+09 -5.849839999999999485e-01 -1.589530000000000109e-01 6.951400000000000634e-02 7.651980000000000448e-01 -2.771170000000000022e-01 5.416050000000000031e-01 2.105760000000000132e-01 +1.403715415912139893e+09 -5.834270000000000289e-01 -1.565120000000000122e-01 6.949299999999999922e-02 7.636359999999999815e-01 -2.776600000000000179e-01 5.435680000000000511e-01 2.104709999999999914e-01 +1.403715415962140083e+09 -5.821490000000000276e-01 -1.537380000000000135e-01 6.729799999999999671e-02 7.638359999999999594e-01 -2.772120000000000140e-01 5.434740000000000126e-01 2.105809999999999904e-01 +1.403715416012140036e+09 -5.820760000000000378e-01 -1.534639999999999893e-01 6.615999999999999659e-02 7.660240000000000382e-01 -2.763539999999999885e-01 5.408650000000000402e-01 2.104769999999999974e-01 +1.403715416062139988e+09 -5.826860000000000372e-01 -1.542630000000000112e-01 6.722799999999999609e-02 7.660200000000000342e-01 -2.759719999999999951e-01 5.405250000000000332e-01 2.118609999999999938e-01 +1.403715416112139940e+09 -5.826270000000000060e-01 -1.542850000000000055e-01 6.764799999999999980e-02 7.655250000000000110e-01 -2.763240000000000141e-01 5.409270000000000467e-01 2.121679999999999955e-01 +1.403715416162139893e+09 -5.824920000000000098e-01 -1.540940000000000087e-01 6.714900000000000035e-02 7.651999999999999913e-01 -2.766040000000000165e-01 5.413599999999999524e-01 2.118690000000000018e-01 +1.403715416212140083e+09 -5.827020000000000532e-01 -1.543519999999999892e-01 6.678099999999999314e-02 7.657990000000000075e-01 -2.775429999999999842e-01 5.404790000000000427e-01 2.107219999999999926e-01 +1.403715416262140036e+09 -5.828579999999999872e-01 -1.540320000000000022e-01 6.608899999999999497e-02 7.664459999999999607e-01 -2.780400000000000094e-01 5.397030000000000438e-01 2.097030000000000005e-01 +1.403715416312139988e+09 -5.831520000000000037e-01 -1.539840000000000098e-01 6.563800000000000190e-02 7.665159999999999751e-01 -2.782990000000000186e-01 5.396279999999999966e-01 2.092940000000000078e-01 +1.403715416362139940e+09 -5.831840000000000357e-01 -1.549929999999999919e-01 6.526300000000000157e-02 7.669259999999999966e-01 -2.783349999999999991e-01 5.391070000000000029e-01 2.090889999999999971e-01 +1.403715416412139893e+09 -5.832610000000000294e-01 -1.553990000000000093e-01 6.524199999999999444e-02 7.670139999999999736e-01 -2.784909999999999886e-01 5.389869999999999939e-01 2.088649999999999951e-01 +1.403715416462140083e+09 -5.833249999999999824e-01 -1.554290000000000116e-01 6.496000000000000385e-02 7.673680000000000501e-01 -2.785750000000000171e-01 5.385379999999999612e-01 2.086129999999999929e-01 +1.403715416512140036e+09 -5.833909999999999929e-01 -1.551289999999999891e-01 6.455600000000000227e-02 7.672109999999999763e-01 -2.787970000000000170e-01 5.386739999999999862e-01 2.085400000000000031e-01 +1.403715416562139988e+09 -5.836000000000000076e-01 -1.550489999999999924e-01 6.443799999999999528e-02 7.669390000000000374e-01 -2.784530000000000061e-01 5.391340000000000021e-01 2.088150000000000006e-01 +1.403715416612139940e+09 -5.836559999999999526e-01 -1.552920000000000134e-01 6.426900000000000668e-02 7.672360000000000291e-01 -2.785400000000000098e-01 5.387509999999999799e-01 2.085930000000000006e-01 +1.403715416662139893e+09 -5.836160000000000236e-01 -1.553180000000000116e-01 6.414000000000000257e-02 7.672550000000000203e-01 -2.788399999999999768e-01 5.387429999999999719e-01 2.081459999999999977e-01 +1.403715416712140083e+09 -5.836770000000000014e-01 -1.551250000000000129e-01 6.398299999999999821e-02 7.672940000000000316e-01 -2.787919999999999843e-01 5.387180000000000302e-01 2.081290000000000084e-01 +1.403715416762140036e+09 -5.837419999999999831e-01 -1.549840000000000106e-01 6.388900000000000134e-02 7.673499999999999766e-01 -2.788200000000000123e-01 5.386849999999999694e-01 2.079719999999999902e-01 +1.403715416812139988e+09 -5.837160000000000126e-01 -1.550269999999999981e-01 6.388299999999999534e-02 7.670860000000000456e-01 -2.787250000000000005e-01 5.390669999999999629e-01 2.080809999999999882e-01 +1.403715416862139940e+09 -5.834909999999999819e-01 -1.552709999999999924e-01 6.388199999999999434e-02 7.673569999999999558e-01 -2.788120000000000043e-01 5.387429999999999719e-01 2.078039999999999887e-01 +1.403715416912139893e+09 -5.833409999999999984e-01 -1.555630000000000068e-01 6.387800000000000422e-02 7.675560000000000160e-01 -2.789909999999999890e-01 5.384590000000000209e-01 2.075660000000000005e-01 +1.403715416962140083e+09 -5.833000000000000407e-01 -1.555709999999999871e-01 6.391099999999999559e-02 7.674180000000000446e-01 -2.788120000000000043e-01 5.386950000000000349e-01 2.077060000000000017e-01 +1.403715417012140036e+09 -5.832370000000000054e-01 -1.555600000000000038e-01 6.383700000000000485e-02 7.672160000000000091e-01 -2.788539999999999908e-01 5.390000000000000346e-01 2.076040000000000108e-01 +1.403715417062139988e+09 -5.831410000000000204e-01 -1.558219999999999883e-01 6.382699999999999485e-02 7.672830000000000483e-01 -2.787569999999999770e-01 5.389279999999999626e-01 2.076729999999999965e-01 +1.403715417112139940e+09 -5.829699999999999882e-01 -1.561639999999999973e-01 6.380099999999999660e-02 7.674330000000000318e-01 -2.789420000000000233e-01 5.387239999999999807e-01 2.073979999999999990e-01 +1.403715417162139893e+09 -5.829010000000000025e-01 -1.563539999999999930e-01 6.382400000000000573e-02 7.674429999999999863e-01 -2.789909999999999890e-01 5.387100000000000222e-01 2.073299999999999865e-01 +1.403715417212140083e+09 -5.828839999999999577e-01 -1.563299999999999967e-01 6.381199999999999373e-02 7.673079999999999901e-01 -2.789249999999999785e-01 5.389230000000000409e-01 2.073649999999999938e-01 +1.403715417262140036e+09 -5.828550000000000120e-01 -1.563160000000000105e-01 6.376400000000000123e-02 7.673280000000000101e-01 -2.788990000000000080e-01 5.389319999999999666e-01 2.073059999999999903e-01 +1.403715417312139988e+09 -5.828489999999999505e-01 -1.564139999999999975e-01 6.376600000000000323e-02 7.672369999999999468e-01 -2.789019999999999833e-01 5.390479999999999716e-01 2.073359999999999925e-01 +1.403715417362139940e+09 -5.827639999999999487e-01 -1.566170000000000062e-01 6.371000000000000274e-02 7.673820000000000086e-01 -2.789349999999999885e-01 5.388889999999999514e-01 2.071699999999999930e-01 +1.403715417412139893e+09 -5.827250000000000485e-01 -1.567369999999999874e-01 6.367299999999999349e-02 7.673870000000000413e-01 -2.790079999999999782e-01 5.388530000000000264e-01 2.071449999999999958e-01 +1.403715417462140083e+09 -5.827390000000000070e-01 -1.566879999999999939e-01 6.361500000000000488e-02 7.673280000000000101e-01 -2.789889999999999870e-01 5.389580000000000481e-01 2.071159999999999946e-01 +1.403715417562139988e+09 -5.828179999999999472e-01 -1.567870000000000097e-01 6.358900000000000663e-02 7.672579999999999956e-01 -2.789820000000000078e-01 5.390580000000000371e-01 2.071260000000000046e-01 +1.403715417612139940e+09 -5.827109999999999790e-01 -1.569029999999999869e-01 6.354799999999999338e-02 7.673200000000000021e-01 -2.790400000000000102e-01 5.389650000000000274e-01 2.070619999999999961e-01 +1.403715417662139893e+09 -5.826099999999999612e-01 -1.569029999999999869e-01 6.350999999999999701e-02 7.673640000000000461e-01 -2.790250000000000230e-01 5.389129999999999754e-01 2.070529999999999871e-01 +1.403715417712140083e+09 -5.825219999999999843e-01 -1.568469999999999864e-01 6.350600000000000689e-02 7.672889999999999988e-01 -2.790259999999999962e-01 5.390289999999999804e-01 2.070259999999999878e-01 +1.403715417762140036e+09 -5.824399999999999578e-01 -1.568070000000000019e-01 6.350300000000000389e-02 7.672539999999999916e-01 -2.789659999999999918e-01 5.390920000000000156e-01 2.070710000000000051e-01 +1.403715417812139988e+09 -5.823390000000000510e-01 -1.568460000000000132e-01 6.347200000000000064e-02 7.672930000000000028e-01 -2.790059999999999762e-01 5.390200000000000546e-01 2.070629999999999971e-01 +1.403715417862139940e+09 -5.822650000000000325e-01 -1.569000000000000117e-01 6.345299999999999552e-02 7.673050000000000148e-01 -2.789980000000000238e-01 5.389909999999999979e-01 2.071050000000000113e-01 +1.403715417912139893e+09 -5.821849999999999525e-01 -1.568740000000000134e-01 6.341299999999999715e-02 7.673189999999999733e-01 -2.789719999999999978e-01 5.389709999999999779e-01 2.071379999999999888e-01 +1.403715417962140083e+09 -5.821290000000000076e-01 -1.567900000000000127e-01 6.336899999999999478e-02 7.672809999999999908e-01 -2.789179999999999993e-01 5.390580000000000371e-01 2.071240000000000026e-01 +1.403715418012140036e+09 -5.820990000000000331e-01 -1.567639999999999867e-01 6.334499999999999853e-02 7.672400000000000331e-01 -2.788990000000000080e-01 5.391249999999999654e-01 2.071320000000000106e-01 +1.403715418062139988e+09 -5.820509999999999851e-01 -1.568019999999999969e-01 6.329999999999999516e-02 7.672799999999999621e-01 -2.788970000000000060e-01 5.390749999999999709e-01 2.071139999999999926e-01 +1.403715418112139940e+09 -5.819830000000000281e-01 -1.568090000000000039e-01 6.322500000000000342e-02 7.673079999999999901e-01 -2.789070000000000160e-01 5.390260000000000051e-01 2.071240000000000026e-01 +1.403715418162139893e+09 -5.819520000000000248e-01 -1.567530000000000034e-01 6.315300000000000080e-02 7.672799999999999621e-01 -2.788939999999999753e-01 5.390639999999999876e-01 2.071439999999999948e-01 +1.403715418212140083e+09 -5.819490000000000496e-01 -1.566859999999999919e-01 6.309399999999999731e-02 7.672590000000000243e-01 -2.788849999999999940e-01 5.390920000000000156e-01 2.071639999999999870e-01 +1.403715418262140036e+09 -5.819450000000000456e-01 -1.566700000000000037e-01 6.302199999999999469e-02 7.672060000000000546e-01 -2.788599999999999968e-01 5.391660000000000341e-01 2.071989999999999943e-01 +1.403715418312139988e+09 -5.819100000000000383e-01 -1.567109999999999892e-01 6.294199999999999795e-02 7.672299999999999676e-01 -2.788860000000000228e-01 5.391270000000000229e-01 2.071780000000000010e-01 +1.403715418362139940e+09 -5.818940000000000223e-01 -1.567330000000000112e-01 6.286600000000000521e-02 7.672430000000000083e-01 -2.788539999999999908e-01 5.391249999999999654e-01 2.071800000000000030e-01 +1.403715418412139893e+09 -5.818950000000000511e-01 -1.566950000000000010e-01 6.279500000000000359e-02 7.672029999999999683e-01 -2.788320000000000243e-01 5.391909999999999759e-01 2.071860000000000090e-01 +1.403715418462140083e+09 -5.818480000000000318e-01 -1.566510000000000125e-01 6.273499999999999910e-02 7.671989999999999643e-01 -2.788070000000000270e-01 5.392010000000000414e-01 2.072039999999999993e-01 +1.403715418512140036e+09 -5.818109999999999671e-01 -1.566359999999999975e-01 6.268700000000000661e-02 7.672170000000000378e-01 -2.787780000000000258e-01 5.392010000000000414e-01 2.071800000000000030e-01 +1.403715418562139988e+09 -5.818210000000000326e-01 -1.565930000000000100e-01 6.260899999999999799e-02 7.672160000000000091e-01 -2.787899999999999823e-01 5.392000000000000126e-01 2.071709999999999940e-01 +1.403715418612139940e+09 -5.817830000000000501e-01 -1.565419999999999867e-01 6.257699999999999374e-02 7.671989999999999643e-01 -2.788610000000000255e-01 5.392019999999999591e-01 2.071320000000000106e-01 +1.403715418662139893e+09 -5.817560000000000509e-01 -1.564989999999999992e-01 6.255299999999999749e-02 7.671679999999999611e-01 -2.788289999999999935e-01 5.392439999999999456e-01 2.071810000000000040e-01 +1.403715418712140083e+09 -5.817130000000000356e-01 -1.564750000000000030e-01 6.254099999999999937e-02 7.671759999999999691e-01 -2.787819999999999743e-01 5.392430000000000279e-01 2.072170000000000123e-01 +1.403715418762140036e+09 -5.816670000000000451e-01 -1.564939999999999942e-01 6.252000000000000612e-02 7.671729999999999938e-01 -2.788019999999999943e-01 5.392559999999999576e-01 2.071659999999999890e-01 diff --git a/test/demos/ape_demo.sh b/test/demos/ape_demo.sh index 1108d634..38713000 100755 --- a/test/demos/ape_demo.sh +++ b/test/demos/ape_demo.sh @@ -34,4 +34,7 @@ log "run multiple and save results" log "first..." echo_and_run evo_ape kitti ../data/KITTI_00_gt.txt ../data/KITTI_00_ORB.txt -a --save_results ORB_ape.zip log "second..." -echo_and_run evo_ape kitti ../data/KITTI_00_gt.txt ../data/KITTI_00_SPTAM.txt -a --save_results SPTAM_ape.zip \ No newline at end of file +echo_and_run evo_ape kitti ../data/KITTI_00_gt.txt ../data/KITTI_00_SPTAM.txt -a --save_results SPTAM_ape.zip + +log "perform yaw-only alignment for visual-inertial trajectory" +echo_and_run evo_ape tum ../data/V101_gt.txt ../data/V101_openvins.txt -a --yaw_only -v $p \ No newline at end of file diff --git a/test/demos/rpe_demo.sh b/test/demos/rpe_demo.sh index 9630c184..bd0791dc 100755 --- a/test/demos/rpe_demo.sh +++ b/test/demos/rpe_demo.sh @@ -34,4 +34,7 @@ log "run multiple and save results" log "first..." echo_and_run evo_rpe kitti ../data/KITTI_00_gt.txt ../data/KITTI_00_ORB.txt -d 10 -u m --save_results ORB_rpe.zip log "second..." -echo_and_run evo_rpe kitti ../data/KITTI_00_gt.txt ../data/KITTI_00_SPTAM.txt -d 10 -u m --save_results SPTAM_rpe.zip \ No newline at end of file +echo_and_run evo_rpe kitti ../data/KITTI_00_gt.txt ../data/KITTI_00_SPTAM.txt -d 10 -u m --save_results SPTAM_rpe.zip + +log "perform yaw-only alignment for visual-inertial trajectory" +echo_and_run evo_rpe tum ../data/V101_gt.txt ../data/V101_openvins.txt -a --yaw_only -v $p -d 1 -u m \ No newline at end of file diff --git a/test/demos/traj_demo.sh b/test/demos/traj_demo.sh index de597ef7..e67963e3 100755 --- a/test/demos/traj_demo.sh +++ b/test/demos/traj_demo.sh @@ -42,3 +42,6 @@ echo_and_run evo_traj tum ../data/fr2_desk_* --ref=../data/fr2_desk_groundtruth. log "plot bag contents" echo_and_run evo_traj bag *.bag --all_topics --ref=fr2_desk_groundtruth $p +log "yaw-only alignment" +echo_and_run evo_traj tum ../data/V101_openvins.txt --ref=../data/V101_gt.txt -a --yaw_only $p -v + diff --git a/test/test_trajectory.py b/test/test_trajectory.py index d1028c5b..7bce6ff9 100755 --- a/test/test_trajectory.py +++ b/test/test_trajectory.py @@ -28,7 +28,7 @@ from evo.core import trajectory from evo.core import lie_algebra as lie from evo.core.trajectory import PosePath3D, PoseTrajectory3D -from evo.core.geometry import GeometryException +from evo.core.geometry import GeometryException, rot_z class TestPosePath3D(unittest.TestCase): @@ -316,6 +316,15 @@ def test_sim3_alignment(self): traj_transformed.align(traj, correct_scale=True) self.assertEqual(traj_transformed, traj) + def test_yaw_only_alignment(self): + traj = helpers.fake_trajectory(1000, 1) + traj_transformed = copy.deepcopy(traj) + t = lie.se3(r=rot_z(np.random.rand()), t=np.random.randn(3)) + traj_transformed.transform(t) + self.assertNotEqual(traj, traj_transformed) + traj_transformed.align(traj, yaw_only=True) + self.assertEqual(traj_transformed, traj) + def test_scale_correction(self): traj = helpers.fake_trajectory(1000, 1) traj_transformed = copy.deepcopy(traj)