From 6463912f6ee5c5d689c16692498557f7b1f5e89f Mon Sep 17 00:00:00 2001 From: zachteed Date: Wed, 1 Sep 2021 19:17:53 -0400 Subject: [PATCH] monocular release --- .gitignore | 158 + .gitmodules | 6 + README.md | 119 +- calib/barn.txt | 1 + calib/eth.txt | 1 + calib/euroc.txt | 1 + calib/tartan.txt | 1 + calib/tum3.txt | 1 + data/euroc_groundtruth/MH_01_easy.txt | 3639 +++++++++++++++++ data/euroc_groundtruth/MH_02_easy.txt | 3000 ++++++++++++++ data/euroc_groundtruth/MH_03_medium.txt | 2632 ++++++++++++ data/euroc_groundtruth/MH_04_difficult.txt | 1977 +++++++++ data/euroc_groundtruth/MH_05_difficult.txt | 2222 ++++++++++ data/euroc_groundtruth/V1_01_easy.txt | 2872 +++++++++++++ data/euroc_groundtruth/V1_02_medium.txt | 1672 ++++++++ data/euroc_groundtruth/V1_03_difficult.txt | 2095 ++++++++++ data/euroc_groundtruth/V2_01_easy.txt | 2241 ++++++++++ data/euroc_groundtruth/V2_02_medium.txt | 2310 +++++++++++ data/euroc_groundtruth/V2_03_difficult.txt | 1891 +++++++++ demo.py | 103 + droid_slam/data_readers/__init__.py | 1 + droid_slam/data_readers/augmentation.py | 58 + droid_slam/data_readers/base.py | 157 + droid_slam/data_readers/factory.py | 82 + droid_slam/data_readers/rgbd_utils.py | 190 + droid_slam/data_readers/stream.py | 234 ++ droid_slam/data_readers/tartan.py | 138 + droid_slam/data_readers/tartan_test.txt | 32 + droid_slam/depth_video.py | 189 + droid_slam/droid.py | 89 + droid_slam/droid_backend.py | 40 + droid_slam/droid_frontend.py | 113 + droid_slam/droid_net.py | 222 + droid_slam/factor_graph.py | 349 ++ droid_slam/geom/__init__.py | 0 droid_slam/geom/ba.py | 158 + droid_slam/geom/chol.py | 73 + droid_slam/geom/graph_utils.py | 113 + droid_slam/geom/losses.py | 118 + droid_slam/geom/projective_ops.py | 137 + droid_slam/logger.py | 54 + droid_slam/modules/__init__.py | 0 droid_slam/modules/clipping.py | 24 + droid_slam/modules/corr.py | 140 + droid_slam/modules/extractor.py | 198 + droid_slam/modules/gru.py | 34 + droid_slam/motion_filter.py | 84 + droid_slam/trajectory_filler.py | 104 + droid_slam/visualization.py | 154 + environment.yaml | 22 + environment_novis.yaml | 20 + evaluation_scripts/test_euroc.py | 135 + evaluation_scripts/test_tum.py | 125 + evaluation_scripts/validate_tartanair.py | 98 + misc/renderoption.json | 40 + setup.py | 61 + src/altcorr_kernel.cu | 356 ++ src/correlation_kernels.cu | 185 + src/droid.cpp | 247 ++ src/droid_kernels.cu | 1518 +++++++ thirdparty/eigen | 1 + thirdparty/lietorch | 1 + thirdparty/tartanair_tools/LICENSE | 12 + thirdparty/tartanair_tools/README.md | 257 ++ .../tartanair_tools/TartanAir_Sample.ipynb | 618 +++ thirdparty/tartanair_tools/data_type.md | 93 + .../download_cvpr_slam_test.txt | 3 + .../tartanair_tools/download_training.py | 159 + .../download_training_zipfiles.txt | 288 ++ .../tartanair_tools/evaluation/__init__.py | 0 .../evaluation/evaluate_ate_scale.py | 133 + .../evaluation/evaluate_kitti.py | 126 + .../evaluation/evaluate_rpe.py | 219 + .../evaluation/evaluator_base.py | 91 + .../tartanair_tools/evaluation/pose_est.txt | 734 ++++ .../tartanair_tools/evaluation/pose_gt.txt | 734 ++++ .../evaluation/tartanair_evaluator.py | 80 + .../evaluation/trajectory_transform.py | 162 + .../evaluation/transformation.py | 164 + thirdparty/tartanair_tools/seg_rgbs.txt | 256 ++ tools/download_sample_data.sh | 26 + tools/evaluate_euroc.sh | 23 + tools/evaluate_tum.sh | 21 + tools/validate_tartanair.sh | 7 + train.py | 187 + 85 files changed, 37428 insertions(+), 1 deletion(-) create mode 100644 .gitignore create mode 100644 .gitmodules create mode 100644 calib/barn.txt create mode 100644 calib/eth.txt create mode 100644 calib/euroc.txt create mode 100644 calib/tartan.txt create mode 100644 calib/tum3.txt create mode 100755 data/euroc_groundtruth/MH_01_easy.txt create mode 100755 data/euroc_groundtruth/MH_02_easy.txt create mode 100755 data/euroc_groundtruth/MH_03_medium.txt create mode 100755 data/euroc_groundtruth/MH_04_difficult.txt create mode 100755 data/euroc_groundtruth/MH_05_difficult.txt create mode 100755 data/euroc_groundtruth/V1_01_easy.txt create mode 100755 data/euroc_groundtruth/V1_02_medium.txt create mode 100755 data/euroc_groundtruth/V1_03_difficult.txt create mode 100755 data/euroc_groundtruth/V2_01_easy.txt create mode 100755 data/euroc_groundtruth/V2_02_medium.txt create mode 100755 data/euroc_groundtruth/V2_03_difficult.txt create mode 100644 demo.py create mode 100644 droid_slam/data_readers/__init__.py create mode 100644 droid_slam/data_readers/augmentation.py create mode 100644 droid_slam/data_readers/base.py create mode 100644 droid_slam/data_readers/factory.py create mode 100644 droid_slam/data_readers/rgbd_utils.py create mode 100644 droid_slam/data_readers/stream.py create mode 100644 droid_slam/data_readers/tartan.py create mode 100644 droid_slam/data_readers/tartan_test.txt create mode 100644 droid_slam/depth_video.py create mode 100644 droid_slam/droid.py create mode 100644 droid_slam/droid_backend.py create mode 100644 droid_slam/droid_frontend.py create mode 100644 droid_slam/droid_net.py create mode 100644 droid_slam/factor_graph.py create mode 100644 droid_slam/geom/__init__.py create mode 100644 droid_slam/geom/ba.py create mode 100644 droid_slam/geom/chol.py create mode 100644 droid_slam/geom/graph_utils.py create mode 100644 droid_slam/geom/losses.py create mode 100644 droid_slam/geom/projective_ops.py create mode 100644 droid_slam/logger.py create mode 100644 droid_slam/modules/__init__.py create mode 100644 droid_slam/modules/clipping.py create mode 100644 droid_slam/modules/corr.py create mode 100644 droid_slam/modules/extractor.py create mode 100644 droid_slam/modules/gru.py create mode 100644 droid_slam/motion_filter.py create mode 100644 droid_slam/trajectory_filler.py create mode 100644 droid_slam/visualization.py create mode 100644 environment.yaml create mode 100644 environment_novis.yaml create mode 100644 evaluation_scripts/test_euroc.py create mode 100644 evaluation_scripts/test_tum.py create mode 100644 evaluation_scripts/validate_tartanair.py create mode 100644 misc/renderoption.json create mode 100644 setup.py create mode 100644 src/altcorr_kernel.cu create mode 100644 src/correlation_kernels.cu create mode 100644 src/droid.cpp create mode 100644 src/droid_kernels.cu create mode 160000 thirdparty/eigen create mode 160000 thirdparty/lietorch create mode 100644 thirdparty/tartanair_tools/LICENSE create mode 100644 thirdparty/tartanair_tools/README.md create mode 100644 thirdparty/tartanair_tools/TartanAir_Sample.ipynb create mode 100644 thirdparty/tartanair_tools/data_type.md create mode 100644 thirdparty/tartanair_tools/download_cvpr_slam_test.txt create mode 100644 thirdparty/tartanair_tools/download_training.py create mode 100644 thirdparty/tartanair_tools/download_training_zipfiles.txt create mode 100644 thirdparty/tartanair_tools/evaluation/__init__.py create mode 100644 thirdparty/tartanair_tools/evaluation/evaluate_ate_scale.py create mode 100644 thirdparty/tartanair_tools/evaluation/evaluate_kitti.py create mode 100644 thirdparty/tartanair_tools/evaluation/evaluate_rpe.py create mode 100644 thirdparty/tartanair_tools/evaluation/evaluator_base.py create mode 100644 thirdparty/tartanair_tools/evaluation/pose_est.txt create mode 100644 thirdparty/tartanair_tools/evaluation/pose_gt.txt create mode 100644 thirdparty/tartanair_tools/evaluation/tartanair_evaluator.py create mode 100644 thirdparty/tartanair_tools/evaluation/trajectory_transform.py create mode 100755 thirdparty/tartanair_tools/evaluation/transformation.py create mode 100644 thirdparty/tartanair_tools/seg_rgbs.txt create mode 100755 tools/download_sample_data.sh create mode 100755 tools/evaluate_euroc.sh create mode 100755 tools/evaluate_tum.sh create mode 100755 tools/validate_tartanair.sh create mode 100644 train.py diff --git a/.gitignore b/.gitignore new file mode 100644 index 00000000..a180f698 --- /dev/null +++ b/.gitignore @@ -0,0 +1,158 @@ +a# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py,cover +.hypothesis/ +.pytest_cache/ +cover/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +.pybuilder/ +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +# For a library or package, you might want to ignore these files since the code is +# intended to run in multiple environments; otherwise, check them in: +# .python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# SageMath parsed files +*.sage.py + +# Environments +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# pytype static type analyzer +.pytype/ + +# Cython debug symbols +cython_debug/ + + + +__pycache__ +build +dist +*.egg-info +*.vscode/ +*.pth +tests +checkpoints +datasets +runs +cache +*.out +*.o +data +figures/*.pdf + + diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 00000000..d47acde9 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,6 @@ +[submodule "thirdparty/lietorch"] + path = thirdparty/lietorch + url = https://github.com/princeton-vl/lietorch +[submodule "thirdparty/eigen"] + path = thirdparty/eigen + url = https://gitlab.com/libeigen/eigen.git diff --git a/README.md b/README.md index 65c5e0bf..7d93cfff 100644 --- a/README.md +++ b/README.md @@ -6,4 +6,121 @@ [DROID-SLAM: Deep Visual SLAM for Monocular, Stereo, and RGB-D Cameras](https://arxiv.org/abs/2108.10869) Zachary Teed and Jia Deng -* Code for our paper DROID-SLAM will be added on September 1st. +``` +@article{teed2021droid, + title={{DROID-SLAM: Deep Visual SLAM for Monocular, Stereo, and RGB-D Cameras}}, + author={Teed, Zachary and Deng, Jia}, + journal={arXiv preprint arXiv:2108.10869}, + year={2021} +} +``` + +**Initial Code Release:** This repo currently provides a single GPU implementation of our monocular SLAM system. It also contains demos, training, and evaluation scripts. Stereo, RGB-D, and multi-GPU code will be added on **September 7**. + + +## Requirements + +To run the code you will need ... +* **Inference:** Running the demos will require a GPU with at least 11G of memory. + +* **Training:** Training requires a GPU with at least 24G of memory. We train on 4 x RTX-3090 GPUs. + +## Getting Started +1. Clone the repo using the `--recursive` flag +```Bash +git clone --recursive https://github.com/princeton-vl/DROID-SLAM.git +``` + +2. Creating a new anaconda environment using the provided .yaml file. Use `environment_novis.yaml` to if you do not want to use the visualization +```Bash +conda env create -f environment.yml +pip install evo --upgrade --no-binary evo +pip install gdown +``` + +3. Compile the extensions (takes about 10 minutes) +```Bash +python setup.py install +``` + + +## Demos + +1. Download the model from google drive: [droid.pth](https://drive.google.com/file/d/1PpqVt1H4maBa_GbPJp4NwxRsd9jk-elh/view?usp=sharing) + +2. Download some sample videos using the provided script. +```Bash +./tools/download_sample_data.sh +``` + +Run the demo on any of the samples (all demos can be run on a GPU with 11G of memory). While running, press the "s" key to increase the filtering threshold (= more points) and "a" to decrease the filtering threshold (= fewer points). + + +```Python +python demo.py --imagedir=data/abandonedfactory --calib=calib/tartan.txt --stride=2 +``` + +```Python +python demo.py --imagedir=data/sfm_bench/rgb --calib=calib/eth.txt +``` + +```Python +python demo.py --imagedir=data/Barn --calib=calib/barn.txt --stride=1 --backend_nms=4 +``` + +```Python +python demo.py --imagedir=data/mav0/cam0/data --calib=calib/euroc.txt --t0=150 +``` + +```Python +python demo.py --imagedir=data/rgbd_dataset_freiburg3_cabinet/rgb --calib=calib/tum3.txt +``` + + +**Running on your own data:** All you need is a calibration file. Calibration files are in the form +``` +fx fy cx cy [k1 k2 p1 p2 [ k3 [ k4 k5 k6 ]]] +``` +with parameters in brackets optional. + +## Evaluation (Monocular) +We provide evaluation scripts for TartanAir, EuRoC, and TUM. EuRoC and TUM can be run on a 1080Ti. The TartanAir validation script will require 24G of memory. + +### EuRoC +Download the [EuRoC](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) sequences (ASL format) and put them in `datasets/EuRoC` +```Bash +./tools/evaluate_euroc.sh +``` + +### TUM-RGBD +Download the fr1 sequences from [TUM-RGBD](https://vision.in.tum.de/data/datasets/rgbd-dataset/download) and put them in `datasets/TUM-RGBD` +```Bash +./tools/evaluate_tum.sh +``` + +### TartanAir +Download the [TartanAir](https://theairlab.org/tartanair-dataset/) dataset using the script `thirdparty/tartanair_tools/download_training.py` and put them in `datasets/TartanAir` +```Bash +./tools/validate_tartanair.sh +``` + +## Training + +First download the TartanAir dataset. The download script can be found in `thirdparty/tartanair_tools/download_training.py`. You will only need the `rgb` and `depth` data. + +``` +python download_training.py --rgb --depth +``` + +You can then run the training script. We use 4x3090 RTX GPUs for training which takes approximatly 1 week. If you use a different number of GPUs, adjust the learning rate accordingly. + +**Note:** On the first training run, covisibility is computed between all pairs of frames. This can take several hours, but the results are cached so that future training runs will start immediately. + + +``` +python train.py --datapath= --gpus=4 --lr=0.00025 +``` + + +## Acknowledgements +Data from [TartanAir](https://theairlab.org/tartanair-dataset/) was used to train our model. We additionally use evaluation tools from [evo](https://github.com/MichaelGrupp/evo) and [tartanair_tools](https://github.com/castacks/tartanair_tools). diff --git a/calib/barn.txt b/calib/barn.txt new file mode 100644 index 00000000..e095d388 --- /dev/null +++ b/calib/barn.txt @@ -0,0 +1 @@ +1161.545689 1161.545689 960.000000 540.000000 -0.025158 0.0 0.0 0.0 \ No newline at end of file diff --git a/calib/eth.txt b/calib/eth.txt new file mode 100644 index 00000000..25ffe5e5 --- /dev/null +++ b/calib/eth.txt @@ -0,0 +1 @@ +726.21081542969 726.21081542969 359.2048034668 202.47247314453 \ No newline at end of file diff --git a/calib/euroc.txt b/calib/euroc.txt new file mode 100644 index 00000000..3d88c2a9 --- /dev/null +++ b/calib/euroc.txt @@ -0,0 +1 @@ +458.654 457.296 367.215 248.375 -0.28340811 0.07395907 0.00019359 1.76187114e-05 \ No newline at end of file diff --git a/calib/tartan.txt b/calib/tartan.txt new file mode 100644 index 00000000..1216bf09 --- /dev/null +++ b/calib/tartan.txt @@ -0,0 +1 @@ +320.0 320.0 320.0 240.0 \ No newline at end of file diff --git a/calib/tum3.txt b/calib/tum3.txt new file mode 100644 index 00000000..8c15af13 --- /dev/null +++ b/calib/tum3.txt @@ -0,0 +1 @@ +535.4 539.2 320.1 247.6 \ No newline at end of file diff --git a/data/euroc_groundtruth/MH_01_easy.txt b/data/euroc_groundtruth/MH_01_easy.txt new file mode 100755 index 00000000..5b19535d --- /dev/null +++ b/data/euroc_groundtruth/MH_01_easy.txt @@ -0,0 +1,3639 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403636580863555584.0000000000 4.6650211767 -1.8472146877 0.7812067206 0.4502123789 0.6912148472 0.4743667630 -0.307419945794 +1403636580913555456.0000000000 4.6629522096 -1.8453728663 0.8207579572 0.4591252838 0.6879037538 0.4717034923 -0.305758425422 +1403636580963555584.0000000000 4.6609846259 -1.8447596485 0.8600052598 0.4660445575 0.6843175905 0.4693424141 -0.306968409074 +1403636581013555456.0000000000 4.6596583694 -1.8446723346 0.8972069305 0.4713357532 0.6806165727 0.4677468540 -0.309542516151 +1403636581063555584.0000000000 4.6584695461 -1.8448832918 0.9323025417 0.4752778607 0.6776230401 0.4653955749 -0.313599951262 +1403636581113555456.0000000000 4.6567707371 -1.8438028560 0.9652596168 0.4796463782 0.6751678155 0.4622955238 -0.316813227926 +1403636581163555584.0000000000 4.6556223951 -1.8430375195 0.9955650996 0.4841999557 0.6731014856 0.4573074353 -0.321488262013 +1403636581213555456.0000000000 4.6551355257 -1.8415718393 1.0225625975 0.4891932100 0.6703409953 0.4529863730 -0.325785664578 +1403636581263555584.0000000000 4.6553100964 -1.8405548393 1.0461137821 0.4942368675 0.6673200214 0.4481619213 -0.33100574038 +1403636581313555456.0000000000 4.6569095013 -1.8399190938 1.0639175259 0.4993648206 0.6632089510 0.4461463972 -0.334278410279 +1403636581363555584.0000000000 4.6586259151 -1.8398263352 1.0738669267 0.5030624088 0.6608493236 0.4440118006 -0.336243818246 +1403636581413555456.0000000000 4.6607757299 -1.8391279976 1.0744901898 0.5056788647 0.6598235611 0.4441487866 -0.334146089982 +1403636581463555584.0000000000 4.6631142052 -1.8386877869 1.0659636925 0.5056610717 0.6600755252 0.4462786578 -0.33082101091 +1403636581513555456.0000000000 4.6656575418 -1.8384611738 1.0492260766 0.5036646983 0.6617892103 0.4492946439 -0.326329949369 +1403636581563555584.0000000000 4.6671015434 -1.8384954213 1.0261007203 0.4994425698 0.6655796249 0.4503608598 -0.323629384298 +1403636581613555456.0000000000 4.6685127859 -1.8387733808 0.9986153796 0.4942885324 0.6689230252 0.4523267921 -0.321902634829 +1403636581663555584.0000000000 4.6697485696 -1.8389791244 0.9680789477 0.4899133836 0.6721475922 0.4528350304 -0.321158724061 +1403636581713555456.0000000000 4.6714020867 -1.8384458341 0.9361128152 0.4878424601 0.6728077815 0.4555164101 -0.319130417483 +1403636581763555584.0000000000 4.6731657492 -1.8384989389 0.9033135722 0.4854743284 0.6740080915 0.4555485216 -0.320161386783 +1403636581813555456.0000000000 4.6759169156 -1.8397860467 0.8702705074 0.4830638064 0.6737530482 0.4575230503 -0.32152581156 +1403636581863555584.0000000000 4.6786374123 -1.8412498240 0.8369674237 0.4807839480 0.6747606350 0.4584005004 -0.321580257632 +1403636581913555456.0000000000 4.6789098604 -1.8380702615 0.8001037439 0.4760575121 0.6774496252 0.4593379990 -0.321620666457 +1403636581963555584.0000000000 4.6811060719 -1.8394680876 0.7678572354 0.4720695674 0.6817977012 0.4597941574 -0.317634303746 +1403636582013555456.0000000000 4.6827184977 -1.8407854533 0.7374569596 0.4669531920 0.6867695511 0.4605834784 -0.313313197384 +1403636582063555584.0000000000 4.6845440892 -1.8424677579 0.7100893352 0.4619379613 0.6910211345 0.4629213875 -0.307907292103 +1403636582113555456.0000000000 4.6864177192 -1.8444039956 0.6874845691 0.4561609730 0.6942993902 0.4664731512 -0.303757012541 +1403636582163555584.0000000000 4.6880835090 -1.8470605446 0.6715031647 0.4501768467 0.6971475546 0.4692614176 -0.301860589863 +1403636582213555456.0000000000 4.6891591032 -1.8492694573 0.6629683725 0.4455292949 0.6988377916 0.4723171530 -0.300076482574 +1403636582263555584.0000000000 4.6889563220 -1.8505991866 0.6629868294 0.4426625338 0.6999479389 0.4740794436 -0.298950573031 +1403636582313555456.0000000000 4.6875128361 -1.8515523631 0.6724144801 0.4412190252 0.6999608359 0.4750752271 -0.299473084755 +1403636582363555584.0000000000 4.6853306676 -1.8524845822 0.6904417901 0.4422588509 0.6989095844 0.4741915863 -0.301786085126 +1403636582413555456.0000000000 4.6828575878 -1.8532336282 0.7145279947 0.4465133834 0.6960274321 0.4722736895 -0.305170729931 +1403636582463555584.0000000000 4.6800233910 -1.8534587651 0.7424402375 0.4517663182 0.6928928083 0.4693560191 -0.30904963568 +1403636582513555456.0000000000 4.6769995062 -1.8528007494 0.7726710934 0.4575838376 0.6895306911 0.4678377566 -0.310309992018 +1403636582563555584.0000000000 4.6739380479 -1.8519962549 0.8046517355 0.4620053163 0.6877136221 0.4654997802 -0.311305342493 +1403636582613555456.0000000000 4.6713172136 -1.8505469065 0.8369736729 0.4661899190 0.6862379573 0.4645350754 -0.309760535102 +1403636582663555584.0000000000 4.6689739902 -1.8491169488 0.8698644611 0.4691330559 0.6859808668 0.4624915396 -0.308943363836 +1403636582713555456.0000000000 4.6669567150 -1.8475400173 0.9022681926 0.4710961986 0.6855959864 0.4606653507 -0.30953828463 +1403636582763555584.0000000000 4.6641369394 -1.8450330233 0.9350271380 0.4737627358 0.6856172229 0.4571780902 -0.310589902665 +1403636582813555456.0000000000 4.6612415428 -1.8419590174 0.9669980498 0.4776873060 0.6856278521 0.4522216783 -0.311808979778 +1403636582863555584.0000000000 4.6653702485 -1.8363505927 1.0041399424 0.4834769855 0.6850957447 0.4460955667 -0.312877884166 +1403636582913555456.0000000000 4.6641805171 -1.8331189909 1.0350233718 0.4895439457 0.6834682530 0.4399560652 -0.315684229999 +1403636582963555584.0000000000 4.6637638722 -1.8303675678 1.0625889369 0.4959597210 0.6801382405 0.4358630400 -0.318526826597 +1403636583013555456.0000000000 4.6639959243 -1.8285458661 1.0843242503 0.5021823857 0.6768995387 0.4317727617 -0.321235347017 +1403636583063555584.0000000000 4.6648170828 -1.8273142000 1.0986794807 0.5061262630 0.6737316664 0.4307271681 -0.323103627829 +1403636583113555456.0000000000 4.6654470081 -1.8261826713 1.1052410223 0.5084066605 0.6724466649 0.4301129087 -0.323018631324 +1403636583163555584.0000000000 4.6661069801 -1.8250725751 1.1027189760 0.5100860128 0.6720337484 0.4305561025 -0.320631163869 +1403636583213555456.0000000000 4.6666013839 -1.8247096993 1.0920801805 0.5101775382 0.6719095514 0.4320376564 -0.318747388683 +1403636583263555584.0000000000 4.6668634644 -1.8249769341 1.0744048486 0.5088293669 0.6722225028 0.4336299058 -0.318079686248 +1403636583313555456.0000000000 4.6666349144 -1.8250098419 1.0518366810 0.5070194545 0.6729730472 0.4347805994 -0.317811863932 +1403636583363555584.0000000000 4.6668029281 -1.8244978174 1.0244160706 0.5052845853 0.6735835375 0.4364386898 -0.317007848266 +1403636583413555456.0000000000 4.6672885335 -1.8241092349 0.9941015029 0.5024233379 0.6744031252 0.4378102114 -0.317920482255 +1403636583463555584.0000000000 4.6689841537 -1.8240200649 0.9608636054 0.4998679042 0.6743663623 0.4413905962 -0.317074800936 +1403636583513555456.0000000000 4.6703067821 -1.8240759622 0.9269100812 0.4972410854 0.6751430874 0.4436488596 -0.316399753402 +1403636583563555584.0000000000 4.6722037704 -1.8239806715 0.8920071943 0.4948060459 0.6762473714 0.4465779937 -0.313726895884 +1403636583613555456.0000000000 4.6732636189 -1.8238805333 0.8565259278 0.4926548717 0.6789277436 0.4483135698 -0.30880939034 +1403636583663555584.0000000000 4.6752087142 -1.8255498139 0.8220253431 0.4851658170 0.6826178392 0.4515209690 -0.307856834023 +1403636583713555456.0000000000 4.6764493059 -1.8232040641 0.7864114095 0.4759844081 0.6886564815 0.4534392572 -0.305914912558 +1403636583763555584.0000000000 4.6786366552 -1.8246669943 0.7559865394 0.4658695444 0.6949291473 0.4557504203 -0.303859510766 +1403636583813555456.0000000000 4.6809242484 -1.8259930800 0.7279563774 0.4577797685 0.7005852291 0.4574316187 -0.300623243508 +1403636583863555584.0000000000 4.6830458322 -1.8272134384 0.7025755972 0.4524292242 0.7040305696 0.4597177548 -0.297167192081 +1403636583913555456.0000000000 4.6855251521 -1.8281195739 0.6803458162 0.4501109680 0.7050454916 0.4631802370 -0.292873759971 +1403636583963555584.0000000000 4.6880728302 -1.8296851333 0.6629059159 0.4483426769 0.7044111762 0.4670810604 -0.290910676758 +1403636584013555456.0000000000 4.6902219140 -1.8320161297 0.6513369776 0.4466859126 0.7033166757 0.4699862637 -0.291427968986 +1403636584063555584.0000000000 4.6916948854 -1.8345220098 0.6463336748 0.4453099975 0.7016740826 0.4724190425 -0.293551930994 +1403636584113555456.0000000000 4.6918607229 -1.8361070450 0.6486878322 0.4439107379 0.7008058549 0.4736256936 -0.295792347624 +1403636584163555584.0000000000 4.6908446926 -1.8367976958 0.6583222756 0.4430081785 0.7000682159 0.4748158010 -0.296981820848 +1403636584213555456.0000000000 4.6889777125 -1.8366758613 0.6748990768 0.4431002416 0.6994101452 0.4755525928 -0.29721600917 +1403636584263555584.0000000000 4.6866021931 -1.8363575563 0.6969871283 0.4440428391 0.6987608564 0.4750926837 -0.298070737513 +1403636584313555456.0000000000 4.6837139879 -1.8357602929 0.7228081469 0.4456393630 0.6978102217 0.4744741210 -0.298899249085 +1403636584363555584.0000000000 4.6801901939 -1.8341942481 0.7519309042 0.4479319739 0.6967025718 0.4743605819 -0.298235664365 +1403636584413555456.0000000000 4.6760637521 -1.8313713890 0.7838519410 0.4521471385 0.6954956156 0.4741846913 -0.294953712322 +1403636584463555584.0000000000 4.6714600354 -1.8283532070 0.8177506288 0.4568685890 0.6938928378 0.4732049525 -0.293020297887 +1403636584513555456.0000000000 4.6668379937 -1.8259003161 0.8532490850 0.4615255360 0.6918373027 0.4712917763 -0.293665435305 +1403636584563555584.0000000000 4.6618533916 -1.8236463385 0.8896899896 0.4667655039 0.6898115461 0.4676187188 -0.296011366453 +1403636584613555456.0000000000 4.6568416420 -1.8214077035 0.9265069909 0.4736645233 0.6871386158 0.4628562927 -0.298741517615 +1403636584663555584.0000000000 4.6523076412 -1.8195301305 0.9621520884 0.4820276179 0.6842863300 0.4566016147 -0.301523729818 +1403636584713555456.0000000000 4.6489145088 -1.8183096693 0.9961487540 0.4908042037 0.6803424653 0.4511525478 -0.304477818735 +1403636584763555584.0000000000 4.6525036096 -1.8166405777 1.0340973124 0.4990939432 0.6771809676 0.4453446850 -0.30659302766 +1403636584813555456.0000000000 4.6515909950 -1.8163605710 1.0634597879 0.5053986819 0.6738785533 0.4414352014 -0.309184137264 +1403636584863555584.0000000000 4.6513760915 -1.8168893670 1.0886058076 0.5095288260 0.6720477406 0.4369287630 -0.31277062842 +1403636584913555456.0000000000 4.6518471565 -1.8179891609 1.1082838877 0.5119105860 0.6703709419 0.4343925575 -0.315995978054 +1403636584963555584.0000000000 4.6519556539 -1.8190238704 1.1206167439 0.5128476353 0.6709422637 0.4309292448 -0.317999634677 +1403636585013555456.0000000000 4.6516828441 -1.8191398689 1.1251993987 0.5129705162 0.6722676954 0.4292822415 -0.317228864343 +1403636585063555584.0000000000 4.6513861861 -1.8191915968 1.1220375000 0.5121904424 0.6742091061 0.4281709448 -0.315868127535 +1403636585113555456.0000000000 4.6510004787 -1.8192327659 1.1122594751 0.5105815009 0.6756291927 0.4285789214 -0.314883840622 +1403636585163555584.0000000000 4.6506428649 -1.8187672629 1.0961943748 0.5095224841 0.6780822333 0.4279188482 -0.312212719781 +1403636585213555456.0000000000 4.6503011901 -1.8176555914 1.0754269348 0.5087223016 0.6802987878 0.4279425484 -0.308642761923 +1403636585263555584.0000000000 4.6502647486 -1.8157203093 1.0510134723 0.5089165880 0.6813985318 0.4297244526 -0.303375744206 +1403636585313555456.0000000000 4.6504151953 -1.8137223477 1.0248494234 0.5089202249 0.6822685972 0.4314116089 -0.298987942471 +1403636585363555584.0000000000 4.6511899976 -1.8119147545 0.9972690536 0.5088115661 0.6820577213 0.4349718695 -0.294461419885 +1403636585413555456.0000000000 4.6518912110 -1.8105774675 0.9700667580 0.5072549248 0.6829156940 0.4374481896 -0.291475003248 +1403636585463555584.0000000000 4.6539702308 -1.8106399458 0.9432271776 0.5033301282 0.6832765043 0.4419151158 -0.290694050665 +1403636585513555456.0000000000 4.6570390131 -1.8114432298 0.9172675251 0.4989648481 0.6843453764 0.4459658513 -0.289516745038 +1403636585563555584.0000000000 4.6596565139 -1.8089960762 0.8908350399 0.4927810636 0.6847824984 0.4514672547 -0.290546160269 +1403636585613555456.0000000000 4.6655216091 -1.8112623344 0.8694285472 0.4855779594 0.6857208176 0.4565357582 -0.292533941794 +1403636585663555584.0000000000 4.6714178742 -1.8136417811 0.8518317050 0.4775005869 0.6877435286 0.4605467610 -0.29478587022 +1403636585713555456.0000000000 4.6778477371 -1.8167346017 0.8380386496 0.4687953561 0.6903170345 0.4641579515 -0.297070197077 +1403636585763555584.0000000000 4.6835295380 -1.8190340095 0.8280330012 0.4606025100 0.6938915761 0.4666767018 -0.297611599905 +1403636585813555456.0000000000 4.6890187011 -1.8218858198 0.8215145495 0.4517456824 0.6978372188 0.4686499068 -0.298858360018 +1403636585863555584.0000000000 4.6943946621 -1.8244561567 0.8178795983 0.4425492394 0.7022359594 0.4710053076 -0.298611500517 +1403636585913555456.0000000000 4.6993281037 -1.8268945198 0.8166444294 0.4338545190 0.7067633639 0.4731523331 -0.297292235768 +1403636585963555584.0000000000 4.7034842739 -1.8285060584 0.8162651209 0.4256271985 0.7124372098 0.4747634370 -0.293043322664 +1403636586013555456.0000000000 4.7065861324 -1.8295895707 0.8165071578 0.4177798263 0.7195056521 0.4753900368 -0.285964938893 +1403636586063555584.0000000000 4.7090442780 -1.8299897497 0.8169467747 0.4116981315 0.7269789708 0.4755500403 -0.275424007038 +1403636586113555456.0000000000 4.7109837893 -1.8314937514 0.8183447701 0.4061476518 0.7341370690 0.4744391002 -0.266447722875 +1403636586163555584.0000000000 4.7126469004 -1.8338590515 0.8204599966 0.4008796213 0.7404896955 0.4731409435 -0.259052480548 +1403636586213555456.0000000000 4.7148760456 -1.8370008843 0.8228286286 0.3948421782 0.7456146013 0.4728380473 -0.254131268501 +1403636586263555584.0000000000 4.7180969722 -1.8402173055 0.8248392724 0.3876990803 0.7501049370 0.4740964552 -0.249528671158 +1403636586313555456.0000000000 4.7217253199 -1.8429728235 0.8266929934 0.3797864590 0.7552838913 0.4745784866 -0.245119867093 +1403636586363555584.0000000000 4.7264149675 -1.8453593331 0.8280296877 0.3717215183 0.7602664663 0.4754879888 -0.240268985885 +1403636586413555456.0000000000 4.7315551107 -1.8476762787 0.8292004826 0.3632955508 0.7653962041 0.4758828922 -0.23605182993 +1403636586463555584.0000000000 4.7376047549 -1.8493863844 0.8299690782 0.3559766013 0.7688271433 0.4783408812 -0.231031349318 +1403636586513555456.0000000000 4.7436274893 -1.8500039870 0.8310796936 0.3496836676 0.7713520074 0.4810950648 -0.226461811055 +1403636586563555584.0000000000 4.7489406699 -1.8495423132 0.8328969621 0.3442502495 0.7728255974 0.4839240554 -0.223718283495 +1403636586613555456.0000000000 4.7531478303 -1.8475940208 0.8352072697 0.3408524234 0.7734462976 0.4858696795 -0.222555846256 +1403636586663555584.0000000000 4.7558890355 -1.8439621864 0.8377280404 0.3401650254 0.7739896418 0.4854777456 -0.222573916649 +1403636586713555456.0000000000 4.7577051072 -1.8396698827 0.8400314352 0.3416201363 0.7728831266 0.4852889042 -0.224593042008 +1403636586763555584.0000000000 4.7584996648 -1.8354887618 0.8416954725 0.3432075023 0.7713499160 0.4847282291 -0.228618593624 +1403636586813555456.0000000000 4.7584585267 -1.8305573568 0.8429445970 0.3455016627 0.7694334290 0.4844295621 -0.232225749499 +1403636586863555584.0000000000 4.7578824973 -1.8265586530 0.8430461638 0.3481874445 0.7674314294 0.4845733392 -0.23452757524 +1403636586913555456.0000000000 4.7567351010 -1.8241079353 0.8426152179 0.3503363930 0.7649684040 0.4861146409 -0.236178552253 +1403636586963555584.0000000000 4.7550759602 -1.8224303278 0.8422723406 0.3514481525 0.7629840399 0.4873674739 -0.23835372102 +1403636587013555456.0000000000 4.7530738720 -1.8205942346 0.8422103039 0.3521605810 0.7605111731 0.4902579723 -0.239275576292 +1403636587063555584.0000000000 4.7510119171 -1.8190298553 0.8421867146 0.3514025669 0.7597607016 0.4919317578 -0.239338793458 +1403636587113555456.0000000000 4.7491116635 -1.8168321332 0.8423070713 0.3497359580 0.7592773918 0.4945150296 -0.237986317599 +1403636587163555584.0000000000 4.7475883481 -1.8135587879 0.8419777677 0.3482283854 0.7592764119 0.4963870299 -0.236296928661 +1403636587213555456.0000000000 4.7463112024 -1.8090096242 0.8417106568 0.3468751072 0.7593277210 0.4974254120 -0.235938618336 +1403636587263555584.0000000000 4.7453167642 -1.8028301048 0.8412297611 0.3460923814 0.7600734511 0.4970699408 -0.235435525131 +1403636587313555456.0000000000 4.7446476217 -1.7947835778 0.8407569168 0.3455707014 0.7609522120 0.4962291516 -0.235136663301 +1403636587363555584.0000000000 4.7443405282 -1.7847863735 0.8403218392 0.3452134783 0.7620613973 0.4951757373 -0.234288434126 +1403636587413555456.0000000000 4.7445378063 -1.7733340651 0.8399805614 0.3446315529 0.7632595367 0.4940203525 -0.233683255014 +1403636587463555584.0000000000 4.7456917159 -1.7604937879 0.8396706039 0.3435018344 0.7648740152 0.4924440615 -0.233394680479 +1403636587513555456.0000000000 4.7477660688 -1.7462569108 0.8395622392 0.3422783833 0.7664556596 0.4908735618 -0.233311758018 +1403636587563555584.0000000000 4.7508131006 -1.7305946001 0.8395723038 0.3415782636 0.7677661090 0.4893586340 -0.233211533032 +1403636587613555456.0000000000 4.7540624486 -1.7135179557 0.8398714950 0.3421310537 0.7690824477 0.4870127492 -0.232974489629 +1403636587663555584.0000000000 4.7574207178 -1.6955372677 0.8406219479 0.3440929278 0.7698874848 0.4840781077 -0.233541652603 +1403636587713555456.0000000000 4.7605786877 -1.6766215509 0.8417113848 0.3471651751 0.7706559336 0.4802666798 -0.234328166254 +1403636587763555584.0000000000 4.7638285412 -1.6576357947 0.8429028634 0.3505226985 0.7716270534 0.4757617019 -0.235321760963 +1403636587813555456.0000000000 4.7674884349 -1.6387311953 0.8435518674 0.3536141351 0.7726676353 0.4719018638 -0.235054035902 +1403636587863555584.0000000000 4.7715497460 -1.6202338642 0.8433813290 0.3550658974 0.7743131786 0.4685209643 -0.234212330928 +1403636587913555456.0000000000 4.7761071969 -1.6025125556 0.8421281731 0.3551598200 0.7762995432 0.4663335769 -0.231848046262 +1403636587963555584.0000000000 4.7809546733 -1.5855564437 0.8401033114 0.3540669140 0.7792985862 0.4644360902 -0.227221152458 +1403636588013555456.0000000000 4.7859073871 -1.5695677517 0.8377432281 0.3521334752 0.7827247992 0.4631933468 -0.22089777696 +1403636588063555584.0000000000 4.7901350152 -1.5551825669 0.8351697747 0.3495298414 0.7863842787 0.4610102164 -0.216560006829 +1403636588113555456.0000000000 4.7939409087 -1.5428546361 0.8325896612 0.3469799047 0.7883446561 0.4604592656 -0.214697260513 +1403636588163555584.0000000000 4.7974896458 -1.5318369422 0.8300698883 0.3459545552 0.7889869057 0.4609082232 -0.213022811502 +1403636588213555456.0000000000 4.8003105905 -1.5227593932 0.8277060855 0.3454976473 0.7888808076 0.4613381439 -0.213226555786 +1403636588263555584.0000000000 4.8023183677 -1.5157529310 0.8257453613 0.3457184162 0.7885322490 0.4612105909 -0.214430547592 +1403636588313555456.0000000000 4.8035735536 -1.5109040302 0.8243949507 0.3461829938 0.7880095020 0.4607025370 -0.216683021973 +1403636588363555584.0000000000 4.8044289687 -1.5081916164 0.8232321834 0.3467232883 0.7870751209 0.4607712174 -0.219056158647 +1403636588413555456.0000000000 4.8049455602 -1.5076406879 0.8223916205 0.3472667827 0.7869306377 0.4597322255 -0.220889641848 +1403636588463555584.0000000000 4.8049884994 -1.5089909839 0.8218451380 0.3474363479 0.7870523005 0.4591107734 -0.221481281736 +1403636588513555456.0000000000 4.8049498711 -1.5120692044 0.8220159868 0.3481366995 0.7873002306 0.4590950389 -0.219524328279 +1403636588563555584.0000000000 4.8041627372 -1.5172627608 0.8233462880 0.3489303818 0.7872560003 0.4590802674 -0.218451108436 +1403636588613555456.0000000000 4.8028727345 -1.5249997312 0.8253557679 0.3491683479 0.7871204764 0.4589704416 -0.218789748706 +1403636588663555584.0000000000 4.8013396082 -1.5347174991 0.8275065820 0.3493042577 0.7865586623 0.4595161198 -0.219446899987 +1403636588713555456.0000000000 4.7997567933 -1.5467168693 0.8288361341 0.3479283270 0.7863475610 0.4602670446 -0.220811322667 +1403636588763555584.0000000000 4.7979965020 -1.5600724199 0.8294046699 0.3461914446 0.7855602373 0.4626992353 -0.221260061568 +1403636588813555456.0000000000 4.7955148294 -1.5746774243 0.8297162606 0.3443070002 0.7851342534 0.4646239695 -0.221678733178 +1403636588863555584.0000000000 4.7921442500 -1.5908513052 0.8299138420 0.3427341695 0.7846385385 0.4660879547 -0.222795133292 +1403636588913555456.0000000000 4.7881713556 -1.6087257249 0.8307052896 0.3416512571 0.7837157499 0.4674878159 -0.224764729928 +1403636588963555584.0000000000 4.7840572809 -1.6277942478 0.8320276616 0.3413826710 0.7822167620 0.4693180256 -0.226573166988 +1403636589013555456.0000000000 4.7797551436 -1.6479092732 0.8339192838 0.3418921369 0.7802110011 0.4710770341 -0.229056736267 +1403636589063555584.0000000000 4.7753651255 -1.6690392400 0.8364197160 0.3429152997 0.7777733626 0.4729017549 -0.232037979435 +1403636589113555456.0000000000 4.7707166218 -1.6905054192 0.8392234960 0.3443340335 0.7750139977 0.4751224329 -0.234618947609 +1403636589163555584.0000000000 4.7654678661 -1.7125016326 0.8423898498 0.3455908031 0.7729639316 0.4763620973 -0.237008247776 +1403636589213555456.0000000000 4.7599001703 -1.7352075788 0.8454893617 0.3459768803 0.7714522679 0.4776571807 -0.238757228852 +1403636589263555584.0000000000 4.7543559135 -1.7584695243 0.8479939057 0.3453021119 0.7703959083 0.4794168722 -0.239616482343 +1403636589313555456.0000000000 4.7488313013 -1.7819333445 0.8497698640 0.3437769170 0.7691084243 0.4824127352 -0.239932523549 +1403636589363555584.0000000000 4.7431729102 -1.8058054022 0.8505887302 0.3413806940 0.7684371170 0.4851321405 -0.240021718232 +1403636589413555456.0000000000 4.7372869246 -1.8291327636 0.8510235217 0.3397116757 0.7673445853 0.4882345674 -0.239593973281 +1403636589463555584.0000000000 4.7313202372 -1.8522555895 0.8513019022 0.3395284258 0.7661858152 0.4903016982 -0.239340739099 +1403636589513555456.0000000000 4.7252038469 -1.8756346388 0.8512711040 0.3398586519 0.7652381581 0.4910565591 -0.240354142492 +1403636589563555584.0000000000 4.7192969066 -1.8991976327 0.8512545720 0.3401500736 0.7640218185 0.4918624151 -0.242156876461 +1403636589613555456.0000000000 4.7133701468 -1.9223268063 0.8509610971 0.3410354383 0.7626654886 0.4928651210 -0.243146364976 +1403636589663555584.0000000000 4.7075078683 -1.9453384153 0.8506575803 0.3416563391 0.7612578099 0.4939957134 -0.244388477707 +1403636589713555456.0000000000 4.7019129612 -1.9681060183 0.8501632065 0.3418041623 0.7601968692 0.4950607715 -0.24532726545 +1403636589763555584.0000000000 4.6964483738 -1.9906131216 0.8490846544 0.3400522715 0.7590841245 0.4969582986 -0.247362474985 +1403636589813555456.0000000000 4.6914986044 -2.0119008104 0.8474656337 0.3370377257 0.7580756652 0.4998927581 -0.248664608978 +1403636589863555584.0000000000 4.6871413950 -2.0315932342 0.8454034911 0.3331518913 0.7573721347 0.5033389317 -0.249092727314 +1403636589913555456.0000000000 4.6830814481 -2.0497554569 0.8431293516 0.3290731235 0.7566236810 0.5066815447 -0.250010593881 +1403636589963555584.0000000000 4.6793020940 -2.0664974687 0.8411348214 0.3253692166 0.7558338939 0.5090581087 -0.252408081792 +1403636590013555456.0000000000 4.6758580526 -2.0815914201 0.8395818704 0.3235960746 0.7541796534 0.5109795140 -0.255731435746 +1403636590063555584.0000000000 4.6727460747 -2.0941126360 0.8393601866 0.3242607991 0.7519972115 0.5120989549 -0.25905557027 +1403636590113555456.0000000000 4.6702240535 -2.1043635999 0.8396018943 0.3256924275 0.7496127680 0.5128082122 -0.26274108574 +1403636590163555584.0000000000 4.6684665841 -2.1118275356 0.8404063538 0.3268679606 0.7475747727 0.5130488737 -0.266589851135 +1403636590213555456.0000000000 4.6679247438 -2.1160599839 0.8413290603 0.3281320038 0.7461431715 0.5134049112 -0.268356391341 +1403636590263555584.0000000000 4.6686342322 -2.1172292147 0.8421886513 0.3289345834 0.7454550204 0.5139064550 -0.268326308784 +1403636590313555456.0000000000 4.6706060580 -2.1154571054 0.8430208154 0.3291244564 0.7454695788 0.5146192970 -0.266681792655 +1403636590363555584.0000000000 4.6735435774 -2.1107657346 0.8438248855 0.3294392575 0.7465146670 0.5140731928 -0.264413275111 +1403636590413555456.0000000000 4.6776477245 -2.1031678525 0.8447008489 0.3303351527 0.7473671028 0.5135193069 -0.261952327528 +1403636590463555584.0000000000 4.6823357763 -2.0925531482 0.8458037808 0.3323947984 0.7485165334 0.5118629116 -0.259293380015 +1403636590513555456.0000000000 4.6879548842 -2.0796935281 0.8473214212 0.3351442992 0.7489249610 0.5105330331 -0.257188109271 +1403636590563555584.0000000000 4.6940305695 -2.0647190861 0.8488526245 0.3382938706 0.7493527911 0.5088750983 -0.255095640676 +1403636590613555456.0000000000 4.7005423887 -2.0482001941 0.8504590613 0.3408769167 0.7496959123 0.5072905575 -0.253801609473 +1403636590663555584.0000000000 4.7070899847 -2.0302202493 0.8515405866 0.3430142226 0.7506476546 0.5053226471 -0.252028498359 +1403636590713555456.0000000000 4.7138344811 -2.0111221807 0.8521930946 0.3440696872 0.7519263433 0.5037170330 -0.249983950167 +1403636590763555584.0000000000 4.7204115577 -1.9909448082 0.8521838723 0.3437615503 0.7541412468 0.5016788964 -0.247825062022 +1403636590813555456.0000000000 4.7269833116 -1.9701599448 0.8516531930 0.3415017658 0.7562903250 0.5005710782 -0.246637555791 +1403636590863555584.0000000000 4.7334582645 -1.9483136461 0.8505312816 0.3390021481 0.7587777867 0.4992459934 -0.245127011976 +1403636590913555456.0000000000 4.7399492419 -1.9255651421 0.8493804814 0.3372037561 0.7607196898 0.4984041816 -0.243294990097 +1403636590963555584.0000000000 4.7464487749 -1.9023273464 0.8480242972 0.3368774538 0.7618719487 0.4976608866 -0.241657519723 +1403636591013555456.0000000000 4.7524687676 -1.8791621561 0.8466576861 0.3368824654 0.7621368701 0.4973073012 -0.241543047803 +1403636591063555584.0000000000 4.7580921190 -1.8566201566 0.8455438929 0.3368633044 0.7619326147 0.4969655395 -0.242913682888 +1403636591113555456.0000000000 4.7632994502 -1.8342652596 0.8447768437 0.3366467210 0.7618408182 0.4966395740 -0.244165285159 +1403636591163555584.0000000000 4.7681349660 -1.8126848956 0.8439912894 0.3361452511 0.7626493906 0.4954139357 -0.244820974358 +1403636591213555456.0000000000 4.7726068559 -1.7918720401 0.8430217296 0.3354661626 0.7635368515 0.4946564984 -0.244517644992 +1403636591263555584.0000000000 4.7768136263 -1.7723244195 0.8412935093 0.3346668353 0.7647730393 0.4937966806 -0.243485412183 +1403636591313555456.0000000000 4.7804912757 -1.7543826935 0.8389357170 0.3341694325 0.7660943386 0.4929436501 -0.241737073396 +1403636591363555584.0000000000 4.7836043364 -1.7386222818 0.8360897169 0.3338791529 0.7677665102 0.4914869930 -0.239791227254 +1403636591413555456.0000000000 4.7859225789 -1.7251636771 0.8326651620 0.3339898378 0.7691785324 0.4898258208 -0.238507523521 +1403636591463555584.0000000000 4.7871977869 -1.7136998588 0.8287076702 0.3339233825 0.7703503672 0.4881014611 -0.238353624041 +1403636591513555456.0000000000 4.7876629575 -1.7029213966 0.8245774257 0.3359151199 0.7708511729 0.4866152356 -0.236970702698 +1403636591563555584.0000000000 4.7869408391 -1.6927615709 0.8203660689 0.3411000161 0.7717997595 0.4823907331 -0.235106552135 +1403636591613555456.0000000000 4.7850710618 -1.6833601847 0.8162035550 0.3490361004 0.7726953037 0.4761710195 -0.233188611516 +1403636591663555584.0000000000 4.7824380097 -1.6756786015 0.8127739948 0.3589114800 0.7718437391 0.4700637450 -0.233409227532 +1403636591713555456.0000000000 4.7798052135 -1.6698702366 0.8101889772 0.3694591934 0.7695358289 0.4650829613 -0.234547120209 +1403636591763555584.0000000000 4.7770767156 -1.6647931150 0.8088478593 0.3801603528 0.7669861016 0.4602422405 -0.235345503921 +1403636591813555456.0000000000 4.7740880248 -1.6599454219 0.8086649063 0.3908352831 0.7646857142 0.4545533178 -0.236399706395 +1403636591863555584.0000000000 4.7714344318 -1.6558985047 0.8089574150 0.3993565219 0.7630300797 0.4493477478 -0.237457506389 +1403636591913555456.0000000000 4.7687261108 -1.6515643632 0.8095493640 0.4050129363 0.7629791753 0.4444044159 -0.23734366352 +1403636591963555584.0000000000 4.7661345485 -1.6472811918 0.8098285185 0.4057523693 0.7655028102 0.4398975615 -0.236348466661 +1403636592013555456.0000000000 4.7629917589 -1.6411997725 0.8097257265 0.4038065067 0.7694486067 0.4365123725 -0.23312249022 +1403636592063555584.0000000000 4.7583776976 -1.6331986621 0.8092288308 0.4019354176 0.7741046495 0.4318940894 -0.229515592735 +1403636592113555456.0000000000 4.7527302135 -1.6239376150 0.8083801399 0.4000626087 0.7785308781 0.4275606871 -0.225901394003 +1403636592163555584.0000000000 4.7461987541 -1.6138200479 0.8072981311 0.3976897518 0.7829489679 0.4236103144 -0.222234282882 +1403636592213555456.0000000000 4.7390292262 -1.6035596005 0.8060268666 0.3946803647 0.7866888571 0.4213893959 -0.218584145871 +1403636592263555584.0000000000 4.7308101897 -1.5935966209 0.8050252847 0.3915656074 0.7894479064 0.4206791214 -0.215586305095 +1403636592313555456.0000000000 4.7213498754 -1.5846030313 0.8042990035 0.3881487485 0.7912255523 0.4212991562 -0.214031996234 +1403636592363555584.0000000000 4.7097299869 -1.5768854694 0.8038933731 0.3839119692 0.7930532428 0.4213402099 -0.214826863929 +1403636592413555456.0000000000 4.6966546147 -1.5709030270 0.8039499493 0.3799568233 0.7930835620 0.4239163959 -0.216670638129 +1403636592463555584.0000000000 4.6815491783 -1.5666388845 0.8045032425 0.3776620832 0.7915445494 0.4271059377 -0.220020670138 +1403636592513555456.0000000000 4.6650349469 -1.5644524706 0.8054925437 0.3773674631 0.7877598718 0.4315804826 -0.225314156725 +1403636592563555584.0000000000 4.6474890994 -1.5644492382 0.8063014029 0.3788015680 0.7825429724 0.4366122903 -0.231312724316 +1403636592613555456.0000000000 4.6291730460 -1.5666147784 0.8067428039 0.3805310158 0.7762107023 0.4429017596 -0.23776274519 +1403636592663555584.0000000000 4.6105931194 -1.5710328014 0.8064470579 0.3818688515 0.7699885123 0.4497376706 -0.242960693853 +1403636592713555456.0000000000 4.5920816671 -1.5780832550 0.8062099706 0.3814146575 0.7641671250 0.4571009768 -0.248254226673 +1403636592763555584.0000000000 4.5741769819 -1.5885630571 0.8057611235 0.3786479243 0.7583267032 0.4657221977 -0.254301386423 +1403636592813555456.0000000000 4.5570980841 -1.6027212719 0.8057368262 0.3738582104 0.7526678581 0.4747139181 -0.261472426539 +1403636592863555584.0000000000 4.5417636608 -1.6210738202 0.8050294324 0.3668101216 0.7471132297 0.4844081616 -0.269482633092 +1403636592913555456.0000000000 4.5285871811 -1.6427167964 0.8038901316 0.3594348249 0.7415777435 0.4945029911 -0.276289429284 +1403636592963555584.0000000000 4.5180296435 -1.6676968784 0.8031655251 0.3518132462 0.7361559071 0.5043618674 -0.282703072272 +1403636593013555456.0000000000 4.5107419585 -1.6962029704 0.8025571633 0.3440283121 0.7302957890 0.5144158382 -0.28929038421 +1403636593063555584.0000000000 4.5062370641 -1.7271022165 0.8024841614 0.3369055728 0.7242880708 0.5241853852 -0.295179788353 +1403636593113555456.0000000000 4.5051370686 -1.7595824328 0.8027441095 0.3312077120 0.7175805626 0.5340250046 -0.300327957829 +1403636593163555584.0000000000 4.5074224034 -1.7937948740 0.8038072324 0.3247071812 0.7118188113 0.5416774007 -0.307351297108 +1403636593213555456.0000000000 4.5122724580 -1.8281423911 0.8056972066 0.3185986450 0.7074561457 0.5468730895 -0.314532238916 +1403636593263555584.0000000000 4.5204919200 -1.8620667406 0.8078788928 0.3118930717 0.7036429667 0.5510986312 -0.322334586972 +1403636593313555456.0000000000 4.5313092892 -1.8934092104 0.8096830434 0.3063518089 0.7011621248 0.5549440728 -0.326431187291 +1403636593363555584.0000000000 4.5449803061 -1.9213287294 0.8105821638 0.3026967955 0.6994614551 0.5584048709 -0.327585596415 +1403636593413555456.0000000000 4.5612901390 -1.9457003594 0.8105210704 0.3001282996 0.6988421575 0.5604241829 -0.327822174306 +1403636593463555584.0000000000 4.5800874198 -1.9654016168 0.8094285641 0.2996677342 0.6988335422 0.5617504182 -0.325986804998 +1403636593513555456.0000000000 4.6008204976 -1.9808813153 0.8074544749 0.3001493370 0.7010467609 0.5604332715 -0.323045449855 +1403636593563555584.0000000000 4.6227026011 -1.9925036361 0.8050550940 0.2996571944 0.7046390940 0.5577373072 -0.320341082544 +1403636593613555456.0000000000 4.6454805325 -1.9999243363 0.8019040360 0.2987069332 0.7101411755 0.5535577439 -0.316302866114 +1403636593663555584.0000000000 4.6688277608 -2.0033993661 0.7987307572 0.2969339180 0.7171059006 0.5478565329 -0.312157964827 +1403636593713555456.0000000000 4.6926886604 -2.0025222776 0.7951515153 0.2966532173 0.7251295011 0.5410937216 -0.305616851138 +1403636593763555584.0000000000 4.7161043171 -1.9973961831 0.7918563205 0.2982590768 0.7345396602 0.5315194948 -0.298295218508 +1403636593813555456.0000000000 4.7387520135 -1.9876737329 0.7890007325 0.3029021928 0.7440212790 0.5199925898 -0.290327925879 +1403636593863555584.0000000000 4.7604676582 -1.9746355485 0.7869630077 0.3102185001 0.7535392485 0.5057519461 -0.283121974127 +1403636593913555456.0000000000 4.7806380295 -1.9582612030 0.7859340459 0.3198183286 0.7623086407 0.4903063799 -0.276046059218 +1403636593963555584.0000000000 4.7995886731 -1.9390944066 0.7854697939 0.3308205249 0.7702916180 0.4744559940 -0.268514642658 +1403636594013555456.0000000000 4.8169717055 -1.9174665481 0.7856712704 0.3419420415 0.7774920759 0.4591612142 -0.260293471927 +1403636594063555584.0000000000 4.8321556968 -1.8937177246 0.7860895418 0.3519064025 0.7847264810 0.4441236597 -0.251237753416 +1403636594113555456.0000000000 4.8446011363 -1.8684513844 0.7865152378 0.3592370771 0.7918096812 0.4301993915 -0.242723370638 +1403636594163555584.0000000000 4.8537941714 -1.8412857086 0.7863612166 0.3642885822 0.7988611627 0.4175715611 -0.23398432206 +1403636594213555456.0000000000 4.8597488282 -1.8124985247 0.7855689184 0.3681700560 0.8046364982 0.4077076357 -0.225356161245 +1403636594263555584.0000000000 4.8621204035 -1.7821695553 0.7842658997 0.3715740674 0.8091404072 0.3999511864 -0.217401845487 +1403636594313555456.0000000000 4.8609515874 -1.7505268802 0.7830390339 0.3748997233 0.8120270308 0.3947752690 -0.21027312165 +1403636594363555584.0000000000 4.8563482567 -1.7180246594 0.7817171859 0.3787913645 0.8137034441 0.3908877053 -0.203986786714 +1403636594413555456.0000000000 4.8482621722 -1.6849214355 0.7807462137 0.3838286950 0.8135897285 0.3884194652 -0.199693779518 +1403636594463555584.0000000000 4.8373677926 -1.6525075407 0.7797515942 0.3898527510 0.8117686905 0.3875338846 -0.197139326242 +1403636594513555456.0000000000 4.8238787693 -1.6217267731 0.7789731072 0.3958723045 0.8089049646 0.3874927598 -0.19699552745 +1403636594563555584.0000000000 4.8074061461 -1.5945646221 0.7787025538 0.4005880949 0.8068604365 0.3855890657 -0.19956574532 +1403636594613555456.0000000000 4.7891721508 -1.5717682741 0.7784316228 0.4036758242 0.8049374020 0.3847563557 -0.202692265627 +1403636594663555584.0000000000 4.7691339566 -1.5549168154 0.7783973288 0.4054991513 0.8036488860 0.3836595687 -0.206214067589 +1403636594713555456.0000000000 4.7478245140 -1.5444706424 0.7780560732 0.4063912687 0.8015084842 0.3854446503 -0.209434257072 +1403636594763555584.0000000000 4.7253906361 -1.5409260240 0.7771418212 0.4060465331 0.7984682756 0.3894736298 -0.214207650258 +1403636594813555456.0000000000 4.7019042185 -1.5443846014 0.7754365893 0.4050821689 0.7935922724 0.3969188293 -0.220397786991 +1403636594863555584.0000000000 4.6777527253 -1.5547124993 0.7736433277 0.4037886093 0.7878767121 0.4056598931 -0.227255575581 +1403636594913555456.0000000000 4.6539969519 -1.5721225021 0.7719341352 0.4025344894 0.7802776839 0.4172094006 -0.234667929045 +1403636594963555584.0000000000 4.6310839858 -1.5959316687 0.7704119126 0.4001254581 0.7715646396 0.4307999380 -0.242897176246 +1403636595013555456.0000000000 4.6106436806 -1.6261585567 0.7694813190 0.3951562682 0.7621679860 0.4453176715 -0.254251167596 +1403636595063555584.0000000000 4.5929550469 -1.6604745924 0.7683136977 0.3888882761 0.7526206469 0.4610589035 -0.264107474474 +1403636595113555456.0000000000 4.5780810793 -1.6975031330 0.7668994531 0.3806768121 0.7439505790 0.4761140345 -0.273748291252 +1403636595163555584.0000000000 4.5661362165 -1.7349900096 0.7656129745 0.3721267320 0.7359237291 0.4900364045 -0.282492977757 +1403636595213555456.0000000000 4.5578485580 -1.7724770000 0.7647700631 0.3626688399 0.7287919367 0.5022739671 -0.291641025174 +1403636595263555584.0000000000 4.5535165417 -1.8078835197 0.7640233797 0.3538635871 0.7217192282 0.5137281338 -0.299975535587 +1403636595313555456.0000000000 4.5535423527 -1.8403252456 0.7632688223 0.3459580163 0.7154788778 0.5237784718 -0.306690624054 +1403636595363555584.0000000000 4.5576744852 -1.8685700710 0.7626902237 0.3402668524 0.7100811737 0.5320434656 -0.311340563747 +1403636595413555456.0000000000 4.5652762054 -1.8914598282 0.7623060338 0.3359190845 0.7067927934 0.5371009167 -0.314841104631 +1403636595463555584.0000000000 4.5765292204 -1.9083836667 0.7620722586 0.3327639439 0.7044298307 0.5410369493 -0.316742467538 +1403636595513555456.0000000000 4.5907220285 -1.9188035221 0.7615660325 0.3299896387 0.7042280375 0.5426668028 -0.317304980475 +1403636595563555584.0000000000 4.6082229645 -1.9230428172 0.7606451177 0.3276592119 0.7036100892 0.5452891262 -0.316594459871 +1403636595613555456.0000000000 4.6277376883 -1.9210150091 0.7593785522 0.3264340955 0.7046940686 0.5457670273 -0.31461945743 +1403636595663555584.0000000000 4.6490635716 -1.9134716096 0.7573018261 0.3268299334 0.7066845055 0.5451660627 -0.310762237769 +1403636595713555456.0000000000 4.6710363170 -1.9011367998 0.7548533207 0.3290153054 0.7105055026 0.5416225859 -0.30590167376 +1403636595763555584.0000000000 4.6932435929 -1.8835662082 0.7519915717 0.3338148131 0.7144901068 0.5374834950 -0.298635313327 +1403636595813555456.0000000000 4.7154233917 -1.8631187811 0.7484574557 0.3405444935 0.7204212766 0.5301850308 -0.289700647689 +1403636595863555584.0000000000 4.7376307386 -1.8412214086 0.7445289751 0.3476045365 0.7266911714 0.5219872624 -0.280393162307 +1403636595913555456.0000000000 4.7577238099 -1.8174984859 0.7412019774 0.3535139528 0.7343340326 0.5119153974 -0.27152171125 +1403636595963555584.0000000000 4.7787964881 -1.7957527572 0.7381714151 0.3584695735 0.7420841731 0.5020043913 -0.262301803279 +1403636596013555456.0000000000 4.8001091760 -1.7767532536 0.7355964222 0.3623926392 0.7498018396 0.4927505050 -0.252320661519 +1403636596063555584.0000000000 4.8207743677 -1.7619701677 0.7337531840 0.3655628156 0.7577449624 0.4827607337 -0.24316347137 +1403636596113555456.0000000000 4.8402078927 -1.7527941841 0.7324605648 0.3676662407 0.7648289205 0.4736251796 -0.235663843132 +1403636596163555584.0000000000 4.8575705428 -1.7500789714 0.7324483155 0.3689255847 0.7701586476 0.4663183697 -0.230860885739 +1403636596213555456.0000000000 4.8725635232 -1.7540648631 0.7339983821 0.3702940054 0.7734693779 0.4607928124 -0.228686368445 +1403636596263555584.0000000000 4.8855796513 -1.7652061145 0.7372013986 0.3709063893 0.7756161844 0.4564547226 -0.229122393231 +1403636596313555456.0000000000 4.8970816434 -1.7816100155 0.7421524962 0.3719095759 0.7766535766 0.4531668396 -0.230504457204 +1403636596363555584.0000000000 4.9085249781 -1.8024304215 0.7481415014 0.3737336429 0.7767649601 0.4511088960 -0.231214456295 +1403636596413555456.0000000000 4.9198567021 -1.8258300095 0.7548410069 0.3764091164 0.7755466866 0.4508012570 -0.231563686049 +1403636596463555584.0000000000 4.9309566265 -1.8503111064 0.7613373314 0.3790925397 0.7733111273 0.4518472259 -0.232621648367 +1403636596513555456.0000000000 4.9410086036 -1.8741211449 0.7670717725 0.3816310470 0.7705954547 0.4538627392 -0.233557280376 +1403636596563555584.0000000000 4.9528404232 -1.8982914172 0.7722777576 0.3837026182 0.7678196394 0.4564516822 -0.234258754159 +1403636596613555456.0000000000 4.9607860090 -1.9188948242 0.7760385846 0.3843081290 0.7669827589 0.4577533503 -0.233466442493 +1403636596663555584.0000000000 4.9664827170 -1.9363265195 0.7791538865 0.3834135905 0.7669947018 0.4588082711 -0.23282636531 +1403636596713555456.0000000000 4.9700348980 -1.9497721948 0.7805526402 0.3822369441 0.7668656050 0.4602152734 -0.232409045756 +1403636596763555584.0000000000 4.9704532453 -1.9579943695 0.7809780360 0.3826175820 0.7653054255 0.4625981833 -0.23219455737 +1403636596813555456.0000000000 4.9671332644 -1.9608840645 0.7802965231 0.3848840958 0.7635133086 0.4633403057 -0.232867819772 +1403636596863555584.0000000000 4.9598599362 -1.9583417812 0.7790356275 0.3884375061 0.7608445365 0.4649163632 -0.232561110949 +1403636596913555456.0000000000 4.9483350049 -1.9514204795 0.7773905575 0.3915306838 0.7590691523 0.4652541167 -0.232500220723 +1403636596963555584.0000000000 4.9331187131 -1.9402062244 0.7753194311 0.3932928341 0.7578172142 0.4670216747 -0.230053411027 +1403636597013555456.0000000000 4.9141022421 -1.9260576319 0.7732655795 0.3920738224 0.7588989188 0.4673282377 -0.227936102947 +1403636597063555584.0000000000 4.8927871530 -1.9096943325 0.7705571454 0.3884589809 0.7603381004 0.4696159503 -0.224602876912 +1403636597113555456.0000000000 4.8689940353 -1.8918894538 0.7682629367 0.3827953608 0.7619087960 0.4721567572 -0.223675423313 +1403636597163555584.0000000000 4.8436149289 -1.8731612337 0.7667574463 0.3774473878 0.7614586075 0.4771710930 -0.223656000452 +1403636597213555456.0000000000 4.8164996177 -1.8535885056 0.7669588540 0.3730985347 0.7596822644 0.4825022873 -0.225547962245 +1403636597263555584.0000000000 4.7879242454 -1.8340398774 0.7686979893 0.3706652073 0.7564548623 0.4880462269 -0.228460556182 +1403636597313555456.0000000000 4.7584647315 -1.8151681591 0.7706954079 0.3697703031 0.7518540665 0.4940113381 -0.232245954658 +1403636597363555584.0000000000 4.7277815929 -1.7977079228 0.7733798008 0.3688777527 0.7471780596 0.4991835753 -0.237633980829 +1403636597413555456.0000000000 4.6976677745 -1.7817141448 0.7752114698 0.3688027584 0.7415620561 0.5057138367 -0.241503121509 +1403636597463555584.0000000000 4.6686156506 -1.7684506486 0.7768884024 0.3678637599 0.7360413137 0.5121159380 -0.246285819111 +1403636597513555456.0000000000 4.6423714956 -1.7587064731 0.7778880767 0.3669570831 0.7294258646 0.5197457353 -0.251286246689 +1403636597563555584.0000000000 4.6190501761 -1.7533505699 0.7785429563 0.3650109521 0.7231882134 0.5259968577 -0.259023393744 +1403636597613555456.0000000000 4.5998806727 -1.7528249966 0.7787960085 0.3628020078 0.7167402207 0.5314873867 -0.268662086967 +1403636597663555584.0000000000 4.5854088461 -1.7568856979 0.7785472320 0.3606573608 0.7101786780 0.5365258091 -0.278769742861 +1403636597713555456.0000000000 4.5758718065 -1.7650057989 0.7780790567 0.3589182523 0.7037251012 0.5411887872 -0.288207159399 +1403636597763555584.0000000000 4.5715364302 -1.7762828003 0.7775143842 0.3582576108 0.6977732517 0.5452854534 -0.295681835326 +1403636597813555456.0000000000 4.5723314367 -1.7895676300 0.7770863608 0.3582941692 0.6924045777 0.5487869012 -0.301718620908 +1403636597863555584.0000000000 4.5780636277 -1.8033476096 0.7762773138 0.3592695575 0.6876179642 0.5524513594 -0.304802256844 +1403636597913555456.0000000000 4.5884773433 -1.8172830236 0.7753417817 0.3596098646 0.6830967383 0.5567396162 -0.306758196506 +1403636597963555584.0000000000 4.6024198057 -1.8307104919 0.7739600773 0.3594036401 0.6800789291 0.5607314782 -0.30643414158 +1403636598013555456.0000000000 4.6195667089 -1.8436825160 0.7724331106 0.3578916372 0.6785900970 0.5642143681 -0.305108510429 +1403636598063555584.0000000000 4.6383701789 -1.8558066878 0.7701823999 0.3552828012 0.6791726023 0.5663347565 -0.30292515742 +1403636598113555456.0000000000 4.6591958187 -1.8669257829 0.7673543527 0.3505399407 0.6814443237 0.5678673301 -0.300469763934 +1403636598163555584.0000000000 4.6801317450 -1.8758627671 0.7635639445 0.3457690823 0.6846761957 0.5696308132 -0.295267650409 +1403636598213555456.0000000000 4.7002986453 -1.8824364727 0.7583545182 0.3402130742 0.6889354685 0.5713446081 -0.288423860194 +1403636598263555584.0000000000 4.7185687794 -1.8866589209 0.7518052368 0.3353299901 0.6922040250 0.5742056235 -0.280526803407 +1403636598313555456.0000000000 4.7333936471 -1.8883970936 0.7447562511 0.3317921050 0.6957912694 0.5749745682 -0.274212972733 +1403636598363555584.0000000000 4.7442382396 -1.8871408818 0.7373948164 0.3312725706 0.6977974614 0.5758862402 -0.267754038636 +1403636598413555456.0000000000 4.7503971269 -1.8836071259 0.7295451922 0.3321737139 0.6999049914 0.5748631497 -0.263298283101 +1403636598463555584.0000000000 4.7520201417 -1.8779432568 0.7216418038 0.3340982436 0.6998653807 0.5748741639 -0.26093391536 +1403636598513555456.0000000000 4.7486815764 -1.8705995546 0.7142478454 0.3365802246 0.6991399510 0.5738843345 -0.261866095484 +1403636598563555584.0000000000 4.7411586547 -1.8618854587 0.7078568109 0.3395180429 0.6960487833 0.5739790096 -0.266067071023 +1403636598613555456.0000000000 4.7301407887 -1.8522951093 0.7017266880 0.3431196446 0.6926230476 0.5730375301 -0.272342087349 +1403636598663555584.0000000000 4.7168177861 -1.8422280517 0.6957537920 0.3467566621 0.6879292920 0.5728980611 -0.279823011987 +1403636598713555456.0000000000 4.7021788659 -1.8323347622 0.6886909372 0.3506993472 0.6825168570 0.5724473399 -0.28893727838 +1403636598763555584.0000000000 4.6871660174 -1.8228408052 0.6806113702 0.3551549382 0.6760428590 0.5719285606 -0.299547565831 +1403636598813555456.0000000000 4.6724516179 -1.8138834237 0.6712697882 0.3600774067 0.6702155753 0.5701491522 -0.309976270254 +1403636598863555584.0000000000 4.6580709204 -1.8047936655 0.6608956087 0.3663987992 0.6648482982 0.5672354902 -0.319331424833 +1403636598913555456.0000000000 4.6445070156 -1.7963543463 0.6496794413 0.3725039268 0.6610830344 0.5633738425 -0.326833229131 +1403636598963555584.0000000000 4.6321309874 -1.7882201558 0.6378752586 0.3793277127 0.6572492913 0.5607602074 -0.331182495455 +1403636599013555456.0000000000 4.6215230230 -1.7814599682 0.6263009866 0.3844347681 0.6536769447 0.5588624459 -0.335543033898 +1403636599063555584.0000000000 4.6119495377 -1.7760258676 0.6167549835 0.3888094898 0.6502030354 0.5558281959 -0.342225379017 +1403636599113555456.0000000000 4.6039993707 -1.7716039257 0.6088991742 0.3926851476 0.6457717077 0.5528698272 -0.350873525026 +1403636599163555584.0000000000 4.5968767071 -1.7680019620 0.6032731692 0.3979136339 0.6403235077 0.5486142320 -0.361487164149 +1403636599213555456.0000000000 4.5893836651 -1.7643208047 0.5983657116 0.4085623471 0.6333845752 0.5431482744 -0.369987486806 +1403636599263555584.0000000000 4.5818007281 -1.7613407876 0.5944577446 0.4180766006 0.6278016916 0.5359105289 -0.379311082149 +1403636599313555456.0000000000 4.5752402722 -1.7586180838 0.5906441193 0.4262871872 0.6230355848 0.5295321413 -0.386912917166 +1403636599363555584.0000000000 4.5691015807 -1.7560441010 0.5864334174 0.4328055706 0.6200008491 0.5244860219 -0.391398387734 +1403636599413555456.0000000000 4.5637228300 -1.7535825879 0.5814665487 0.4384594984 0.6179885265 0.5217914208 -0.391889222355 +1403636599463555584.0000000000 4.5590786946 -1.7512657409 0.5761095859 0.4425657732 0.6176170767 0.5204463161 -0.3896412645 +1403636599513555456.0000000000 4.5551288757 -1.7496124921 0.5713649768 0.4433558655 0.6208182711 0.5180168667 -0.386883414699 +1403636599563555584.0000000000 4.5520437942 -1.7481826904 0.5669755422 0.4429252875 0.6245997277 0.5162033718 -0.383700988694 +1403636599613555456.0000000000 4.5503211842 -1.7470296772 0.5624172430 0.4415626770 0.6277078997 0.5156074278 -0.38099104372 +1403636599663555584.0000000000 4.5492624984 -1.7458243040 0.5579106016 0.4411685692 0.6294838944 0.5158010581 -0.378245408181 +1403636599713555456.0000000000 4.5489139221 -1.7449309663 0.5547480871 0.4419832251 0.6295318662 0.5144072961 -0.379111582335 +1403636599763555584.0000000000 4.5492823107 -1.7438739231 0.5547388953 0.4475683248 0.6245168614 0.5118632745 -0.384261984277 +1403636599813555456.0000000000 4.5494052102 -1.7430067414 0.5551080720 0.4527040293 0.6210877149 0.5083926064 -0.388389070405 +1403636599863555584.0000000000 4.5498055193 -1.7426737029 0.5547960405 0.4563427016 0.6186223907 0.5053367975 -0.392036219607 +1403636599913555456.0000000000 4.5508115056 -1.7424333874 0.5545740340 0.4567201023 0.6179861898 0.5039811042 -0.39433851443 +1403636599963555584.0000000000 4.5507886264 -1.7419330534 0.5542800026 0.4561294071 0.6196777300 0.5027479822 -0.393941545503 +1403636600013555456.0000000000 4.5510742463 -1.7416402280 0.5538744895 0.4557039787 0.6207606727 0.5019175723 -0.393787787535 +1403636600063555584.0000000000 4.5514154806 -1.7408821566 0.5529716943 0.4545034790 0.6215130504 0.5007047366 -0.395528611515 +1403636600113555456.0000000000 4.5519075401 -1.7403229153 0.5533039684 0.4553260885 0.6207351754 0.4983051767 -0.398820694007 +1403636600163555584.0000000000 4.5523268689 -1.7399078825 0.5530417321 0.4564386244 0.6198649914 0.4988535167 -0.398216452951 +1403636600213555456.0000000000 4.5522755897 -1.7404205471 0.5530334958 0.4555465458 0.6204681854 0.4983041635 -0.398985634121 +1403636600263555584.0000000000 4.5523832956 -1.7406496117 0.5529116434 0.4553510479 0.6204803801 0.4982925353 -0.399204296498 +1403636600313555456.0000000000 4.5526672279 -1.7409019294 0.5528985970 0.4550639829 0.6206683918 0.4980454492 -0.399547555875 +1403636600363555584.0000000000 4.5527538435 -1.7410206842 0.5528866195 0.4549011374 0.6208368577 0.4976767155 -0.399930541655 +1403636600413555456.0000000000 4.5528600609 -1.7410814619 0.5528518902 0.4548535409 0.6207990297 0.4977147331 -0.399996081766 +1403636600463555584.0000000000 4.5529499924 -1.7411518009 0.5528859139 0.4545271309 0.6210265220 0.4974074093 -0.400396073076 +1403636600513555456.0000000000 4.5530310567 -1.7409346072 0.5529241383 0.4548870787 0.6209038949 0.4973554098 -0.400242045928 +1403636600563555584.0000000000 4.5529996575 -1.7408561313 0.5528509035 0.4549473620 0.6207845479 0.4976680769 -0.39996990907 +1403636600613555456.0000000000 4.5529781603 -1.7409970789 0.5529271632 0.4546283883 0.6210261831 0.4973394785 -0.400366021931 +1403636600663555584.0000000000 4.5530353683 -1.7408625279 0.5529115653 0.4546853147 0.6210408813 0.4974134611 -0.400186627815 +1403636600713555456.0000000000 4.5530698183 -1.7408680574 0.5529114686 0.4545973484 0.6210863096 0.4974580836 -0.40016059514 +1403636600763555584.0000000000 4.5530014951 -1.7409086917 0.5528931063 0.4544718570 0.6211671355 0.4973134305 -0.400357431438 +1403636600813555456.0000000000 4.5530619822 -1.7407676905 0.5528446800 0.4547305763 0.6210240793 0.4975034354 -0.400049406564 +1403636600863555584.0000000000 4.5530661333 -1.7408964414 0.5528607810 0.4544357117 0.6212108515 0.4973347869 -0.400304098963 +1403636600913555456.0000000000 4.5530180506 -1.7408048214 0.5528081712 0.4546584626 0.6210876748 0.4974787659 -0.400063320148 +1403636600963555584.0000000000 4.5530305884 -1.7409024471 0.5528496323 0.4544004623 0.6212963865 0.4972681967 -0.400294092627 +1403636601013555456.0000000000 4.5530842127 -1.7407578433 0.5528035271 0.4546561688 0.6211264957 0.4975139990 -0.399961829789 +1403636601063555584.0000000000 4.5530333731 -1.7409142030 0.5529096183 0.4543715906 0.6213449170 0.4972424819 -0.400283482014 +1403636601113555456.0000000000 4.5530084569 -1.7407824594 0.5528429205 0.4546010688 0.6212012617 0.4974563223 -0.399980084665 +1403636601163555584.0000000000 4.5529956058 -1.7408944086 0.5529085107 0.4544039745 0.6213383488 0.4972633228 -0.400231023261 +1403636601213555456.0000000000 4.5529703156 -1.7408358576 0.5528981228 0.4545989202 0.6212072520 0.4974423006 -0.399990661686 +1403636601263555584.0000000000 4.5528859286 -1.7409502884 0.5529569997 0.4543474249 0.6213829019 0.4972389449 -0.400256340906 +1403636601313555456.0000000000 4.5529148926 -1.7408267896 0.5529865690 0.4545422236 0.6212501614 0.4974191340 -0.400017260986 +1403636601363555584.0000000000 4.5528168299 -1.7408348288 0.5529341618 0.4543882773 0.6213907944 0.4972431195 -0.400192521392 +1403636601413555456.0000000000 4.5527128810 -1.7407785435 0.5528959037 0.4544899911 0.6213390866 0.4973342636 -0.400044019731 +1403636601463555584.0000000000 4.5526162841 -1.7408136894 0.5529418873 0.4543821670 0.6214319721 0.4972067801 -0.400180669459 +1403636601513555456.0000000000 4.5525749391 -1.7407089160 0.5529810505 0.4545098146 0.6213606023 0.4972322588 -0.400114872414 +1403636601563555584.0000000000 4.5524635454 -1.7407169509 0.5530815531 0.4544383133 0.6214537874 0.4970908206 -0.400227092498 +1403636601613555456.0000000000 4.5524345451 -1.7406901166 0.5530799430 0.4544604522 0.6214267812 0.4971582448 -0.400160133764 +1403636601663555584.0000000000 4.5523640938 -1.7406311061 0.5531053078 0.4545233540 0.6214200934 0.4970992995 -0.400172306163 +1403636601713555456.0000000000 4.5523912595 -1.7406550895 0.5530823701 0.4544853876 0.6214382250 0.4970964468 -0.400190813914 +1403636601763555584.0000000000 4.5523315329 -1.7406652895 0.5531021109 0.4545149605 0.6214381514 0.4970877952 -0.400168087928 +1403636601813555456.0000000000 4.5522990837 -1.7407251571 0.5529933268 0.4544164791 0.6214646051 0.4971137684 -0.400206583436 +1403636601863555584.0000000000 4.5522130801 -1.7407139876 0.5529802971 0.4544895917 0.6214550053 0.4970967558 -0.400159596672 +1403636601913555456.0000000000 4.5521804455 -1.7407122089 0.5529776684 0.4544384779 0.6214954168 0.4970579135 -0.400203132486 +1403636601963555584.0000000000 4.5521663366 -1.7407008422 0.5529809905 0.4544885623 0.6214703418 0.4971101369 -0.400120322892 +1403636602013555456.0000000000 4.5521681429 -1.7407017651 0.5530561897 0.4544566301 0.6215073270 0.4970197569 -0.40021141313 +1403636602063555584.0000000000 4.5522190798 -1.7406549249 0.5531457067 0.4544773185 0.6214793993 0.4971181886 -0.400109022397 +1403636602113555456.0000000000 4.5521604270 -1.7406794513 0.5531518204 0.4543847778 0.6215787018 0.4969961661 -0.400211446603 +1403636602163555584.0000000000 4.5521610921 -1.7405777461 0.5531264728 0.4544688544 0.6215057530 0.4971329053 -0.400059413055 +1403636602213555456.0000000000 4.5521280731 -1.7405922614 0.5531625901 0.4543662347 0.6216029295 0.4969795821 -0.400215464334 +1403636602263555584.0000000000 4.5521983867 -1.7404546359 0.5531190175 0.4544970188 0.6215125968 0.4971533577 -0.399991363465 +1403636602313555456.0000000000 4.5521764693 -1.7405207023 0.5531401195 0.4543387486 0.6216223297 0.4970232007 -0.400162365367 +1403636602363555584.0000000000 4.5521866140 -1.7405095795 0.5530968926 0.4544184144 0.6215588394 0.4971408942 -0.400024305649 +1403636602413555456.0000000000 4.5521559812 -1.7405918608 0.5531039909 0.4543358095 0.6216042182 0.4970474940 -0.400163662581 +1403636602463555584.0000000000 4.5521247506 -1.7406040738 0.5531106324 0.4543992169 0.6215757527 0.4970627879 -0.400116883148 +1403636602513555456.0000000000 4.5521781136 -1.7406531826 0.5531575247 0.4543472270 0.6216441463 0.4970201170 -0.40012267618 +1403636602563555584.0000000000 4.5521716707 -1.7406538115 0.5531108464 0.4543516504 0.6216385135 0.4970286672 -0.400115783593 +1403636602613555456.0000000000 4.5522103068 -1.7406365521 0.5530839684 0.4543354789 0.6216456209 0.4970578900 -0.400086801445 +1403636602663555584.0000000000 4.5522072331 -1.7406206665 0.5530573057 0.4543448772 0.6216592572 0.4970463083 -0.400069328824 +1403636602713555456.0000000000 4.5522085139 -1.7406360220 0.5530639548 0.4543328506 0.6216786433 0.4970086038 -0.400099703969 +1403636602763555584.0000000000 4.5522071578 -1.7406304751 0.5531229316 0.4543350582 0.6217175076 0.4969698992 -0.400084884639 +1403636602813555456.0000000000 4.5522641083 -1.7406303317 0.5530452363 0.4543777873 0.6216941230 0.4969745427 -0.400066929196 +1403636602863555584.0000000000 4.5523119252 -1.7406432951 0.5530235396 0.4543523268 0.6217220399 0.4969356243 -0.400100804214 +1403636602913555456.0000000000 4.5524057726 -1.7406169042 0.5529970450 0.4543837098 0.6216922888 0.4969769127 -0.40006010877 +1403636602963555584.0000000000 4.5524365729 -1.7406096015 0.5530382597 0.4543753446 0.6217302425 0.4968994069 -0.400106899669 +1403636603013555456.0000000000 4.5524239646 -1.7405699912 0.5530398839 0.4544295553 0.6217108466 0.4969431427 -0.400021143655 +1403636603063555584.0000000000 4.5523964990 -1.7406046912 0.5531227653 0.4543475098 0.6217620839 0.4968835913 -0.400108670224 +1403636603113555456.0000000000 4.5523660212 -1.7405649180 0.5530715286 0.4544800476 0.6217199008 0.4969166788 -0.399982581562 +1403636603163555584.0000000000 4.5523851464 -1.7406110123 0.5531625638 0.4544067247 0.6217936896 0.4968549519 -0.400027865144 +1403636603213555456.0000000000 4.5523830740 -1.7406168178 0.5531249129 0.4544290031 0.6217673914 0.4969041895 -0.399982272818 +1403636603263555584.0000000000 4.5523610131 -1.7406355881 0.5531358103 0.4544000467 0.6217688604 0.4968838201 -0.400038186932 +1403636603313555456.0000000000 4.5523296489 -1.7406115495 0.5531225684 0.4544430186 0.6217487756 0.4969078697 -0.399990714798 +1403636603363555584.0000000000 4.5523022283 -1.7405916273 0.5531416785 0.4544317395 0.6217535280 0.4968677792 -0.400045940504 +1403636603413555456.0000000000 4.5522665874 -1.7405082942 0.5531517936 0.4544706813 0.6217399271 0.4968724404 -0.400017050824 +1403636603463555584.0000000000 4.5522517518 -1.7404873179 0.5531472700 0.4544605322 0.6217631083 0.4968620759 -0.400005424158 +1403636603513555456.0000000000 4.5522704463 -1.7404567395 0.5531990676 0.4544330852 0.6218157816 0.4968639968 -0.399952339161 +1403636603563555584.0000000000 4.5522656150 -1.7404269514 0.5531511341 0.4544283625 0.6218072872 0.4968781975 -0.399953269503 +1403636603613555456.0000000000 4.5522578907 -1.7404486785 0.5531977624 0.4544184523 0.6218262188 0.4968807192 -0.399931962522 +1403636603663555584.0000000000 4.5522364649 -1.7404564705 0.5531549009 0.4544573047 0.6218162300 0.4968775917 -0.399907230816 +1403636603713555456.0000000000 4.5522653240 -1.7404760644 0.5531700167 0.4544396772 0.6218340759 0.4968731072 -0.399905085176 +1403636603763555584.0000000000 4.5522843244 -1.7404873545 0.5531931407 0.4544018274 0.6218763212 0.4968581021 -0.399901046301 +1403636603813555456.0000000000 4.5523174076 -1.7405024716 0.5531298088 0.4543957343 0.6218735129 0.4968971869 -0.399863772233 +1403636603863555584.0000000000 4.5522919847 -1.7405224511 0.5531350049 0.4544751800 0.6218258769 0.4968313093 -0.399929418437 +1403636603913555456.0000000000 4.5523263678 -1.7405617539 0.5531104648 0.4543765491 0.6218815368 0.4968358499 -0.399949301843 +1403636603963555584.0000000000 4.5522990358 -1.7405128030 0.5531173935 0.4545197998 0.6218064645 0.4968676368 -0.399863756678 +1403636604013555456.0000000000 4.5523025636 -1.7405878009 0.5531436678 0.4543944295 0.6218781910 0.4967772940 -0.400006922636 +1403636604063555584.0000000000 4.5523030188 -1.7405585616 0.5531754971 0.4544444979 0.6218604756 0.4968169471 -0.399928329077 +1403636604113555456.0000000000 4.5522822514 -1.7405931292 0.5531171553 0.4544156554 0.6218707618 0.4967637089 -0.400011231432 +1403636604163555584.0000000000 4.5523132509 -1.7405641017 0.5530996225 0.4544884247 0.6218107091 0.4968342865 -0.399934251566 +1403636604213555456.0000000000 4.5522829945 -1.7405843164 0.5531089768 0.4544422710 0.6218601376 0.4967744609 -0.39998415783 +1403636604263555584.0000000000 4.5522598624 -1.7405701632 0.5531249364 0.4544599719 0.6218543465 0.4967785781 -0.399967936256 +1403636604313555456.0000000000 4.5522330237 -1.7405813931 0.5531562618 0.4544412844 0.6218837934 0.4967442924 -0.39998596776 +1403636604363555584.0000000000 4.5522259910 -1.7405659848 0.5531736139 0.4544634060 0.6218651071 0.4967899866 -0.399933132343 +1403636604413555456.0000000000 4.5522297808 -1.7405755036 0.5532096342 0.4544021598 0.6218898856 0.4967824224 -0.399973589247 +1403636604463555584.0000000000 4.5522522208 -1.7405556012 0.5532257620 0.4544613236 0.6218553398 0.4967898244 -0.399950887128 +1403636604513555456.0000000000 4.5522156666 -1.7405453057 0.5532308536 0.4544561682 0.6218764672 0.4967540415 -0.399968339971 +1403636604563555584.0000000000 4.5522075131 -1.7405156663 0.5532578629 0.4544309094 0.6219148521 0.4967176035 -0.39998260932 +1403636604613555456.0000000000 4.5521712011 -1.7404802432 0.5531797107 0.4544750632 0.6219110128 0.4967021982 -0.39995754193 +1403636604663555584.0000000000 4.5521758353 -1.7404646113 0.5531595713 0.4544464608 0.6219140884 0.4967168566 -0.399967055176 +1403636604713555456.0000000000 4.5521774978 -1.7404399814 0.5531286958 0.4544569988 0.6219082069 0.4967208775 -0.399959233268 +1403636604763555584.0000000000 4.5521933104 -1.7404372781 0.5531112207 0.4544592850 0.6219182102 0.4967226850 -0.399938835718 +1403636604813555456.0000000000 4.5522444512 -1.7404386551 0.5531647181 0.4544648830 0.6218982456 0.4967539590 -0.399924675889 +1403636604863555584.0000000000 4.5522327420 -1.7404788768 0.5531279113 0.4544703684 0.6219195322 0.4967372688 -0.399906070971 +1403636604913555456.0000000000 4.5522376778 -1.7405161816 0.5531429434 0.4544536894 0.6219149550 0.4967671727 -0.39989499761 +1403636604963555584.0000000000 4.5522840322 -1.7405617450 0.5531446775 0.4544334587 0.6219075230 0.4967737026 -0.399921433251 +1403636605013555456.0000000000 4.5523380598 -1.7405841976 0.5531513281 0.4544374630 0.6219186143 0.4967666061 -0.399908450145 +1403636605063555584.0000000000 4.5523731773 -1.7405837599 0.5531286246 0.4543845289 0.6219450042 0.4967666387 -0.399927516285 +1403636605113555456.0000000000 4.5523899158 -1.7405219047 0.5530913015 0.4544638483 0.6218915873 0.4967846045 -0.399898138135 +1403636605163555584.0000000000 4.5523726820 -1.7405114011 0.5531042233 0.4543935147 0.6219544237 0.4967199961 -0.399960590814 +1403636605213555456.0000000000 4.5523329092 -1.7404816447 0.5531104802 0.4544273393 0.6219399830 0.4967470529 -0.399911010491 +1403636605263555584.0000000000 4.5522991840 -1.7404840177 0.5531245916 0.4544034294 0.6219655899 0.4966969401 -0.399960595467 +1403636605313555456.0000000000 4.5523000819 -1.7404347632 0.5531524147 0.4544532196 0.6219373051 0.4967240532 -0.399914334203 +1403636605363555584.0000000000 4.5522691708 -1.7404546249 0.5530937101 0.4543995118 0.6219886382 0.4966588806 -0.399976466715 +1403636605413555456.0000000000 4.5522569708 -1.7404551099 0.5530941012 0.4544642180 0.6219587678 0.4966930769 -0.399906930643 +1403636605463555584.0000000000 4.5522355438 -1.7404688381 0.5531212871 0.4544014168 0.6220023783 0.4966589285 -0.399952875358 +1403636605513555456.0000000000 4.5522162740 -1.7404734276 0.5531110936 0.4544282244 0.6219966693 0.4966791791 -0.399906145579 +1403636605563555584.0000000000 4.5522065908 -1.7404920205 0.5531730624 0.4543930345 0.6220543574 0.4966311268 -0.399916079298 +1403636605613555456.0000000000 4.5521956966 -1.7405052437 0.5531450523 0.4544434587 0.6220026178 0.4966739835 -0.39988603426 +1403636605663555584.0000000000 4.5522049941 -1.7405431546 0.5531762948 0.4544145043 0.6220209019 0.4966553870 -0.399913593665 +1403636605713555456.0000000000 4.5522241911 -1.7405598098 0.5531799771 0.4544032024 0.6220368220 0.4966663443 -0.399888064467 +1403636605763555584.0000000000 4.5522536074 -1.7405479013 0.5531746363 0.4543970719 0.6220730003 0.4966567070 -0.399850720579 +1403636605813555456.0000000000 4.5522914541 -1.7405206820 0.5531682934 0.4544490743 0.6220508825 0.4966438056 -0.399842054876 +1403636605863555584.0000000000 4.5523200552 -1.7405105384 0.5531500247 0.4544229035 0.6220902762 0.4966213689 -0.399838378581 +1403636605913555456.0000000000 4.5523537459 -1.7405084060 0.5531387582 0.4544139048 0.6220812379 0.4966538832 -0.399822281553 +1403636605963555584.0000000000 4.5523678586 -1.7405133835 0.5531505090 0.4543951073 0.6221074073 0.4966307014 -0.399831723065 +1403636606013555456.0000000000 4.5523863899 -1.7405099779 0.5531729664 0.4543931887 0.6221043638 0.4966492237 -0.399815631555 +1403636606063555584.0000000000 4.5523942836 -1.7405405380 0.5531240851 0.4544058155 0.6221045251 0.4966363891 -0.399816972691 +1403636606113555456.0000000000 4.5524052429 -1.7405616013 0.5531182362 0.4544218288 0.6221100851 0.4966234984 -0.399806133518 +1403636606163555584.0000000000 4.5524392816 -1.7405792807 0.5530717905 0.4544313693 0.6221323407 0.4966122611 -0.399774615678 +1403636606213555456.0000000000 4.5524804006 -1.7405939104 0.5530472107 0.4544469034 0.6221211604 0.4966063307 -0.399781723027 +1403636606263555584.0000000000 4.5525188582 -1.7405574888 0.5530331053 0.4544648694 0.6221312969 0.4965968763 -0.399757269161 +1403636606313555456.0000000000 4.5525407420 -1.7405250932 0.5530969185 0.4544287624 0.6221809191 0.4965605079 -0.399766263986 +1403636606363555584.0000000000 4.5525433124 -1.7405334512 0.5530413600 0.4544800136 0.6221649254 0.4965526312 -0.399742676239 +1403636606413555456.0000000000 4.5525782784 -1.7405763412 0.5530245433 0.4544820788 0.6221750683 0.4965386606 -0.3997418955 +1403636606463555584.0000000000 4.5526175111 -1.7406126879 0.5530385391 0.4544754786 0.6221790322 0.4965370762 -0.399745197794 +1403636606513555456.0000000000 4.5526271006 -1.7406359311 0.5530781227 0.4544653011 0.6222067846 0.4964879448 -0.399774596544 +1403636606563555584.0000000000 4.5526335209 -1.7406028467 0.5530954244 0.4544781808 0.6222148324 0.4964819162 -0.399754915378 +1403636606613555456.0000000000 4.5526361585 -1.7405570480 0.5530809072 0.4545252828 0.6221906788 0.4964697390 -0.399754080219 +1403636606663555584.0000000000 4.5526277038 -1.7405579556 0.5530550874 0.4545395701 0.6221963057 0.4964642688 -0.399735870511 +1403636606713555456.0000000000 4.5526227142 -1.7405479434 0.5531188933 0.4545277952 0.6221909993 0.4964672702 -0.39975379091 +1403636606763555584.0000000000 4.5525895310 -1.7405447186 0.5530415633 0.4545501929 0.6222061067 0.4964644830 -0.399708268651 +1403636606813555456.0000000000 4.5526140816 -1.7405580062 0.5530216738 0.4545287108 0.6221898767 0.4964921909 -0.399723545386 +1403636606863555584.0000000000 4.5526437629 -1.7405560042 0.5530145313 0.4545146105 0.6221950974 0.4964860127 -0.399739125969 +1403636606913555456.0000000000 4.5526728988 -1.7405578439 0.5529934992 0.4545101723 0.6222097002 0.4965072911 -0.399695011489 +1403636606963555584.0000000000 4.5526789480 -1.7405553093 0.5529819476 0.4545234105 0.6222147836 0.4964895112 -0.399694130079 +1403636607013555456.0000000000 4.5526281684 -1.7405606088 0.5529963232 0.4545219617 0.6222243714 0.4964720272 -0.399702569669 +1403636607063555584.0000000000 4.5526323435 -1.7405616735 0.5530932632 0.4544994913 0.6222308327 0.4964787231 -0.399709745674 +1403636607113555456.0000000000 4.5525669479 -1.7405474075 0.5530441347 0.4545080996 0.6222130247 0.4964918859 -0.399711328961 +1403636607163555584.0000000000 4.5525267252 -1.7405196086 0.5530753668 0.4545177849 0.6222147738 0.4964923775 -0.3996969822 +1403636607213555456.0000000000 4.5524808238 -1.7404728587 0.5530903720 0.4544952953 0.6222344099 0.4965042749 -0.399677208133 +1403636607263555584.0000000000 4.5524057362 -1.7404233820 0.5530995015 0.4545204333 0.6222391915 0.4964891624 -0.399659950393 +1403636607313555456.0000000000 4.5523440016 -1.7404066930 0.5531542950 0.4544565395 0.6222689667 0.4965129776 -0.399656664992 +1403636607363555584.0000000000 4.5522619485 -1.7403708673 0.5530495367 0.4544997376 0.6222450162 0.4965357871 -0.399616491692 +1403636607413555456.0000000000 4.5522197919 -1.7403880480 0.5530404174 0.4544767427 0.6222704641 0.4965161754 -0.399627385717 +1403636607463555584.0000000000 4.5521733940 -1.7404048340 0.5531228519 0.4544811665 0.6222489818 0.4965137967 -0.399658758967 +1403636607513555456.0000000000 4.5521237492 -1.7404004949 0.5530864324 0.4544931897 0.6222347638 0.4965177178 -0.399662351482 +1403636607563555584.0000000000 4.5521035781 -1.7403686690 0.5531071493 0.4545214722 0.6222216663 0.4965286987 -0.399636935989 +1403636607613555456.0000000000 4.5521202532 -1.7403395001 0.5531377380 0.4545397120 0.6222280405 0.4965166467 -0.399621239957 +1403636607663555584.0000000000 4.5521421379 -1.7403379545 0.5531551280 0.4545458377 0.6222457440 0.4965238104 -0.399577803628 +1403636607713555456.0000000000 4.5521754478 -1.7403545818 0.5531716305 0.4545035977 0.6222771758 0.4965219172 -0.399579256015 +1403636607763555584.0000000000 4.5521844275 -1.7403579444 0.5531802548 0.4545087529 0.6222820465 0.4965228643 -0.399564629688 +1403636607813555456.0000000000 4.5522010450 -1.7403502360 0.5531530039 0.4545047786 0.6222751689 0.4965314961 -0.399569135169 +1403636607863555584.0000000000 4.5522164680 -1.7403638739 0.5531178988 0.4544965304 0.6223008071 0.4964976350 -0.399580664981 +1403636607913555456.0000000000 4.5522436960 -1.7403940567 0.5530804052 0.4544979799 0.6223193015 0.4964662947 -0.39958915338 +1403636607963555584.0000000000 4.5522971869 -1.7404159360 0.5530475322 0.4545329125 0.6223224117 0.4964785534 -0.399529339848 +1403636608013555456.0000000000 4.5523489023 -1.7404537276 0.5530478107 0.4545313353 0.6223335923 0.4964729626 -0.399520665884 +1403636608063555584.0000000000 4.5524053084 -1.7404586825 0.5531122621 0.4545095973 0.6223619090 0.4964533220 -0.399525692901 +1403636608113555456.0000000000 4.5524358836 -1.7404557762 0.5530708186 0.4545267866 0.6223679413 0.4964366426 -0.399517466116 +1403636608163555584.0000000000 4.5524602795 -1.7404697302 0.5530862765 0.4545232329 0.6223735884 0.4964106232 -0.399545041754 +1403636608213555456.0000000000 4.5524883079 -1.7404933403 0.5530787010 0.4545235187 0.6223821626 0.4964096271 -0.399532597717 +1403636608263555584.0000000000 4.5525107351 -1.7405220697 0.5530680805 0.4544887358 0.6223884433 0.4963956183 -0.399579785333 +1403636608313555456.0000000000 4.5525316576 -1.7405074659 0.5530494768 0.4545159680 0.6223742420 0.4964040739 -0.399560424895 +1403636608363555584.0000000000 4.5525439489 -1.7404900078 0.5530289410 0.4544803300 0.6223924453 0.4964085123 -0.399567094095 +1403636608413555456.0000000000 4.5525264911 -1.7404847014 0.5530150206 0.4544864585 0.6223958262 0.4964005461 -0.399564753741 +1403636608463555584.0000000000 4.5525052503 -1.7405035023 0.5529940038 0.4544568172 0.6224016242 0.4964021824 -0.399587403231 +1403636608513555456.0000000000 4.5524828315 -1.7405218098 0.5530436665 0.4544528984 0.6224237085 0.4963732802 -0.399593364414 +1403636608563555584.0000000000 4.5524246353 -1.7405475189 0.5529902116 0.4544960023 0.6223877101 0.4963703081 -0.399604103468 +1403636608613555456.0000000000 4.5523994445 -1.7405401485 0.5530152508 0.4545193781 0.6223827983 0.4963681027 -0.399587905183 +1403636608663555584.0000000000 4.5524088298 -1.7405298788 0.5530367242 0.4545334143 0.6223969492 0.4963569705 -0.399563725538 +1403636608713555456.0000000000 4.5523949957 -1.7405196164 0.5530740057 0.4545732491 0.6223885344 0.4963512737 -0.399538591945 +1403636608763555584.0000000000 4.5523802117 -1.7405071737 0.5531207263 0.4545548742 0.6224055283 0.4963502576 -0.399534286845 +1403636608813555456.0000000000 4.5523677817 -1.7404881890 0.5531949590 0.4545209972 0.6224301748 0.4963572514 -0.399525743341 +1403636608863555584.0000000000 4.5523099468 -1.7404855899 0.5531275717 0.4545266926 0.6224329684 0.4963587593 -0.399513038019 +1403636608913555456.0000000000 4.5523261353 -1.7404640522 0.5531192247 0.4545225194 0.6224273856 0.4963615473 -0.399523019908 +1403636608963555584.0000000000 4.5523754111 -1.7404141182 0.5531206912 0.4545194428 0.6224437499 0.4963178464 -0.399555314908 +1403636609013555456.0000000000 4.5524271705 -1.7403534350 0.5530917950 0.4545202555 0.6224441320 0.4963342113 -0.399533466141 +1403636609063555584.0000000000 4.5524462172 -1.7403421933 0.5530720253 0.4545118545 0.6224305661 0.4963474418 -0.399547721226 +1403636609113555456.0000000000 4.5524322051 -1.7403625550 0.5530568736 0.4545238075 0.6224211083 0.4963535039 -0.39954132647 +1403636609163555584.0000000000 4.5524367844 -1.7403913552 0.5530746726 0.4545359978 0.6224073134 0.4963258478 -0.399583302772 +1403636609213555456.0000000000 4.5524514197 -1.7403999765 0.5530770565 0.4545381721 0.6224014358 0.4963123647 -0.399606731036 +1403636609263555584.0000000000 4.5524797414 -1.7404072239 0.5531031827 0.4545320590 0.6224166924 0.4962980651 -0.399607681215 +1403636609313555456.0000000000 4.5524911206 -1.7403915812 0.5530355612 0.4545485607 0.6224020140 0.4963290653 -0.399573269725 +1403636609363555584.0000000000 4.5524911133 -1.7404045985 0.5530398578 0.4545288307 0.6224207822 0.4963429825 -0.399549190543 +1403636609413555456.0000000000 4.5524639390 -1.7404274648 0.5530522222 0.4545412489 0.6224390366 0.4963260638 -0.399527642605 +1403636609463555584.0000000000 4.5524651949 -1.7404628816 0.5530502843 0.4545463587 0.6224303240 0.4963429965 -0.399514366904 +1403636609513555456.0000000000 4.5524785851 -1.7404918731 0.5530338728 0.4545544170 0.6224439078 0.4963371493 -0.399491298832 +1403636609563555584.0000000000 4.5525140105 -1.7405046491 0.5530780935 0.4545491375 0.6224445643 0.4962986731 -0.39954408147 +1403636609613555456.0000000000 4.5525129961 -1.7404916882 0.5530226186 0.4545576544 0.6224479372 0.4963037124 -0.399522877194 +1403636609663555584.0000000000 4.5525337986 -1.7404955098 0.5530597065 0.4545158915 0.6224916121 0.4962799351 -0.399531880046 +1403636609713555456.0000000000 4.5525187939 -1.7404805891 0.5531025879 0.4545787545 0.6224436286 0.4962978194 -0.399512903003 +1403636609763555584.0000000000 4.5525067005 -1.7405264144 0.5531737626 0.4545448921 0.6224741066 0.4962484692 -0.399565244395 +1403636609813555456.0000000000 4.5525532383 -1.7405537311 0.5531536043 0.4544180430 0.6225261489 0.4963391805 -0.399515774381 +1403636609863555584.0000000000 4.5525359474 -1.7405529554 0.5531441782 0.4545176990 0.6224816289 0.4963041669 -0.399515277382 +1403636609913555456.0000000000 4.5525578152 -1.7405890887 0.5530854436 0.4544429067 0.6225118571 0.4962994347 -0.399559136365 +1403636609963555584.0000000000 4.5525605900 -1.7405679326 0.5530223199 0.4544235288 0.6225329090 0.4963144142 -0.399529768453 +1403636610013555456.0000000000 4.5525037701 -1.7405671894 0.5530541232 0.4544382547 0.6225344318 0.4962768693 -0.399557283737 +1403636610063555584.0000000000 4.5524695429 -1.7405972018 0.5530766567 0.4544185950 0.6225285790 0.4962952823 -0.399565891501 +1403636610113555456.0000000000 4.5524102730 -1.7406343415 0.5530970312 0.4544171713 0.6225396025 0.4962531452 -0.399602669681 +1403636610163555584.0000000000 4.5523887633 -1.7406161602 0.5531541881 0.4544325256 0.6225391745 0.4962557145 -0.399582684419 +1403636610213555456.0000000000 4.5523609210 -1.7405955928 0.5531374592 0.4544089356 0.6225671440 0.4962271059 -0.3996014638 +1403636610263555584.0000000000 4.5523746449 -1.7405021383 0.5531065732 0.4544366866 0.6225718674 0.4962873823 -0.399487674336 +1403636610313555456.0000000000 4.5523988303 -1.7404953874 0.5531472852 0.4544185832 0.6225947592 0.4962055132 -0.399574280669 +1403636610363555584.0000000000 4.5524220625 -1.7404619784 0.5531150278 0.4544077317 0.6226277809 0.4961953654 -0.399547768334 +1403636610413555456.0000000000 4.5523908678 -1.7404280912 0.5530577686 0.4544630212 0.6225986114 0.4962301296 -0.399487158668 +1403636610463555584.0000000000 4.5523738348 -1.7404161500 0.5530369308 0.4544146958 0.6226389956 0.4961898280 -0.399529247883 +1403636610513555456.0000000000 4.5524025955 -1.7404060994 0.5529687003 0.4544340323 0.6226189800 0.4962602571 -0.399450964927 +1403636610563555584.0000000000 4.5523471726 -1.7404099707 0.5530176729 0.4544132431 0.6226488632 0.4962118850 -0.39948812604 +1403636610613555456.0000000000 4.5523632225 -1.7404521047 0.5529389160 0.4544624999 0.6226341005 0.4962663124 -0.399387481364 +1403636610663555584.0000000000 4.5523657946 -1.7405163865 0.5529105854 0.4544434545 0.6226495002 0.4962490650 -0.399406574913 +1403636610713555456.0000000000 4.5524126214 -1.7405964429 0.5528604504 0.4544354432 0.6226453738 0.4962954120 -0.399364533345 +1403636610763555584.0000000000 4.5525100984 -1.7406857857 0.5526964190 0.4543521265 0.6226658913 0.4963950241 -0.39930353493 +1403636610813555456.0000000000 4.5526128627 -1.7406625923 0.5526178748 0.4543633743 0.6226544378 0.4964469406 -0.399244048709 +1403636610863555584.0000000000 4.5529663554 -1.7407403755 0.5526093004 0.4541953778 0.6226400008 0.4964741736 -0.399423814027 +1403636610913555456.0000000000 4.5529696687 -1.7406396233 0.5525691681 0.4543580559 0.6225639691 0.4965182066 -0.399302556808 +1403636610963555584.0000000000 4.5530296143 -1.7408030436 0.5525676238 0.4541343847 0.6226542139 0.4965295069 -0.39940222742 +1403636611013555456.0000000000 4.5528717867 -1.7407821164 0.5526204991 0.4543535130 0.6225740851 0.4964199486 -0.399414106405 +1403636611063555584.0000000000 4.5529814063 -1.7408040353 0.5525821234 0.4541909156 0.6226219133 0.4965421211 -0.39937261698 +1403636611113555456.0000000000 4.5529400605 -1.7407611470 0.5525821210 0.4542889022 0.6225638488 0.4964768780 -0.399432794282 +1403636611163555584.0000000000 4.5530717237 -1.7407183837 0.5525652062 0.4542395910 0.6225763821 0.4965233080 -0.399411625983 +1403636611213555456.0000000000 4.5530908670 -1.7406470473 0.5525546501 0.4543114271 0.6225167853 0.4965767849 -0.399356326881 +1403636611263555584.0000000000 4.5529963137 -1.7406971671 0.5526270925 0.4542444397 0.6225691539 0.4964750230 -0.399477395129 +1403636611313555456.0000000000 4.5529104723 -1.7406607264 0.5526979134 0.4542929824 0.6225715120 0.4964704998 -0.399424137372 +1403636611363555584.0000000000 4.5529118619 -1.7410264897 0.5528186706 0.4536706420 0.6227396647 0.4963077805 -0.400071050659 +1403636611413555456.0000000000 4.5528913883 -1.7408179752 0.5528872994 0.4541088033 0.6225371479 0.4963794203 -0.399800156751 +1403636611463555584.0000000000 4.5531094679 -1.7405198706 0.5526727204 0.4534888343 0.6230702296 0.4960089007 -0.400133148573 +1403636611513555456.0000000000 4.5531657307 -1.7399876159 0.5526289442 0.4547551104 0.6224478421 0.4964602375 -0.399103628213 +1403636611563555584.0000000000 4.5530658620 -1.7402708032 0.5526058769 0.4540785355 0.6228531604 0.4961733989 -0.399598026021 +1403636611613555456.0000000000 4.5529321174 -1.7401933144 0.5525138234 0.4544685995 0.6224980251 0.4964229342 -0.399398011084 +1403636611663555584.0000000000 4.5528787886 -1.7403703959 0.5524727992 0.4540875792 0.6228236157 0.4960419746 -0.399796915532 +1403636611713555456.0000000000 4.5529125595 -1.7400956871 0.5523862383 0.4547655743 0.6224195701 0.4962589386 -0.399386050106 +1403636611763555584.0000000000 4.5529063991 -1.7402987721 0.5524162902 0.4542507262 0.6226873842 0.4960513534 -0.399812148449 +1403636611813555456.0000000000 4.5529282253 -1.7403505985 0.5524117862 0.4542037530 0.6228068296 0.4958854931 -0.399885210388 +1403636611863555584.0000000000 4.5528693212 -1.7400178686 0.5524584169 0.4549053090 0.6224321032 0.4960466514 -0.399471095821 +1403636611913555456.0000000000 4.5529395365 -1.7401223348 0.5524512320 0.4545227531 0.6225118755 0.4962723568 -0.399501914491 +1403636611963555584.0000000000 4.5527844653 -1.7403214067 0.5525528116 0.4542236719 0.6226089853 0.4961061655 -0.399896961637 +1403636612013555456.0000000000 4.5527069526 -1.7403654156 0.5526629111 0.4540430093 0.6226494389 0.4959170230 -0.400273566785 +1403636612063555584.0000000000 4.5528706201 -1.7400622373 0.5525453279 0.4544883617 0.6224683864 0.4963975242 -0.399453294998 +1403636612113555456.0000000000 4.5527740540 -1.7404884692 0.5526815345 0.4536551067 0.6228807271 0.4958296687 -0.400461713029 +1403636612163555584.0000000000 4.5525609628 -1.7404563837 0.5526375705 0.4539222151 0.6226227091 0.4959155023 -0.400453991497 +1403636612213555456.0000000000 4.5527261119 -1.7403851494 0.5525271114 0.4536689527 0.6228624572 0.4959716345 -0.400298611667 +1403636612263555584.0000000000 4.5528364578 -1.7394015939 0.5522875429 0.4557111256 0.6215933197 0.4971607115 -0.398472510892 +1403636612313555456.0000000000 4.5527936949 -1.7403768317 0.5525738799 0.4536276514 0.6228508873 0.4958023754 -0.400573002834 +1403636612363555584.0000000000 4.5528511498 -1.7396516923 0.5521753291 0.4552494880 0.6217794562 0.4971776079 -0.398688647665 +1403636612413555456.0000000000 4.5528813839 -1.7403025214 0.5524460571 0.4539483645 0.6226404205 0.4960287976 -0.40025644414 +1403636612463555584.0000000000 4.5529301236 -1.7397804011 0.5522328740 0.4551985086 0.6218342373 0.4969753203 -0.398913562222 +1403636612513555456.0000000000 4.5527992257 -1.7403464978 0.5524174683 0.4540956692 0.6225802869 0.4961185772 -0.400071577327 +1403636612563555584.0000000000 4.5528224479 -1.7398827020 0.5523008389 0.4550431647 0.6219988099 0.4967390240 -0.399128476512 +1403636612613555456.0000000000 4.5528920707 -1.7400758788 0.5524689816 0.4544007584 0.6224652825 0.4962034878 -0.399798726342 +1403636612663555584.0000000000 4.5529009952 -1.7397932220 0.5524042428 0.4549185566 0.6220992146 0.4967051276 -0.399156222785 +1403636612713555456.0000000000 4.5528756217 -1.7400623617 0.5525733012 0.4543466939 0.6224507004 0.4962602435 -0.39981242864 +1403636612763555584.0000000000 4.5530071539 -1.7397531048 0.5524680370 0.4548551480 0.6221965765 0.4966537952 -0.399140604704 +1403636612813555456.0000000000 4.5529114615 -1.7400360192 0.5525877828 0.4545291560 0.6224205808 0.4963312526 -0.399563705395 +1403636612863555584.0000000000 4.5528417071 -1.7399597198 0.5524609283 0.4546458348 0.6223088455 0.4964707362 -0.399431688473 +1403636612913555456.0000000000 4.5528434404 -1.7398790772 0.5524547047 0.4546777810 0.6223534517 0.4964498179 -0.399351818502 +1403636612963555584.0000000000 4.5527940290 -1.7399040845 0.5525111676 0.4545565817 0.6224399405 0.4963053379 -0.399534536734 +1403636613013555456.0000000000 4.5526866753 -1.7397963926 0.5525337238 0.4548022630 0.6223345513 0.4963580430 -0.399353604018 +1403636613063555584.0000000000 4.5525913595 -1.7399643645 0.5526940709 0.4544346266 0.6225467445 0.4961011390 -0.399760404458 +1403636613113555456.0000000000 4.5525166088 -1.7397500219 0.5525145956 0.4548122842 0.6222956416 0.4965056973 -0.399219254458 +1403636613163555584.0000000000 4.5523336285 -1.7399858387 0.5526510943 0.4544796773 0.6225685043 0.4959995600 -0.399801346677 +1403636613213555456.0000000000 4.5523964670 -1.7397871835 0.5525578164 0.4548879418 0.6223332581 0.4963600764 -0.399255495566 +1403636613263555584.0000000000 4.5524601252 -1.7399400514 0.5526564763 0.4544904763 0.6225700486 0.4960520439 -0.399721542159 +1403636613313555456.0000000000 4.5523735429 -1.7398035904 0.5527040020 0.4548769886 0.6223270470 0.4962169442 -0.3994555246 +1403636613363555584.0000000000 4.5523217839 -1.7400071346 0.5527283745 0.4544465939 0.6225979194 0.4959912180 -0.399803496246 +1403636613413555456.0000000000 4.5523223833 -1.7398452023 0.5526625099 0.4548255323 0.6223782370 0.4962620565 -0.399378312627 +1403636613463555584.0000000000 4.5523426338 -1.7399891840 0.5527487831 0.4545276546 0.6225888742 0.4959517198 -0.399774432028 +1403636613513555456.0000000000 4.5524078971 -1.7398304341 0.5527422641 0.4547905558 0.6224120951 0.4961727839 -0.399476285505 +1403636613563555584.0000000000 4.5525131840 -1.7399301368 0.5527136562 0.4545245725 0.6225783936 0.4959724835 -0.399768498626 +1403636613613555456.0000000000 4.5525909723 -1.7398116593 0.5526578890 0.4547845829 0.6224203175 0.4961408400 -0.399509947794 +1403636613663555584.0000000000 4.5525782838 -1.7399714092 0.5527006686 0.4545061175 0.6225958421 0.4959516182 -0.39978819253 +1403636613713555456.0000000000 4.5525806774 -1.7399013605 0.5527252767 0.4546978377 0.6224882823 0.4960147704 -0.399659307894 +1403636613763555584.0000000000 4.5525737690 -1.7398957553 0.5527584221 0.4546391202 0.6225411620 0.4959425099 -0.399733409831 +1403636613813555456.0000000000 4.5525241395 -1.7398844781 0.5527570328 0.4546405024 0.6225423591 0.4959728581 -0.39969231759 +1403636613863555584.0000000000 4.5524974555 -1.7399056640 0.5527649712 0.4545624123 0.6225763837 0.4959953076 -0.399700281019 +1403636613913555456.0000000000 4.5524797903 -1.7398851507 0.5528022026 0.4545639415 0.6225711162 0.4960129740 -0.399684823264 +1403636613963555584.0000000000 4.5524129638 -1.7399047620 0.5527267654 0.4545355694 0.6225860988 0.4960054636 -0.399703072051 +1403636614013555456.0000000000 4.5523655416 -1.7398941607 0.5527218570 0.4545002739 0.6225979818 0.4959669951 -0.399772427538 +1403636614063555584.0000000000 4.5523364585 -1.7398290501 0.5527849872 0.4545680665 0.6225748614 0.4959486665 -0.399754093173 +1403636614113555456.0000000000 4.5522824660 -1.7398494820 0.5527226954 0.4545446681 0.6225718361 0.4959323204 -0.399805686774 +1403636614163555584.0000000000 4.5522745002 -1.7398773675 0.5527053237 0.4545894735 0.6225363471 0.4959748663 -0.399757225143 +1403636614213555456.0000000000 4.5523096261 -1.7399151104 0.5527073923 0.4545186793 0.6225807067 0.4959546242 -0.399793752614 +1403636614263555584.0000000000 4.5523809734 -1.7398669319 0.5527400092 0.4546067474 0.6225500391 0.4959895112 -0.399698084566 +1403636614313555456.0000000000 4.5523760889 -1.7399445037 0.5527961682 0.4545259629 0.6225975252 0.4958809909 -0.399850614053 +1403636614363555584.0000000000 4.5522598730 -1.7398886462 0.5527845777 0.4546638992 0.6225190172 0.4959526325 -0.39972715482 +1403636614413555456.0000000000 4.5522140850 -1.7399713512 0.5528044760 0.4544446891 0.6226605659 0.4958542427 -0.399877999231 +1403636614463555584.0000000000 4.5521955073 -1.7398463234 0.5527894539 0.4546576928 0.6225142886 0.4959795451 -0.399708185687 +1403636614513555456.0000000000 4.5521684369 -1.7399026453 0.5528025766 0.4545084784 0.6225906450 0.4958387198 -0.399933614144 +1403636614563555584.0000000000 4.5522269804 -1.7397931202 0.5528286752 0.4545512759 0.6225721785 0.4959558921 -0.39976839935 +1403636614613555456.0000000000 4.5522188412 -1.7398398499 0.5527848153 0.4544357988 0.6226572888 0.4958622886 -0.399883228255 +1403636614663555584.0000000000 4.5521776893 -1.7398140407 0.5527334004 0.4545432658 0.6225903175 0.4959503809 -0.399756095287 +1403636614713555456.0000000000 4.5521242341 -1.7399025275 0.5527619604 0.4544439375 0.6226591445 0.4958527513 -0.399882915844 +1403636614763555584.0000000000 4.5521733668 -1.7398840744 0.5527680124 0.4545035278 0.6226129882 0.4959436959 -0.39977426215 +1403636614813555456.0000000000 4.5522058483 -1.7398434313 0.5528871323 0.4544516925 0.6226695111 0.4958811785 -0.399822705553 +1403636614863555584.0000000000 4.5522533605 -1.7398562108 0.5527953356 0.4544705683 0.6226329792 0.4959515290 -0.399770880066 +1403636614913555456.0000000000 4.5522557059 -1.7398449460 0.5527787388 0.4544735565 0.6226672028 0.4958817451 -0.399800745086 +1403636614963555584.0000000000 4.5522683954 -1.7398141891 0.5527724521 0.4545638210 0.6226313262 0.4958805935 -0.399755426914 +1403636615013555456.0000000000 4.5522324882 -1.7398473954 0.5527972150 0.4545259087 0.6226539399 0.4958114424 -0.399849075195 +1403636615063555584.0000000000 4.5522437133 -1.7398314836 0.5528024219 0.4544829254 0.6226797518 0.4958326895 -0.399831391035 +1403636615113555456.0000000000 4.5522776803 -1.7398477660 0.5526933526 0.4545117009 0.6226382394 0.4959036297 -0.399775345162 +1403636615163555584.0000000000 4.5522942125 -1.7398622886 0.5526991967 0.4544766014 0.6226402409 0.4959011789 -0.399815169744 +1403636615213555456.0000000000 4.5522705152 -1.7398525592 0.5527198383 0.4545400828 0.6226024475 0.4959269464 -0.399769895503 +1403636615263555584.0000000000 4.5522073638 -1.7398700774 0.5527572798 0.4545253727 0.6226060730 0.4958827168 -0.399835834721 +1403636615313555456.0000000000 4.5521732599 -1.7398611887 0.5527350058 0.4545268608 0.6226178090 0.4959430620 -0.399741011158 +1403636615363555584.0000000000 4.5521396955 -1.7398789108 0.5527581492 0.4545244483 0.6226383217 0.4958746895 -0.399796621464 +1403636615413555456.0000000000 4.5521896547 -1.7398467210 0.5527668906 0.4545772593 0.6226112455 0.4958928614 -0.399756203628 +1403636615463555584.0000000000 4.5522241315 -1.7398110681 0.5527787213 0.4545411325 0.6226279015 0.4958783622 -0.399789325876 +1403636615513555456.0000000000 4.5522301860 -1.7397620263 0.5528212290 0.4545585367 0.6226377959 0.4958598881 -0.399777041944 +1403636615563555584.0000000000 4.5521768819 -1.7397951875 0.5527425559 0.4545514144 0.6226586229 0.4958426323 -0.399774104991 +1403636615613555456.0000000000 4.5521708482 -1.7397945299 0.5527367846 0.4545737326 0.6226477477 0.4958850954 -0.399712992197 +1403636615663555584.0000000000 4.5521826103 -1.7398566131 0.5527502112 0.4545329073 0.6226796904 0.4958401436 -0.399765420262 +1403636615713555456.0000000000 4.5522462841 -1.7398990533 0.5526983048 0.4545234166 0.6226778115 0.4959034110 -0.399700655221 +1403636615763555584.0000000000 4.5522952950 -1.7399336791 0.5526725319 0.4545097612 0.6226898089 0.4958434229 -0.399771908492 +1403636615813555456.0000000000 4.5523119499 -1.7398476331 0.5527546313 0.4545783198 0.6226782397 0.4958069625 -0.399757197504 +1403636615863555584.0000000000 4.5522962767 -1.7398756885 0.5527367608 0.4545125066 0.6227325698 0.4957827269 -0.399777457588 +1403636615913555456.0000000000 4.5522519304 -1.7398625111 0.5527472121 0.4545827059 0.6226966727 0.4958322223 -0.399692162354 +1403636615963555584.0000000000 4.5522193649 -1.7399183080 0.5527636031 0.4545430185 0.6227141940 0.4958113636 -0.399735873695 +1403636616013555456.0000000000 4.5522023265 -1.7399318616 0.5527610378 0.4545523380 0.6227323787 0.4958089721 -0.399699912184 +1403636616063555584.0000000000 4.5522132989 -1.7399272176 0.5527832906 0.4545142611 0.6227542920 0.4957912490 -0.399731054203 +1403636616113555456.0000000000 4.5521656194 -1.7398950951 0.5528185640 0.4545767550 0.6227501382 0.4957319898 -0.399739957303 +1403636616163555584.0000000000 4.5521005040 -1.7398949977 0.5528055721 0.4545376568 0.6227719122 0.4957287401 -0.399754524893 +1403636616213555456.0000000000 4.5520745459 -1.7398592999 0.5527916925 0.4545738399 0.6227667265 0.4957378984 -0.399710100708 +1403636616263555584.0000000000 4.5520684168 -1.7398075609 0.5527798290 0.4545861829 0.6227698743 0.4957297528 -0.399701261007 +1403636616313555456.0000000000 4.5520775240 -1.7397350258 0.5528470993 0.4545855813 0.6227718246 0.4957157923 -0.399716220614 +1403636616363555584.0000000000 4.5520838655 -1.7397390687 0.5527709277 0.4545805382 0.6227788216 0.4956883071 -0.399745138605 +1403636616413555456.0000000000 4.5521153426 -1.7397054696 0.5527263724 0.4545684506 0.6227762222 0.4957044314 -0.399742939284 +1403636616463555584.0000000000 4.5521205787 -1.7397037555 0.5526927092 0.4545682657 0.6227841950 0.4956867435 -0.39975266172 +1403636616513555456.0000000000 4.5521146609 -1.7397061709 0.5526834544 0.4546101915 0.6227909707 0.4956389703 -0.39975366382 +1403636616563555584.0000000000 4.5521193373 -1.7397116404 0.5527632258 0.4545911247 0.6228384416 0.4956294433 -0.39971319713 +1403636616613555456.0000000000 4.5521522581 -1.7397554013 0.5527196015 0.4545820781 0.6228234012 0.4956730720 -0.399692820633 +1403636616663555584.0000000000 4.5521826501 -1.7397641773 0.5527327098 0.4545798770 0.6228230610 0.4956567396 -0.399716107512 +1403636616713555456.0000000000 4.5522146353 -1.7397772233 0.5527407282 0.4545538834 0.6228351732 0.4956635736 -0.39971832077 +1403636616763555584.0000000000 4.5522265138 -1.7397925001 0.5527879379 0.4545340573 0.6228555320 0.4956414086 -0.399736627049 +1403636616813555456.0000000000 4.5522556864 -1.7398356834 0.5528629054 0.4544924670 0.6228705933 0.4956440441 -0.399757180045 +1403636616863555584.0000000000 4.5522837818 -1.7399017674 0.5528079411 0.4545093748 0.6228509686 0.4956611858 -0.399747280143 +1403636616913555456.0000000000 4.5523315566 -1.7399221779 0.5528267595 0.4545199272 0.6228786854 0.4956207519 -0.399742228537 +1403636616963555584.0000000000 4.5523946791 -1.7399261771 0.5528318388 0.4545097198 0.6228879835 0.4956015550 -0.399763146436 +1403636617013555456.0000000000 4.5524222339 -1.7399442773 0.5528207979 0.4545197884 0.6228683471 0.4956316730 -0.399744954849 +1403636617063555584.0000000000 4.5524174814 -1.7399557602 0.5528050965 0.4545604447 0.6228636514 0.4955993519 -0.399746114597 +1403636617113555456.0000000000 4.5524179064 -1.7399489856 0.5527713582 0.4545512557 0.6228734933 0.4956257006 -0.399708559051 +1403636617163555584.0000000000 4.5523983560 -1.7399456357 0.5527396705 0.4545338118 0.6228756224 0.4956394442 -0.39970803637 +1403636617213555456.0000000000 4.5523773227 -1.7399201744 0.5527807041 0.4545252403 0.6228791941 0.4956097807 -0.399748997249 +1403636617263555584.0000000000 4.5523415310 -1.7398897964 0.5527037807 0.4545585045 0.6228739800 0.4956160162 -0.399711565385 +1403636617313555456.0000000000 4.5523175945 -1.7398570538 0.5526933818 0.4545510959 0.6228864354 0.4956074407 -0.399711213972 +1403636617363555584.0000000000 4.5522902787 -1.7398081822 0.5526560646 0.4545445200 0.6228953671 0.4956052833 -0.399707448195 +1403636617413555456.0000000000 4.5522563441 -1.7397494556 0.5527383435 0.4545020688 0.6229371453 0.4955998454 -0.399697354999 +1403636617463555584.0000000000 4.5522309713 -1.7397548961 0.5526624040 0.4545121617 0.6229141710 0.4956249771 -0.399690520969 +1403636617513555456.0000000000 4.5522255484 -1.7397402053 0.5526695585 0.4545087862 0.6229239529 0.4956105421 -0.399697013736 +1403636617563555584.0000000000 4.5522206614 -1.7397288861 0.5527611883 0.4544627241 0.6229664882 0.4956000975 -0.399696047419 +1403636617613555456.0000000000 4.5522451432 -1.7397754258 0.5527212972 0.4544861687 0.6229353526 0.4956341240 -0.399675723621 +1403636617663555584.0000000000 4.5522413710 -1.7398224826 0.5527576677 0.4544633046 0.6229566031 0.4955955080 -0.39971648438 +1403636617713555456.0000000000 4.5522424631 -1.7398503963 0.5527619006 0.4544974081 0.6229227555 0.4956019861 -0.399722426347 +1403636617763555584.0000000000 4.5522760366 -1.7399069591 0.5527702790 0.4544668908 0.6229587754 0.4955454774 -0.399771045873 +1403636617813555456.0000000000 4.5523209146 -1.7399074376 0.5527615684 0.4544863532 0.6229623996 0.4955712773 -0.39971128657 +1403636617863555584.0000000000 4.5523454693 -1.7399205220 0.5527444542 0.4545006976 0.6229894057 0.4955331437 -0.399700162324 +1403636617913555456.0000000000 4.5524056176 -1.7399260822 0.5527248422 0.4544908218 0.6230046133 0.4955448038 -0.399673231784 +1403636617963555584.0000000000 4.5524557116 -1.7399278237 0.5526976214 0.4544785114 0.6230303959 0.4955153909 -0.399683507078 +1403636618013555456.0000000000 4.5524648404 -1.7399218773 0.5527406298 0.4544890725 0.6230417978 0.4955056853 -0.399665756531 +1403636618063555584.0000000000 4.5524414678 -1.7399973010 0.5526778412 0.4544984686 0.6230659007 0.4954717340 -0.399659587842 +1403636618113555456.0000000000 4.5524521198 -1.7399826567 0.5526737394 0.4545281377 0.6230391181 0.4954929805 -0.399641258668 +1403636618163555584.0000000000 4.5524292386 -1.7399748167 0.5526992998 0.4545371171 0.6230488916 0.4954583429 -0.399658752385 +1403636618213555456.0000000000 4.5523978496 -1.7399521194 0.5526843910 0.4545325112 0.6230310144 0.4955367235 -0.399594678419 +1403636618263555584.0000000000 4.5523379692 -1.7399450869 0.5526899177 0.4545304381 0.6230419596 0.4955002990 -0.399625138152 +1403636618313555456.0000000000 4.5522738012 -1.7398967320 0.5527524665 0.4544936021 0.6230776372 0.4955087979 -0.399600869508 +1403636618363555584.0000000000 4.5522283361 -1.7399067232 0.5527076828 0.4545250274 0.6230699616 0.4954573179 -0.399640924511 +1403636618413555456.0000000000 4.5522253746 -1.7398221413 0.5527872257 0.4545331880 0.6230760205 0.4954493076 -0.399632127535 +1403636618463555584.0000000000 4.5522455392 -1.7397752529 0.5527988518 0.4545622438 0.6230521346 0.4954474221 -0.399638656811 +1403636618513555456.0000000000 4.5523185097 -1.7397814525 0.5528721981 0.4544130680 0.6228552140 0.4956896519 -0.399814850854 +1403636618563555584.0000000000 4.5523275745 -1.7397510113 0.5529160596 0.4544824088 0.6228840241 0.4956102751 -0.399789554485 +1403636618613555456.0000000000 4.5523155320 -1.7397602317 0.5528735720 0.4544501115 0.6229314745 0.4955790206 -0.399791081126 +1403636618663555584.0000000000 4.5523019219 -1.7397772202 0.5528220362 0.4545020500 0.6229906801 0.4955097935 -0.399725585513 +1403636618713555456.0000000000 4.5522724593 -1.7396948526 0.5527752421 0.4545778468 0.6232460649 0.4952577943 -0.399553551952 +1403636618763555584.0000000000 4.5522995650 -1.7397464051 0.5527855609 0.4545253433 0.6231229822 0.4953421346 -0.399700676814 +1403636618813555456.0000000000 4.5522957449 -1.7397978032 0.5526986622 0.4544491458 0.6231708053 0.4953370854 -0.399719017792 +1403636618863555584.0000000000 4.5523353272 -1.7398427536 0.5526817020 0.4544976844 0.6230901022 0.4953478195 -0.399776333807 +1403636618913555456.0000000000 4.5523497152 -1.7399731466 0.5527284802 0.4542819678 0.6230272035 0.4954599985 -0.399980483629 +1403636618963555584.0000000000 4.5523643703 -1.7398764076 0.5527689176 0.4543623907 0.6229865211 0.4954842380 -0.39992247039 +1403636619013555456.0000000000 4.5523895121 -1.7398825173 0.5527824245 0.4542625186 0.6230639605 0.4954131020 -0.400003404668 +1403636619063555584.0000000000 4.5524496610 -1.7398525074 0.5527874054 0.4542653313 0.6230995224 0.4954710281 -0.399873047786 +1403636619113555456.0000000000 4.5524186673 -1.7399152363 0.5527491500 0.4542930965 0.6232051932 0.4952868064 -0.399905050072 +1403636619163555584.0000000000 4.5524044054 -1.7399407113 0.5526928166 0.4544085918 0.6232730512 0.4952591618 -0.39970226182 +1403636619213555456.0000000000 4.5523676462 -1.7399310872 0.5526772501 0.4544430156 0.6233689424 0.4951110707 -0.399697053783 +1403636619263555584.0000000000 4.5523353508 -1.7398954644 0.5526645250 0.4545151434 0.6233775051 0.4950842520 -0.399634900894 +1403636619313555456.0000000000 4.5522894020 -1.7399385781 0.5526969430 0.4544992850 0.6233156304 0.4951929263 -0.399614802719 +1403636619363555584.0000000000 4.5522406874 -1.7401321758 0.5527933104 0.4543100006 0.6231440833 0.4953892906 -0.39985413038 +1403636619413555456.0000000000 4.5521585046 -1.7401670063 0.5528793196 0.4543924181 0.6231038558 0.4953660811 -0.399851923719 +1403636619463555584.0000000000 4.5521307193 -1.7400761935 0.5529456919 0.4543601620 0.6232217334 0.4952713339 -0.399822235561 +1403636619513555456.0000000000 4.5520567905 -1.7399569626 0.5529350464 0.4544080669 0.6233038307 0.4952133475 -0.39971162575 +1403636619563555584.0000000000 4.5520985614 -1.7398555803 0.5529137115 0.4544063750 0.6234423593 0.4951014452 -0.399636122046 +1403636619613555456.0000000000 4.5521590302 -1.7397616807 0.5528845152 0.4545202900 0.6233164480 0.4951750336 -0.399611808866 +1403636619663555584.0000000000 4.5522095010 -1.7397647315 0.5529259612 0.4544869916 0.6233207691 0.4951242565 -0.39970584678 +1403636619713555456.0000000000 4.5523048166 -1.7397646397 0.5528599048 0.4545646075 0.6233514666 0.4951252539 -0.399568454257 +1403636619763555584.0000000000 4.5523206373 -1.7398074788 0.5528506687 0.4545152826 0.6233957444 0.4950324648 -0.399670442305 +1403636619813555456.0000000000 4.5522901186 -1.7397963712 0.5528244763 0.4545593069 0.6233703076 0.4950638444 -0.399621178105 +1403636619863555584.0000000000 4.5522360669 -1.7398271770 0.5528146670 0.4544939053 0.6234198908 0.4949692806 -0.399735338693 +1403636619913555456.0000000000 4.5521857794 -1.7397992870 0.5528349429 0.4545614205 0.6233906983 0.4949533353 -0.399723839855 +1403636619963555584.0000000000 4.5521854161 -1.7398150824 0.5528566417 0.4544812432 0.6233715358 0.4950051367 -0.399780743053 +1403636620013555456.0000000000 4.5521397620 -1.7398293131 0.5528269409 0.4544591178 0.6234008941 0.4950041490 -0.39976133877 +1403636620063555584.0000000000 4.5521321382 -1.7398162528 0.5527976761 0.4545065581 0.6234058479 0.4949879433 -0.399719743638 +1403636620113555456.0000000000 4.5520825646 -1.7398277632 0.5527498482 0.4545854909 0.6233262278 0.4950042940 -0.399733903995 +1403636620163555584.0000000000 4.5520957584 -1.7398042182 0.5527025584 0.4545711490 0.6233046824 0.4950481938 -0.399729444955 +1403636620213555456.0000000000 4.5521197496 -1.7397798004 0.5527145513 0.4545666903 0.6233053324 0.4950402058 -0.399743394243 +1403636620263555584.0000000000 4.5521419444 -1.7397763868 0.5527292475 0.4545117225 0.6233477411 0.4950498599 -0.39972781246 +1403636620313555456.0000000000 4.5521322462 -1.7397749057 0.5527712764 0.4545805657 0.6233674073 0.4949564045 -0.399734589966 +1403636620363555584.0000000000 4.5520788717 -1.7397453875 0.5528070424 0.4545954934 0.6233466649 0.4949955724 -0.39970145863 +1403636620413555456.0000000000 4.5520393289 -1.7397715176 0.5528031084 0.4545529754 0.6233244756 0.4950226672 -0.399750859512 +1403636620463555584.0000000000 4.5520091375 -1.7397422904 0.5528479405 0.4546065059 0.6233207619 0.4950102839 -0.399711109924 +1403636620513555456.0000000000 4.5520146769 -1.7398345765 0.5528244894 0.4545469442 0.6233726166 0.4949427944 -0.399781548704 +1403636620563555584.0000000000 4.5520801959 -1.7398757126 0.5528120694 0.4545618693 0.6233841249 0.4949493757 -0.399738483692 +1403636620613555456.0000000000 4.5521124946 -1.7399319503 0.5527695394 0.4544963176 0.6234193109 0.4949440878 -0.399764693291 +1403636620663555584.0000000000 4.5521627686 -1.7399243860 0.5527183780 0.4545418243 0.6233856553 0.4949958415 -0.399701353084 +1403636620713555456.0000000000 4.5521622391 -1.7399541202 0.5527234920 0.4545402467 0.6233816255 0.4949567428 -0.399757846561 +1403636620763555584.0000000000 4.5521677815 -1.7399397288 0.5527335800 0.4545045692 0.6234063176 0.4949782194 -0.399733313673 +1403636620813555456.0000000000 4.5521500719 -1.7398668528 0.5528021538 0.4544337364 0.6234148357 0.4949664356 -0.399815144172 +1403636620863555584.0000000000 4.5522205457 -1.7398050369 0.5527997808 0.4544529808 0.6234008272 0.4949691070 -0.399811805677 +1403636620913555456.0000000000 4.5522624988 -1.7397542153 0.5528468227 0.4544290569 0.6234238085 0.4949266065 -0.399855775819 +1403636620963555584.0000000000 4.5522702572 -1.7396805681 0.5528783663 0.4544090303 0.6234671296 0.4949273007 -0.399810127972 +1403636621013555456.0000000000 4.5522925549 -1.7396144030 0.5528776371 0.4543599346 0.6235022620 0.4949553903 -0.399776363374 +1403636621063555584.0000000000 4.5522846752 -1.7393929325 0.5528632673 0.4547418175 0.6233085135 0.4951244323 -0.399434816926 +1403636621113555456.0000000000 4.5523497476 -1.7396874406 0.5529551550 0.4543390277 0.6234698342 0.4949282385 -0.39988429894 +1403636621163555584.0000000000 4.5523345662 -1.7396619903 0.5528776082 0.4546379520 0.6232438056 0.4951933406 -0.399568575881 +1403636621213555456.0000000000 4.5522510870 -1.7398489492 0.5529095394 0.4544388082 0.6233818752 0.4949693932 -0.399857108416 +1403636621263555584.0000000000 4.5521834486 -1.7397986257 0.5528325838 0.4546357898 0.6232732482 0.4951692109 -0.399555014065 +1403636621313555456.0000000000 4.5520241043 -1.7399208947 0.5528681417 0.4544211204 0.6234070675 0.4950003007 -0.399799669666 +1403636621363555584.0000000000 4.5519182844 -1.7398390814 0.5528444824 0.4546023969 0.6232864317 0.4951234641 -0.399629128292 +1403636621413555456.0000000000 4.5518894010 -1.7399705580 0.5528238595 0.4543472120 0.6234547458 0.4949834312 -0.399830206105 +1403636621463555584.0000000000 4.5519125391 -1.7399130917 0.5527865447 0.4545537345 0.6233200159 0.4950933176 -0.399669447246 +1403636621513555456.0000000000 4.5519711924 -1.7399692703 0.5528020089 0.4544016312 0.6234104343 0.4950240425 -0.399787175071 +1403636621563555584.0000000000 4.5520647505 -1.7398141791 0.5527547442 0.4544989733 0.6233605804 0.4951186116 -0.399637123582 +1403636621613555456.0000000000 4.5520911581 -1.7399106081 0.5528107538 0.4543680896 0.6234610130 0.4950149348 -0.399757699966 +1403636621663555584.0000000000 4.5520914033 -1.7398349079 0.5528718074 0.4545172747 0.6233735393 0.4951004162 -0.39961863743 +1403636621713555456.0000000000 4.5520754544 -1.7398657965 0.5529358193 0.4543639072 0.6234457098 0.4950379803 -0.399757782874 +1403636621763555584.0000000000 4.5520567773 -1.7398147382 0.5529481498 0.4544150732 0.6234032057 0.4951036616 -0.399684561406 +1403636621813555456.0000000000 4.5520885998 -1.7397790118 0.5529774622 0.4543638429 0.6234401688 0.4950668225 -0.399730778681 +1403636621863555584.0000000000 4.5520735763 -1.7398114764 0.5529208274 0.4543812867 0.6234401678 0.4951018397 -0.399667576522 +1403636621913555456.0000000000 4.5520416587 -1.7398046351 0.5528814291 0.4543712287 0.6234738258 0.4950734466 -0.399661678902 +1403636621963555584.0000000000 4.5520240373 -1.7397686037 0.5528758333 0.4543561762 0.6234765846 0.4950182261 -0.399742879104 +1403636622013555456.0000000000 4.5520287666 -1.7396993227 0.5528361678 0.4544160490 0.6234685261 0.4950826760 -0.399607551614 +1403636622063555584.0000000000 4.5520422565 -1.7397587573 0.5528382674 0.4543838868 0.6234852182 0.4950029071 -0.399716884844 +1403636622113555456.0000000000 4.5520563982 -1.7397344090 0.5527833573 0.4543757049 0.6235088679 0.4950524776 -0.399627895489 +1403636622163555584.0000000000 4.5520252871 -1.7397722116 0.5527513205 0.4543277453 0.6235109538 0.4950675479 -0.39966049766 +1403636622213555456.0000000000 4.5520172557 -1.7397641326 0.5527217562 0.4542814080 0.6235324902 0.4950507852 -0.399700332885 +1403636622263555584.0000000000 4.5520727341 -1.7397478853 0.5527029950 0.4542844236 0.6235136771 0.4951035423 -0.399660905396 +1403636622313555456.0000000000 4.5520986898 -1.7396452264 0.5527490343 0.4542825250 0.6235677913 0.4950547346 -0.399639095778 +1403636622363555584.0000000000 4.5522582393 -1.7396393394 0.5527608185 0.4542847653 0.6235607233 0.4951111946 -0.39957762865 +1403636622413555456.0000000000 4.5523383228 -1.7397006483 0.5528110495 0.4542287574 0.6236017987 0.4950773841 -0.399619089051 +1403636622463555584.0000000000 4.5523023588 -1.7397181518 0.5527835435 0.4542284389 0.6236004857 0.4950933241 -0.399601751637 +1403636622513555456.0000000000 4.5522459453 -1.7397166045 0.5527357593 0.4542316419 0.6236122115 0.4950593083 -0.399621954357 +1403636622563555584.0000000000 4.5521985377 -1.7397089257 0.5527177403 0.4542122252 0.6236474508 0.4950427764 -0.399609510723 +1403636622613555456.0000000000 4.5521590580 -1.7398056569 0.5527059304 0.4542615698 0.6236195610 0.4950440664 -0.399595347275 +1403636622663555584.0000000000 4.5521091829 -1.7398885960 0.5527221610 0.4542302373 0.6236013534 0.4950216687 -0.399687116372 +1403636622713555456.0000000000 4.5520860564 -1.7399810353 0.5527264437 0.4542182737 0.6236505524 0.4949415187 -0.399723205933 +1403636622763555584.0000000000 4.5521395371 -1.7400370724 0.5527223563 0.4542584808 0.6236144775 0.4949631821 -0.399706973132 +1403636622813555456.0000000000 4.5522343466 -1.7401155153 0.5527664924 0.4542194016 0.6237034758 0.4948843463 -0.399710136456 +1403636622863555584.0000000000 4.5522994423 -1.7400282694 0.5528697999 0.4543275681 0.6237161977 0.4947430844 -0.399742224643 +1403636622913555456.0000000000 4.5522943219 -1.7398302606 0.5529741659 0.4544136188 0.6237299169 0.4946101217 -0.39978754521 +1403636622963555584.0000000000 4.5522620668 -1.7397556231 0.5531004600 0.4543097911 0.6238520162 0.4944801699 -0.399875777151 +1403636623013555456.0000000000 4.5521948672 -1.7395984539 0.5531658184 0.4545318272 0.6237436629 0.4944626727 -0.399814114699 +1403636623063555584.0000000000 4.5521102616 -1.7394549923 0.5531876237 0.4544537657 0.6238083738 0.4944348916 -0.399836248415 +1403636623113555456.0000000000 4.5520229210 -1.7394326984 0.5531996779 0.4544187782 0.6238649731 0.4944103467 -0.399818056779 +1403636623163555584.0000000000 4.5518916185 -1.7394102508 0.5531606871 0.4544667341 0.6238507719 0.4944013711 -0.399796806305 +1403636623213555456.0000000000 4.5517569108 -1.7393807965 0.5531542296 0.4543699590 0.6239163324 0.4944644236 -0.399726511824 +1403636623263555584.0000000000 4.5514946095 -1.7393954839 0.5531545307 0.4542951504 0.6239710906 0.4944114837 -0.39979154469 +1403636623313555456.0000000000 4.5511164727 -1.7392227163 0.5532097031 0.4544427622 0.6239173817 0.4944035192 -0.399717446268 +1403636623363555584.0000000000 4.5510370084 -1.7394238969 0.5532224036 0.4542508554 0.6240632336 0.4942837110 -0.399856041422 +1403636623413555456.0000000000 4.5509671326 -1.7394003526 0.5531610678 0.4543586262 0.6239787026 0.4943618767 -0.399768873571 +1403636623463555584.0000000000 4.5511507935 -1.7397688911 0.5532591546 0.4543601444 0.6240084360 0.4942495770 -0.399859583708 +1403636623513555456.0000000000 4.5519195198 -1.7398577152 0.5531719187 0.4543426440 0.6240532197 0.4942577288 -0.399799497702 +1403636623563555584.0000000000 4.5527691886 -1.7399041621 0.5530238599 0.4542247525 0.6241522734 0.4942383225 -0.399802819493 +1403636623613555456.0000000000 4.5533527552 -1.7399257415 0.5529427710 0.4542233093 0.6242627340 0.4941621118 -0.399726195553 +1403636623663555584.0000000000 4.5531872607 -1.7399467165 0.5530190838 0.4541118943 0.6243044625 0.4942461750 -0.399683679939 +1403636623713555456.0000000000 4.5528620816 -1.7398343590 0.5531281497 0.4542675430 0.6243345120 0.4941003161 -0.399640205837 +1403636623763555584.0000000000 4.5525544985 -1.7397498509 0.5531824417 0.4543416952 0.6244208346 0.4939075512 -0.399659325233 +1403636623813555456.0000000000 4.5522311300 -1.7396029301 0.5531053568 0.4541903840 0.6247495068 0.4939088713 -0.399315884496 +1403636623863555584.0000000000 4.5518590688 -1.7393986405 0.5530997592 0.4543718281 0.6248111293 0.4935831257 -0.399415814176 +1403636623913555456.0000000000 4.5516298600 -1.7393233632 0.5529620784 0.4544136881 0.6248707921 0.4936493738 -0.399192922021 +1403636623963555584.0000000000 4.5516086760 -1.7393923080 0.5529251971 0.4543417904 0.6251143612 0.4933579752 -0.399253655254 +1403636624013555456.0000000000 4.5518177847 -1.7393429406 0.5528717367 0.4544919050 0.6249310212 0.4935350094 -0.399151000885 +1403636624063555584.0000000000 4.5516984649 -1.7391797671 0.5530666282 0.4544759413 0.6251184182 0.4933208734 -0.399140448732 +1403636624113555456.0000000000 4.5517153002 -1.7392552214 0.5528865257 0.4545134606 0.6256044199 0.4932183457 -0.398462404025 +1403636624163555584.0000000000 4.5522748794 -1.7393469590 0.5528770108 0.4544302721 0.6259317524 0.4928397354 -0.398511686589 +1403636624213555456.0000000000 4.5528147157 -1.7393815679 0.5527455711 0.4543872934 0.6259782184 0.4929857840 -0.398307010415 +1403636624263555584.0000000000 4.5531016295 -1.7392781178 0.5530864850 0.4541387432 0.6261372600 0.4930612026 -0.398247139308 +1403636624313555456.0000000000 4.5528619569 -1.7386595074 0.5530765306 0.4533277163 0.6274473872 0.4939853487 -0.395957362926 +1403636624363555584.0000000000 4.5534909221 -1.7377989698 0.5527341264 0.4512179597 0.6299120613 0.4955242820 -0.392516030026 +1403636624413555456.0000000000 4.5552965448 -1.7363218991 0.5527251963 0.4499151991 0.6320398088 0.4964306358 -0.389433713971 +1403636624463555584.0000000000 4.5579678594 -1.7345876076 0.5525880490 0.4473350331 0.6350103148 0.4972520402 -0.386514782014 +1403636624513555456.0000000000 4.5613595305 -1.7325364470 0.5524676700 0.4452834740 0.6378552324 0.4982134964 -0.382944698685 +1403636624563555584.0000000000 4.5650630006 -1.7302414806 0.5526202787 0.4440473782 0.6400445046 0.4987226081 -0.380053572832 +1403636624613555456.0000000000 4.5691567352 -1.7272143975 0.5525287762 0.4448264341 0.6401008858 0.4995130914 -0.3780039299 +1403636624663555584.0000000000 4.5731111551 -1.7232928182 0.5521983897 0.4476299131 0.6387731386 0.4995026071 -0.376952893336 +1403636624713555456.0000000000 4.5779273680 -1.7187019617 0.5505251614 0.4501924318 0.6371227319 0.5014952160 -0.374037360634 +1403636624763555584.0000000000 4.5836048757 -1.7136813767 0.5497518667 0.4532153767 0.6350557777 0.5018149981 -0.37347247462 +1403636624813555456.0000000000 4.5908470114 -1.7079737600 0.5485635984 0.4546655105 0.6338443897 0.5068934816 -0.366850870936 +1403636624863555584.0000000000 4.5989077776 -1.7022666669 0.5491991577 0.4554647367 0.6328920948 0.5117363492 -0.360728954971 +1403636624913555456.0000000000 4.6078426887 -1.6963527191 0.5515010530 0.4550570457 0.6328195658 0.5183111217 -0.351875067865 +1403636624963555584.0000000000 4.6173539512 -1.6910116939 0.5563574259 0.4545779335 0.6326355696 0.5244803125 -0.343586292448 +1403636625013555456.0000000000 4.6267163386 -1.6864382153 0.5638534058 0.4529389757 0.6332771100 0.5291163109 -0.337405269368 +1403636625063555584.0000000000 4.6355114341 -1.6828128953 0.5734297724 0.4503208476 0.6347001911 0.5330154000 -0.332056297979 +1403636625113555456.0000000000 4.6431623404 -1.6806254043 0.5852157513 0.4468529788 0.6365332934 0.5354363414 -0.329326139368 +1403636625163555584.0000000000 4.6492504624 -1.6795576726 0.5990037871 0.4428093192 0.6393273442 0.5343422891 -0.331147658654 +1403636625213555456.0000000000 4.6537747628 -1.6789129543 0.6140146194 0.4415703417 0.6399931874 0.5322428156 -0.334876004958 +1403636625263555584.0000000000 4.6569786727 -1.6784689594 0.6291469351 0.4422727144 0.6395042705 0.5293769541 -0.339395307285 +1403636625313555456.0000000000 4.6586487304 -1.6781472544 0.6411315237 0.4431970413 0.6385954328 0.5271060663 -0.343411488751 +1403636625363555584.0000000000 4.6598476947 -1.6780514403 0.6477681780 0.4435728768 0.6377257155 0.5260046486 -0.346219763259 +1403636625413555456.0000000000 4.6606881793 -1.6777490571 0.6489171935 0.4422911386 0.6381698311 0.5266791633 -0.346015713892 +1403636625463555584.0000000000 4.6609299183 -1.6774022530 0.6465019729 0.4400990512 0.6391150783 0.5283404099 -0.344530336921 +1403636625513555456.0000000000 4.6596660883 -1.6769793117 0.6421830273 0.4387079088 0.6397693501 0.5289805499 -0.34410772613 +1403636625563555584.0000000000 4.6573510743 -1.6768713585 0.6379646469 0.4378898720 0.6397617148 0.5300041344 -0.343588454 +1403636625613555456.0000000000 4.6537443915 -1.6767410750 0.6362767877 0.4381019147 0.6390551278 0.5309013604 -0.343247726198 +1403636625663555584.0000000000 4.6490864741 -1.6768178856 0.6384918972 0.4392372539 0.6378882490 0.5309517399 -0.343888741478 +1403636625713555456.0000000000 4.6426625753 -1.6772080071 0.6457309903 0.4406629672 0.6363508995 0.5299851596 -0.346394879703 +1403636625763555584.0000000000 4.6352749594 -1.6776601339 0.6566435178 0.4440339170 0.6337400099 0.5285068664 -0.349124580285 +1403636625813555456.0000000000 4.6271037834 -1.6783727237 0.6719136449 0.4469201598 0.6314550302 0.5265686433 -0.352494509897 +1403636625863555584.0000000000 4.6181759662 -1.6793381693 0.6913617983 0.4499252992 0.6290406555 0.5239995498 -0.356790625847 +1403636625913555456.0000000000 4.6094451343 -1.6807375892 0.7136427772 0.4514945905 0.6277249627 0.5222061489 -0.359742608019 +1403636625963555584.0000000000 4.6007692679 -1.6821815627 0.7378674690 0.4528097991 0.6265849493 0.5209148396 -0.361942422204 +1403636626013555456.0000000000 4.5923143225 -1.6837200111 0.7623325161 0.4537802860 0.6256569960 0.5197941530 -0.363937925929 +1403636626063555584.0000000000 4.5851656038 -1.6858043941 0.7864844554 0.4523073881 0.6264429488 0.5175857636 -0.367548957116 +1403636626113555456.0000000000 4.5780819695 -1.6878329569 0.8099583750 0.4499447132 0.6278451213 0.5151898143 -0.37140236127 +1403636626163555584.0000000000 4.5713098479 -1.6894646242 0.8325207479 0.4477576326 0.6292470267 0.5126370257 -0.375186036196 +1403636626213555456.0000000000 4.5649343935 -1.6904430904 0.8529497426 0.4456737363 0.6305120154 0.5105066318 -0.378434271683 +1403636626263555584.0000000000 4.5593044940 -1.6905181723 0.8702228937 0.4444559048 0.6312603574 0.5092130585 -0.38035689937 +1403636626313555456.0000000000 4.5539501323 -1.6897740406 0.8837290221 0.4438997328 0.6314014056 0.5088427888 -0.381266715662 +1403636626363555584.0000000000 4.5493393253 -1.6881923201 0.8933219222 0.4440970283 0.6312533025 0.5088788750 -0.381234033383 +1403636626413555456.0000000000 4.5452861151 -1.6857164458 0.8993672257 0.4453597483 0.6301832160 0.5095782569 -0.380596648579 +1403636626463555584.0000000000 4.5415062650 -1.6823101165 0.9030547003 0.4474318708 0.6285081338 0.5108161923 -0.379274392069 +1403636626513555456.0000000000 4.5382667889 -1.6781904783 0.9059293721 0.4512746029 0.6254663389 0.5114411740 -0.378907663285 +1403636626563555584.0000000000 4.5358761547 -1.6735412656 0.9078343793 0.4554502278 0.6220560676 0.5122152779 -0.378479653138 +1403636626613555456.0000000000 4.5344689610 -1.6686462321 0.9087993663 0.4591259124 0.6187579281 0.5130548350 -0.378307757373 +1403636626663555584.0000000000 4.5342220734 -1.6636868758 0.9087494333 0.4620735311 0.6159542975 0.5139667012 -0.378056325513 +1403636626713555456.0000000000 4.5353128313 -1.6589986173 0.9073204632 0.4620700009 0.6152685357 0.5152013053 -0.377496434735 +1403636626763555584.0000000000 4.5376387277 -1.6546029690 0.9046515279 0.4603654617 0.6155898290 0.5170353280 -0.376546509376 +1403636626813555456.0000000000 4.5407613839 -1.6503838321 0.9011286546 0.4583268978 0.6163669404 0.5187732718 -0.375369873713 +1403636626863555584.0000000000 4.5449942422 -1.6462744727 0.8962213302 0.4558098877 0.6175532755 0.5208231745 -0.373642234048 +1403636626913555456.0000000000 4.5497424381 -1.6423701188 0.8907051235 0.4531190605 0.6190088802 0.5229402282 -0.371543592261 +1403636626963555584.0000000000 4.5550121831 -1.6385377337 0.8842901303 0.4504872056 0.6207104700 0.5252571985 -0.368625372698 +1403636627013555456.0000000000 4.5606353814 -1.6348877428 0.8772892197 0.4478202355 0.6223618353 0.5272477153 -0.366241217489 +1403636627063555584.0000000000 4.5661762138 -1.6312908985 0.8708234949 0.4455135510 0.6240504657 0.5288401120 -0.363877490451 +1403636627113555456.0000000000 4.5718491752 -1.6278814048 0.8658734379 0.4423456963 0.6259893790 0.5309071052 -0.361393453121 +1403636627163555584.0000000000 4.5764573434 -1.6244467307 0.8650501782 0.4427761805 0.6255280180 0.5304077472 -0.362396984524 +1403636627213555456.0000000000 4.5812738321 -1.6211963365 0.8668987551 0.4447141519 0.6240983103 0.5296963267 -0.363527748144 +1403636627263555584.0000000000 4.5849878996 -1.6178273788 0.8718033303 0.4473480427 0.6222137192 0.5282722248 -0.36559304252 +1403636627313555456.0000000000 4.5892726065 -1.6148162295 0.8791543534 0.4487018387 0.6209346947 0.5267563500 -0.368285911277 +1403636627363555584.0000000000 4.5931130746 -1.6116221732 0.8886566638 0.4490636633 0.6207018166 0.5257776479 -0.369633529462 +1403636627413555456.0000000000 4.5975123311 -1.6086131097 0.9002876890 0.4487049289 0.6208029195 0.5252884111 -0.370593722347 +1403636627463555584.0000000000 4.6023053534 -1.6053579685 0.9141604751 0.4488746915 0.6212131831 0.5238359363 -0.371754763637 +1403636627513555456.0000000000 4.6066870365 -1.6016423740 0.9275362130 0.4482391842 0.6233944147 0.5222811500 -0.371057189367 +1403636627563555584.0000000000 4.6111431328 -1.5972957724 0.9376288215 0.4484652295 0.6261063165 0.5199183995 -0.369533051568 +1403636627613555456.0000000000 4.6162076742 -1.5925635415 0.9433384231 0.4491026294 0.6290983624 0.5176199731 -0.366894592763 +1403636627663555584.0000000000 4.6217976244 -1.5879445167 0.9445586326 0.4485653204 0.6323821403 0.5164739657 -0.363506017267 +1403636627713555456.0000000000 4.6278248546 -1.5831226926 0.9417806699 0.4474262609 0.6368316746 0.5154394194 -0.358576859461 +1403636627763555584.0000000000 4.6335299926 -1.5777648391 0.9367053317 0.4459027376 0.6421901936 0.5143656954 -0.352406633357 +1403636627813555456.0000000000 4.6383782478 -1.5720809955 0.9307656747 0.4448899844 0.6474726889 0.5128580882 -0.346162678801 +1403636627863555584.0000000000 4.6425271022 -1.5658307256 0.9242866554 0.4442484493 0.6529698236 0.5107800382 -0.339672603053 +1403636627913555456.0000000000 4.6458401288 -1.5595605042 0.9186753001 0.4434043906 0.6575745998 0.5094549787 -0.333832018909 +1403636627963555584.0000000000 4.6479161086 -1.5533032921 0.9150234202 0.4439834312 0.6606114866 0.5079335684 -0.329354925039 +1403636628013555456.0000000000 4.6479675928 -1.5466755083 0.9136778644 0.4452562578 0.6628172670 0.5060359777 -0.326109988572 +1403636628063555584.0000000000 4.6452228570 -1.5395965834 0.9157912074 0.4480546951 0.6634022587 0.5032743924 -0.325360291458 +1403636628113555456.0000000000 4.6416778715 -1.5327515892 0.9217112973 0.4532296839 0.6621048363 0.4990219860 -0.327379133187 +1403636628163555584.0000000000 4.6367265964 -1.5258751686 0.9300939238 0.4593496180 0.6597804149 0.4936240252 -0.331697232944 +1403636628213555456.0000000000 4.6313079866 -1.5189908631 0.9400232097 0.4645510090 0.6576117305 0.4884844852 -0.336336259923 +1403636628263555584.0000000000 4.6258576854 -1.5123129207 0.9513394598 0.4673539927 0.6568872512 0.4835462247 -0.340972774913 +1403636628313555456.0000000000 4.6210837035 -1.5056807051 0.9637446647 0.4682011495 0.6569458659 0.4793680057 -0.345566387185 +1403636628363555584.0000000000 4.6168341265 -1.4985161352 0.9763914288 0.4682169580 0.6573002604 0.4771499914 -0.34793265693 +1403636628413555456.0000000000 4.6131469925 -1.4909324514 0.9885422358 0.4674564061 0.6580810924 0.4756758569 -0.349494296539 +1403636628463555584.0000000000 4.6100934181 -1.4828988159 0.9993454349 0.4667358842 0.6584848949 0.4750201049 -0.350586875807 +1403636628513555456.0000000000 4.6076273048 -1.4742631852 1.0085651219 0.4656313704 0.6589568665 0.4748696223 -0.351371764464 +1403636628563555584.0000000000 4.6058281164 -1.4651617052 1.0161132291 0.4643304745 0.6595653460 0.4747290179 -0.35214077354 +1403636628613555456.0000000000 4.6045496353 -1.4554496202 1.0220571396 0.4630137938 0.6597553839 0.4750127160 -0.35313450683 +1403636628663555584.0000000000 4.6037395399 -1.4447741597 1.0263645111 0.4626541472 0.6595195477 0.4753853335 -0.353544750976 +1403636628713555456.0000000000 4.6032179208 -1.4326995933 1.0288017643 0.4637738446 0.6592067537 0.4760148612 -0.351809790755 +1403636628763555584.0000000000 4.6032415628 -1.4195140948 1.0289739160 0.4646204676 0.6602704300 0.4769488715 -0.347405461036 +1403636628813555456.0000000000 4.6035073280 -1.4055964476 1.0275347885 0.4652583467 0.6623285512 0.4776996637 -0.341553205726 +1403636628863555584.0000000000 4.6030261610 -1.3909173781 1.0249833245 0.4651772416 0.6651376077 0.4780970028 -0.335597009279 +1403636628913555456.0000000000 4.6016131998 -1.3757953979 1.0240277508 0.4645646564 0.6682628880 0.4780497718 -0.330261726911 +1403636628963555584.0000000000 4.6013220905 -1.3610882044 1.0251619645 0.4640783560 0.6707691562 0.4780212455 -0.325876828568 +1403636629013555456.0000000000 4.6013494877 -1.3466378650 1.0288630187 0.4633063195 0.6732855821 0.4774143772 -0.32265971508 +1403636629063555584.0000000000 4.6017304031 -1.3322837815 1.0350733711 0.4634121929 0.6752656612 0.4760922893 -0.320314780098 +1403636629113555456.0000000000 4.6016701125 -1.3174775468 1.0425141789 0.4645932164 0.6764486932 0.4749538251 -0.317787936771 +1403636629163555584.0000000000 4.6005117021 -1.3020025315 1.0494556735 0.4658447437 0.6787086752 0.4719966137 -0.315535109949 +1403636629213555456.0000000000 4.5980978800 -1.2858579601 1.0552675342 0.4683889330 0.6808662948 0.4678599643 -0.313272963703 +1403636629263555584.0000000000 4.5950022060 -1.2695882646 1.0600022222 0.4711787609 0.6826293235 0.4635283465 -0.311687750688 +1403636629313555456.0000000000 4.5905620499 -1.2530391739 1.0633264641 0.4736832583 0.6843525966 0.4586267301 -0.311363480147 +1403636629363555584.0000000000 4.5857851190 -1.2364859972 1.0654735288 0.4757062428 0.6858277848 0.4540076890 -0.311802563357 +1403636629413555456.0000000000 4.5806187951 -1.2198216592 1.0665245257 0.4773454101 0.6873272868 0.4486149100 -0.313794873798 +1403636629463555584.0000000000 4.5753622114 -1.2024276162 1.0661659476 0.4797076490 0.6893553542 0.4418115225 -0.315392367783 +1403636629513555456.0000000000 4.5703732243 -1.1844413986 1.0639106051 0.4815198627 0.6923993832 0.4350145644 -0.315410913928 +1403636629563555584.0000000000 4.5657547108 -1.1655862920 1.0594802360 0.4823507580 0.6965752839 0.4290987465 -0.313041348443 +1403636629613555456.0000000000 4.5615434658 -1.1455173024 1.0526671501 0.4832675401 0.7015182445 0.4244114630 -0.306919447747 +1403636629663555584.0000000000 4.5577421867 -1.1245873063 1.0441343220 0.4830544514 0.7075692670 0.4201282907 -0.299159403558 +1403636629713555456.0000000000 4.5535337088 -1.1026265617 1.0341525111 0.4833134155 0.7135849307 0.4155143832 -0.290779102615 +1403636629763555584.0000000000 4.5493349430 -1.0796932507 1.0230341633 0.4841624639 0.7195743318 0.4102701318 -0.281918265645 +1403636629813555456.0000000000 4.5444462928 -1.0556061756 1.0110605682 0.4857903466 0.7252992860 0.4037302478 -0.273771021036 +1403636629863555584.0000000000 4.5381727452 -1.0304068226 0.9983626190 0.4875318200 0.7309067274 0.3965381079 -0.26616838526 +1403636629913555456.0000000000 4.5309665366 -1.0045341316 0.9860461864 0.4895290900 0.7357345860 0.3894466249 -0.259590476167 +1403636629963555584.0000000000 4.5235467132 -0.9784963024 0.9753583794 0.4919791036 0.7393913040 0.3833311033 -0.253602694166 +1403636630013555456.0000000000 4.5160259691 -0.9527325429 0.9669350543 0.4941849066 0.7421702667 0.3777841264 -0.249486927762 +1403636630063555584.0000000000 4.5078515992 -0.9266882603 0.9605933180 0.4972645579 0.7435969913 0.3727992087 -0.246601346348 +1403636630113555456.0000000000 4.4979687881 -0.8995044279 0.9565521963 0.5022468055 0.7431666599 0.3677720779 -0.245347020929 +1403636630163555584.0000000000 4.4872963155 -0.8717980882 0.9551274862 0.5085481275 0.7413464928 0.3624128365 -0.245847748682 +1403636630213555456.0000000000 4.4763730415 -0.8437234056 0.9552693595 0.5148006918 0.7391249432 0.3579743581 -0.246026268829 +1403636630263555584.0000000000 4.4651923125 -0.8154212107 0.9575109204 0.5199334792 0.7371428710 0.3539854069 -0.24694917845 +1403636630313555456.0000000000 4.4544060227 -0.7873374008 0.9606009167 0.5232388265 0.7359206527 0.3516765879 -0.246911929503 +1403636630363555584.0000000000 4.4441732187 -0.7596482546 0.9647220387 0.5232912410 0.7365344940 0.3511242045 -0.245753960869 +1403636630413555456.0000000000 4.4340958509 -0.7320183676 0.9701457465 0.5227687668 0.7372732783 0.3512402983 -0.244481456175 +1403636630463555584.0000000000 4.4244437085 -0.7046308090 0.9766705608 0.5212353289 0.7382869161 0.3529032220 -0.242292132239 +1403636630513555456.0000000000 4.4142919652 -0.6773862526 0.9854112994 0.5206539673 0.7384395584 0.3543395297 -0.240977099802 +1403636630563555584.0000000000 4.4039551876 -0.6502473614 0.9951609874 0.5203840087 0.7380780811 0.3570063751 -0.238720920292 +1403636630613555456.0000000000 4.3932845709 -0.6233001496 1.0050760998 0.5208800457 0.7369867533 0.3594664933 -0.237314862016 +1403636630663555584.0000000000 4.3822518852 -0.5967800032 1.0136744033 0.5202545319 0.7365183013 0.3621560136 -0.236048799488 +1403636630713555456.0000000000 4.3706949021 -0.5705854768 1.0210640743 0.5197540873 0.7359961217 0.3641428856 -0.235723050537 +1403636630763555584.0000000000 4.3584307322 -0.5448038313 1.0274116438 0.5189817048 0.7358816993 0.3644812386 -0.237254170511 +1403636630813555456.0000000000 4.3456561880 -0.5194611466 1.0321670842 0.5173888327 0.7361593988 0.3650159347 -0.239042888981 +1403636630863555584.0000000000 4.3324789369 -0.4943694517 1.0355365113 0.5162913160 0.7363358947 0.3649608722 -0.24094872684 +1403636630913555456.0000000000 4.3193030331 -0.4695409701 1.0374328082 0.5153272589 0.7363550671 0.3647773328 -0.24322115213 +1403636630963555584.0000000000 4.3059276756 -0.4447013852 1.0379114729 0.5144959401 0.7364219005 0.3645580494 -0.2451002666 +1403636631013555456.0000000000 4.2923812005 -0.4194706542 1.0372618014 0.5141701115 0.7364296089 0.3643878035 -0.24601230911 +1403636631063555584.0000000000 4.2787513064 -0.3942237322 1.0357968988 0.5145065072 0.7356904202 0.3644974417 -0.247354552733 +1403636631113555456.0000000000 4.2649282030 -0.3688956979 1.0337398926 0.5156287375 0.7347644335 0.3640491095 -0.248428014142 +1403636631163555584.0000000000 4.2510007824 -0.3437296120 1.0310779588 0.5165752583 0.7339099752 0.3638466610 -0.249282486367 +1403636631213555456.0000000000 4.2369928288 -0.3187944765 1.0282416900 0.5178074051 0.7326859576 0.3635930203 -0.250692828731 +1403636631263555584.0000000000 4.2232823726 -0.2937613962 1.0250979102 0.5189554728 0.7317043004 0.3636378813 -0.251120539291 +1403636631313555456.0000000000 4.2096436657 -0.2690262434 1.0214980718 0.5186569625 0.7316444780 0.3637314394 -0.251775203417 +1403636631363555584.0000000000 4.1962275265 -0.2442037895 1.0167668604 0.5188652921 0.7312886306 0.3642261684 -0.251664549868 +1403636631413555456.0000000000 4.1825621495 -0.2196333996 1.0105173458 0.5186682782 0.7311754154 0.3644797210 -0.252032263767 +1403636631463555584.0000000000 4.1692549523 -0.1953226997 1.0027400061 0.5188035045 0.7308184929 0.3652411741 -0.251686588444 +1403636631513555456.0000000000 4.1561253245 -0.1712952379 0.9938366906 0.5189297203 0.7304045181 0.3662876235 -0.251106675064 +1403636631563555584.0000000000 4.1428988269 -0.1476314468 0.9843897388 0.5196020663 0.7296971931 0.3671937034 -0.250448564074 +1403636631613555456.0000000000 4.1298980265 -0.1245896228 0.9753138680 0.5196166595 0.7292555237 0.3683971658 -0.249936865273 +1403636631663555584.0000000000 4.1166082841 -0.1017077882 0.9668121000 0.5191369050 0.7290726221 0.3696612548 -0.249600765688 +1403636631713555456.0000000000 4.1033110735 -0.0789919745 0.9591549030 0.5189777859 0.7288517181 0.3704839905 -0.249356859869 +1403636631763555584.0000000000 4.0913653079 -0.0576115073 0.9532766432 0.5187329428 0.7287060920 0.3713559719 -0.248994593584 +1403636631813555456.0000000000 4.0782422090 -0.0360883841 0.9498847383 0.5189171266 0.7281741735 0.3718845433 -0.24937777614 +1403636631863555584.0000000000 4.0639981507 -0.0139513752 0.9480164808 0.5189567532 0.7279837027 0.3728187881 -0.248454760942 +1403636631913555456.0000000000 4.0499541232 0.0076922925 0.9475092457 0.5186088950 0.7280209960 0.3738125902 -0.247577040119 +1403636631963555584.0000000000 4.0356787810 0.0291220057 0.9474479517 0.5185198519 0.7280199126 0.3742191673 -0.247152149233 +1403636632013555456.0000000000 4.0212238376 0.0499184584 0.9480144811 0.5187423709 0.7279735727 0.3739491272 -0.247230419533 +1403636632063555584.0000000000 4.0062464100 0.0705598513 0.9492768531 0.5200100462 0.7272035770 0.3735248246 -0.247474675262 +1403636632113555456.0000000000 3.9919200484 0.0902089112 0.9501803754 0.5217502472 0.7259096168 0.3738797371 -0.247074583677 +1403636632163555584.0000000000 3.9776925843 0.1092379864 0.9512848112 0.5243417211 0.7243773682 0.3745842501 -0.245009851768 +1403636632213555456.0000000000 3.9628700281 0.1275378101 0.9519888511 0.5246947561 0.7243180715 0.3749477133 -0.243870778348 +1403636632263555584.0000000000 3.9475235626 0.1449998603 0.9519158405 0.5250213262 0.7244910867 0.3737054921 -0.244559762547 +1403636632313555456.0000000000 3.9321315025 0.1617461217 0.9500035343 0.5249216093 0.7249128661 0.3727811975 -0.24493431667 +1403636632363555584.0000000000 3.9168121194 0.1775297608 0.9465582782 0.5248939907 0.7251515136 0.3719135863 -0.245605099892 +1403636632413555456.0000000000 3.9016557831 0.1926050297 0.9409483699 0.5242747921 0.7259571494 0.3716055621 -0.245013195142 +1403636632463555584.0000000000 3.8863977670 0.2066073881 0.9337239115 0.5209149682 0.7285840370 0.3706503212 -0.245827655672 +1403636632513555456.0000000000 3.8708421559 0.2197312237 0.9253922007 0.5163845154 0.7310966851 0.3705567317 -0.248057206824 +1403636632563555584.0000000000 3.8550468287 0.2323557819 0.9158863797 0.5094985741 0.7345597346 0.3711514898 -0.251156865025 +1403636632613555456.0000000000 3.8388998430 0.2449654974 0.9057648476 0.5026817291 0.7370768084 0.3728597341 -0.254959754548 +1403636632663555584.0000000000 3.8224172241 0.2578943750 0.8951592278 0.4967624597 0.7378869228 0.3762160145 -0.259251727589 +1403636632713555456.0000000000 3.8050073556 0.2715116712 0.8850159391 0.4919255391 0.7368262815 0.3810964717 -0.264313779629 +1403636632763555584.0000000000 3.7874250823 0.2857775902 0.8763018604 0.4880013293 0.7341219431 0.3873983830 -0.269892882581 +1403636632813555456.0000000000 3.7698036488 0.3007060268 0.8696312556 0.4861714128 0.7288621407 0.3959689528 -0.274965316975 +1403636632863555584.0000000000 3.7512520919 0.3168949375 0.8649268028 0.4870017189 0.7211038095 0.4058197851 -0.279551290014 +1403636632913555456.0000000000 3.7324894964 0.3338206553 0.8624593941 0.4888077057 0.7123320869 0.4156638175 -0.28438286807 +1403636632963555584.0000000000 3.7132921023 0.3514313745 0.8610659319 0.4897524949 0.7048805013 0.4247828133 -0.28782900146 +1403636633013555456.0000000000 3.6934990184 0.3694831351 0.8612466837 0.4905270610 0.6981905513 0.4327385014 -0.290947668684 +1403636633063555584.0000000000 3.6737357112 0.3874076925 0.8622445331 0.4898734102 0.6932044119 0.4397403958 -0.29346221146 +1403636633113555456.0000000000 3.6536713355 0.4052321858 0.8636073835 0.4890006133 0.6890723339 0.4451769972 -0.296437447054 +1403636633163555584.0000000000 3.6333376424 0.4229104531 0.8635649165 0.4878767897 0.6859161203 0.4498689382 -0.298518428869 +1403636633213555456.0000000000 3.6125005924 0.4401798599 0.8620614432 0.4866161217 0.6836630261 0.4531290061 -0.30080512081 +1403636633263555584.0000000000 3.5915374494 0.4570804472 0.8588930555 0.4841271100 0.6830015007 0.4555027919 -0.30273271698 +1403636633313555456.0000000000 3.5701937667 0.4736746621 0.8545789127 0.4815760097 0.6829789120 0.4570790789 -0.304471785661 +1403636633363555584.0000000000 3.5486766359 0.4900717037 0.8490022443 0.4784272846 0.6838171239 0.4576507832 -0.306687520332 +1403636633413555456.0000000000 3.5265193375 0.5065225653 0.8422910852 0.4756079433 0.6852429843 0.4577815174 -0.307693384636 +1403636633463555584.0000000000 3.5042941797 0.5229004609 0.8344009547 0.4730210002 0.6866357607 0.4576222657 -0.308811151614 +1403636633513555456.0000000000 3.4814934699 0.5397143371 0.8255054466 0.4715173161 0.6878507670 0.4573836122 -0.308760383383 +1403636633563555584.0000000000 3.4581125464 0.5569008170 0.8161265953 0.4699662914 0.6894778091 0.4568140561 -0.308339024076 +1403636633613555456.0000000000 3.4342860709 0.5747715109 0.8069153800 0.4685625674 0.6910308056 0.4566395908 -0.307255317659 +1403636633663555584.0000000000 3.4094481423 0.5933393831 0.7989179597 0.4681722457 0.6923079779 0.4562265023 -0.305584343132 +1403636633713555456.0000000000 3.3840091823 0.6123958017 0.7930242498 0.4688060188 0.6929344325 0.4549431558 -0.305105742293 +1403636633763555584.0000000000 3.3580765071 0.6318993492 0.7885886409 0.4693836260 0.6935022052 0.4534242630 -0.305188696853 +1403636633813555456.0000000000 3.3311728788 0.6521814028 0.7862915374 0.4697410504 0.6943430399 0.4520049645 -0.30483208583 +1403636633863555584.0000000000 3.3037452214 0.6726886590 0.7858409231 0.4702787426 0.6950215738 0.4497943822 -0.305725252368 +1403636633913555456.0000000000 3.2758405952 0.6933926103 0.7869670799 0.4696963622 0.6964735160 0.4465747531 -0.308027529265 +1403636633963555584.0000000000 3.2473835105 0.7144619044 0.7880473369 0.4694489671 0.6976718136 0.4428304711 -0.311083399804 +1403636634013555456.0000000000 3.2187340442 0.7362366578 0.7879237306 0.4696119503 0.6986249562 0.4393810903 -0.313579406672 +1403636634063555584.0000000000 3.1899985222 0.7590444218 0.7865409954 0.4694355318 0.6997651992 0.4373352464 -0.314160516077 +1403636634113555456.0000000000 3.1613901608 0.7824639300 0.7854029174 0.4690171600 0.6999287172 0.4374560787 -0.314252881555 +1403636634163555584.0000000000 3.1330226582 0.8070752556 0.7855601271 0.4686659286 0.6999566906 0.4386316096 -0.313073776699 +1403636634213555456.0000000000 3.1044363998 0.8329352869 0.7873908314 0.4689310567 0.6993245007 0.4410976331 -0.310615171789 +1403636634263555584.0000000000 3.0751018090 0.8600249613 0.7912901532 0.4709072854 0.6974465506 0.4435951352 -0.308282327894 +1403636634313555456.0000000000 3.0450012199 0.8877696901 0.7968404193 0.4744497495 0.6944913785 0.4448925580 -0.307652031064 +1403636634363555584.0000000000 3.0146134005 0.9158994088 0.8024438272 0.4786879509 0.6909924951 0.4454872015 -0.308104480041 +1403636634413555456.0000000000 2.9840685175 0.9443366517 0.8069752640 0.4829180106 0.6874490465 0.4460005805 -0.308686711139 +1403636634463555584.0000000000 2.9536904621 0.9727780632 0.8096518531 0.4856641859 0.6849910415 0.4466543530 -0.308897168231 +1403636634513555456.0000000000 2.9234334515 1.0008986871 0.8107987197 0.4883096893 0.6824116659 0.4468788525 -0.310108459647 +1403636634563555584.0000000000 2.8934993897 1.0288476550 0.8103360268 0.4899960225 0.6805309790 0.4472763243 -0.311007032599 +1403636634613555456.0000000000 2.8640995593 1.0560840675 0.8081143000 0.4908669502 0.6785598786 0.4489926739 -0.311467024098 +1403636634663555584.0000000000 2.8351198105 1.0824104828 0.8045527171 0.4906004533 0.6762414273 0.4517678437 -0.312912995121 +1403636634713555456.0000000000 2.8066813922 1.1083148634 0.8007555586 0.4903848768 0.6735722813 0.4553108976 -0.313871057946 +1403636634763555584.0000000000 2.7787982298 1.1333738725 0.7974643051 0.4881086589 0.6723503959 0.4590962081 -0.314524329639 +1403636634813555456.0000000000 2.7511734464 1.1577828771 0.7954512592 0.4853823839 0.6717780588 0.4621474191 -0.315496345753 +1403636634863555584.0000000000 2.7237880463 1.1817928385 0.7947971491 0.4827242005 0.6713205601 0.4649412070 -0.316442294696 +1403636634913555456.0000000000 2.6965363702 1.2051772714 0.7958360897 0.4804168028 0.6704206964 0.4678875046 -0.317517036636 +1403636634963555584.0000000000 2.6692927468 1.2281634544 0.7983192876 0.4778137229 0.6699076712 0.4711969262 -0.317633774931 +1403636635013555456.0000000000 2.6415726676 1.2508608635 0.8027077982 0.4770932817 0.6683102749 0.4738290501 -0.31816569306 +1403636635063555584.0000000000 2.6138720333 1.2729973296 0.8065500011 0.4756060739 0.6675277391 0.4764781260 -0.318078882413 +1403636635113555456.0000000000 2.5859536367 1.2948515620 0.8091160256 0.4742094991 0.6670276953 0.4786568866 -0.317941802217 +1403636635163555584.0000000000 2.5580355290 1.3162912887 0.8101457551 0.4729044853 0.6666991128 0.4800425415 -0.318485163115 +1403636635213555456.0000000000 2.5299572464 1.3375238269 0.8095524073 0.4711437001 0.6668822683 0.4813730925 -0.318702996496 +1403636635263555584.0000000000 2.5012433409 1.3584044970 0.8079119684 0.4690734603 0.6673548035 0.4816354201 -0.320366941378 +1403636635313555456.0000000000 2.4722348077 1.3789458396 0.8050819817 0.4666580155 0.6683518613 0.4817018828 -0.321713198705 +1403636635363555584.0000000000 2.4424538237 1.3993510004 0.8022183405 0.4632618156 0.6703019916 0.4808368121 -0.323851339907 +1403636635413555456.0000000000 2.4126230119 1.4200226613 0.8003312607 0.4614283186 0.6710765054 0.4808136238 -0.324897660435 +1403636635463555584.0000000000 2.3816675772 1.4412015701 0.7996034669 0.4609429565 0.6713582999 0.4800273003 -0.326164705143 +1403636635513555456.0000000000 2.3495144143 1.4626769755 0.8011948509 0.4591345257 0.6726763969 0.4787079584 -0.327933900315 +1403636635563555584.0000000000 2.3181733345 1.4842711176 0.8046607965 0.4586625388 0.6730262802 0.4783169716 -0.328446611246 +1403636635613555456.0000000000 2.2877478815 1.5060312547 0.8088499573 0.4586860085 0.6731553418 0.4774207588 -0.329451742191 +1403636635663555584.0000000000 2.2569098701 1.5285591819 0.8142578938 0.4592228539 0.6732285444 0.4762882887 -0.330192615746 +1403636635713555456.0000000000 2.2253801236 1.5517105499 0.8209870471 0.4600242832 0.6730399695 0.4753286619 -0.33084365123 +1403636635763555584.0000000000 2.1924252245 1.5757238966 0.8304166752 0.4613537716 0.6725102731 0.4728236904 -0.333647100728 +1403636635813555456.0000000000 2.1597114959 1.6000653244 0.8421379213 0.4622566168 0.6722958137 0.4690667765 -0.338102821967 +1403636635863555584.0000000000 2.1267318904 1.6255970928 0.8558872465 0.4624574524 0.6726788358 0.4659867079 -0.341310235288 +1403636635913555456.0000000000 2.0952093585 1.6517783151 0.8704858518 0.4598788337 0.6748167449 0.4642315715 -0.342961903399 +1403636635963555584.0000000000 2.0637451062 1.6794665025 0.8853578583 0.4573712791 0.6769377480 0.4646984949 -0.341499790998 +1403636636013555456.0000000000 2.0329358432 1.7080227412 0.8996171100 0.4549881988 0.6788594789 0.4673110430 -0.337277239092 +1403636636063555584.0000000000 2.0019803811 1.7377701109 0.9124339516 0.4547550182 0.6793101631 0.4706472717 -0.332004098577 +1403636636113555456.0000000000 1.9707573203 1.7682012877 0.9242194047 0.4554065999 0.6789778952 0.4738081436 -0.327260889385 +1403636636163555584.0000000000 1.9387412704 1.7993177091 0.9369306465 0.4586994008 0.6767337753 0.4753413431 -0.325079781883 +1403636636213555456.0000000000 1.9063869861 1.8309210565 0.9514210684 0.4642372874 0.6728646751 0.4759017987 -0.324429265047 +1403636636263555584.0000000000 1.8737262281 1.8627096351 0.9680498677 0.4702039683 0.6687546454 0.4755266068 -0.324884439037 +1403636636313555456.0000000000 1.8411176677 1.8942084201 0.9863334061 0.4748255017 0.6655393572 0.4745615625 -0.32617392647 +1403636636363555584.0000000000 1.8085141232 1.9255409868 1.0056009363 0.4801828900 0.6618310070 0.4729275794 -0.328243225362 +1403636636413555456.0000000000 1.7763259780 1.9563596241 1.0243374388 0.4863781994 0.6572621632 0.4705298658 -0.331729319507 +1403636636463555584.0000000000 1.7450725284 1.9865696579 1.0412706968 0.4912362385 0.6536181456 0.4685243414 -0.334597099934 +1403636636513555456.0000000000 1.7150638895 2.0162234838 1.0552809418 0.4946933128 0.6511587195 0.4688861622 -0.333791275 +1403636636563555584.0000000000 1.6864328304 2.0449943950 1.0670193311 0.4972553843 0.6492688110 0.4702143285 -0.331791469412 +1403636636613555456.0000000000 1.6587449424 2.0729640267 1.0770647896 0.4997453960 0.6474034179 0.4720650306 -0.329056166178 +1403636636663555584.0000000000 1.6323628070 2.0997889023 1.0847712774 0.5016437365 0.6459575798 0.4745033235 -0.325482661216 +1403636636713555456.0000000000 1.6069405644 2.1250999948 1.0905471141 0.5034960565 0.6446171280 0.4763493531 -0.322570570921 +1403636636763555584.0000000000 1.5823666208 2.1487081089 1.0941130671 0.5049878888 0.6433939961 0.4785239205 -0.319446796035 +1403636636813555456.0000000000 1.5586838769 2.1705170362 1.0953786358 0.5070948392 0.6415697468 0.4812910062 -0.31559792694 +1403636636863555584.0000000000 1.5358245332 2.1901973902 1.0945876847 0.5080495941 0.6405545348 0.4840987404 -0.311807484391 +1403636636913555456.0000000000 1.5134813412 2.2071625686 1.0925112830 0.5046480387 0.6427651440 0.4842206450 -0.312591896252 +1403636636963555584.0000000000 1.4915245382 2.2219287597 1.0894210743 0.5002491860 0.6455214929 0.4827195352 -0.31628247569 +1403636637013555456.0000000000 1.4701778511 2.2348963868 1.0850964405 0.4947338763 0.6490596234 0.4807903960 -0.320625314028 +1403636637063555584.0000000000 1.4494024539 2.2467681796 1.0797718958 0.4903312293 0.6518192625 0.4787496076 -0.324816483244 +1403636637113555456.0000000000 1.4295925285 2.2576293518 1.0729385735 0.4859857847 0.6544755294 0.4777672439 -0.327441688066 +1403636637163555584.0000000000 1.4103713509 2.2681203439 1.0649524045 0.4819231408 0.6570343560 0.4779564348 -0.328045100306 +1403636637213555456.0000000000 1.3919828690 2.2780067438 1.0561029544 0.4783582788 0.6592891648 0.4791832500 -0.32694734632 +1403636637263555584.0000000000 1.3740673308 2.2874768862 1.0480915698 0.4756877788 0.6607194281 0.4802479109 -0.326393809073 +1403636637313555456.0000000000 1.3547764701 2.2972811492 1.0416713284 0.4735716382 0.6617736050 0.4813981274 -0.325640050075 +1403636637363555584.0000000000 1.3345270701 2.3070607665 1.0376069755 0.4726581414 0.6622446053 0.4825299201 -0.324331990844 +1403636637413555456.0000000000 1.3127467160 2.3167117276 1.0361276818 0.4712498315 0.6625723338 0.4830193920 -0.324982716297 +1403636637463555584.0000000000 1.2905201413 2.3263370878 1.0374462945 0.4701016945 0.6628033426 0.4845552978 -0.323886228834 +1403636637513555456.0000000000 1.2692292742 2.3353254985 1.0403917671 0.4692141515 0.6630864854 0.4846415834 -0.324464063584 +1403636637563555584.0000000000 1.2488302385 2.3438578964 1.0440792914 0.4677347201 0.6636696833 0.4853715263 -0.324316611604 +1403636637613555456.0000000000 1.2289759788 2.3519260923 1.0492488254 0.4667304304 0.6638842231 0.4852811800 -0.325457554803 +1403636637663555584.0000000000 1.2094499589 2.3598922905 1.0561913973 0.4656202481 0.6644052253 0.4854782489 -0.32569057547 +1403636637713555456.0000000000 1.1879959514 2.3685293772 1.0656366951 0.4660479151 0.6637527001 0.4856972775 -0.326082579464 +1403636637763555584.0000000000 1.1650838067 2.3776815401 1.0762372344 0.4667534246 0.6628353423 0.4857951548 -0.326792927106 +1403636637813555456.0000000000 1.1423818106 2.3866535622 1.0887212674 0.4683614818 0.6614762728 0.4854305554 -0.32778626996 +1403636637863555584.0000000000 1.1198428876 2.3952838770 1.1031781680 0.4693496870 0.6605118725 0.4851840691 -0.328681238563 +1403636637913555456.0000000000 1.0963294171 2.4039334870 1.1191317005 0.4704453417 0.6594234132 0.4847392809 -0.329954197164 +1403636637963555584.0000000000 1.0731821325 2.4124327528 1.1330464862 0.4720688619 0.6580958778 0.4839807988 -0.331396124893 +1403636638013555456.0000000000 1.0501392217 2.4209088189 1.1426049601 0.4730704558 0.6572342349 0.4834688053 -0.33242355301 +1403636638063555584.0000000000 1.0272659064 2.4291732729 1.1478287498 0.4740117413 0.6562570931 0.4830734803 -0.333585835306 +1403636638113555456.0000000000 1.0043581755 2.4374349077 1.1488681260 0.4752055765 0.6552871071 0.4822879970 -0.334927985263 +1403636638163555584.0000000000 0.9818552240 2.4453315088 1.1471185318 0.4758756010 0.6546083173 0.4817643057 -0.336055824209 +1403636638213555456.0000000000 0.9599034624 2.4530803150 1.1434875703 0.4760193809 0.6542273532 0.4819373752 -0.336345782959 +1403636638263555584.0000000000 0.9383424794 2.4607545804 1.1386399590 0.4765514529 0.6538038138 0.4819483174 -0.336400215804 +1403636638313555456.0000000000 0.9174543360 2.4679539813 1.1323503804 0.4742083549 0.6551862279 0.4819502998 -0.337018325049 +1403636638363555584.0000000000 0.8971173428 2.4749281370 1.1240507497 0.4680558701 0.6594084602 0.4819170127 -0.337431738278 +1403636638413555456.0000000000 0.8774790694 2.4819680892 1.1138898395 0.4586154338 0.6659590208 0.4828184582 -0.336239204917 +1403636638463555584.0000000000 0.8572480226 2.4897004094 1.1026327597 0.4495805902 0.6719619442 0.4842351499 -0.334455913366 +1403636638513555456.0000000000 0.8359993806 2.4983389284 1.0911969324 0.4414069690 0.6773500619 0.4849191835 -0.333481883917 +1403636638563555584.0000000000 0.8152277241 2.5080909091 1.0809195218 0.4373996041 0.6800418004 0.4857938749 -0.332007601178 +1403636638613555456.0000000000 0.7931153109 2.5196814385 1.0724419897 0.4369972153 0.6801101720 0.4876491848 -0.329669319583 +1403636638663555584.0000000000 0.7690969613 2.5329992820 1.0670028835 0.4406924789 0.6773260198 0.4899576351 -0.327049106079 +1403636638713555456.0000000000 0.7434235985 2.5477686683 1.0648256088 0.4446150077 0.6747176007 0.4908554815 -0.325782980713 +1403636638763555584.0000000000 0.7168791084 2.5632650451 1.0650040487 0.4491720220 0.6714107642 0.4909726592 -0.326186953074 +1403636638813555456.0000000000 0.6888215133 2.5794706815 1.0679644070 0.4533927073 0.6683458119 0.4901177304 -0.327923068875 +1403636638863555584.0000000000 0.6600027602 2.5959995387 1.0731678308 0.4563433456 0.6663964676 0.4884547961 -0.330270209147 +1403636638913555456.0000000000 0.6318077100 2.6123363085 1.0788792291 0.4574979456 0.6653543133 0.4866779253 -0.333382459883 +1403636638963555584.0000000000 0.6029152050 2.6293367712 1.0865539719 0.4578995439 0.6649444974 0.4847307778 -0.336471241261 +1403636639013555456.0000000000 0.5732395978 2.6467148673 1.0949595105 0.4554703176 0.6665307652 0.4821099893 -0.340372571021 +1403636639063555584.0000000000 0.5428709665 2.6646927367 1.1032683079 0.4529256277 0.6681675074 0.4790335320 -0.34487306803 +1403636639113555456.0000000000 0.5125047648 2.6835688324 1.1090470486 0.4506378634 0.6696000134 0.4765232926 -0.348549694939 +1403636639163555584.0000000000 0.4824620418 2.7034669428 1.1111945944 0.4481251479 0.6712890919 0.4746825023 -0.351043200956 +1403636639213555456.0000000000 0.4526082374 2.7244937220 1.1094023149 0.4462568080 0.6725154403 0.4731751713 -0.353104943643 +1403636639263555584.0000000000 0.4226401182 2.7469939323 1.1032314031 0.4449002835 0.6733887339 0.4728843368 -0.353541729873 +1403636639313555456.0000000000 0.3931427448 2.7714196008 1.0939547188 0.4472270655 0.6719253273 0.4751826510 -0.350293811889 +1403636639363555584.0000000000 0.3640604441 2.7971550323 1.0831208969 0.4502007151 0.6698839861 0.4784256251 -0.345953295438 +1403636639413555456.0000000000 0.3347371219 2.8240501047 1.0711768924 0.4531326465 0.6678586729 0.4817961330 -0.341332805421 +1403636639463555584.0000000000 0.3053603486 2.8517334713 1.0582869220 0.4562896056 0.6655629091 0.4850801396 -0.336931844793 +1403636639513555456.0000000000 0.2758253439 2.8799404465 1.0446697790 0.4605006550 0.6625588564 0.4879523462 -0.332952573803 +1403636639563555584.0000000000 0.2462575652 2.9082864864 1.0301998980 0.4655615114 0.6588662307 0.4909543982 -0.328803205505 +1403636639613555456.0000000000 0.2163027908 2.9360793992 1.0150961427 0.4694061470 0.6558699787 0.4932242563 -0.325917586514 +1403636639663555584.0000000000 0.1858413348 2.9629682634 1.0009374196 0.4723960429 0.6534673312 0.4932157921 -0.32643622365 +1403636639713555456.0000000000 0.1554934909 2.9888659834 0.9883279989 0.4744790733 0.6518837739 0.4913389104 -0.329398283984 +1403636639763555584.0000000000 0.1253406952 3.0140787144 0.9770596211 0.4754243312 0.6511465946 0.4886221356 -0.333508959618 +1403636639813555456.0000000000 0.0960810032 3.0387496642 0.9671627859 0.4757587226 0.6509089477 0.4869602862 -0.335917935305 +1403636639863555584.0000000000 0.0670085991 3.0629467801 0.9592516969 0.4751917151 0.6512117393 0.4852646638 -0.338576890229 +1403636639913555456.0000000000 0.0393882900 3.0863673024 0.9531666746 0.4742816592 0.6515068630 0.4842553204 -0.340723494698 +1403636639963555584.0000000000 0.0122031369 3.1096744118 0.9483778705 0.4742804582 0.6514625559 0.4837945848 -0.34146359231 +1403636640013555456.0000000000 -0.0144513598 3.1326018022 0.9451245174 0.4743335717 0.6508777928 0.4839840124 -0.342235645964 +1403636640063555584.0000000000 -0.0411017010 3.1552571968 0.9438476090 0.4741189652 0.6491998629 0.4858751974 -0.343039410853 +1403636640113555456.0000000000 -0.0675111659 3.1777737360 0.9448589462 0.4742529735 0.6461170228 0.4896344633 -0.343329291217 +1403636640163555584.0000000000 -0.0931672111 3.1996438395 0.9477943982 0.4729858638 0.6435551967 0.4927303975 -0.345453089193 +1403636640213555456.0000000000 -0.1177240329 3.2211343705 0.9528114860 0.4716118432 0.6410624088 0.4956931657 -0.34772049533 +1403636640263555584.0000000000 -0.1410360532 3.2423399320 0.9583781630 0.4697639635 0.6392752293 0.4993561815 -0.348270589812 +1403636640313555456.0000000000 -0.1637442860 3.2630183079 0.9633380345 0.4681029019 0.6380663596 0.5013890986 -0.349799893895 +1403636640363555584.0000000000 -0.1858909481 3.2834051203 0.9670537428 0.4672437695 0.6361742148 0.5036924566 -0.351083376752 +1403636640413555456.0000000000 -0.2074983529 3.3034311606 0.9689890041 0.4665717943 0.6346251355 0.5056744174 -0.351930506979 +1403636640463555584.0000000000 -0.2286422483 3.3231429341 0.9694744533 0.4661938047 0.6331685821 0.5073589576 -0.352629793498 +1403636640513555456.0000000000 -0.2488775779 3.3424062328 0.9679121787 0.4645767789 0.6328900680 0.5089177771 -0.353017385468 +1403636640563555584.0000000000 -0.2689215975 3.3615209285 0.9654833527 0.4642876205 0.6317801352 0.5102094206 -0.353521163823 +1403636640613555456.0000000000 -0.2887728580 3.3802616568 0.9620676417 0.4637957117 0.6312359526 0.5107689449 -0.354330064821 +1403636640663555584.0000000000 -0.3079137109 3.3986270096 0.9574470226 0.4638612003 0.6303994235 0.5113119658 -0.354949894154 +1403636640713555456.0000000000 -0.3265782412 3.4165920720 0.9515329714 0.4629879066 0.6303902733 0.5120228261 -0.355081578319 +1403636640763555584.0000000000 -0.3446962167 3.4340745924 0.9453464721 0.4615608998 0.6308223112 0.5128840384 -0.35492916265 +1403636640813555456.0000000000 -0.3630965646 3.4512698498 0.9404890892 0.4608183194 0.6308922545 0.5139207134 -0.354269586781 +1403636640863555584.0000000000 -0.3806364685 3.4678172620 0.9363165715 0.4597694724 0.6312021515 0.5150981514 -0.353369170458 +1403636640913555456.0000000000 -0.3985178338 3.4841592622 0.9344515522 0.4592173225 0.6313353436 0.5155964288 -0.353122439501 +1403636640963555584.0000000000 -0.4162785208 3.5002263195 0.9348310966 0.4591464288 0.6313923961 0.5159450899 -0.352602982546 +1403636641013555456.0000000000 -0.4327900333 3.5157255753 0.9358634927 0.4598232427 0.6310707861 0.5157541675 -0.352576072706 +1403636641063555584.0000000000 -0.4493414328 3.5307221717 0.9362910937 0.4603502117 0.6309958038 0.5146721965 -0.353602189423 +1403636641113555456.0000000000 -0.4656780993 3.5453296774 0.9351928219 0.4611521169 0.6307711552 0.5143262567 -0.353461421403 +1403636641163555584.0000000000 -0.4821528424 3.5595164549 0.9324841255 0.4613074569 0.6309468967 0.5143531597 -0.352905470106 +1403636641213555456.0000000000 -0.4984318624 3.5732703920 0.9287173687 0.4621346517 0.6307855343 0.5136553135 -0.353128011199 +1403636641263555584.0000000000 -0.5145394998 3.5863203700 0.9237983787 0.4621104411 0.6310131328 0.5124103162 -0.354558929216 +1403636641313555456.0000000000 -0.5302379856 3.5988893259 0.9174828368 0.4603538497 0.6327435859 0.5105208325 -0.356480528455 +1403636641363555584.0000000000 -0.5455479854 3.6112196869 0.9102982186 0.4580481846 0.6347412097 0.5083626284 -0.358974783653 +1403636641413555456.0000000000 -0.5607078132 3.6236865009 0.9022251305 0.4560349927 0.6363039008 0.5065470241 -0.361330241872 +1403636641463555584.0000000000 -0.5756394491 3.6367426897 0.8932130298 0.4559707816 0.6366166921 0.5059578150 -0.361685669069 +1403636641513555456.0000000000 -0.5896981328 3.6500071645 0.8844236725 0.4571464755 0.6360730337 0.5062435218 -0.360757109969 +1403636641563555584.0000000000 -0.6019799180 3.6630378360 0.8761719023 0.4579701862 0.6355116160 0.5072482986 -0.359287430933 +1403636641613555456.0000000000 -0.6140811981 3.6760502894 0.8696091878 0.4594274703 0.6348207390 0.5079942651 -0.357590346012 +1403636641663555584.0000000000 -0.6257743557 3.6890264572 0.8645401271 0.4601052792 0.6345633685 0.5087525728 -0.356094486249 +1403636641713555456.0000000000 -0.6364401107 3.7017347022 0.8620771787 0.4614550585 0.6337088266 0.5089262560 -0.355621172028 +1403636641763555584.0000000000 -0.6466354338 3.7142579494 0.8621488431 0.4616069320 0.6339711694 0.5091937019 -0.354572094984 +1403636641813555456.0000000000 -0.6567830590 3.7264353588 0.8646444445 0.4623469770 0.6334918646 0.5090045044 -0.354736162323 +1403636641863555584.0000000000 -0.6679600326 3.7386554912 0.8683581161 0.4630559118 0.6331245819 0.5087244937 -0.354868815029 +1403636641913555456.0000000000 -0.6796442722 3.7509819474 0.8732189229 0.4636259027 0.6337102136 0.5078180588 -0.354377209795 +1403636641963555584.0000000000 -0.6900217871 3.7631336906 0.8810750724 0.4645314634 0.6352871663 0.5054480492 -0.353755572954 +1403636642013555456.0000000000 -0.7002312115 3.7753762088 0.8897423528 0.4669128223 0.6367838810 0.5023540198 -0.352333853121 +1403636642063555584.0000000000 -0.7099659843 3.7875448050 0.8995046447 0.4689779407 0.6391185188 0.4986271444 -0.350653933353 +1403636642113555456.0000000000 -0.7195717536 3.7995640769 0.9085509981 0.4713674363 0.6408290112 0.4957567558 -0.348390811511 +1403636642163555584.0000000000 -0.7285694343 3.8111597260 0.9164675687 0.4734052136 0.6424203927 0.4931400598 -0.346405000287 +1403636642213555456.0000000000 -0.7366496383 3.8221907189 0.9228217047 0.4750069520 0.6438158123 0.4905337678 -0.345320456967 +1403636642263555584.0000000000 -0.7441631220 3.8327668367 0.9276991776 0.4761503768 0.6454694530 0.4880397953 -0.344190589896 +1403636642313555456.0000000000 -0.7510735910 3.8431651277 0.9307675668 0.4774108254 0.6475336452 0.4849850816 -0.342882709801 +1403636642363555584.0000000000 -0.7572249389 3.8536049319 0.9316500950 0.4793928659 0.6499262677 0.4812944950 -0.340784295079 +1403636642413555456.0000000000 -0.7628839116 3.8637833594 0.9310086793 0.4812967925 0.6520169558 0.4775208564 -0.339412902706 +1403636642463555584.0000000000 -0.7678728200 3.8736719158 0.9285281413 0.4825870521 0.6541042586 0.4747761934 -0.337409131977 +1403636642513555456.0000000000 -0.7720721478 3.8830368553 0.9244516312 0.4827013845 0.6564707069 0.4727674001 -0.33546470719 +1403636642563555584.0000000000 -0.7753294809 3.8919579673 0.9185059819 0.4817608669 0.6593095211 0.4722195823 -0.332003145456 +1403636642613555456.0000000000 -0.7782315688 3.9002891190 0.9112214956 0.4794619078 0.6625501613 0.4717390895 -0.329553932073 +1403636642663555584.0000000000 -0.7810180002 3.9084844199 0.9024201208 0.4769390281 0.6657122302 0.4717569992 -0.326805330113 +1403636642713555456.0000000000 -0.7839211561 3.9166723068 0.8928735590 0.4748239739 0.6683751972 0.4720060608 -0.324078799146 +1403636642763555584.0000000000 -0.7872597624 3.9249199368 0.8838435242 0.4725338784 0.6706004444 0.4725010940 -0.322101682521 +1403636642813555456.0000000000 -0.7911614698 3.9332062314 0.8772903026 0.4706043348 0.6725295295 0.4725836365 -0.320780764009 +1403636642863555584.0000000000 -0.7948925838 3.9412699007 0.8729747322 0.4692763883 0.6737988907 0.4724638987 -0.320238334107 +1403636642913555456.0000000000 -0.7996488916 3.9496487417 0.8703576896 0.4679566256 0.6747218924 0.4729779471 -0.319466470925 +1403636642963555584.0000000000 -0.8040753261 3.9580077953 0.8697968664 0.4672652511 0.6753768271 0.4726933452 -0.319515770999 +1403636643013555456.0000000000 -0.8090000323 3.9665918298 0.8715027068 0.4674858030 0.6751428389 0.4723420224 -0.320206472309 +1403636643063555584.0000000000 -0.8154511570 3.9761193799 0.8745442868 0.4698605585 0.6735137068 0.4710202332 -0.322102906198 +1403636643113555456.0000000000 -0.8223452866 3.9859530651 0.8773593160 0.4725921320 0.6715805448 0.4693515224 -0.324569556503 +1403636643163555584.0000000000 -0.8292052189 3.9959342681 0.8787608882 0.4743150879 0.6702707644 0.4679646254 -0.326758946585 +1403636643213555456.0000000000 -0.8358778610 4.0061773874 0.8785258368 0.4758250771 0.6692030213 0.4668724701 -0.328310689599 +1403636643263555584.0000000000 -0.8421029582 4.0163267816 0.8765322018 0.4763272205 0.6686402791 0.4666248087 -0.329080300327 +1403636643313555456.0000000000 -0.8479080301 4.0266926567 0.8732379015 0.4761532894 0.6686032206 0.4670462030 -0.328809401788 +1403636643363555584.0000000000 -0.8528661781 4.0368849518 0.8696554519 0.4748443534 0.6693014028 0.4681068928 -0.32777188591 +1403636643413555456.0000000000 -0.8582540864 4.0473642472 0.8679592441 0.4728255548 0.6705055871 0.4688182617 -0.327211995308 +1403636643463555584.0000000000 -0.8640558882 4.0581839684 0.8684388551 0.4698111505 0.6722830726 0.4699659855 -0.326258985431 +1403636643513555456.0000000000 -0.8708555623 4.0698461839 0.8699660456 0.4669976992 0.6738252835 0.4716994668 -0.324610920027 +1403636643563555584.0000000000 -0.8792153813 4.0823519297 0.8740314384 0.4645693288 0.6750035779 0.4733413517 -0.32325450236 +1403636643613555456.0000000000 -0.8880110825 4.0955229282 0.8789001429 0.4623312508 0.6763080377 0.4751837583 -0.321025931284 +1403636643663555584.0000000000 -0.8967481175 4.1085143138 0.8858849505 0.4600416789 0.6770391352 0.4772939422 -0.319640666722 +1403636643713555456.0000000000 -0.9063071986 4.1222009480 0.8944783423 0.4581156539 0.6777923304 0.4790958064 -0.318111321372 +1403636643763555584.0000000000 -0.9160009327 4.1355943082 0.9047350709 0.4572369414 0.6780409518 0.4802243256 -0.31714262449 +1403636643813555456.0000000000 -0.9264782902 4.1495152597 0.9142406432 0.4558005678 0.6786447451 0.4821856695 -0.314935124246 +1403636643863555584.0000000000 -0.9382335471 4.1639312942 0.9228036058 0.4537305012 0.6797584583 0.4834240579 -0.313621190058 +1403636643913555456.0000000000 -0.9513014138 4.1785240449 0.9302460253 0.4525571239 0.6802738625 0.4845152792 -0.312513144978 +1403636643963555584.0000000000 -0.9658425683 4.1938194365 0.9359420841 0.4515201167 0.6807895549 0.4857384125 -0.310987718152 +1403636644013555456.0000000000 -0.9819655575 4.2095817615 0.9402168867 0.4512546040 0.6809728727 0.4863406888 -0.310028972025 +1403636644063555584.0000000000 -0.9994703652 4.2255565500 0.9431952389 0.4506367932 0.6812445553 0.4866940434 -0.30977612003 +1403636644113555456.0000000000 -1.0184152351 4.2419782788 0.9446633889 0.4501351705 0.6816532130 0.4870527419 -0.309041828958 +1403636644163555584.0000000000 -1.0391328375 4.2589905339 0.9452151971 0.4511423184 0.6809305607 0.4868150554 -0.309540436584 +1403636644213555456.0000000000 -1.0617861107 4.2763350699 0.9453073978 0.4536513536 0.6794586353 0.4838050867 -0.313797785724 +1403636644263555584.0000000000 -1.0859868602 4.2941307854 0.9447680545 0.4558670409 0.6783434728 0.4785400648 -0.320990311874 +1403636644313555456.0000000000 -1.1112237647 4.3124300029 0.9432344473 0.4583349721 0.6768968639 0.4724650799 -0.329418331715 +1403636644363555584.0000000000 -1.1367035768 4.3318418248 0.9398759597 0.4607198505 0.6756077879 0.4667274464 -0.33683353004 +1403636644413555456.0000000000 -1.1618792511 4.3522162706 0.9343946384 0.4628053242 0.6741952824 0.4627850782 -0.342201584369 +1403636644463555584.0000000000 -1.1865894882 4.3737656003 0.9268259756 0.4649188961 0.6728683876 0.4594333372 -0.346438395254 +1403636644513555456.0000000000 -1.2105572302 4.3961327129 0.9175642090 0.4655366033 0.6723303031 0.4552152026 -0.352174323018 +1403636644563555584.0000000000 -1.2335188821 4.4196976444 0.9058891606 0.4651669341 0.6722940868 0.4524680547 -0.356248570175 +1403636644613555456.0000000000 -1.2553012999 4.4447552136 0.8922259065 0.4656915839 0.6720549569 0.4511331407 -0.357704309501 +1403636644663555584.0000000000 -1.2757220351 4.4712751030 0.8762864712 0.4685678760 0.6701984239 0.4528607178 -0.355239902776 +1403636644713555456.0000000000 -1.2948560802 4.4988806746 0.8584251796 0.4728265384 0.6674606694 0.4560695640 -0.350616417464 +1403636644763555584.0000000000 -1.3126911805 4.5271312861 0.8383063340 0.4770537003 0.6646462715 0.4608260532 -0.343954138632 +1403636644813555456.0000000000 -1.3296526562 4.5558645672 0.8171083502 0.4816922643 0.6617723687 0.4647032308 -0.337758496363 +1403636644863555584.0000000000 -1.3458569710 4.5840574568 0.7942282693 0.4837317518 0.6608210872 0.4679921903 -0.332118040438 +1403636644913555456.0000000000 -1.3616838473 4.6117748400 0.7720971103 0.4832124279 0.6617460866 0.4694439325 -0.328968479635 +1403636644963555584.0000000000 -1.3771975749 4.6388869715 0.7516810781 0.4814440556 0.6633573586 0.4702144384 -0.327210968671 +1403636645013555456.0000000000 -1.3917777331 4.6652130150 0.7328445394 0.4767347469 0.6669745836 0.4726163414 -0.323268742346 +1403636645063555584.0000000000 -1.4060770878 4.6909879447 0.7158018691 0.4683246857 0.6732431132 0.4751214801 -0.318865612013 +1403636645113555456.0000000000 -1.4198674691 4.7164990283 0.7010433134 0.4599070918 0.6792521404 0.4778354488 -0.314285348979 +1403636645163555584.0000000000 -1.4334848736 4.7422389555 0.6877467007 0.4534538884 0.6836550641 0.4816158425 -0.308288022227 +1403636645213555456.0000000000 -1.4501444998 4.7688494070 0.6773543846 0.4467184721 0.6883479031 0.4834368772 -0.304809049646 +1403636645263555584.0000000000 -1.4697715453 4.7967575746 0.6698817321 0.4437563629 0.6903483308 0.4851021030 -0.301952682191 +1403636645313555456.0000000000 -1.4915929239 4.8253754297 0.6644902351 0.4441648651 0.6901835945 0.4847164572 -0.302347704807 +1403636645363555584.0000000000 -1.5158532950 4.8550651965 0.6604814707 0.4475669798 0.6881353391 0.4834368490 -0.304043363414 +1403636645413555456.0000000000 -1.5421502649 4.8855135088 0.6567743398 0.4516423700 0.6858156902 0.4818247773 -0.30581185825 +1403636645463555584.0000000000 -1.5700337758 4.9162216896 0.6524068771 0.4544591019 0.6842423570 0.4801895616 -0.307729274523 +1403636645513555456.0000000000 -1.5991708929 4.9472958972 0.6466053378 0.4568771931 0.6827202802 0.4792736382 -0.308954736457 +1403636645563555584.0000000000 -1.6297351606 4.9787252261 0.6389218255 0.4580944440 0.6821183943 0.4788519240 -0.30913558735 +1403636645613555456.0000000000 -1.6617127585 5.0106847300 0.6302524329 0.4597963609 0.6813019800 0.4779926204 -0.309738556591 +1403636645663555584.0000000000 -1.6947050280 5.0428743173 0.6210631790 0.4611502509 0.6802730514 0.4780715996 -0.30986540174 +1403636645713555456.0000000000 -1.7289150515 5.0758430202 0.6125744589 0.4622109672 0.6796441194 0.4777446336 -0.310169240615 +1403636645763555584.0000000000 -1.7647320188 5.1088717877 0.6057430999 0.4624051810 0.6793659339 0.4772195302 -0.311295512964 +1403636645813555456.0000000000 -1.8018087109 5.1421241113 0.6013571796 0.4622205415 0.6794550469 0.4766216671 -0.312289603735 +1403636645863555584.0000000000 -1.8398404173 5.1757340538 0.6000887444 0.4614380124 0.6801283936 0.4765062702 -0.312157177412 +1403636645913555456.0000000000 -1.8779089477 5.2090070801 0.6022814393 0.4604294755 0.6807244833 0.4760999580 -0.312965982046 +1403636645963555584.0000000000 -1.9179857737 5.2432308565 0.6078999853 0.4634184375 0.6798585594 0.4728091397 -0.315415929199 +1403636646013555456.0000000000 -1.9582655433 5.2779073990 0.6154118259 0.4664896615 0.6800841586 0.4681450754 -0.317353306861 +1403636646063555584.0000000000 -1.9970615247 5.3101616193 0.6244279252 0.4686418904 0.6821276987 0.4617552293 -0.31915308145 +1403636646113555456.0000000000 -2.0361687145 5.3444130922 0.6341222266 0.4719066528 0.6849393831 0.4542162205 -0.319139119541 +1403636646163555584.0000000000 -2.0752377644 5.3775455838 0.6438781043 0.4760064355 0.6886208751 0.4453444666 -0.31762787936 +1403636646213555456.0000000000 -2.1150980380 5.4120933899 0.6528517486 0.4799855574 0.6930665048 0.4351326460 -0.316120649301 +1403636646263555584.0000000000 -2.1538383923 5.4474701169 0.6603305732 0.4847417480 0.6980238614 0.4237728104 -0.313376342179 +1403636646313555456.0000000000 -2.1920105732 5.4832279260 0.6672452387 0.4904870819 0.7028016584 0.4113147491 -0.310342437648 +1403636646363555584.0000000000 -2.2289344499 5.5201741097 0.6723377004 0.4961611224 0.7076182735 0.3984392808 -0.307159012739 +1403636646413555456.0000000000 -2.2639413515 5.5581079358 0.6751401636 0.5031802606 0.7117138362 0.3873575562 -0.300378368752 +1403636646463555584.0000000000 -2.2976888297 5.5964125863 0.6773131635 0.5117126618 0.7134910976 0.3778826110 -0.293743659817 +1403636646513555456.0000000000 -2.3300434418 5.6351241166 0.6800853583 0.5199615872 0.7142407068 0.3705189583 -0.286733085339 +1403636646563555584.0000000000 -2.3603193970 5.6735154550 0.6832907710 0.5260840288 0.7155637075 0.3641897001 -0.280303473884 +1403636646613555456.0000000000 -2.3891870506 5.7117433345 0.6870798466 0.5290092860 0.7180258933 0.3594318123 -0.274584712085 +1403636646663555584.0000000000 -2.4167434469 5.7499225307 0.6928479065 0.5307033948 0.7206468678 0.3570050516 -0.267524562873 +1403636646713555456.0000000000 -2.4431989584 5.7873778839 0.7013292439 0.5311380952 0.7234739589 0.3540515678 -0.262916796721 +1403636646763555584.0000000000 -2.4685768976 5.8241690389 0.7122984811 0.5318821873 0.7254476140 0.3513718162 -0.259547577421 +1403636646813555456.0000000000 -2.4929936159 5.8602053644 0.7255091621 0.5331741279 0.7263638829 0.3493221912 -0.257089217574 +1403636646863555584.0000000000 -2.5160323106 5.8957580740 0.7405543292 0.5343659405 0.7272217902 0.3472803789 -0.254946754842 +1403636646913555456.0000000000 -2.5378936076 5.9301461399 0.7558706061 0.5339025605 0.7283815590 0.3462828787 -0.253961667023 +1403636646963555584.0000000000 -2.5587868901 5.9640242037 0.7703050323 0.5333097102 0.7295701286 0.3458406606 -0.252393379328 +1403636647013555456.0000000000 -2.5788150563 5.9972631961 0.7833601673 0.5325411709 0.7306120131 0.3459028919 -0.250912688017 +1403636647063555584.0000000000 -2.5981184916 6.0298151598 0.7947102643 0.5310957866 0.7317073490 0.3468993085 -0.249404271578 +1403636647113555456.0000000000 -2.6162972730 6.0618269439 0.8041864550 0.5284070332 0.7337526592 0.3481243420 -0.247391359958 +1403636647163555584.0000000000 -2.6343704975 6.0936204980 0.8124808421 0.5260145865 0.7353084696 0.3491024022 -0.246490612455 +1403636647213555456.0000000000 -2.6516460755 6.1249107943 0.8196213176 0.5247710789 0.7360176699 0.3503323410 -0.245276487448 +1403636647263555584.0000000000 -2.6689399086 6.1562064942 0.8259653077 0.5243772296 0.7359755419 0.3503875880 -0.246164702846 +1403636647313555456.0000000000 -2.6860578143 6.1873835272 0.8311156263 0.5242667183 0.7355472707 0.3500453157 -0.248159016715 +1403636647363555584.0000000000 -2.7028954857 6.2186860938 0.8351448824 0.5247534015 0.7347231005 0.3496485485 -0.250123421139 +1403636647413555456.0000000000 -2.7191326534 6.2498052119 0.8377115697 0.5254465927 0.7337684009 0.3492986151 -0.251952950958 +1403636647463555584.0000000000 -2.7345478082 6.2803431122 0.8391325486 0.5258884401 0.7328086775 0.3487770344 -0.254533634386 +1403636647513555456.0000000000 -2.7492254679 6.3107447397 0.8397010915 0.5272938523 0.7310882681 0.3480447630 -0.257557722711 +1403636647563555584.0000000000 -2.7623856305 6.3403373827 0.8406283381 0.5289317716 0.7291532988 0.3465671409 -0.261644538635 +1403636647613555456.0000000000 -2.7743137663 6.3699510796 0.8426944700 0.5310204684 0.7271580524 0.3438436799 -0.266514451184 +1403636647663555584.0000000000 -2.7849960562 6.4002410668 0.8450739938 0.5318129446 0.7270459934 0.3427456307 -0.266654360625 +1403636647713555456.0000000000 -2.7944416927 6.4306745138 0.8484598646 0.5317333311 0.7275962616 0.3430295946 -0.264941582031 +1403636647763555584.0000000000 -2.8030223754 6.4615368651 0.8530735463 0.5309956824 0.7287315603 0.3437718575 -0.262325767487 +1403636647813555456.0000000000 -2.8106300316 6.4925374692 0.8583515472 0.5315564216 0.7292097663 0.3440706308 -0.259453826922 +1403636647863555584.0000000000 -2.8166213643 6.5230834585 0.8623949270 0.5312503889 0.7310711236 0.3428476528 -0.256443996898 +1403636647913555456.0000000000 -2.8215136078 6.5537490800 0.8647920702 0.5327022308 0.7324453426 0.3400904971 -0.253161227452 +1403636647963555584.0000000000 -2.8255394679 6.5844088228 0.8651273135 0.5343064774 0.7345161265 0.3355954823 -0.249756522294 +1403636648013555456.0000000000 -2.8283663416 6.6150635738 0.8628164576 0.5360822281 0.7374376920 0.3300739864 -0.244648030142 +1403636648063555584.0000000000 -2.8297910581 6.6456712683 0.8582549867 0.5381416499 0.7409942724 0.3228818072 -0.238910844029 +1403636648113555456.0000000000 -2.8303736001 6.6763140974 0.8516492976 0.5403932755 0.7451020540 0.3141826695 -0.232566736745 +1403636648163555584.0000000000 -2.8302166144 6.7069674769 0.8437324513 0.5432125012 0.7492050324 0.3044895160 -0.225606144879 +1403636648213555456.0000000000 -2.8294676576 6.7375239068 0.8350691593 0.5462543018 0.7530039783 0.2947169384 -0.218479227236 +1403636648263555584.0000000000 -2.8275955757 6.7678532732 0.8251181732 0.5491194312 0.7570765792 0.2839306310 -0.211391343882 +1403636648313555456.0000000000 -2.8246051185 6.7974768710 0.8139588887 0.5516428588 0.7613032580 0.2730148958 -0.203888136967 +1403636648363555584.0000000000 -2.8208101052 6.8267662213 0.8018241067 0.5549167368 0.7647554858 0.2622595434 -0.196052018568 +1403636648413555456.0000000000 -2.8158127276 6.8554247733 0.7885667660 0.5574840423 0.7686261454 0.2513602712 -0.187732270192 +1403636648463555584.0000000000 -2.8098211374 6.8835896665 0.7742925324 0.5596785251 0.7726818763 0.2399142981 -0.179342678099 +1403636648513555456.0000000000 -2.8033725187 6.9116462496 0.7600009391 0.5619602780 0.7762275756 0.2286066878 -0.17149454563 +1403636648563555584.0000000000 -2.7963567385 6.9391885155 0.7474769365 0.5640239165 0.7791546260 0.2183828669 -0.164632966914 +1403636648613555456.0000000000 -2.7883424127 6.9656803428 0.7361555104 0.5658037766 0.7815409544 0.2099031889 -0.158115382727 +1403636648663555584.0000000000 -2.7792721192 6.9906660618 0.7266463706 0.5662929458 0.7841545499 0.2034271446 -0.151760792612 +1403636648713555456.0000000000 -2.7695954230 7.0148217657 0.7183202709 0.5658554171 0.7868925468 0.1989343082 -0.145027265449 +1403636648763555584.0000000000 -2.7600963417 7.0387469792 0.7119974284 0.5642742324 0.7898958169 0.1949500764 -0.140191500793 +1403636648813555456.0000000000 -2.7504378012 7.0621030256 0.7070647741 0.5591814688 0.7948557323 0.1928435906 -0.135394975309 +1403636648863555584.0000000000 -2.7408728428 7.0854691597 0.7050885778 0.5540588930 0.7994424421 0.1911362637 -0.13182357001 +1403636648913555456.0000000000 -2.7314989573 7.1091127220 0.7050930172 0.5492967434 0.8034288420 0.1910206888 -0.127617710122 +1403636648963555584.0000000000 -2.7223597714 7.1327662233 0.7083747943 0.5459632298 0.8060889186 0.1909723490 -0.125197320267 +1403636649013555456.0000000000 -2.7138342835 7.1578293982 0.7140567600 0.5455138707 0.8067003766 0.1908320882 -0.123418934384 +1403636649063555584.0000000000 -2.7055321051 7.1826664732 0.7226968876 0.5484850078 0.8047963246 0.1904199305 -0.12331797211 +1403636649113555456.0000000000 -2.6983594656 7.2088222415 0.7334707054 0.5543680149 0.8007040394 0.1899539083 -0.124365019808 +1403636649163555584.0000000000 -2.6917672692 7.2352690699 0.7460957418 0.5605936150 0.7962721952 0.1888442342 -0.126582958076 +1403636649213555456.0000000000 -2.6840845753 7.2591214291 0.7603490772 0.5662130103 0.7920924133 0.1888843810 -0.127730679084 +1403636649263555584.0000000000 -2.6769794594 7.2839889011 0.7755671989 0.5704614905 0.7887489074 0.1891287852 -0.129147789416 +1403636649313555456.0000000000 -2.6694414557 7.3078289372 0.7918106701 0.5716784097 0.7875218356 0.1900119540 -0.12995619123 +1403636649363555584.0000000000 -2.6617130237 7.3309461914 0.8090844814 0.5707459815 0.7877285191 0.1917077546 -0.130310942157 +1403636649413555456.0000000000 -2.6537917907 7.3533652291 0.8278558797 0.5686344292 0.7887654671 0.1934456217 -0.130700862003 +1403636649463555584.0000000000 -2.6458074173 7.3752733263 0.8478664417 0.5655072778 0.7904070624 0.1959046630 -0.13068878097 +1403636649513555456.0000000000 -2.6378843508 7.3966772926 0.8701952529 0.5653163590 0.7899204648 0.1974402106 -0.132137945877 +1403636649563555584.0000000000 -2.6300599443 7.4178556560 0.8949604558 0.5668787844 0.7882267429 0.1979560132 -0.134760760083 +1403636649613555456.0000000000 -2.6221878237 7.4390102761 0.9208864270 0.5685937519 0.7867944510 0.1969110141 -0.137410660437 +1403636649663555584.0000000000 -2.6137256054 7.4596961282 0.9463308935 0.5712511268 0.7852419072 0.1939140386 -0.13951574444 +1403636649713555456.0000000000 -2.6041551067 7.4796420935 0.9697952057 0.5728046066 0.7850661056 0.1898975200 -0.139660389442 +1403636649763555584.0000000000 -2.5938558637 7.4993149997 0.9912696895 0.5748739438 0.7848397550 0.1862749481 -0.137288569813 +1403636649813555456.0000000000 -2.5831094313 7.5183599980 1.0108616969 0.5763539897 0.7848867057 0.1834506459 -0.134591226884 +1403636649863555584.0000000000 -2.5718298598 7.5365251377 1.0287273568 0.5782376342 0.7845977869 0.1806676976 -0.131934583086 +1403636649913555456.0000000000 -2.5604222157 7.5541238073 1.0447733190 0.5794136455 0.7846681884 0.1783526808 -0.129483523213 +1403636649963555584.0000000000 -2.5486639611 7.5712178445 1.0582850057 0.5804610495 0.7847434503 0.1764943331 -0.126855971976 +1403636650013555456.0000000000 -2.5364871204 7.5875685925 1.0692418123 0.5809885606 0.7851008205 0.1748549085 -0.124477930183 +1403636650063555584.0000000000 -2.5239232151 7.6029982428 1.0776167409 0.5819313050 0.7851580274 0.1724152569 -0.123108925487 +1403636650113555456.0000000000 -2.5104473998 7.6172030257 1.0835627274 0.5826802555 0.7857647708 0.1686672412 -0.120866896135 +1403636650163555584.0000000000 -2.4960664581 7.6308010037 1.0874705142 0.5837657293 0.7865930139 0.1634599734 -0.117344964819 +1403636650213555456.0000000000 -2.4803607776 7.6431612326 1.0890477352 0.5844312613 0.7882617918 0.1569678650 -0.111555088437 +1403636650263555584.0000000000 -2.4640659841 7.6546398464 1.0892057525 0.5851180811 0.7902718123 0.1485560216 -0.105063801033 +1403636650313555456.0000000000 -2.4474917909 7.6658560021 1.0877304386 0.5853769076 0.7927369598 0.1384490132 -0.0986603235073 +1403636650363555584.0000000000 -2.4303132277 7.6768937327 1.0849881662 0.5851319148 0.7956405051 0.1277635615 -0.0908476812971 +1403636650413555456.0000000000 -2.4125690730 7.6870072303 1.0811673324 0.5846012294 0.7986009632 0.1171143705 -0.0822321618401 +1403636650463555584.0000000000 -2.3942341619 7.6958378937 1.0762388427 0.5833086186 0.8019432920 0.1062202292 -0.0731797421816 +1403636650513555456.0000000000 -2.3756274396 7.7034157238 1.0701239749 0.5814734531 0.8053420066 0.0956346967 -0.0645513789887 +1403636650563555584.0000000000 -2.3571361533 7.7098631059 1.0628156168 0.5792008081 0.8085917447 0.0859520452 -0.0576026060359 +1403636650613555456.0000000000 -2.3389612181 7.7158456424 1.0545495052 0.5776178213 0.8109432649 0.0780538090 -0.051344683741 +1403636650663555584.0000000000 -2.3210403988 7.7214499219 1.0455824809 0.5765416882 0.8126303358 0.0712763251 -0.0463821588244 +1403636650713555456.0000000000 -2.3031416932 7.7268053220 1.0363000497 0.5757273990 0.8139516820 0.0658449272 -0.0410495672089 +1403636650763555584.0000000000 -2.2855922869 7.7315257844 1.0284419000 0.5754894415 0.8146821380 0.0606685811 -0.037739104649 +1403636650813555456.0000000000 -2.2682943822 7.7361279024 1.0225984661 0.5762069413 0.8145941982 0.0566193023 -0.034872736455 +1403636650863555584.0000000000 -2.2512860927 7.7408895549 1.0196967899 0.5783323589 0.8133947594 0.0536290943 -0.0323197823674 +1403636650913555456.0000000000 -2.2343261644 7.7451979865 1.0189235780 0.5820085200 0.8109836157 0.0514083841 -0.0304768073095 +1403636650963555584.0000000000 -2.2175860020 7.7488313981 1.0195052412 0.5851868148 0.8088298879 0.0496577754 -0.0297440684959 +1403636651013555456.0000000000 -2.2009359721 7.7518709563 1.0213527061 0.5879798930 0.8068837026 0.0489275532 -0.0287128989419 +1403636651063555584.0000000000 -2.1845603633 7.7542055909 1.0249147117 0.5895383060 0.8057746852 0.0487106569 -0.0282668427559 +1403636651113555456.0000000000 -2.1683307164 7.7555269874 1.0299096102 0.5908652214 0.8047858852 0.0486830278 -0.0287738055023 +1403636651163555584.0000000000 -2.1520521220 7.7561275932 1.0361147888 0.5906898040 0.8048912741 0.0491467623 -0.0286389258524 +1403636651213555456.0000000000 -2.1358807082 7.7552261256 1.0435984086 0.5890878442 0.8059834153 0.0500779957 -0.0292991539535 +1403636651263555584.0000000000 -2.1196345217 7.7530050654 1.0525902575 0.5870887691 0.8073627359 0.0511934435 -0.0295198439451 +1403636651313555456.0000000000 -2.1035287758 7.7501386861 1.0625451425 0.5846265246 0.8090324062 0.0527217775 -0.0299801053175 +1403636651363555584.0000000000 -2.0877443828 7.7468750740 1.0724333974 0.5820418508 0.8107749412 0.0539023589 -0.0310775544573 +1403636651413555456.0000000000 -2.0719813445 7.7434170174 1.0812361811 0.5807445667 0.8115755692 0.0554825350 -0.0316627856351 +1403636651463555584.0000000000 -2.0562563683 7.7395618342 1.0882424576 0.5797403343 0.8121420778 0.0569085952 -0.032981844006 +1403636651513555456.0000000000 -2.0405107027 7.7356494773 1.0933948743 0.5802425613 0.8116380534 0.0584588851 -0.0338348785009 +1403636651563555584.0000000000 -2.0250053190 7.7315870698 1.0972379159 0.5822362833 0.8100676276 0.0592684188 -0.0357575671221 +1403636651613555456.0000000000 -2.0095404580 7.7274081528 1.0997852367 0.5853158577 0.8077033067 0.0604562415 -0.0369561619328 +1403636651663555584.0000000000 -1.9941173238 7.7227188756 1.1010950483 0.5880210607 0.8056171944 0.0609128802 -0.0387529269272 +1403636651713555456.0000000000 -1.9785679553 7.7172106051 1.1011412325 0.5895897977 0.8044019671 0.0603772265 -0.0409382020336 +1403636651763555584.0000000000 -1.9625511617 7.7113821884 1.1002709199 0.5908390184 0.8035712944 0.0575959926 -0.0431871611713 +1403636651813555456.0000000000 -1.9459169931 7.7050377423 1.0986913140 0.5917807211 0.8031083760 0.0522532704 -0.0456301473253 +1403636651863555584.0000000000 -1.9282956884 7.6979912269 1.0960659231 0.5933104720 0.8023340302 0.0459029436 -0.0462137164623 +1403636651913555456.0000000000 -1.9092351051 7.6899490200 1.0918942249 0.5941015554 0.8022379392 0.0381788895 -0.0447213947523 +1403636651963555584.0000000000 -1.8886747779 7.6809115622 1.0865516735 0.5950030023 0.8021196391 0.0294428826 -0.0413355590856 +1403636652013555456.0000000000 -1.8667710229 7.6720806632 1.0802134651 0.5961708307 0.8018245512 0.0203170135 -0.0352838300481 +1403636652063555584.0000000000 -1.8432345635 7.6626174527 1.0718752304 0.5954403530 0.8028971997 0.0104972574 -0.0263947024566 +1403636652113555456.0000000000 -1.8182300679 7.6523636280 1.0626742467 0.5938644028 0.8044338106 0.0007354339 -0.0145180772041 +1403636652163555584.0000000000 -1.7921821666 7.6411353442 1.0529401054 0.5916697014 0.8061094742 -0.0105921620 -0.00151199683156 +1403636652213555456.0000000000 -1.7654266956 7.6294722983 1.0426251857 0.5881684854 0.8083011846 -0.0238305858 0.0117953817899 +1403636652263555584.0000000000 -1.7383766350 7.6155282723 1.0307271186 0.5842461911 0.8103226902 -0.0380949625 0.0241308896381 +1403636652313555456.0000000000 -1.7111931753 7.5992398955 1.0170558366 0.5780672898 0.8134594831 -0.0530162150 0.0362099261813 +1403636652363555584.0000000000 -1.6839952973 7.5829016181 1.0023520998 0.5722364222 0.8159338629 -0.0677422996 0.0469935028132 +1403636652413555456.0000000000 -1.6569224374 7.5674772228 0.9881859596 0.5677942669 0.8172348268 -0.0807958765 0.0566474604081 +1403636652463555584.0000000000 -1.6304089790 7.5526645616 0.9747915859 0.5642973568 0.8178893224 -0.0923973933 0.0639395897223 +1403636652513555456.0000000000 -1.6041301216 7.5381050396 0.9624804252 0.5607177900 0.8186803818 -0.1023898671 0.0698162406794 +1403636652563555584.0000000000 -1.5779719782 7.5245355448 0.9524132975 0.5564589153 0.8199995156 -0.1111753446 0.0747951385495 +1403636652613555456.0000000000 -1.5517826196 7.5117399072 0.9444445051 0.5519622130 0.8217258249 -0.1177928370 0.0789254811385 +1403636652663555584.0000000000 -1.5251625833 7.5004659122 0.9384492924 0.5473049606 0.8237365469 -0.1225092632 0.0831075317917 +1403636652713555456.0000000000 -1.4981882171 7.4902705871 0.9352712623 0.5446674658 0.8246107642 -0.1250372476 0.0878642475179 +1403636652763555584.0000000000 -1.4715884059 7.4815501417 0.9350540523 0.5432087067 0.8249807187 -0.1279550268 0.0892111301855 +1403636652813555456.0000000000 -1.4445152469 7.4743139010 0.9368670297 0.5428761013 0.8247719590 -0.1292593154 0.0912621699442 +1403636652863555584.0000000000 -1.4173340585 7.4691264684 0.9407383918 0.5435138876 0.8240738670 -0.1305422554 0.0919436526829 +1403636652913555456.0000000000 -1.3899879733 7.4652997862 0.9466757234 0.5452493366 0.8228460427 -0.1303029903 0.09299828812 +1403636652963555584.0000000000 -1.3625025132 7.4625947032 0.9540621988 0.5472368107 0.8215464681 -0.1294019535 0.0940659782227 +1403636653013555456.0000000000 -1.3349686890 7.4610709845 0.9609873406 0.5491475678 0.8203636896 -0.1285279012 0.0944507505135 +1403636653063555584.0000000000 -1.3075184232 7.4603030099 0.9654248203 0.5514162169 0.8190387233 -0.1264490007 0.0955320661704 +1403636653113555456.0000000000 -1.2799756244 7.4611150499 0.9654917649 0.5546108264 0.8171407676 -0.1250771973 0.095097275635 +1403636653163555584.0000000000 -1.2522717058 7.4633439699 0.9624381733 0.5582479947 0.8149605961 -0.1229489578 0.0952993025643 +1403636653213555456.0000000000 -1.2249885726 7.4659092390 0.9588664110 0.5631779168 0.8119029261 -0.1206514641 0.0953283630438 +1403636653263555584.0000000000 -1.1979078821 7.4688620879 0.9556018853 0.5683952635 0.8086480666 -0.1182790321 0.0950010494232 +1403636653313555456.0000000000 -1.1712151725 7.4715489544 0.9531788496 0.5725720256 0.8060848868 -0.1152833773 0.095384347595 +1403636653363555584.0000000000 -1.1452129689 7.4741498812 0.9522538602 0.5750309686 0.8047798368 -0.1128244047 0.0945486814675 +1403636653413555456.0000000000 -1.1199363877 7.4760424645 0.9532777710 0.5762658005 0.8043354406 -0.1104665944 0.0935914399863 +1403636653463555584.0000000000 -1.0953415046 7.4775621367 0.9562879494 0.5762965690 0.8047005707 -0.1086505572 0.0923813425052 +1403636653513555456.0000000000 -1.0713319048 7.4786837019 0.9617555395 0.5762318024 0.8051552253 -0.1065843828 0.0912235852662 +1403636653563555584.0000000000 -1.0479853100 7.4790548541 0.9686410990 0.5759119354 0.8057695195 -0.1050861267 0.0895423361592 +1403636653613555456.0000000000 -1.0249603421 7.4796421985 0.9773964730 0.5774072810 0.8049823113 -0.1041233229 0.0881058680212 +1403636653663555584.0000000000 -1.0022986944 7.4799594859 0.9864346150 0.5795271095 0.8037522371 -0.1025044248 0.0873127349506 +1403636653713555456.0000000000 -0.9800324817 7.4797008893 0.9942199455 0.5816844293 0.8023914369 -0.1011092803 0.0871098164274 +1403636653763555584.0000000000 -0.9583879122 7.4788324053 1.0004134960 0.5838000592 0.8010007130 -0.1004543579 0.0865116789741 +1403636653813555456.0000000000 -0.9374142991 7.4770737556 1.0044795943 0.5850510095 0.8002359720 -0.0991924562 0.0865942374718 +1403636653863555584.0000000000 -0.9169000941 7.4746125617 1.0067440619 0.5862179618 0.7994296842 -0.0984283787 0.0870203166617 +1403636653913555456.0000000000 -0.8970359792 7.4711818662 1.0070754740 0.5864836806 0.7992800178 -0.0981034348 0.0869716135494 +1403636653963555584.0000000000 -0.8780602583 7.4667231402 1.0056030073 0.5854343441 0.8001260119 -0.0989781325 0.0852544606696 +1403636654013555456.0000000000 -0.8595776960 7.4615281768 1.0024068296 0.5840202920 0.8012011436 -0.1004319410 0.0831291237094 +1403636654063555584.0000000000 -0.8415114265 7.4555092840 0.9976687017 0.5832578873 0.8017964025 -0.1017752942 0.0810836311429 +1403636654113555456.0000000000 -0.8234527282 7.4489421018 0.9917878697 0.5832918765 0.8015915843 -0.1035801895 0.080577063757 +1403636654163555584.0000000000 -0.8052985387 7.4417808013 0.9866273826 0.5841448872 0.8005189001 -0.1065192380 0.0812274168943 +1403636654213555456.0000000000 -0.7869401743 7.4341946925 0.9828203518 0.5845984520 0.7994747798 -0.1100062319 0.0835664728024 +1403636654263555584.0000000000 -0.7683833662 7.4252814857 0.9799165345 0.5835133778 0.7993007164 -0.1135702480 0.0879335061023 +1403636654313555456.0000000000 -0.7496619439 7.4156207367 0.9792428886 0.5820792840 0.7990984095 -0.1184571126 0.0927003319431 +1403636654363555584.0000000000 -0.7312159639 7.4049151656 0.9802398092 0.5796922798 0.7993563317 -0.1244447121 0.0974670681336 +1403636654413555456.0000000000 -0.7126870855 7.3939107955 0.9832671069 0.5769755562 0.7995066566 -0.1312419513 0.103265986148 +1403636654463555584.0000000000 -0.6945547105 7.3820888683 0.9883674399 0.5745669708 0.7992132429 -0.1388679353 0.108842477942 +1403636654513555456.0000000000 -0.6764732507 7.3697240979 0.9954814861 0.5725137150 0.7983051365 -0.1466792789 0.115853978649 +1403636654563555584.0000000000 -0.6587373102 7.3568195914 1.0040646830 0.5703074193 0.7972457123 -0.1551091423 0.122840854746 +1403636654613555456.0000000000 -0.6419053094 7.3434609879 1.0130132204 0.5671357937 0.7971151846 -0.1635389180 0.12735539325 +1403636654663555584.0000000000 -0.6257977593 7.3300438183 1.0213274257 0.5640543441 0.7971125689 -0.1723136614 0.129469113818 +1403636654713555456.0000000000 -0.6100570369 7.3164648442 1.0282443027 0.5614781073 0.7969610848 -0.1787338508 0.132851702989 +1403636654763555584.0000000000 -0.5946442840 7.3027775541 1.0335863309 0.5590413044 0.7969717842 -0.1840677178 0.135749292373 +1403636654813555456.0000000000 -0.5792514550 7.2893888799 1.0372070858 0.5573528511 0.7965473481 -0.1883706417 0.139235853467 +1403636654863555584.0000000000 -0.5642612211 7.2760249629 1.0392426167 0.5557970717 0.7962864002 -0.1918109252 0.142218680203 +1403636654913555456.0000000000 -0.5493475593 7.2631869975 1.0396473626 0.5555161391 0.7952978437 -0.1946294634 0.144991486285 +1403636654963555584.0000000000 -0.5344979348 7.2509071753 1.0388382985 0.5579486691 0.7926163090 -0.1959494497 0.148514250501 +1403636655013555456.0000000000 -0.5201613864 7.2388391690 1.0369369066 0.5618920940 0.7890316272 -0.1973583550 0.150851071318 +1403636655063555584.0000000000 -0.5063122794 7.2267494601 1.0339366549 0.5654975969 0.7858810100 -0.1984748640 0.152352336236 +1403636655113555456.0000000000 -0.4930727670 7.2143288642 1.0300052490 0.5681753663 0.7834943050 -0.1994593030 0.15339300372 +1403636655163555584.0000000000 -0.4803598530 7.2013923234 1.0253896172 0.5706946701 0.7813105596 -0.1998272211 0.154694811748 +1403636655213555456.0000000000 -0.4683971540 7.1878680635 1.0205303272 0.5729535093 0.7795319405 -0.2005987578 0.154319047132 +1403636655263555584.0000000000 -0.4565446521 7.1733463680 1.0149960420 0.5745768142 0.7777147198 -0.2028230221 0.154544883122 +1403636655313555456.0000000000 -0.4448570162 7.1576208365 1.0088845325 0.5754390566 0.7761074462 -0.2054818123 0.155898521383 +1403636655363555584.0000000000 -0.4335078080 7.1408035454 1.0027191503 0.5760993005 0.7742787987 -0.2096211087 0.157037984512 +1403636655413555456.0000000000 -0.4230134098 7.1226635239 0.9972398369 0.5765071186 0.7726118538 -0.2137451417 0.158188115409 +1403636655463555584.0000000000 -0.4124648725 7.1037826428 0.9933570270 0.5763630653 0.7710824110 -0.2174786823 0.161060719034 +1403636655513555456.0000000000 -0.4023341867 7.0832438829 0.9915048820 0.5749719184 0.7700377263 -0.2224695924 0.164184267399 +1403636655563555584.0000000000 -0.3933419463 7.0605510516 0.9904128777 0.5706107738 0.7709748563 -0.2286833282 0.1664483438 +1403636655613555456.0000000000 -0.3846918708 7.0361227619 0.9889840237 0.5641510258 0.7729537869 -0.2362398351 0.168721082835 +1403636655663555584.0000000000 -0.3760969389 7.0112912623 0.9866845681 0.5582011623 0.7745040667 -0.2443092230 0.169905611196 +1403636655713555456.0000000000 -0.3676454964 6.9860715645 0.9820617415 0.5527549841 0.7759659610 -0.2513040844 0.170836214401 +1403636655763555584.0000000000 -0.3584766362 6.9609823830 0.9744137969 0.5481414228 0.7766042221 -0.2575967062 0.173409341638 +1403636655813555456.0000000000 -0.3486523739 6.9360621365 0.9634725843 0.5447924820 0.7759256474 -0.2647622287 0.176185991275 +1403636655863555584.0000000000 -0.3380174136 6.9109024425 0.9493934274 0.5415444945 0.7746474810 -0.2728616798 0.179436184704 +1403636655913555456.0000000000 -0.3264828758 6.8856980535 0.9335208629 0.5387986482 0.7724337856 -0.2817509164 0.183462488401 +1403636655963555584.0000000000 -0.3139650780 6.8606002632 0.9178006679 0.5367813428 0.7694120808 -0.2904919498 0.188375335622 +1403636656013555456.0000000000 -0.3009272358 6.8353074471 0.9034728750 0.5356357579 0.7663560179 -0.2979439633 0.192411494875 +1403636656063555584.0000000000 -0.2870779570 6.8095857377 0.8915071477 0.5343506681 0.7635838026 -0.3041345506 0.197259511953 +1403636656113555456.0000000000 -0.2727073619 6.7833433016 0.8811718567 0.5320177658 0.7621660742 -0.3085441832 0.20213970198 +1403636656163555584.0000000000 -0.2576329067 6.7571684033 0.8740454600 0.5300377518 0.7609669683 -0.3121498066 0.206280762778 +1403636656213555456.0000000000 -0.2424835160 6.7302317876 0.8693022401 0.5267868992 0.7611123689 -0.3142100418 0.210892328978 +1403636656263555584.0000000000 -0.2271223617 6.7034211144 0.8679335482 0.5249446341 0.7607826547 -0.3164697778 0.213283293086 +1403636656313555456.0000000000 -0.2111770138 6.6769475636 0.8686770184 0.5228396397 0.7610152529 -0.3181769794 0.215076511565 +1403636656363555584.0000000000 -0.1947525679 6.6513224064 0.8723980581 0.5217636197 0.7608927332 -0.3198517827 0.215638148046 +1403636656413555456.0000000000 -0.1774485442 6.6265766180 0.8781675645 0.5206175388 0.7612899260 -0.3202344495 0.216436882619 +1403636656463555584.0000000000 -0.1590484333 6.6025975689 0.8859783716 0.5204271739 0.7611842499 -0.3207141888 0.216556005302 +1403636656513555456.0000000000 -0.1400287633 6.5789420425 0.8948565109 0.5197246713 0.7617748964 -0.3200088109 0.217208733923 +1403636656563555584.0000000000 -0.1202773196 6.5559346116 0.9039012595 0.5203168064 0.7616562154 -0.3185455653 0.218355108337 +1403636656613555456.0000000000 -0.1010305557 6.5347472557 0.9129498146 0.5217883371 0.7610718097 -0.3169130835 0.219254941151 +1403636656663555584.0000000000 -0.0808536718 6.5137526076 0.9211237888 0.5255358613 0.7589610332 -0.3151143194 0.220211657917 +1403636656713555456.0000000000 -0.0602682093 6.4932092041 0.9286269031 0.5322093259 0.7549094418 -0.3127348066 0.221499230049 +1403636656763555584.0000000000 -0.0397275393 6.4724190983 0.9343313796 0.5383520268 0.7511546064 -0.3102779170 0.222870964254 +1403636656813555456.0000000000 -0.0192721863 6.4512288370 0.9377310175 0.5423493167 0.7488556017 -0.3072866176 0.225049863521 +1403636656863555584.0000000000 0.0008600032 6.4295971221 0.9391207711 0.5446857395 0.7477120134 -0.3044786967 0.227017429746 +1403636656913555456.0000000000 0.0202129406 6.4073949111 0.9389771256 0.5472800638 0.7464358188 -0.3023737686 0.227789824811 +1403636656963555584.0000000000 0.0384085647 6.3845088269 0.9370241603 0.5492696366 0.7456057939 -0.3011422360 0.227350434489 +1403636657013555456.0000000000 0.0556832257 6.3607016470 0.9333353092 0.5512937380 0.7446937123 -0.3007208440 0.225994387888 +1403636657063555584.0000000000 0.0722025721 6.3360796767 0.9278633873 0.5530571329 0.7438987763 -0.3006747908 0.224359284567 +1403636657113555456.0000000000 0.0877056983 6.3102160182 0.9211946948 0.5544212956 0.7433818301 -0.3010215925 0.222230696758 +1403636657163555584.0000000000 0.1024016080 6.2835935300 0.9146575269 0.5557092289 0.7428207977 -0.3017461314 0.219894946567 +1403636657213555456.0000000000 0.1162346526 6.2551634655 0.9092629796 0.5560386935 0.7429704594 -0.3026754393 0.217263541011 +1403636657263555584.0000000000 0.1297085602 6.2257319402 0.9048319715 0.5543294936 0.7444510985 -0.3037844496 0.215003215522 +1403636657313555456.0000000000 0.1427198827 6.1951008097 0.9015602572 0.5523619886 0.7459850961 -0.3045183326 0.213707873166 +1403636657363555584.0000000000 0.1554030821 6.1630912422 0.8997132544 0.5500489989 0.7476538915 -0.3060706520 0.211614066769 +1403636657413555456.0000000000 0.1679943254 6.1306024749 0.8978303931 0.5467109039 0.7499685282 -0.3085483678 0.208452150164 +1403636657463555584.0000000000 0.1806735586 6.0972747742 0.8950278562 0.5427744952 0.7527346085 -0.3106304548 0.205657912665 +1403636657513555456.0000000000 0.1938247437 6.0635304085 0.8912565815 0.5395876305 0.7549464108 -0.3125751175 0.202972662525 +1403636657563555584.0000000000 0.2077623539 6.0293655549 0.8862194989 0.5368733774 0.7567305283 -0.3134720827 0.202141380017 +1403636657613555456.0000000000 0.2223636036 5.9950871942 0.8802127617 0.5356129190 0.7575355069 -0.3138089727 0.201947234378 +1403636657663555584.0000000000 0.2376258649 5.9608638941 0.8733351604 0.5352458484 0.7577752439 -0.3138874952 0.201898989434 +1403636657713555456.0000000000 0.2536556506 5.9267339941 0.8657515206 0.5358293736 0.7571634035 -0.3142944429 0.202013529152 +1403636657763555584.0000000000 0.2707140545 5.8925915500 0.8571205881 0.5360421436 0.7562127485 -0.3160065882 0.202338665333 +1403636657813555456.0000000000 0.2883694154 5.8581497970 0.8473307247 0.5356544737 0.7555450752 -0.3184866791 0.201970689387 +1403636657863555584.0000000000 0.3065945932 5.8234836829 0.8367898854 0.5351107446 0.7550043292 -0.3222458008 0.199455753799 +1403636657913555456.0000000000 0.3257224461 5.7882788085 0.8266065673 0.5336230939 0.7551785638 -0.3261316190 0.196443115369 +1403636657963555584.0000000000 0.3460355578 5.7520997518 0.8177996767 0.5320555671 0.7555236803 -0.3289280290 0.194697698471 +1403636658013555456.0000000000 0.3686776167 5.7160887083 0.8110529911 0.5307220895 0.7559052819 -0.3297652392 0.195438367507 +1403636658063555584.0000000000 0.3923798071 5.6788869729 0.8063557893 0.5284501666 0.7570385682 -0.3293476707 0.197896789945 +1403636658113555456.0000000000 0.4172957488 5.6409142670 0.8038878469 0.5270745461 0.7576931330 -0.3267734141 0.20325519651 +1403636658163555584.0000000000 0.4433875916 5.6028673141 0.8028607418 0.5249908439 0.7587491569 -0.3248051046 0.207812354587 +1403636658213555456.0000000000 0.4704982935 5.5649022581 0.8027404743 0.5237228370 0.7591970460 -0.3231784417 0.211872438387 +1403636658263555584.0000000000 0.4983700837 5.5269948295 0.8017356333 0.5219060342 0.7601415277 -0.3206589063 0.216741355424 +1403636658313555456.0000000000 0.5264950995 5.4895836388 0.7996233544 0.5204951720 0.7608019055 -0.3195529119 0.219433755288 +1403636658363555584.0000000000 0.5549374815 5.4527292454 0.7963276612 0.5191756034 0.7613671525 -0.3188781753 0.221570443024 +1403636658413555456.0000000000 0.5836632474 5.4166872274 0.7921574405 0.5178054776 0.7620897661 -0.3182700989 0.223160972991 +1403636658463555584.0000000000 0.6127130191 5.3813679071 0.7870254726 0.5162013826 0.7629246573 -0.3171194004 0.225648810562 +1403636658513555456.0000000000 0.6421109285 5.3471011268 0.7815057026 0.5147256928 0.7637799689 -0.3155195643 0.228352851413 +1403636658563555584.0000000000 0.6717005559 5.3137431259 0.7753920880 0.5132978882 0.7645449653 -0.3131234337 0.232271369951 +1403636658613555456.0000000000 0.7011112797 5.2817000622 0.7687555285 0.5123476135 0.7650800164 -0.3111886442 0.235189538891 +1403636658663555584.0000000000 0.7300957334 5.2509225594 0.7616299200 0.5119074257 0.7652650503 -0.3101571714 0.236902341207 +1403636658713555456.0000000000 0.7587183907 5.2217037803 0.7538569088 0.5122476181 0.7649248861 -0.3089926523 0.238779892766 +1403636658763555584.0000000000 0.7869634687 5.1937878632 0.7453399484 0.5129851809 0.7643084706 -0.3071677255 0.241509325717 +1403636658813555456.0000000000 0.8148302926 5.1671201791 0.7361719624 0.5143141409 0.7632102073 -0.3044817114 0.245523993636 +1403636658863555584.0000000000 0.8417592550 5.1421226859 0.7266402395 0.5163520509 0.7616609985 -0.3028466750 0.248066471428 +1403636658913555456.0000000000 0.8674661285 5.1185146728 0.7168027674 0.5197758749 0.7592495242 -0.3032713947 0.247789549924 +1403636658963555584.0000000000 0.8919125337 5.0959849945 0.7061927903 0.5236097204 0.7566499668 -0.3048815805 0.245684574825 +1403636659013555456.0000000000 0.9152718694 5.0742519330 0.6945188096 0.5268402853 0.7544774159 -0.3064477752 0.243501342408 +1403636659063555584.0000000000 0.9380281701 5.0529559171 0.6820868124 0.5310841094 0.7515003244 -0.3070469813 0.242732532912 +1403636659113555456.0000000000 0.9595319038 5.0316256810 0.6682362982 0.5334296858 0.7499058413 -0.3073937115 0.242080783228 +1403636659163555584.0000000000 0.9801414586 5.0104194452 0.6532765563 0.5356494384 0.7483308791 -0.3077275277 0.24162852311 +1403636659213555456.0000000000 0.9995122975 4.9891124594 0.6377345767 0.5371404488 0.7473843511 -0.3076627196 0.241330522151 +1403636659263555584.0000000000 1.0174157328 4.9676735921 0.6227982069 0.5374220363 0.7472434828 -0.3079875723 0.240724713158 +1403636659313555456.0000000000 1.0340777431 4.9459161005 0.6087758181 0.5356320200 0.7486350469 -0.3082814743 0.240013412816 +1403636659363555584.0000000000 1.0498684058 4.9242713422 0.5961872122 0.5330575024 0.7505099839 -0.3090084101 0.238952434185 +1403636659413555456.0000000000 1.0646909282 4.9025328847 0.5847680639 0.5292654529 0.7533307336 -0.3092577292 0.238181743847 +1403636659463555584.0000000000 1.0790937822 4.8814675811 0.5749925633 0.5251948770 0.7563158834 -0.3097154813 0.237134869432 +1403636659513555456.0000000000 1.0933234190 4.8609048352 0.5679908446 0.5235513648 0.7573181412 -0.3093229035 0.238080958486 +1403636659563555584.0000000000 1.1069117962 4.8410271472 0.5618533657 0.5234323088 0.7573640212 -0.3105076823 0.236650241121 +1403636659613555456.0000000000 1.1199602741 4.8213764960 0.5554924150 0.5241757533 0.7566354434 -0.3097265904 0.23835273155 +1403636659663555584.0000000000 1.1325709352 4.8023474285 0.5481956329 0.5253706279 0.7554742508 -0.3096318375 0.239525541138 +1403636659713555456.0000000000 1.1445395174 4.7838203093 0.5394631770 0.5264732967 0.7543699860 -0.3094628136 0.240799831872 +1403636659763555584.0000000000 1.1556949444 4.7658876612 0.5292093822 0.5276589851 0.7531227371 -0.3096599010 0.241853021657 +1403636659813555456.0000000000 1.1660660676 4.7484438360 0.5174201530 0.5277480887 0.7527015741 -0.3097855720 0.242806908116 +1403636659863555584.0000000000 1.1752624831 4.7313892474 0.5047806869 0.5279028371 0.7521947083 -0.3108542260 0.242675432607 +1403636659913555456.0000000000 1.1835859680 4.7143428578 0.4900883967 0.5264846488 0.7529174939 -0.3117039026 0.242424914252 +1403636659963555584.0000000000 1.1910792530 4.6973814346 0.4741069603 0.5228140861 0.7550016996 -0.3128566043 0.242401753377 +1403636660013555456.0000000000 1.1978637473 4.6810978242 0.4572765632 0.5194119850 0.7571234687 -0.3141991582 0.241358927579 +1403636660063555584.0000000000 1.2041428010 4.6653814209 0.4395670005 0.5156222272 0.7593482969 -0.3159047622 0.24026665196 +1403636660113555456.0000000000 1.2101641804 4.6502658839 0.4210941802 0.5122862241 0.7613045921 -0.3168893631 0.239915139449 +1403636660163555584.0000000000 1.2158464409 4.6360617681 0.4020576595 0.5095201970 0.7629950992 -0.3176947582 0.239369355148 +1403636660213555456.0000000000 1.2218317761 4.6230399015 0.3826448603 0.5087876577 0.7634248251 -0.3181616869 0.238936804912 +1403636660263555584.0000000000 1.2277143022 4.6110685596 0.3628924492 0.5058749999 0.7651568642 -0.3190472086 0.238399530984 +1403636660313555456.0000000000 1.2337577361 4.6004897360 0.3442352152 0.5025967318 0.7672358611 -0.3196914404 0.23778780773 +1403636660363555584.0000000000 1.2398321995 4.5909394738 0.3264080824 0.4966461335 0.7710739742 -0.3209115373 0.236227283798 +1403636660413555456.0000000000 1.2465239764 4.5834608882 0.3108847784 0.4914233625 0.7743491912 -0.3225166883 0.234242170694 +1403636660463555584.0000000000 1.2539113708 4.5779746265 0.2982632357 0.4887604942 0.7760492239 -0.3232721680 0.233143489575 +1403636660513555456.0000000000 1.2619122194 4.5745840197 0.2865840517 0.4883989282 0.7763871050 -0.3227430765 0.233509007891 +1403636660563555584.0000000000 1.2708851785 4.5735862414 0.2751844545 0.4914478850 0.7744305573 -0.3214512853 0.235383430626 +1403636660613555456.0000000000 1.2808300142 4.5746369155 0.2632275240 0.4969663696 0.7709539601 -0.3192527294 0.238185040817 +1403636660663555584.0000000000 1.2911342956 4.5773111618 0.2500576733 0.5032955417 0.7668675002 -0.3161861688 0.242144877064 +1403636660713555456.0000000000 1.3013718206 4.5813730596 0.2352536348 0.5091386212 0.7629933508 -0.3128655074 0.246443066885 +1403636660763555584.0000000000 1.3110843640 4.5864628359 0.2189903724 0.5139317421 0.7597020557 -0.3089207201 0.25158485593 +1403636660813555456.0000000000 1.3199730317 4.5922475866 0.2011676662 0.5167875757 0.7576728767 -0.3049877584 0.256602573622 +1403636660863555584.0000000000 1.3275060147 4.5986683671 0.1819141172 0.5184599660 0.7564329449 -0.3011893936 0.261330083757 +1403636660913555456.0000000000 1.3335748739 4.6060682123 0.1616220831 0.5199923987 0.7552505530 -0.2990892141 0.264102535836 +1403636660963555584.0000000000 1.3379209926 4.6144681385 0.1404959918 0.5216645954 0.7542454923 -0.2993951854 0.263329280935 +1403636661013555456.0000000000 1.3406355877 4.6239094840 0.1184663689 0.5237754052 0.7530355053 -0.3009696181 0.260795210057 +1403636661063555584.0000000000 1.3420704971 4.6340609741 0.0957447548 0.5259643861 0.7516524292 -0.3027794670 0.258272500518 +1403636661113555456.0000000000 1.3421825954 4.6447669957 0.0720645708 0.5280106753 0.7503918599 -0.3044481723 0.255789158719 +1403636661163555584.0000000000 1.3410065033 4.6558432323 0.0476907857 0.5294280405 0.7494698244 -0.3062027971 0.25345764809 +1403636661213555456.0000000000 1.3387852182 4.6672751443 0.0245445004 0.5317099411 0.7479270814 -0.3072026791 0.252024072997 +1403636661263555584.0000000000 1.3349333548 4.6781029429 0.0024559697 0.5317479056 0.7479409670 -0.3085148912 0.250293900801 +1403636661313555456.0000000000 1.3296310216 4.6884595500 -0.0174585418 0.5329496941 0.7471648391 -0.3089781064 0.249483178992 +1403636661363555584.0000000000 1.3233849359 4.6985753914 -0.0357505029 0.5333406483 0.7469320794 -0.3092462106 0.249012053818 +1403636661413555456.0000000000 1.3163373537 4.7086916519 -0.0522292471 0.5334976151 0.7468818596 -0.3089844706 0.249151318404 +1403636661463555584.0000000000 1.3085527223 4.7189433478 -0.0666428350 0.5336221563 0.7468406882 -0.3094737846 0.248399592273 +1403636661513555456.0000000000 1.2997015540 4.7287815485 -0.0792023630 0.5328194806 0.7475502821 -0.3099189847 0.247431202132 +1403636661563555584.0000000000 1.2897286004 4.7385170703 -0.0895823989 0.5327447121 0.7478582135 -0.3109143941 0.245404571709 +1403636661613555456.0000000000 1.2786071166 4.7477409541 -0.0984664658 0.5319266893 0.7486122011 -0.3122466710 0.243178506301 +1403636661663555584.0000000000 1.2668582558 4.7567627583 -0.1050932792 0.5329898975 0.7480725041 -0.3126321590 0.242013286791 +1403636661713555456.0000000000 1.2548989182 4.7658011053 -0.1103485407 0.5340637484 0.7474545631 -0.3122498123 0.242048845217 +1403636661763555584.0000000000 1.2419459218 4.7746713324 -0.1132466111 0.5367719787 0.7456163734 -0.3146121812 0.238644593616 +1403636661813555456.0000000000 1.2283870895 4.7828300698 -0.1145541754 0.5391893982 0.7442072855 -0.3168364939 0.234616591933 +1403636661863555584.0000000000 1.2145915663 4.7900221174 -0.1141504515 0.5413185114 0.7429914591 -0.3178231208 0.232220638282 +1403636661913555456.0000000000 1.2010029618 4.7962441698 -0.1118724898 0.5424879082 0.7422073099 -0.3183034108 0.231339830563 +1403636661963555584.0000000000 1.1870564441 4.8013255514 -0.1079495280 0.5432529899 0.7420204752 -0.3182321637 0.230239208874 +1403636662013555456.0000000000 1.1732126912 4.8054494397 -0.1021762650 0.5435943898 0.7418309338 -0.3178312463 0.230597710021 +1403636662063555584.0000000000 1.1591278333 4.8083721698 -0.0948019636 0.5439251340 0.7416501807 -0.3171049175 0.231397772921 +1403636662113555456.0000000000 1.1448974004 4.8103456569 -0.0868223370 0.5439374253 0.7417699666 -0.3163717542 0.231987730663 +1403636662163555584.0000000000 1.1304600902 4.8110821796 -0.0799296162 0.5418769648 0.7431933449 -0.3148836547 0.234267563069 +1403636662213555456.0000000000 1.1154739301 4.8107848249 -0.0746072483 0.5391090014 0.7450451455 -0.3127485378 0.237608013148 +1403636662263555584.0000000000 1.1000463835 4.8097503253 -0.0709919245 0.5362507459 0.7468635174 -0.3101169030 0.241779921419 +1403636662313555456.0000000000 1.0839545444 4.8083241678 -0.0686218368 0.5336630188 0.7483762590 -0.3089205309 0.244345785329 +1403636662363555584.0000000000 1.0672533682 4.8067816904 -0.0676188399 0.5307964713 0.7501189835 -0.3079145491 0.246506079217 +1403636662413555456.0000000000 1.0499653735 4.8054880425 -0.0679131012 0.5275867676 0.7520393373 -0.3082471475 0.24712898226 +1403636662463555584.0000000000 1.0318132581 4.8043134603 -0.0701111857 0.5232071942 0.7548660290 -0.3093193539 0.246481332919 +1403636662513555456.0000000000 1.0129015436 4.8034805204 -0.0733682788 0.5191362140 0.7575229191 -0.3106960767 0.245203112497 +1403636662563555584.0000000000 0.9936965320 4.8035584501 -0.0773390661 0.5167793501 0.7589441936 -0.3130815741 0.242740071632 +1403636662613555456.0000000000 0.9738976737 4.8042930721 -0.0817854430 0.5166600702 0.7589531506 -0.3171424047 0.237640868039 +1403636662663555584.0000000000 0.9543306654 4.8058354204 -0.0865935057 0.5189581750 0.7570445563 -0.3229368992 0.230819651431 +1403636662713555456.0000000000 0.9355371682 4.8078520917 -0.0920785880 0.5223303357 0.7545260074 -0.3275132365 0.22493688995 +1403636662763555584.0000000000 0.9178427043 4.8098597144 -0.0986369243 0.5256230999 0.7520149115 -0.3307741945 0.220867294971 +1403636662813555456.0000000000 0.9011614519 4.8113987981 -0.1065759601 0.5279013731 0.7499997142 -0.3335320077 0.218121454061 +1403636662863555584.0000000000 0.8852845938 4.8123356186 -0.1164552833 0.5272509993 0.7503493790 -0.3350362313 0.216177975114 +1403636662913555456.0000000000 0.8705391415 4.8123500518 -0.1280284751 0.5239073701 0.7524778717 -0.3351870441 0.216674330649 +1403636662963555584.0000000000 0.8567973708 4.8120521656 -0.1401608756 0.5210217633 0.7542994381 -0.3362209368 0.215694602347 +1403636663013555456.0000000000 0.8442221540 4.8116854114 -0.1515998189 0.5188952451 0.7555307540 -0.3388716654 0.212336993559 +1403636663063555584.0000000000 0.8331889199 4.8111694487 -0.1613071847 0.5176964162 0.7560083894 -0.3421996036 0.208185415465 +1403636663113555456.0000000000 0.8239278431 4.8102489054 -0.1695388714 0.5172143456 0.7561232143 -0.3449226323 0.204439192154 +1403636663163555584.0000000000 0.8169022065 4.8091163618 -0.1761759650 0.5153629343 0.7572130876 -0.3464035920 0.202568352412 +1403636663213555456.0000000000 0.8126503404 4.8073257342 -0.1821949574 0.5133079350 0.7584217604 -0.3447066850 0.206127869394 +1403636663263555584.0000000000 0.8107693986 4.8049941151 -0.1892329698 0.5095494456 0.7612400546 -0.3385494640 0.215074875718 +1403636663313555456.0000000000 0.8101095582 4.8029745447 -0.1976142782 0.5052366733 0.7642187567 -0.3334645750 0.222501624906 +1403636663363555584.0000000000 0.8105038750 4.8014229550 -0.2076845226 0.5006090179 0.7672496969 -0.3290478694 0.229010946231 +1403636663413555456.0000000000 0.8114196922 4.8008733234 -0.2197156522 0.4953896532 0.7707200142 -0.3255249279 0.233694827769 +1403636663463555584.0000000000 0.8130197275 4.8020938793 -0.2327670287 0.4910843297 0.7735921160 -0.3234668027 0.236136923786 +1403636663513555456.0000000000 0.8155710269 4.8050279773 -0.2470909558 0.4867509002 0.7762074320 -0.3220314522 0.238477100702 +1403636663563555584.0000000000 0.8185417532 4.8100718779 -0.2619052341 0.4840318899 0.7779317711 -0.3210339226 0.239734247808 +1403636663613555456.0000000000 0.8223277132 4.8176092796 -0.2776501905 0.4825345585 0.7789766956 -0.3208570020 0.239596518909 +1403636663663555584.0000000000 0.8271948162 4.8275255840 -0.2939281731 0.4811608025 0.7798975071 -0.3203922825 0.239985303311 +1403636663713555456.0000000000 0.8332989735 4.8398449536 -0.3099995877 0.4799024653 0.7807990306 -0.3175195586 0.243367679816 +1403636663763555584.0000000000 0.8399866447 4.8546388363 -0.3249779507 0.4795845545 0.7811984359 -0.3139361541 0.247329233845 +1403636663813555456.0000000000 0.8471856349 4.8723286291 -0.3385016411 0.4806200100 0.7807177572 -0.3087605178 0.253280738085 +1403636663863555584.0000000000 0.8544487328 4.8934945912 -0.3502383087 0.4823699302 0.7798902674 -0.3034760732 0.258829469316 +1403636663913555456.0000000000 0.8613177069 4.9182866247 -0.3599839869 0.4851164138 0.7784043650 -0.2999938576 0.262206779095 +1403636663963555584.0000000000 0.8676759117 4.9461668330 -0.3677387746 0.4892833431 0.7760281823 -0.2948541058 0.26728847097 +1403636664013555456.0000000000 0.8727800488 4.9767226934 -0.3733129206 0.4938365709 0.7732532455 -0.2903192425 0.271881586203 +1403636664063555584.0000000000 0.8756128593 5.0093953894 -0.3775427560 0.4977425588 0.7711539502 -0.2884710760 0.272687309164 +1403636664113555456.0000000000 0.8765278610 5.0449157434 -0.3795995751 0.5023793663 0.7688987303 -0.2883686315 0.270653370795 +1403636664163555584.0000000000 0.8760528105 5.0814163925 -0.3794816137 0.5076373873 0.7661655186 -0.2893883440 0.267486574347 +1403636664213555456.0000000000 0.8737117762 5.1200589327 -0.3781737151 0.5135188202 0.7632110870 -0.2904760442 0.263497487217 +1403636664263555584.0000000000 0.8700119365 5.1578228467 -0.3768512400 0.5190868755 0.7603715374 -0.2910595966 0.260131220696 +1403636664313555456.0000000000 0.8647005278 5.1961749543 -0.3789561574 0.5235117434 0.7582184470 -0.2918007396 0.256695480306 +1403636664363555584.0000000000 0.8579525354 5.2340981807 -0.3854631438 0.5264258442 0.7571008339 -0.2918068714 0.254013597323 +1403636664413555456.0000000000 0.8501591688 5.2720722111 -0.3963545289 0.5292450867 0.7560563434 -0.2915246839 0.251578620757 +1403636664463555584.0000000000 0.8408904666 5.3097407123 -0.4101196356 0.5308675695 0.7558601485 -0.2911091424 0.249219836297 +1403636664513555456.0000000000 0.8305896121 5.3475239012 -0.4251424528 0.5335005171 0.7549769909 -0.2903233404 0.247182725008 +1403636664563555584.0000000000 0.8191841434 5.3855773192 -0.4405084639 0.5356806421 0.7545774545 -0.2899125284 0.244151266135 +1403636664613555456.0000000000 0.8060778870 5.4238932902 -0.4545582824 0.5392462351 0.7533202412 -0.2917371004 0.237931873538 +1403636664663555584.0000000000 0.7921616493 5.4617206327 -0.4678727219 0.5413657643 0.7529085627 -0.2916048875 0.234560002959 +1403636664713555456.0000000000 0.7775282882 5.4994757401 -0.4795010306 0.5423600370 0.7532679150 -0.2925754589 0.229853517246 +1403636664763555584.0000000000 0.7625694422 5.5362431420 -0.4900951329 0.5401274466 0.7556403243 -0.2902103593 0.230321490546 +1403636664813555456.0000000000 0.7466076663 5.5722468465 -0.4988219830 0.5381819006 0.7577636205 -0.2873043418 0.231539958921 +1403636664863555584.0000000000 0.7302292131 5.6088971293 -0.5053449753 0.5378537418 0.7588939031 -0.2855694452 0.230745505145 +1403636664913555456.0000000000 0.7132452036 5.6455540962 -0.5099946327 0.5384920873 0.7591993883 -0.2851437413 0.228769769646 +1403636664963555584.0000000000 0.6956457027 5.6819786135 -0.5139938418 0.5362867992 0.7614382224 -0.2847217290 0.227028278976 +1403636665013555456.0000000000 0.6775342465 5.7188156092 -0.5157809689 0.5341738383 0.7636126310 -0.2855802084 0.223602336414 +1403636665063555584.0000000000 0.6585797573 5.7545162504 -0.5157977861 0.5303394011 0.7667619723 -0.2859710674 0.221442421702 +1403636665113555456.0000000000 0.6390300269 5.7899512295 -0.5137024189 0.5276753586 0.7691854110 -0.2864688221 0.218742161733 +1403636665163555584.0000000000 0.6198226437 5.8257664295 -0.5096484851 0.5253772015 0.7710477903 -0.2867858818 0.217296938187 +1403636665213555456.0000000000 0.6002239552 5.8616710461 -0.5042183001 0.5262213310 0.7709580670 -0.2887463812 0.21293261168 +1403636665263555584.0000000000 0.5810500479 5.8978067748 -0.4975816642 0.5306956271 0.7680542718 -0.2914377606 0.208611645439 +1403636665313555456.0000000000 0.5634745786 5.9346280768 -0.4902979320 0.5351347973 0.7651168177 -0.2922715023 0.206892176971 +1403636665363555584.0000000000 0.5462980044 5.9709613760 -0.4838788945 0.5371929252 0.7638195324 -0.2923735927 0.206206608193 +1403636665413555456.0000000000 0.5301764200 6.0068941331 -0.4775421133 0.5374111109 0.7636168658 -0.2910104802 0.208306218137 +1403636665463555584.0000000000 0.5146226643 6.0420410248 -0.4718815854 0.5351695283 0.7650007989 -0.2886193959 0.212288006886 +1403636665513555456.0000000000 0.4987402027 6.0756433604 -0.4666189648 0.5319307003 0.7668967006 -0.2858714456 0.217248008629 +1403636665563555584.0000000000 0.4824735804 6.1090783788 -0.4603511665 0.5298623774 0.7678888786 -0.2829530209 0.222553631769 +1403636665613555456.0000000000 0.4655310754 6.1423808550 -0.4535394377 0.5267337402 0.7697390662 -0.2812017040 0.225785160323 +1403636665663555584.0000000000 0.4480743475 6.1763270331 -0.4464924938 0.5254808202 0.7701265037 -0.2805107659 0.228229678362 +1403636665713555456.0000000000 0.4303132637 6.2111718725 -0.4389116990 0.5259588724 0.7693112480 -0.2799969330 0.230497691596 +1403636665763555584.0000000000 0.4122337431 6.2469146678 -0.4305386748 0.5278339876 0.7675306559 -0.2793976588 0.23286245306 +1403636665813555456.0000000000 0.3931455426 6.2830039992 -0.4218812978 0.5300937122 0.7654610790 -0.2803438631 0.233403751502 +1403636665863555584.0000000000 0.3728205219 6.3200294587 -0.4118958709 0.5353238365 0.7616666361 -0.2845193716 0.228781670405 +1403636665913555456.0000000000 0.3520077240 6.3569731010 -0.4017916237 0.5394082661 0.7585769529 -0.2896942231 0.222883346504 +1403636665963555584.0000000000 0.3307722809 6.3932876695 -0.3924046944 0.5424062571 0.7561541327 -0.2946341395 0.217294969431 +1403636666013555456.0000000000 0.3095001841 6.4287853182 -0.3849280861 0.5435516339 0.7550241593 -0.2985669440 0.212950510937 +1403636666063555584.0000000000 0.2885435550 6.4632995432 -0.3793099549 0.5441850928 0.7544033541 -0.3005586798 0.210719349173 +1403636666113555456.0000000000 0.2680872998 6.4964420492 -0.3755361802 0.5441598335 0.7542426560 -0.2998711948 0.212333129701 +1403636666163555584.0000000000 0.2481030914 6.5284332632 -0.3734916975 0.5435577770 0.7544394315 -0.2975370437 0.216420412522 +1403636666213555456.0000000000 0.2279415219 6.5597574353 -0.3724960081 0.5441109271 0.7540199439 -0.2959680849 0.218632376177 +1403636666263555584.0000000000 0.2075773373 6.5905543953 -0.3728076150 0.5444649643 0.7538147204 -0.2955922975 0.218966809381 +1403636666313555456.0000000000 0.1872184184 6.6204786526 -0.3745063957 0.5460544123 0.7526395613 -0.2961674323 0.218273043499 +1403636666363555584.0000000000 0.1665814850 6.6496003060 -0.3773733760 0.5480427570 0.7515020752 -0.2969899810 0.216080352407 +1403636666413555456.0000000000 0.1456865758 6.6775681241 -0.3803741374 0.5484780103 0.7513972611 -0.2987771708 0.212852602768 +1403636666463555584.0000000000 0.1248423032 6.7042720759 -0.3828342366 0.5480128774 0.7520435460 -0.3000329637 0.209982408179 +1403636666513555456.0000000000 0.1042747835 6.7294854850 -0.3838648497 0.5470231959 0.7532078040 -0.3001123803 0.208269504352 +1403636666563555584.0000000000 0.0837296702 6.7523660970 -0.3832191118 0.5442934031 0.7554406565 -0.2990330553 0.20888594393 +1403636666613555456.0000000000 0.0636027175 6.7744365317 -0.3803046172 0.5408072308 0.7583879308 -0.2973212942 0.209702964988 +1403636666663555584.0000000000 0.0437119664 6.7956990869 -0.3759489031 0.5372059294 0.7613439166 -0.2945755555 0.212109575648 +1403636666713555456.0000000000 0.0234923819 6.8160592460 -0.3706504215 0.5326117920 0.7649854892 -0.2927851434 0.21306980142 +1403636666763555584.0000000000 0.0035336821 6.8366656744 -0.3642696082 0.5283820160 0.7683573671 -0.2915504885 0.213161239821 +1403636666813555456.0000000000 -0.0164937780 6.8575707182 -0.3570980275 0.5254186625 0.7708065289 -0.2918450338 0.211232100554 +1403636666863555584.0000000000 -0.0360413568 6.8789243458 -0.3509005325 0.5220340368 0.7734255569 -0.2941065103 0.206868878754 +1403636666913555456.0000000000 -0.0553633201 6.9008405453 -0.3457962002 0.5197862439 0.7751649236 -0.3000238877 0.197299945853 +1403636666963555584.0000000000 -0.0736380363 6.9226483777 -0.3422566161 0.5182512238 0.7761951980 -0.3057036550 0.188366554826 +1403636667013555456.0000000000 -0.0894770356 6.9450182171 -0.3400493191 0.5189355678 0.7757487684 -0.3080401073 0.184474976749 +1403636667063555584.0000000000 -0.1031710677 6.9674160722 -0.3388768364 0.5207858503 0.7746470098 -0.3080905818 0.18380506426 +1403636667113555456.0000000000 -0.1145278883 6.9896799238 -0.3385988072 0.5254834778 0.7717369446 -0.3036521839 0.189959348642 +1403636667163555584.0000000000 -0.1239865793 7.0123812573 -0.3394433213 0.5309163776 0.7683265571 -0.2969949496 0.198987691834 +1403636667213555456.0000000000 -0.1331307316 7.0345553787 -0.3413811866 0.5353726255 0.7653919066 -0.2915406277 0.206289708089 +1403636667263555584.0000000000 -0.1418404139 7.0566288263 -0.3443717285 0.5382568024 0.7634478174 -0.2857564027 0.213939999057 +1403636667313555456.0000000000 -0.1512013852 7.0784373461 -0.3487988074 0.5397454554 0.7625128821 -0.2818097548 0.218705761629 +1403636667363555584.0000000000 -0.1614257887 7.0999621721 -0.3541284391 0.5411388695 0.7616479960 -0.2799337226 0.220676607592 +1403636667413555456.0000000000 -0.1722859033 7.1212013716 -0.3603714749 0.5404822635 0.7621871467 -0.2790880811 0.221493835418 +1403636667463555584.0000000000 -0.1842680050 7.1419225588 -0.3670368079 0.5376997404 0.7643969504 -0.2789457056 0.220829311134 +1403636667513555456.0000000000 -0.1970236831 7.1625460089 -0.3741539575 0.5346121314 0.7667772857 -0.2797048423 0.21910651348 +1403636667563555584.0000000000 -0.2100215738 7.1836223934 -0.3811679423 0.5308124722 0.7696518872 -0.2825165825 0.214612377338 +1403636667613555456.0000000000 -0.2233535950 7.2049644153 -0.3866692846 0.5278432613 0.7717515501 -0.2862760587 0.209349121496 +1403636667663555584.0000000000 -0.2363116670 7.2266392902 -0.3897037168 0.5260179746 0.7731703633 -0.2892210937 0.204606545919 +1403636667713555456.0000000000 -0.2487364560 7.2484697427 -0.3904679465 0.5258818913 0.7732947519 -0.2915696922 0.201123289557 +1403636667763555584.0000000000 -0.2603485209 7.2702511168 -0.3892872672 0.5266342778 0.7727574096 -0.2926316471 0.199672337986 +1403636667813555456.0000000000 -0.2709151759 7.2924393982 -0.3870188622 0.5278706588 0.7717866396 -0.2931963685 0.199333489642 +1403636667863555584.0000000000 -0.2812372132 7.3143840543 -0.3844733483 0.5284608295 0.7712078352 -0.2939965454 0.198830726857 +1403636667913555456.0000000000 -0.2911763768 7.3357551323 -0.3820778080 0.5290572943 0.7705697310 -0.2949420689 0.198317535583 +1403636667963555584.0000000000 -0.3002675892 7.3570692707 -0.3810198649 0.5280491873 0.7710899683 -0.2953132208 0.198429882146 +1403636668013555456.0000000000 -0.3084847343 7.3787268540 -0.3811483920 0.5284383585 0.7706028871 -0.2954911849 0.19902022829 +1403636668063555584.0000000000 -0.3157126988 7.4004145196 -0.3836473414 0.5279667942 0.7705222464 -0.2945290823 0.201987998945 +1403636668113555456.0000000000 -0.3221516435 7.4224255106 -0.3882050179 0.5274114216 0.7704688461 -0.2934665874 0.205164108912 +1403636668163555584.0000000000 -0.3281454713 7.4445490006 -0.3942703376 0.5263485864 0.7706613592 -0.2925001912 0.208523075942 +1403636668213555456.0000000000 -0.3338328844 7.4670240111 -0.4021131376 0.5240264038 0.7716871840 -0.2922045982 0.210977939699 +1403636668263555584.0000000000 -0.3391662418 7.4898750810 -0.4108972889 0.5220522967 0.7724725229 -0.2918722486 0.213443649139 +1403636668313555456.0000000000 -0.3442086236 7.5132585527 -0.4205590223 0.5205697411 0.7727008841 -0.2922364771 0.215727443313 +1403636668363555584.0000000000 -0.3494305485 7.5372992396 -0.4310014547 0.5200920160 0.7724512167 -0.2928266041 0.21697002708 +1403636668413555456.0000000000 -0.3546760046 7.5617323634 -0.4421085481 0.5205152869 0.7715792067 -0.2931827620 0.218570885472 +1403636668463555584.0000000000 -0.3597005990 7.5866721786 -0.4538440126 0.5216192638 0.7701969877 -0.2935106030 0.220366671127 +1403636668513555456.0000000000 -0.3647260039 7.6121865878 -0.4661437054 0.5219320378 0.7694558166 -0.2938321152 0.221782285742 +1403636668563555584.0000000000 -0.3701831517 7.6382436799 -0.4786007048 0.5218649119 0.7689576822 -0.2948485752 0.22231827286 +1403636668613555456.0000000000 -0.3758253642 7.6647018444 -0.4910554419 0.5216409815 0.7686670093 -0.2953057947 0.223240235804 +1403636668663555584.0000000000 -0.3813442011 7.6919880112 -0.5035503533 0.5209756327 0.7685345801 -0.2958877557 0.224475890363 +1403636668713555456.0000000000 -0.3867729640 7.7197853058 -0.5163737372 0.5201348499 0.7686219934 -0.2942979070 0.228185694311 +1403636668763555584.0000000000 -0.3921188055 7.7487388394 -0.5290171539 0.5200264253 0.7682506790 -0.2913158596 0.233449097333 +1403636668813555456.0000000000 -0.3980092776 7.7786124805 -0.5409468844 0.5209086588 0.7670451801 -0.2887463640 0.238582057272 +1403636668863555584.0000000000 -0.4051470039 7.8093213844 -0.5517121286 0.5212581190 0.7665376565 -0.2847408173 0.244197996533 +1403636668913555456.0000000000 -0.4133321946 7.8415866354 -0.5601342903 0.5228786583 0.7650009231 -0.2814626498 0.249299565095 +1403636668963555584.0000000000 -0.4233396817 7.8754893208 -0.5659291847 0.5258394031 0.7629295814 -0.2821146063 0.248681975244 +1403636669013555456.0000000000 -0.4359477590 7.9093830702 -0.5692776396 0.5292930727 0.7607249921 -0.2847883402 0.245034550607 +1403636669063555584.0000000000 -0.4499605432 7.9435643691 -0.5709455138 0.5326763499 0.7584292945 -0.2874256594 0.241717607444 +1403636669113555456.0000000000 -0.4653004121 7.9770982976 -0.5701998004 0.5355889896 0.7564035713 -0.2902059032 0.238282616684 +1403636669163555584.0000000000 -0.4815289808 8.0100275151 -0.5699699303 0.5368689883 0.7553484271 -0.2921008400 0.236426610867 +1403636669213555456.0000000000 -0.4986089765 8.0424523412 -0.5708653616 0.5382302416 0.7542287478 -0.2931308365 0.235630039969 +1403636669263555584.0000000000 -0.5164208834 8.0733836737 -0.5725117912 0.5388349390 0.7536559052 -0.2935541416 0.235553923623 +1403636669313555456.0000000000 -0.5351829738 8.1042081910 -0.5762489468 0.5384225340 0.7537279069 -0.2934900870 0.23634505723 +1403636669363555584.0000000000 -0.5547895561 8.1344191612 -0.5811850902 0.5379283994 0.7539753497 -0.2943846224 0.235567194922 +1403636669413555456.0000000000 -0.5751025172 8.1646736510 -0.5871490963 0.5390170775 0.7531466151 -0.2944058076 0.235703175132 +1403636669463555584.0000000000 -0.5963678022 8.1947326878 -0.5939652930 0.5413386037 0.7514685585 -0.2944432932 0.235691893684 +1403636669513555456.0000000000 -0.6185292228 8.2243868427 -0.6020275402 0.5435940065 0.7500249582 -0.2934543099 0.23633172899 +1403636669563555584.0000000000 -0.6416652003 8.2534758598 -0.6109922097 0.5464339777 0.7480263573 -0.2924273220 0.237387316939 +1403636669613555456.0000000000 -0.6659282918 8.2816979705 -0.6200130215 0.5506318833 0.7450298220 -0.2905406278 0.239418539443 +1403636669663555584.0000000000 -0.6918498786 8.3086734041 -0.6281371173 0.5547383242 0.7422315087 -0.2890651367 0.240414487683 +1403636669713555456.0000000000 -0.7189613556 8.3349071272 -0.6347786635 0.5588455750 0.7393180664 -0.2876007227 0.241632456831 +1403636669763555584.0000000000 -0.7475797212 8.3599841611 -0.6401227585 0.5613268350 0.7377062310 -0.2874520578 0.240983434106 +1403636669813555456.0000000000 -0.7785923481 8.3837168686 -0.6434089395 0.5645647122 0.7360342152 -0.2920486690 0.232868835812 +1403636669863555584.0000000000 -0.8113838907 8.4059523348 -0.6442256534 0.5683148004 0.7339468608 -0.2995814879 0.220434174523 +1403636669913555456.0000000000 -0.8455670156 8.4253525535 -0.6432631461 0.5686062613 0.7341471168 -0.3081639091 0.206760575526 +1403636669963555584.0000000000 -0.8789157853 8.4424883003 -0.6415459626 0.5678655801 0.7347885415 -0.3145035328 0.196728264609 +1403636670013555456.0000000000 -0.9114033665 8.4565879150 -0.6387163520 0.5656824699 0.7363868664 -0.3186156026 0.190320319395 +1403636670063555584.0000000000 -0.9431383527 8.4677350252 -0.6346826013 0.5643107226 0.7374905035 -0.3215434534 0.185124210228 +1403636670113555456.0000000000 -0.9738756374 8.4762324587 -0.6291252929 0.5634859399 0.7387094464 -0.3231530957 0.179900044457 +1403636670163555584.0000000000 -1.0029699478 8.4821313752 -0.6217863876 0.5664083818 0.7374022826 -0.3235298077 0.175350740612 +1403636670213555456.0000000000 -1.0303969828 8.4856771180 -0.6132320252 0.5723596510 0.7339710080 -0.3247467426 0.168019470652 +1403636670263555584.0000000000 -1.0560433601 8.4860285258 -0.6055157431 0.5784116629 0.7304468248 -0.3252635952 0.161527019255 +1403636670313555456.0000000000 -1.0799093051 8.4830662750 -0.5995790212 0.5830750803 0.7279366628 -0.3256131122 0.155266760279 +1403636670363555584.0000000000 -1.1018073481 8.4763240300 -0.5957680373 0.5852222175 0.7277223701 -0.3251648557 0.14900645895 +1403636670413555456.0000000000 -1.1216969828 8.4656896578 -0.5934479245 0.5860667482 0.7290953623 -0.3232638452 0.142990229444 +1403636670463555584.0000000000 -1.1393884756 8.4508962582 -0.5913505013 0.5865511103 0.7311640192 -0.3210461544 0.135226990097 +1403636670513555456.0000000000 -1.1542798463 8.4316936343 -0.5877283868 0.5873680135 0.7335198423 -0.3170880537 0.128072729027 +1403636670563555584.0000000000 -1.1662185028 8.4083566531 -0.5829266657 0.5882849336 0.7365493365 -0.3111659548 0.120795944944 +1403636670613555456.0000000000 -1.1747916685 8.3808284996 -0.5761513152 0.5891843723 0.7398380962 -0.3041324198 0.114038756718 +1403636670663555584.0000000000 -1.1794913149 8.3496394321 -0.5671586726 0.5902415846 0.7433141043 -0.2956598520 0.108093783458 +1403636670713555456.0000000000 -1.1808771212 8.3142870487 -0.5568745668 0.5917783514 0.7465679712 -0.2863669629 0.102120564448 +1403636670763555584.0000000000 -1.1785137152 8.2757922080 -0.5454721205 0.5936507569 0.7495087083 -0.2770128462 0.0952856653 +1403636670813555456.0000000000 -1.1731249075 8.2340149334 -0.5342260623 0.5960456374 0.7518657841 -0.2683258444 0.086189803059 +1403636670863555584.0000000000 -1.1648071297 8.1886600052 -0.5237129169 0.5989535487 0.7536927133 -0.2599720267 0.0749432164576 +1403636670913555456.0000000000 -1.1529650941 8.1403572586 -0.5140183510 0.6025257488 0.7548805648 -0.2512934562 0.0630051891056 +1403636670963555584.0000000000 -1.1373895716 8.0882028728 -0.5034454014 0.6073940013 0.7549668131 -0.2422294764 0.0492190923729 +1403636671013555456.0000000000 -1.1176199766 8.0317885169 -0.4916223927 0.6117030467 0.7559392426 -0.2301406043 0.037557241527 +1403636671063555584.0000000000 -1.0928070153 7.9707989441 -0.4774355025 0.6149241599 0.7579438806 -0.2157458670 0.0290357081719 +1403636671113555456.0000000000 -1.0627900345 7.9058832620 -0.4616909056 0.6162698452 0.7615747089 -0.1991270853 0.0237454122259 +1403636671163555584.0000000000 -1.0281879581 7.8363036204 -0.4444207879 0.6158765534 0.7661955849 -0.1824057123 0.0191977281621 +1403636671213555456.0000000000 -0.9885767214 7.7636010067 -0.4251955921 0.6138550179 0.7713699779 -0.1671326179 0.0153968283419 +1403636671263555584.0000000000 -0.9446539989 7.6863361326 -0.4049279200 0.6100921899 0.7774577480 -0.1521197809 0.0143715759697 +1403636671313555456.0000000000 -0.8965365585 7.6065179482 -0.3856607167 0.6033823757 0.7855009030 -0.1362929813 0.0185003585052 +1403636671363555584.0000000000 -0.8449402045 7.5238738359 -0.3662825770 0.5952475210 0.7943118920 -0.1184222620 0.0269290690704 +1403636671413555456.0000000000 -0.7914289363 7.4404064295 -0.3474736065 0.5868906250 0.8026929481 -0.0997027456 0.0360941527838 +1403636671463555584.0000000000 -0.7371884665 7.3566087817 -0.3294536451 0.5781919839 0.8106169354 -0.0829941414 0.0413060078004 +1403636671513555456.0000000000 -0.6827488579 7.2730100638 -0.3120281532 0.5696956967 0.8177818951 -0.0694937054 0.0430140687711 +1403636671563555584.0000000000 -0.6283810731 7.1901205890 -0.2954420072 0.5618019414 0.8240748195 -0.0594293831 0.0418021413999 +1403636671613555456.0000000000 -0.5739470447 7.1086675418 -0.2803650388 0.5538418579 0.8300588727 -0.0513145415 0.0403519773989 +1403636671663555584.0000000000 -0.5197200482 7.0292764596 -0.2662585024 0.5466259672 0.8352465266 -0.0457139663 0.0383865206957 +1403636671713555456.0000000000 -0.4655402791 6.9524727491 -0.2530202092 0.5407597622 0.8393652018 -0.0414364076 0.0364412085667 +1403636671763555584.0000000000 -0.4115185877 6.8780291956 -0.2410436391 0.5361118621 0.8425400093 -0.0383795284 0.0351769226202 +1403636671813555456.0000000000 -0.3576385081 6.8063341120 -0.2300760474 0.5311999719 0.8457611160 -0.0348947315 0.0360150284867 +1403636671863555584.0000000000 -0.3043414288 6.7377335917 -0.2187672898 0.5263571423 0.8488517732 -0.0335086823 0.0357210589168 +1403636671913555456.0000000000 -0.2512518951 6.6728321879 -0.2069755319 0.5200179287 0.8527489001 -0.0328245636 0.0363760254981 +1403636671963555584.0000000000 -0.1984877270 6.6121670142 -0.1932107126 0.5137276301 0.8564948011 -0.0314731218 0.0388589809867 +1403636672013555456.0000000000 -0.1463942446 6.5559606356 -0.1774533058 0.5072978488 0.8602114490 -0.0298883605 0.0423301497938 +1403636672063555584.0000000000 -0.0948512935 6.5052528065 -0.1594677712 0.5045281790 0.8616219391 -0.0267432112 0.0484123048689 +1403636672113555456.0000000000 -0.0444545397 6.4599048509 -0.1394551711 0.5044756068 0.8613076166 -0.0220634359 0.0562739410962 +1403636672163555584.0000000000 0.0039749984 6.4193826789 -0.1168795204 0.5056615553 0.8602465774 -0.0191025656 0.0625884136242 +1403636672213555456.0000000000 0.0501910236 6.3832367508 -0.0933607230 0.5062032533 0.8595923906 -0.0169086533 0.0676260736374 +1403636672263555584.0000000000 0.0941688948 6.3524831312 -0.0697212344 0.5072071718 0.8587390656 -0.0164411912 0.0709773858289 +1403636672313555456.0000000000 0.1361852518 6.3260865907 -0.0473956069 0.5091916597 0.8572248478 -0.0145606966 0.075348523865 +1403636672363555584.0000000000 0.1761068013 6.3041972808 -0.0266606896 0.5134267915 0.8541890803 -0.0110226977 0.0814398239591 +1403636672413555456.0000000000 0.2134081632 6.2858575936 -0.0088343534 0.5190630146 0.8502096827 -0.0067749650 0.087585285804 +1403636672463555584.0000000000 0.2476109755 6.2712752180 0.0063040919 0.5283580902 0.8440411769 -0.0038929612 0.0917445644821 +1403636672513555456.0000000000 0.2779019508 6.2595526235 0.0189213861 0.5410137195 0.8363166384 -0.0067230461 0.0885067022816 +1403636672563555584.0000000000 0.3050961864 6.2497743901 0.0279464908 0.5541159112 0.8281998569 -0.0104306732 0.0832571620145 +1403636672613555456.0000000000 0.3297230083 6.2411189462 0.0314480175 0.5646988642 0.8216739206 -0.0157917308 0.0756160187502 +1403636672663555584.0000000000 0.3524365332 6.2329127917 0.0304051305 0.5728248459 0.8164994890 -0.0207108271 0.0690749018137 +1403636672713555456.0000000000 0.3734909982 6.2244281283 0.0235638196 0.5749186429 0.8154025859 -0.0254399991 0.062769287354 +1403636672763555584.0000000000 0.3932226654 6.2153017011 0.0114583814 0.5717393478 0.8179077844 -0.0291029129 0.0573933340383 +1403636672813555456.0000000000 0.4112238455 6.2057004619 -0.0029788177 0.5671503017 0.8213922638 -0.0304792917 0.0522139543306 +1403636672863555584.0000000000 0.4281191117 6.1968483478 -0.0166133234 0.5647184635 0.8233338785 -0.0278946165 0.0493586053424 +1403636672913555456.0000000000 0.4436427780 6.1887436073 -0.0283865838 0.5640219349 0.8241725158 -0.0232675093 0.0455800858902 +1403636672963555584.0000000000 0.4575454317 6.1804715461 -0.0392823731 0.5633320825 0.8249784123 -0.0166009548 0.0423319314502 +1403636673013555456.0000000000 0.4700690103 6.1731533229 -0.0481677102 0.5628899253 0.8255873936 -0.0088114272 0.0385064440126 +1403636673063555584.0000000000 0.4813085820 6.1665683623 -0.0555215703 0.5618790446 0.8264462376 -0.0002907377 0.035755712855 +1403636673113555456.0000000000 0.4912381951 6.1608285948 -0.0612713587 0.5600989950 0.8277828536 0.0073061738 0.0318006751592 +1403636673163555584.0000000000 0.5000419896 6.1567634561 -0.0643016107 0.5549657516 0.8312934923 0.0134896693 0.0279673571002 +1403636673213555456.0000000000 0.5077018364 6.1533097355 -0.0655514293 0.5479263985 0.8359431033 0.0190581643 0.0247502772206 +1403636673263555584.0000000000 0.5141258199 6.1514904025 -0.0656351875 0.5408939919 0.8404134339 0.0248371919 0.0228487086829 +1403636673313555456.0000000000 0.5192028564 6.1515029363 -0.0634985725 0.5349878680 0.8441401700 0.0283460797 0.0202941918019 +1403636673363555584.0000000000 0.5226815035 6.1542833568 -0.0599238700 0.5309970871 0.8465743596 0.0317312082 0.0186300187226 +1403636673413555456.0000000000 0.5248782427 6.1600662180 -0.0561499863 0.5303510653 0.8469108000 0.0343969845 0.0169319778741 +1403636673463555584.0000000000 0.5256923480 6.1686000690 -0.0533181253 0.5310082966 0.8464555264 0.0362668750 0.0150978358342 +1403636673513555456.0000000000 0.5253865453 6.1796946683 -0.0521317429 0.5322413218 0.8456160293 0.0380774823 0.014241197516 +1403636673563555584.0000000000 0.5237178637 6.1931757689 -0.0517634646 0.5352559194 0.8436642366 0.0395230195 0.0130264148497 +1403636673613555456.0000000000 0.5208217803 6.2093102308 -0.0521991055 0.5413357700 0.8397094292 0.0410163517 0.0127010831006 +1403636673663555584.0000000000 0.5164332428 6.2272868969 -0.0535835851 0.5477829838 0.8354806363 0.0419858651 0.011962280522 +1403636673713555456.0000000000 0.5105179921 6.2469237482 -0.0556043241 0.5542936096 0.8311579748 0.0426257480 0.0108655834474 +1403636673763555584.0000000000 0.5034116738 6.2671598175 -0.0575637881 0.5617360133 0.8260787005 0.0438636087 0.0110732011597 +1403636673813555456.0000000000 0.4946925097 6.2867560458 -0.0589955785 0.5671713973 0.8223769937 0.0438849628 0.00931646151464 +1403636673863555584.0000000000 0.4849846529 6.3060834781 -0.0598997775 0.5702591980 0.8201880985 0.0447741855 0.00955000276225 +1403636673913555456.0000000000 0.4740062058 6.3260400514 -0.0604090860 0.5698273323 0.8203798375 0.0463732843 0.0111018953613 +1403636673963555584.0000000000 0.4613678876 6.3466439742 -0.0590798841 0.5697978673 0.8203831073 0.0466574272 0.0111817758691 +1403636674013555456.0000000000 0.4472267526 6.3675196024 -0.0583227522 0.5687614459 0.8211536980 0.0459723095 0.0101768700157 +1403636674063555584.0000000000 0.4316857166 6.3892135873 -0.0584936066 0.5684934537 0.8213615746 0.0456337494 0.00989534327142 +1403636674113555456.0000000000 0.4147056460 6.4111611954 -0.0597868091 0.5682501255 0.8216024989 0.0446145684 0.00840647874983 +1403636674163555584.0000000000 0.3965208683 6.4331870413 -0.0625523810 0.5691519895 0.8210228766 0.0439433987 0.00751177258882 +1403636674213555456.0000000000 0.3772194094 6.4553958816 -0.0668185103 0.5708280552 0.8199459034 0.0425344243 0.00590505430936 +1403636674263555584.0000000000 0.3568567613 6.4775172269 -0.0727476222 0.5727789195 0.8187407250 0.0397777615 0.00237996901715 +1403636674313555456.0000000000 0.3353770754 6.4991490913 -0.0803740495 0.5738470267 0.8181895842 0.0353997828 -0.00349994893157 +1403636674363555584.0000000000 0.3132235285 6.5198556904 -0.0896610407 0.5736212997 0.8184400157 0.0318187826 -0.0101049639804 +1403636674413555456.0000000000 0.2904890640 6.5401235912 -0.1003619433 0.5736532006 0.8183584331 0.0296561590 -0.0182206640301 +1403636674463555584.0000000000 0.2678184889 6.5600462214 -0.1124524791 0.5743345243 0.8176696927 0.0298188860 -0.0258256060926 +1403636674513555456.0000000000 0.2455220206 6.5794552227 -0.1261927850 0.5752739542 0.8166691263 0.0319873653 -0.0329882453151 +1403636674563555584.0000000000 0.2241496495 6.5984313314 -0.1418533670 0.5755278363 0.8161107468 0.0358530643 -0.0380199462 +1403636674613555456.0000000000 0.2037402476 6.6172372217 -0.1587741571 0.5762103972 0.8152686684 0.0401780243 -0.0412832025376 +1403636674663555584.0000000000 0.1841452503 6.6362092857 -0.1767008408 0.5772254084 0.8141861135 0.0451619526 -0.0432689094346 +1403636674713555456.0000000000 0.1652351375 6.6548009555 -0.1961540834 0.5760584569 0.8146572870 0.0483255161 -0.0464198606476 +1403636674763555584.0000000000 0.1473002236 6.6732096991 -0.2173153114 0.5717337630 0.8173564475 0.0515844288 -0.0488670509747 +1403636674813555456.0000000000 0.1305182615 6.6912408456 -0.2384324843 0.5648876017 0.8217930227 0.0542943150 -0.051091610488 +1403636674863555584.0000000000 0.1145491378 6.7105081820 -0.2583329142 0.5578687077 0.8263260741 0.0566300168 -0.052542987076 +1403636674913555456.0000000000 0.0996183616 6.7305955958 -0.2766269199 0.5518385647 0.8301482738 0.0586460768 -0.0537464381025 +1403636674963555584.0000000000 0.0855944227 6.7525945545 -0.2931469592 0.5460881303 0.8337925101 0.0606586309 -0.0538361833257 +1403636675013555456.0000000000 0.0721999911 6.7768410070 -0.3067625193 0.5414413233 0.8367071576 0.0615613346 -0.0545218117567 +1403636675063555584.0000000000 0.0596348261 6.8030726832 -0.3181076959 0.5373026072 0.8392958634 0.0637242244 -0.0531750431888 +1403636675113555456.0000000000 0.0479876798 6.8319740568 -0.3272427497 0.5356527045 0.8403546062 0.0666291440 -0.0494051928506 +1403636675163555584.0000000000 0.0368787304 6.8630285926 -0.3345254189 0.5339199013 0.8413955819 0.0716170364 -0.043058261796 +1403636675213555456.0000000000 0.0255870353 6.8973102092 -0.3392216052 0.5352526937 0.8403888788 0.0773543149 -0.0356005091594 +1403636675263555584.0000000000 0.0133756326 6.9347000033 -0.3424898788 0.5363762640 0.8395195273 0.0815089415 -0.0293897786303 +1403636675313555456.0000000000 -0.0001348093 6.9744386986 -0.3437376409 0.5378968299 0.8383897023 0.0846798697 -0.0244750294062 +1403636675363555584.0000000000 -0.0151570641 7.0157658997 -0.3424861948 0.5431987619 0.8347703309 0.0873481682 -0.0215382745994 +1403636675413555456.0000000000 -0.0321766717 7.0552252077 -0.3391446393 0.5508274077 0.8294616689 0.0902000018 -0.0211297526956 +1403636675463555584.0000000000 -0.0512443202 7.0969490347 -0.3368505127 0.5570716105 0.8248715552 0.0933599962 -0.0232819531553 +1403636675513555456.0000000000 -0.0717319405 7.1390011418 -0.3363158635 0.5627194688 0.8203612620 0.0987853615 -0.0244059738535 +1403636675563555584.0000000000 -0.0936869861 7.1764578226 -0.3355581411 0.5681312447 0.8158886167 0.1044526838 -0.0253434565252 +1403636675613555456.0000000000 -0.1170924027 7.2158392482 -0.3371515934 0.5725906874 0.8119980063 0.1099967922 -0.0264546428983 +1403636675663555584.0000000000 -0.1423118103 7.2544898629 -0.3399918078 0.5755650007 0.8090879240 0.1151208996 -0.0291348531253 +1403636675713555456.0000000000 -0.1692371561 7.2922740407 -0.3438977854 0.5785321821 0.8060814529 0.1199011473 -0.0340135352253 +1403636675763555584.0000000000 -0.1980125733 7.3292914539 -0.3487323882 0.5819527112 0.8026309535 0.1240346425 -0.04159329172 +1403636675813555456.0000000000 -0.2286518505 7.3652438627 -0.3545641857 0.5834631386 0.8005565682 0.1251241733 -0.0549898919563 +1403636675863555584.0000000000 -0.2602182791 7.4004113289 -0.3617503665 0.5840597626 0.7988363635 0.1254913020 -0.0706158001801 +1403636675913555456.0000000000 -0.2918196527 7.4342028765 -0.3709619447 0.5810418936 0.7993158322 0.1263285250 -0.0867503427995 +1403636675963555584.0000000000 -0.3229233914 7.4670036810 -0.3817971461 0.5766125261 0.8003968409 0.1290930826 -0.10108346941 +1403636676013555456.0000000000 -0.3529159110 7.4991366235 -0.3942906527 0.5717436185 0.8015230763 0.1349169555 -0.111657547675 +1403636676063555584.0000000000 -0.3814426206 7.5311092600 -0.4080977657 0.5680111659 0.8016949340 0.1432846383 -0.118819445476 +1403636676113555456.0000000000 -0.4085191055 7.5628710945 -0.4234440047 0.5645291408 0.8016556570 0.1544598234 -0.121643823378 +1403636676163555584.0000000000 -0.4345517080 7.5947761883 -0.4397637325 0.5630852697 0.7998652762 0.1691261885 -0.120610328246 +1403636676213555456.0000000000 -0.4602097095 7.6264443144 -0.4567482769 0.5618561244 0.7976128060 0.1838683173 -0.119682701497 +1403636676263555584.0000000000 -0.4854546745 7.6578997079 -0.4748071357 0.5607549307 0.7947716797 0.2008918850 -0.11633716267 +1403636676313555456.0000000000 -0.5114559998 7.6886814713 -0.4929900801 0.5578141525 0.7928229683 0.2160957878 -0.116523486183 +1403636676363555584.0000000000 -0.5385531829 7.7195173985 -0.5097534160 0.5580969478 0.7882373514 0.2316150652 -0.116465171757 +1403636676413555456.0000000000 -0.5670523079 7.7495374378 -0.5247850804 0.5569055143 0.7845710823 0.2459414443 -0.117546887861 +1403636676463555584.0000000000 -0.5975682929 7.7784160609 -0.5371127760 0.5544572025 0.7818589300 0.2571965366 -0.122978720852 +1403636676513555456.0000000000 -0.6293955828 7.8051067150 -0.5476676273 0.5509607748 0.7800215092 0.2661549395 -0.131035178455 +1403636676563555584.0000000000 -0.6636156717 7.8316904353 -0.5556974552 0.5482891795 0.7779438893 0.2717032870 -0.142687085867 +1403636676613555456.0000000000 -0.6995100423 7.8583591988 -0.5612865226 0.5456224920 0.7761194904 0.2765637736 -0.153124498422 +1403636676663555584.0000000000 -0.7366736706 7.8854813904 -0.5645180351 0.5439572492 0.7742148165 0.2797446871 -0.16261869195 +1403636676713555456.0000000000 -0.7743899378 7.9124465008 -0.5659638649 0.5423659391 0.7728173290 0.2815441917 -0.171246699967 +1403636676763555584.0000000000 -0.8124275057 7.9395348691 -0.5658056379 0.5414717330 0.7714496772 0.2822749787 -0.178870328236 +1403636676813555456.0000000000 -0.8507275452 7.9664340409 -0.5640534280 0.5394680613 0.7708885414 0.2831625592 -0.185806438705 +1403636676863555584.0000000000 -0.8889906011 7.9930073759 -0.5601460855 0.5364231671 0.7710091268 0.2839793125 -0.192745589422 +1403636676913555456.0000000000 -0.9261427920 8.0194759789 -0.5562894249 0.5357501634 0.7699383818 0.2850428101 -0.197274547547 +1403636676963555584.0000000000 -0.9628443169 8.0457019625 -0.5538073945 0.5349562952 0.7693303742 0.2857522767 -0.200744050684 +1403636677013555456.0000000000 -0.9989261307 8.0726005366 -0.5553844849 0.5355576446 0.7681538529 0.2876872950 -0.20088227348 +1403636677063555584.0000000000 -1.0344081613 8.1000561026 -0.5611277831 0.5374485843 0.7663759556 0.2911423174 -0.197618483137 +1403636677113555456.0000000000 -1.0699031468 8.1279776272 -0.5705583920 0.5394962960 0.7647023543 0.2943266047 -0.193767658996 +1403636677163555584.0000000000 -1.1052486579 8.1557064809 -0.5832900409 0.5410753974 0.7635187996 0.2970030628 -0.189909551063 +1403636677213555456.0000000000 -1.1406516033 8.1830216205 -0.5978534925 0.5437153525 0.7616216439 0.2985054109 -0.187618247479 +1403636677263555584.0000000000 -1.1764109826 8.2094550690 -0.6125430499 0.5470126567 0.7588875291 0.2999311111 -0.186837362851 +1403636677313555456.0000000000 -1.2125640529 8.2341744556 -0.6260377924 0.5499760344 0.7557538386 0.3014336397 -0.188415121045 +1403636677363555584.0000000000 -1.2488761035 8.2576997012 -0.6380394045 0.5541415994 0.7508734459 0.3040969441 -0.191418924483 +1403636677413555456.0000000000 -1.2856718032 8.2792597508 -0.6469106062 0.5581696824 0.7456313367 0.3069167469 -0.195659464151 +1403636677463555584.0000000000 -1.3221854654 8.2990719632 -0.6536051708 0.5617113104 0.7402075995 0.3096848402 -0.201664109895 +1403636677513555456.0000000000 -1.3578665614 8.3165058534 -0.6584613809 0.5631677528 0.7357985126 0.3126893873 -0.208968844796 +1403636677563555584.0000000000 -1.3926289457 8.3319249445 -0.6616589643 0.5631425326 0.7319563892 0.3167836692 -0.216236997746 +1403636677613555456.0000000000 -1.4264848431 8.3453504848 -0.6632999743 0.5607944200 0.7293777342 0.3211516942 -0.224453399775 +1403636677663555584.0000000000 -1.4593055950 8.3572597691 -0.6631851258 0.5566101483 0.7278484308 0.3264134358 -0.232112200388 +1403636677713555456.0000000000 -1.4907461963 8.3672571463 -0.6614468068 0.5515103916 0.7262887787 0.3319386999 -0.241158863353 +1403636677763555584.0000000000 -1.5204717677 8.3757257913 -0.6587220875 0.5449323930 0.7254729979 0.3389856408 -0.248649053169 +1403636677813555456.0000000000 -1.5484987263 8.3826233861 -0.6549954247 0.5352788647 0.7261501308 0.3461479044 -0.2576124083 +1403636677863555584.0000000000 -1.5746247174 8.3885833946 -0.6507535440 0.5245517760 0.7269598849 0.3531123636 -0.267743195533 +1403636677913555456.0000000000 -1.5993814832 8.3947521025 -0.6457685405 0.5142424167 0.7269448812 0.3615118488 -0.276432740003 +1403636677963555584.0000000000 -1.6229351854 8.4014792315 -0.6398967215 0.5058435481 0.7252586041 0.3703353778 -0.284559255558 +1403636678013555456.0000000000 -1.6451949962 8.4094206950 -0.6347239997 0.4990368796 0.7224152854 0.3807049809 -0.290072517999 +1403636678063555584.0000000000 -1.6665179454 8.4188056367 -0.6303560812 0.4951988972 0.7178470655 0.3902628910 -0.295243151782 +1403636678113555456.0000000000 -1.6869304626 8.4296417189 -0.6277403346 0.4945854837 0.7119616133 0.4002848978 -0.297099076247 +1403636678163555584.0000000000 -1.7066309826 8.4417269995 -0.6266226090 0.4948396291 0.7061952804 0.4092419556 -0.29823311206 +1403636678213555456.0000000000 -1.7255633295 8.4545885854 -0.6273779160 0.4951407438 0.7010353936 0.4182458796 -0.297414533995 +1403636678263555584.0000000000 -1.7439498812 8.4676889619 -0.6284519387 0.4952355515 0.6959965465 0.4261510292 -0.297868857416 +1403636678313555456.0000000000 -1.7619302655 8.4804984801 -0.6288052844 0.4942073176 0.6913473381 0.4332199252 -0.300197404511 +1403636678363555584.0000000000 -1.7796874219 8.4927983658 -0.6272780886 0.4914938857 0.6875844775 0.4385071455 -0.305569681024 +1403636678413555456.0000000000 -1.7970526438 8.5050121252 -0.6246693301 0.4877085209 0.6843510915 0.4448594245 -0.309683830011 +1403636678463555584.0000000000 -1.8142358622 8.5171543530 -0.6202913307 0.4844994818 0.6804858236 0.4514188501 -0.313720126694 +1403636678513555456.0000000000 -1.8310835914 8.5291053200 -0.6144325185 0.4808667802 0.6765907293 0.4585455386 -0.317376926984 +1403636678563555584.0000000000 -1.8479280895 8.5407808741 -0.6065860936 0.4777823675 0.6719868319 0.4650131589 -0.322366978944 +1403636678613555456.0000000000 -1.8641028900 8.5519307125 -0.5972507131 0.4743870276 0.6662794598 0.4727216469 -0.327967794265 +1403636678663555584.0000000000 -1.8797390387 8.5632182285 -0.5888691219 0.4725461566 0.6589116235 0.4822956392 -0.331551683299 +1403636678713555456.0000000000 -1.8951686907 8.5744105877 -0.5817949291 0.4718016065 0.6501705314 0.4935154350 -0.333352725395 +1403636678763555584.0000000000 -1.9104541173 8.5851756030 -0.5761127777 0.4710902737 0.6404833219 0.5058794071 -0.33457599111 +1403636678813555456.0000000000 -1.9256455081 8.5952683974 -0.5726589664 0.4706486738 0.6304971921 0.5186164171 -0.334664202669 +1403636678863555584.0000000000 -1.9409721767 8.6043836092 -0.5707573770 0.4697934905 0.6214836223 0.5302206618 -0.334541825809 +1403636678913555456.0000000000 -1.9567544496 8.6121488514 -0.5705207551 0.4697696404 0.6124283317 0.5407926621 -0.334352090033 +1403636678963555584.0000000000 -1.9725193679 8.6176329234 -0.5714749498 0.4671790279 0.6053919248 0.5496123110 -0.336408502916 +1403636679013555456.0000000000 -1.9885999905 8.6208312505 -0.5729118004 0.4641209790 0.5988892511 0.5562133864 -0.341394274473 +1403636679063555584.0000000000 -2.0048029115 8.6216991178 -0.5753499766 0.4597402537 0.5932012670 0.5615212745 -0.348489618659 +1403636679113555456.0000000000 -2.0209292015 8.6205166351 -0.5786951044 0.4553061033 0.5872629417 0.5661147751 -0.356837008947 +1403636679163555584.0000000000 -2.0368278634 8.6171635541 -0.5830490783 0.4487467590 0.5826909440 0.5690237295 -0.367844539744 +1403636679213555456.0000000000 -2.0522761074 8.6119206562 -0.5876681998 0.4415252711 0.5776743051 0.5709653946 -0.38124316425 +1403636679263555584.0000000000 -2.0670243229 8.6055380705 -0.5918207694 0.4340179310 0.5723157426 0.5735423032 -0.39386844588 +1403636679313555456.0000000000 -2.0809386052 8.5984500062 -0.5948580727 0.4259860025 0.5670496473 0.5770408158 -0.404987061614 +1403636679363555584.0000000000 -2.0939398977 8.5911829167 -0.5966528369 0.4192243857 0.5600049732 0.5822747517 -0.414248063351 +1403636679413555456.0000000000 -2.1060557014 8.5840097921 -0.5967805347 0.4122493966 0.5533863977 0.5883715923 -0.421465063001 +1403636679463555584.0000000000 -2.1168541742 8.5770364104 -0.5949821703 0.4056416793 0.5462785092 0.5948131933 -0.428055934953 +1403636679513555456.0000000000 -2.1267116500 8.5703749245 -0.5917946228 0.3994588301 0.5393987216 0.6017353998 -0.432892793841 +1403636679563555584.0000000000 -2.1358039980 8.5642140959 -0.5871898915 0.3940098830 0.5334761219 0.6079748673 -0.436492840896 +1403636679613555456.0000000000 -2.1448862669 8.5583748922 -0.5805383746 0.3888213461 0.5287273394 0.6129070367 -0.440011733682 +1403636679663555584.0000000000 -2.1523979795 8.5532485610 -0.5729287809 0.3837296820 0.5253189462 0.6179051754 -0.441570753233 +1403636679713555456.0000000000 -2.1589031502 8.5487825086 -0.5638876293 0.3802788893 0.5218168963 0.6221993664 -0.442677130167 +1403636679763555584.0000000000 -2.1645910309 8.5452527912 -0.5532771758 0.3793919747 0.5178323908 0.6258307914 -0.442997929053 +1403636679813555456.0000000000 -2.1699172242 8.5420102952 -0.5401771311 0.3804252226 0.5134942157 0.6268546748 -0.445705684424 +1403636679863555584.0000000000 -2.1757797559 8.5388633398 -0.5246868521 0.3827414225 0.5095798557 0.6271539906 -0.44778928778 +1403636679913555456.0000000000 -2.1813332472 8.5359968562 -0.5078764968 0.3877270586 0.5040846737 0.6278031801 -0.448809020426 +1403636679963555584.0000000000 -2.1861887931 8.5327864196 -0.4899163933 0.3903154706 0.5012812544 0.6292715744 -0.447647431584 +1403636680013555456.0000000000 -2.1898420382 8.5295859762 -0.4709292737 0.3956471879 0.4972843052 0.6316838836 -0.444012492796 +1403636680063555584.0000000000 -2.1914470535 8.5260629832 -0.4507950811 0.4010279884 0.4935404561 0.6342084876 -0.439743066943 +1403636680113555456.0000000000 -2.1915342048 8.5215366092 -0.4306292411 0.4075759413 0.4890890010 0.6366736543 -0.435109709189 +1403636680163555584.0000000000 -2.1899764987 8.5154485753 -0.4113712519 0.4108322849 0.4874541460 0.6377546962 -0.432289528739 +1403636680213555456.0000000000 -2.1866604584 8.5071277209 -0.3930116603 0.4107178753 0.4881546958 0.6370015450 -0.432717981493 +1403636680263555584.0000000000 -2.1819838825 8.4970849684 -0.3757491232 0.4123857571 0.4876672615 0.6352119843 -0.434309065537 +1403636680313555456.0000000000 -2.1756922102 8.4859768263 -0.3610628552 0.4155320051 0.4864871716 0.6354912207 -0.432220190343 +1403636680363555584.0000000000 -2.1676719091 8.4734368342 -0.3486978655 0.4186188038 0.4854053611 0.6381191671 -0.426548779349 +1403636680413555456.0000000000 -2.1579152561 8.4590114656 -0.3378257626 0.4203968582 0.4855360440 0.6405662877 -0.42094662689 +1403636680463555584.0000000000 -2.1468203209 8.4423528178 -0.3280180826 0.4212611666 0.4862310460 0.6422537659 -0.416687532209 +1403636680513555456.0000000000 -2.1345442918 8.4232792151 -0.3195756769 0.4219646381 0.4871766178 0.6434868806 -0.412952081641 +1403636680563555584.0000000000 -2.1210902938 8.4015086130 -0.3121092308 0.4204303884 0.4897545364 0.6430646711 -0.412124509503 +1403636680613555456.0000000000 -2.1065734864 8.3771113245 -0.3055282056 0.4184895987 0.4925263046 0.6411655051 -0.413752450322 +1403636680663555584.0000000000 -2.0912363585 8.3506533005 -0.3003540878 0.4176477420 0.4944943843 0.6399839980 -0.414084713377 +1403636680713555456.0000000000 -2.0748953525 8.3218136269 -0.2962178034 0.4145054672 0.4978886656 0.6386557499 -0.415223948588 +1403636680763555584.0000000000 -2.0575364112 8.2906144747 -0.2925623589 0.4079561707 0.5038908266 0.6357277644 -0.418946305834 +1403636680813555456.0000000000 -2.0396455848 8.2577642158 -0.2892844063 0.4012953895 0.5096725206 0.6324079900 -0.423386426706 +1403636680863555584.0000000000 -2.0211713930 8.2237484900 -0.2867392035 0.3930255409 0.5165162961 0.6285492409 -0.428564687935 +1403636680913555456.0000000000 -2.0022544014 8.1891864247 -0.2856615449 0.3835017241 0.5240011406 0.6256367643 -0.432351560085 +1403636680963555584.0000000000 -1.9829767328 8.1549934614 -0.2870045830 0.3747634770 0.5304942630 0.6258496922 -0.43178737367 +1403636681013555456.0000000000 -1.9645134948 8.1214722221 -0.2905319140 0.3692104329 0.5347742916 0.6281161374 -0.427983914657 +1403636681063555584.0000000000 -1.9467058170 8.0885125648 -0.2957226311 0.3644344478 0.5381639843 0.6311905936 -0.423279451154 +1403636681113555456.0000000000 -1.9302818614 8.0562378057 -0.3017663776 0.3622256143 0.5396483664 0.6343854082 -0.418482256244 +1403636681163555584.0000000000 -1.9157685823 8.0242743947 -0.3077209942 0.3634925759 0.5387692316 0.6354013605 -0.416972389211 +1403636681213555456.0000000000 -1.9033447183 7.9924011153 -0.3136243272 0.3697890783 0.5342335495 0.6353363807 -0.417370621361 +1403636681263555584.0000000000 -1.8922987048 7.9600813198 -0.3184351089 0.3773607854 0.5285859357 0.6338847673 -0.419983151993 +1403636681313555456.0000000000 -1.8815465977 7.9270513142 -0.3218683907 0.3822494324 0.5247965193 0.6318974916 -0.423296048671 +1403636681363555584.0000000000 -1.8716831712 7.8934648356 -0.3234506868 0.3864433321 0.5217796840 0.6293917381 -0.426935068255 +1403636681413555456.0000000000 -1.8613173214 7.8594077728 -0.3232598979 0.3883439709 0.5198926426 0.6270769738 -0.430900300935 +1403636681463555584.0000000000 -1.8506213842 7.8251168667 -0.3213265091 0.3884781833 0.5193387454 0.6250242070 -0.434415364954 +1403636681513555456.0000000000 -1.8394128222 7.7907143224 -0.3181831721 0.3884947403 0.5187530378 0.6240130374 -0.436548796491 +1403636681563555584.0000000000 -1.8278670613 7.7563033928 -0.3148054005 0.3881825615 0.5179542436 0.6243778273 -0.43725282074 +1403636681613555456.0000000000 -1.8160117802 7.7223477341 -0.3125297391 0.3894505799 0.5163684106 0.6258904583 -0.435836029529 +1403636681663555584.0000000000 -1.8037433271 7.6882999399 -0.3112474222 0.3899925247 0.5152656702 0.6266125243 -0.435618943679 +1403636681713555456.0000000000 -1.7910055885 7.6541129830 -0.3111906155 0.3906376952 0.5139143019 0.6275630479 -0.435268770185 +1403636681763555584.0000000000 -1.7782709907 7.6197257792 -0.3120140854 0.3911156064 0.5129013087 0.6279821588 -0.435429946369 +1403636681813555456.0000000000 -1.7649926114 7.5848593532 -0.3135362328 0.3912688235 0.5119956356 0.6284234232 -0.435721445552 +1403636681863555584.0000000000 -1.7512056347 7.5495648032 -0.3144670564 0.3909711859 0.5114062477 0.6284050270 -0.436706198423 +1403636681913555456.0000000000 -1.7370191160 7.5141150578 -0.3141129020 0.3908972420 0.5106682961 0.6281898332 -0.437943798964 +1403636681963555584.0000000000 -1.7221995482 7.4784277308 -0.3119331272 0.3896896505 0.5106370118 0.6281291815 -0.439141833335 +1403636682013555456.0000000000 -1.7076475852 7.4424493021 -0.3078110037 0.3884183636 0.5108134467 0.6279977553 -0.440249493878 +1403636682063555584.0000000000 -1.6922677646 7.4063467624 -0.3014886061 0.3867379147 0.5113588661 0.6277991130 -0.441377581125 +1403636682113555456.0000000000 -1.6759081983 7.3705790546 -0.2934158218 0.3859626097 0.5112982843 0.6275881042 -0.442425247808 +1403636682163555584.0000000000 -1.6586599026 7.3347612959 -0.2844611977 0.3846402438 0.5117951211 0.6275182449 -0.443100992076 +1403636682213555456.0000000000 -1.6407683724 7.2991189153 -0.2761039089 0.3822608765 0.5131249897 0.6285971981 -0.442091540151 +1403636682263555584.0000000000 -1.6226267377 7.2636792759 -0.2690718091 0.3788577766 0.5154819999 0.6296123067 -0.440832662315 +1403636682313555456.0000000000 -1.6042607226 7.2286133635 -0.2642563264 0.3753914200 0.5179348603 0.6321022673 -0.437345956884 +1403636682363555584.0000000000 -1.5864483299 7.1936534702 -0.2608018216 0.3714745847 0.5208541395 0.6341706982 -0.434217829991 +1403636682413555456.0000000000 -1.5695255535 7.1588681656 -0.2583792084 0.3695060380 0.5225963221 0.6351781704 -0.432327496107 +1403636682463555584.0000000000 -1.5536437094 7.1243544469 -0.2561688646 0.3707273563 0.5222517966 0.6341071041 -0.433269510578 +1403636682513555456.0000000000 -1.5384011428 7.0901689618 -0.2549382346 0.3746650561 0.5204109095 0.6325885900 -0.434315849158 +1403636682563555584.0000000000 -1.5234403394 7.0559307168 -0.2546969836 0.3787535453 0.5184073617 0.6310013510 -0.435473138347 +1403636682613555456.0000000000 -1.5084069425 7.0214580104 -0.2556688543 0.3823136734 0.5164873621 0.6296798282 -0.436555121197 +1403636682663555584.0000000000 -1.4932685282 6.9868803357 -0.2574758365 0.3854983157 0.5152747764 0.6280196906 -0.437577674976 +1403636682713555456.0000000000 -1.4777349930 6.9520725305 -0.2588366595 0.3862715237 0.5154366396 0.6261113909 -0.439435896109 +1403636682763555584.0000000000 -1.4620920575 6.9174251993 -0.2589357793 0.3871896631 0.5156664520 0.6240365081 -0.441305689516 +1403636682813555456.0000000000 -1.4459066124 6.8830812917 -0.2575648990 0.3887213672 0.5156804007 0.6221227806 -0.442642823176 +1403636682863555584.0000000000 -1.4293731473 6.8489553636 -0.2551547918 0.3910880374 0.5145342259 0.6219034065 -0.442199989184 +1403636682913555456.0000000000 -1.4121647692 6.8149342411 -0.2515453384 0.3934909099 0.5140083605 0.6222715840 -0.440157227497 +1403636682963555584.0000000000 -1.3939397340 6.7804595431 -0.2462001019 0.3954143516 0.5131968731 0.6229854378 -0.438366974357 +1403636683013555456.0000000000 -1.3746772654 6.7457849452 -0.2400528675 0.3972988119 0.5120124456 0.6243514955 -0.436098749936 +1403636683063555584.0000000000 -1.3552009752 6.7103629578 -0.2338382485 0.3982028605 0.5115904280 0.6237528208 -0.436625851712 +1403636683113555456.0000000000 -1.3347631681 6.6743060585 -0.2292864459 0.3971868899 0.5120848515 0.6242134896 -0.436313188774 +1403636683163555584.0000000000 -1.3137376626 6.6377059890 -0.2263713416 0.3954485643 0.5130228450 0.6238997857 -0.437237979735 +1403636683213555456.0000000000 -1.2919593156 6.6005626122 -0.2250625684 0.3928985323 0.5143373685 0.6240877064 -0.437724056287 +1403636683263555584.0000000000 -1.2697021426 6.5630909240 -0.2249258558 0.3913835542 0.5149629074 0.6241266861 -0.438289855213 +1403636683313555456.0000000000 -1.2467812352 6.5251448230 -0.2260035396 0.3895519448 0.5154047972 0.6241648332 -0.439346603863 +1403636683363555584.0000000000 -1.2235257108 6.4871560269 -0.2282128934 0.3879779462 0.5157524035 0.6242556065 -0.440201668952 +1403636683413555456.0000000000 -1.1999062247 6.4494169809 -0.2316589285 0.3868871618 0.5157201435 0.6245584029 -0.440769621163 +1403636683463555584.0000000000 -1.1761258642 6.4116069410 -0.2361539176 0.3851543983 0.5159147260 0.6248530357 -0.441640995281 +1403636683513555456.0000000000 -1.1521902307 6.3743032599 -0.2417387220 0.3850125352 0.5153895385 0.6253266839 -0.441707493314 +1403636683563555584.0000000000 -1.1280755960 6.3371469050 -0.2479972072 0.3843749297 0.5152322590 0.6253923507 -0.44235284609 +1403636683613555456.0000000000 -1.1034627258 6.3004561103 -0.2555213686 0.3832460763 0.5155146083 0.6263473522 -0.441651591125 +1403636683663555584.0000000000 -1.0785724440 6.2641475406 -0.2639040642 0.3812064325 0.5162738218 0.6273975082 -0.441038959083 +1403636683713555456.0000000000 -1.0535013768 6.2282602614 -0.2723424674 0.3792604694 0.5170597959 0.6287543632 -0.439862040371 +1403636683763555584.0000000000 -1.0284495983 6.1925297151 -0.2794209501 0.3765667005 0.5184953568 0.6294893691 -0.4394351138 +1403636683813555456.0000000000 -1.0033769235 6.1573120465 -0.2851032177 0.3747222158 0.5190925843 0.6314371400 -0.437508043412 +1403636683863555584.0000000000 -0.9780488648 6.1222568694 -0.2886246262 0.3712729355 0.5205536261 0.6319493500 -0.437973000007 +1403636683913555456.0000000000 -0.9538593025 6.0876845267 -0.2913929992 0.3719707980 0.5192675440 0.6334622827 -0.436720138739 +1403636683963555584.0000000000 -0.9306017024 6.0529953763 -0.2914949678 0.3711798269 0.5191856688 0.6333278436 -0.437684383952 +1403636684013555456.0000000000 -0.9080895244 6.0186485018 -0.2891212384 0.3715127299 0.5181965390 0.6327256596 -0.439441552601 +1403636684063555584.0000000000 -0.8867669458 5.9845248532 -0.2844457432 0.3723245166 0.5167777978 0.6323278218 -0.440995110899 +1403636684113555456.0000000000 -0.8644527246 5.9508562238 -0.2779619075 0.3730052603 0.5153486196 0.6322801657 -0.442159098146 +1403636684163555584.0000000000 -0.8422622827 5.9173008033 -0.2704336647 0.3730277831 0.5142529442 0.6324770422 -0.443133132896 +1403636684213555456.0000000000 -0.8200323092 5.8839141164 -0.2608164104 0.3731055798 0.5132440776 0.6321919877 -0.444641466683 +1403636684263555584.0000000000 -0.7980004133 5.8506041519 -0.2498382849 0.3729434168 0.5123139413 0.6317683750 -0.446448601501 +1403636684313555456.0000000000 -0.7759393568 5.8177491160 -0.2390442926 0.3741437933 0.5106289923 0.6315527134 -0.447678036402 +1403636684363555584.0000000000 -0.7535268672 5.7854121009 -0.2296304536 0.3747283416 0.5094202732 0.6311061642 -0.449193349034 +1403636684413555456.0000000000 -0.7309631890 5.7536175398 -0.2220482960 0.3750861691 0.5084366198 0.6309489205 -0.450228863111 +1403636684463555584.0000000000 -0.7081760380 5.7222485585 -0.2162809543 0.3743309567 0.5084489039 0.6304819471 -0.451495915121 +1403636684513555456.0000000000 -0.6850946452 5.6910823629 -0.2118716614 0.3723794651 0.5090625474 0.6294522173 -0.45384883272 +1403636684563555584.0000000000 -0.6620649587 5.6607920081 -0.2088938155 0.3718874484 0.5090941243 0.6284037278 -0.455666164228 +1403636684613555456.0000000000 -0.6385024080 5.6310383280 -0.2074979233 0.3706708598 0.5095768925 0.6275241975 -0.457326891699 +1403636684663555584.0000000000 -0.6146670463 5.6020853385 -0.2077303627 0.3703614940 0.5093028098 0.6272730745 -0.45822647426 +1403636684713555456.0000000000 -0.5905734237 5.5739065140 -0.2093614768 0.3704102921 0.5090329145 0.6267691955 -0.459175438227 +1403636684763555584.0000000000 -0.5659141390 5.5466781337 -0.2127269423 0.3709391242 0.5084790965 0.6268324770 -0.459275756267 +1403636684813555456.0000000000 -0.5407239528 5.5202705970 -0.2176365493 0.3710761742 0.5083641372 0.6266358498 -0.459560538688 +1403636684863555584.0000000000 -0.5148200495 5.4949114134 -0.2245061248 0.3714695924 0.5079538176 0.6273927368 -0.458662855354 +1403636684913555456.0000000000 -0.4884852606 5.4704824579 -0.2322345888 0.3741488434 0.5062006904 0.6283108106 -0.457164116335 +1403636684963555584.0000000000 -0.4614716496 5.4467604804 -0.2401005234 0.3772158475 0.5041307883 0.6311140119 -0.453051273857 +1403636685013555456.0000000000 -0.4337393855 5.4234470489 -0.2468535409 0.3792891240 0.5031873761 0.6327444451 -0.450085205418 +1403636685063555584.0000000000 -0.4062388325 5.4000178207 -0.2518426283 0.3805691232 0.5027917916 0.6338334967 -0.447909204289 +1403636685113555456.0000000000 -0.3781959822 5.3762121903 -0.2540879870 0.3805198026 0.5034582253 0.6346859888 -0.445991245245 +1403636685163555584.0000000000 -0.3494897613 5.3524410515 -0.2545812962 0.3789084000 0.5054365381 0.6349956664 -0.444682846537 +1403636685213555456.0000000000 -0.3199835006 5.3291472043 -0.2540157137 0.3797046438 0.5059851158 0.6364145379 -0.441338851658 +1403636685263555584.0000000000 -0.2902366187 5.3056645345 -0.2523179234 0.3807781372 0.5064379821 0.6377757646 -0.437916264373 +1403636685313555456.0000000000 -0.2609498330 5.2816774200 -0.2486064340 0.3819818021 0.5068597081 0.6385847269 -0.435192699552 +1403636685363555584.0000000000 -0.2316084770 5.2570772729 -0.2435745066 0.3830326902 0.5071917116 0.6387788665 -0.433594379185 +1403636685413555456.0000000000 -0.2025681857 5.2319606920 -0.2384998950 0.3834331870 0.5081720193 0.6378724574 -0.433426946565 +1403636685463555584.0000000000 -0.1733442814 5.2062910852 -0.2345987346 0.3824494638 0.5098588606 0.6368259437 -0.433853739502 +1403636685513555456.0000000000 -0.1443248375 5.1802484665 -0.2321393162 0.3817531550 0.5112573832 0.6355472590 -0.434695408708 +1403636685563555584.0000000000 -0.1151859389 5.1540994378 -0.2315533976 0.3808710098 0.5126196340 0.6349876400 -0.434682736891 +1403636685613555456.0000000000 -0.0861546711 5.1274845068 -0.2321706119 0.3799920764 0.5138824053 0.6335845604 -0.436006307572 +1403636685663555584.0000000000 -0.0572206585 5.1009725763 -0.2344835794 0.3811823782 0.5136596472 0.6332936280 -0.435652317904 +1403636685713555456.0000000000 -0.0281611169 5.0743211802 -0.2383367434 0.3824924236 0.5129632467 0.6331222637 -0.43557370522 +1403636685763555584.0000000000 0.0007815645 5.0472844815 -0.2435206242 0.3834086283 0.5123542590 0.6332257936 -0.435334390243 +1403636685813555456.0000000000 0.0294616413 5.0200415620 -0.2497551414 0.3858239184 0.5107774768 0.6335377773 -0.434598847138 +1403636685863555584.0000000000 0.0583224696 4.9925515658 -0.2570717693 0.3879105534 0.5093609933 0.6337199118 -0.43413805918 +1403636685913555456.0000000000 0.0874473034 4.9641715773 -0.2651390077 0.3870059264 0.5099884116 0.6334433451 -0.434612196628 +1403636685963555584.0000000000 0.1169832412 4.9351884848 -0.2738550005 0.3842949479 0.5116280489 0.6328296934 -0.435982467333 +1403636686013555456.0000000000 0.1468151775 4.9060391733 -0.2822620735 0.3813708515 0.5136165486 0.6325217019 -0.43665846069 +1403636686063555584.0000000000 0.1769898246 4.8766162919 -0.2891591583 0.3776721506 0.5158309075 0.6326068517 -0.437139328619 +1403636686113555456.0000000000 0.2065941531 4.8472171100 -0.2940515181 0.3751554157 0.5175069430 0.6324310476 -0.437579647697 +1403636686163555584.0000000000 0.2352008455 4.8180016715 -0.2964852928 0.3750409879 0.5177234700 0.6319383714 -0.43813304006 +1403636686213555456.0000000000 0.2638533856 4.7890713729 -0.2976553404 0.3739901562 0.5186975706 0.6318635903 -0.437986982116 +1403636686263555584.0000000000 0.2921594092 4.7603492262 -0.2974484681 0.3725553949 0.5198586845 0.6316855409 -0.438089948785 +1403636686313555456.0000000000 0.3199978939 4.7319332972 -0.2954193013 0.3714959700 0.5208539107 0.6317263681 -0.437748493802 +1403636686363555584.0000000000 0.3472938398 4.7038343520 -0.2916338076 0.3703954309 0.5215907783 0.6317580931 -0.437757919964 +1403636686413555456.0000000000 0.3739146220 4.6763056806 -0.2873536734 0.3701711298 0.5219587647 0.6322394086 -0.436813132625 +1403636686463555584.0000000000 0.4002154987 4.6491645564 -0.2840224561 0.3689518602 0.5227690703 0.6327038538 -0.436202770881 +1403636686513555456.0000000000 0.4260633472 4.6225744390 -0.2822507655 0.3675139932 0.5236124425 0.6330195810 -0.435946883106 +1403636686563555584.0000000000 0.4509585347 4.5964187207 -0.2817875601 0.3678837767 0.5233792044 0.6332983310 -0.435509999028 +1403636686613555456.0000000000 0.4754168606 4.5707330962 -0.2833864969 0.3682437460 0.5225414328 0.6343837347 -0.434631190387 +1403636686663555584.0000000000 0.4992214492 4.5450339032 -0.2864220255 0.3686037065 0.5222081112 0.6346122212 -0.434393053442 +1403636686713555456.0000000000 0.5222865941 4.5192207542 -0.2903815341 0.3686203000 0.5219810524 0.6345107843 -0.434799861898 +1403636686763555584.0000000000 0.5445768209 4.4934806925 -0.2944509796 0.3690932811 0.5212607854 0.6338704299 -0.436194476723 +1403636686813555456.0000000000 0.5659836552 4.4680401337 -0.2976636865 0.3701211432 0.5205062430 0.6331440997 -0.437278103062 +1403636686863555584.0000000000 0.5869725016 4.4427665894 -0.2994394599 0.3700104768 0.5200987361 0.6324034535 -0.438925305456 +1403636686913555456.0000000000 0.6075341982 4.4179032557 -0.2993100906 0.3699896070 0.5198219486 0.6315593957 -0.440483327897 +1403636686963555584.0000000000 0.6278584379 4.3934716920 -0.2974534411 0.3700178239 0.5195448234 0.6310267607 -0.441548653887 +1403636687013555456.0000000000 0.6475764105 4.3693631807 -0.2940803345 0.3701181037 0.5190007724 0.6305868021 -0.442731377456 +1403636687063555584.0000000000 0.6668375491 4.3457174664 -0.2888518829 0.3696696870 0.5193942298 0.6299543044 -0.443544282923 +1403636687113555456.0000000000 0.6860469713 4.3225876259 -0.2822276547 0.3694595751 0.5192354020 0.6300398203 -0.443783781191 +1403636687163555584.0000000000 0.7051663041 4.2997923230 -0.2756075728 0.3694956521 0.5188067172 0.6301612384 -0.444082612668 +1403636687213555456.0000000000 0.7238763094 4.2775000545 -0.2695053770 0.3705182782 0.5181072626 0.6296069856 -0.444832680487 +1403636687263555584.0000000000 0.7425760792 4.2557840046 -0.2649645122 0.3708681415 0.5175481969 0.6297733889 -0.444956361982 +1403636687313555456.0000000000 0.7611450031 4.2344676501 -0.2618799502 0.3712583084 0.5169430814 0.6296423338 -0.445519528839 +1403636687363555584.0000000000 0.7795489920 4.2138367829 -0.2604569990 0.3728398003 0.5157699320 0.6293494239 -0.445972155125 +1403636687413555456.0000000000 0.7978777046 4.1934571062 -0.2604127521 0.3739140490 0.5146293087 0.6293564510 -0.44638034919 +1403636687463555584.0000000000 0.8161104603 4.1731759306 -0.2616554412 0.3745211367 0.5139973758 0.6292282756 -0.446780027577 +1403636687513555456.0000000000 0.8343078222 4.1530508422 -0.2645089101 0.3747488527 0.5137585257 0.6289330647 -0.447279191181 +1403636687563555584.0000000000 0.8528107294 4.1331198963 -0.2692761676 0.3735970117 0.5141819876 0.6286572314 -0.44814310432 +1403636687613555456.0000000000 0.8713724083 4.1134126821 -0.2754660096 0.3734661656 0.5139367515 0.6279182081 -0.449567306064 +1403636687663555584.0000000000 0.8903380323 4.0942771347 -0.2835606718 0.3726943145 0.5140079136 0.6277461526 -0.450366051823 +1403636687713555456.0000000000 0.9094360502 4.0756577154 -0.2930256493 0.3725434588 0.5137706340 0.6267114330 -0.452198945921 +1403636687763555584.0000000000 0.9287913759 4.0574189112 -0.3045383262 0.3716963337 0.5139848513 0.6269011338 -0.452389629144 +1403636687813555456.0000000000 0.9480858930 4.0398316630 -0.3174589985 0.3719784514 0.5135900556 0.6274123825 -0.451897099722 +1403636687863555584.0000000000 0.9674048793 4.0227065150 -0.3315117129 0.3716598826 0.5136295229 0.6276718878 -0.451753966274 +1403636687913555456.0000000000 0.9868370211 4.0062636886 -0.3471206128 0.3722338186 0.5131082781 0.6284447073 -0.45079832427 +1403636687963555584.0000000000 1.0063574068 3.9903255977 -0.3639356746 0.3736563952 0.5119203701 0.6297342301 -0.449169491799 +1403636688013555456.0000000000 1.0257994046 3.9745034599 -0.3814515293 0.3750586459 0.5109476394 0.6303600915 -0.448229491437 +1403636688063555584.0000000000 1.0453891520 3.9590280118 -0.3995510721 0.3773099748 0.5090532877 0.6321368601 -0.44598758196 +1403636688113555456.0000000000 1.0654617242 3.9437038430 -0.4164908820 0.3790255559 0.5079083831 0.6332271817 -0.444288238308 +1403636688163555584.0000000000 1.0859429586 3.9281338071 -0.4316217081 0.3792669415 0.5076192593 0.6338618279 -0.443506998576 +1403636688213555456.0000000000 1.1062527125 3.9122108640 -0.4448527180 0.3790978899 0.5077281707 0.6339458569 -0.44340674893 +1403636688263555584.0000000000 1.1268716302 3.8959053988 -0.4562919827 0.3786156418 0.5079280551 0.6331802110 -0.444682029198 +1403636688313555456.0000000000 1.1476107548 3.8792129244 -0.4663416478 0.3763431068 0.5094084429 0.6326508995 -0.445669993993 +1403636688363555584.0000000000 1.1685916840 3.8625605765 -0.4756247783 0.3745930031 0.5105144678 0.6319392288 -0.446886866318 +1403636688413555456.0000000000 1.1896517992 3.8460671014 -0.4858090561 0.3732707410 0.5112748573 0.6324288723 -0.44643106489 +1403636688463555584.0000000000 1.2105312041 3.8300442908 -0.4968837146 0.3747206876 0.5104792344 0.6329883606 -0.445332564304 +1403636688513555456.0000000000 1.2317126870 3.8140117505 -0.5091952923 0.3759316564 0.5094403714 0.6344049768 -0.443481931009 +1403636688563555584.0000000000 1.2527863608 3.7980938249 -0.5225824941 0.3786794559 0.5076160735 0.6363285680 -0.440469914037 +1403636688613555456.0000000000 1.2739698675 3.7818643359 -0.5372711466 0.3812266557 0.5055605514 0.6385987829 -0.437340096892 +1403636688663555584.0000000000 1.2950114788 3.7648122384 -0.5525300435 0.3828772290 0.5039587011 0.6399800517 -0.435724900094 +1403636688713555456.0000000000 1.3161120478 3.7470488253 -0.5685379605 0.3836172826 0.5029000358 0.6408007050 -0.435090554879 +1403636688763555584.0000000000 1.3375685108 3.7285971117 -0.5851564364 0.3835920860 0.5020076936 0.6420399055 -0.434315722547 +1403636688813555456.0000000000 1.3589611367 3.7090113986 -0.6005248475 0.3818149670 0.5023027189 0.6419788462 -0.43562882204 +1403636688863555584.0000000000 1.3803418485 3.6886017075 -0.6145207741 0.3802346715 0.5012081243 0.6438217477 -0.435552026625 +1403636688913555456.0000000000 1.4019749447 3.6669751958 -0.6263961827 0.3766011912 0.5004889519 0.6453838390 -0.437220827702 +1403636688963555584.0000000000 1.4234516699 3.6446539428 -0.6363600093 0.3725047025 0.5001402843 0.6469972600 -0.438741938028 +1403636689013555456.0000000000 1.4445880474 3.6217110178 -0.6442729724 0.3686400489 0.4996987821 0.6484031278 -0.440430500161 +1403636689063555584.0000000000 1.4654857166 3.5983118660 -0.6497444566 0.3645347989 0.4992432790 0.6496676372 -0.442495751263 +1403636689113555456.0000000000 1.4856228455 3.5744366635 -0.6539279368 0.3601696784 0.4990053938 0.6508740419 -0.444560908379 +1403636689163555584.0000000000 1.5052284905 3.5503623765 -0.6562789595 0.3560217114 0.4987731031 0.6523961783 -0.445929544966 +1403636689213555456.0000000000 1.5244571222 3.5263780405 -0.6567816405 0.3532348368 0.4977398503 0.6543428374 -0.446447804978 +1403636689263555584.0000000000 1.5430858975 3.5025119158 -0.6553743848 0.3505213735 0.4970347949 0.6555157125 -0.44764978509 +1403636689313555456.0000000000 1.5605173543 3.4787351030 -0.6520303548 0.3481145686 0.4963131098 0.6571261868 -0.447967318933 +1403636689363555584.0000000000 1.5759262058 3.4547528384 -0.6465969672 0.3470571034 0.4951075304 0.6579098554 -0.448970514075 +1403636689413555456.0000000000 1.5901217889 3.4308804718 -0.6392563511 0.3464722353 0.4936049470 0.6590012480 -0.449475807654 +1403636689463555584.0000000000 1.6036621659 3.4070678966 -0.6297648505 0.3455642556 0.4929040624 0.6591984657 -0.450653207373 +1403636689513555456.0000000000 1.6166276748 3.3834852085 -0.6182616557 0.3444206026 0.4925406477 0.6600414425 -0.450692193283 +1403636689563555584.0000000000 1.6294727133 3.3601917083 -0.6055305739 0.3423716601 0.4929887769 0.6608816681 -0.450532055376 +1403636689613555456.0000000000 1.6424174110 3.3374621018 -0.5913153111 0.3400923620 0.4940172250 0.6618518470 -0.449706903817 +1403636689663555584.0000000000 1.6544924045 3.3148320397 -0.5769855920 0.3364988088 0.4961978946 0.6622708967 -0.449392323509 +1403636689713555456.0000000000 1.6635062847 3.2918392252 -0.5645889532 0.3319764958 0.4992961599 0.6624918639 -0.448998308681 +1403636689763555584.0000000000 1.6723047964 3.2696244877 -0.5530446297 0.3263221368 0.5036603072 0.6622288117 -0.44865706166 +1403636689813555456.0000000000 1.6789530882 3.2478944515 -0.5426428947 0.3225112544 0.5066522903 0.6614497548 -0.449192797534 +1403636689863555584.0000000000 1.6834994314 3.2267831078 -0.5329364998 0.3206364034 0.5086283217 0.6594658378 -0.451214290491 +1403636689913555456.0000000000 1.6861475839 3.2063784716 -0.5237141209 0.3175154472 0.5113954662 0.6558134853 -0.455595533853 +1403636689963555584.0000000000 1.6867809657 3.1874285496 -0.5156534700 0.3168878178 0.5128800471 0.6527895184 -0.458695991734 +1403636690013555456.0000000000 1.6857620919 3.1702718646 -0.5091470316 0.3179478698 0.5130173688 0.6515198728 -0.459613083797 +1403636690063555584.0000000000 1.6832800686 3.1549111780 -0.5040128696 0.3197705237 0.5125858772 0.6514831995 -0.458881435161 +1403636690113555456.0000000000 1.6794694303 3.1411853465 -0.5006610654 0.3225722411 0.5112400340 0.6539055487 -0.45495967989 +1403636690163555584.0000000000 1.6739869775 3.1287007934 -0.4977294655 0.3267181092 0.5091525755 0.6563053362 -0.450868315292 +1403636690213555456.0000000000 1.6669855527 3.1169056225 -0.4936379979 0.3299751751 0.5074874770 0.6582839045 -0.447476418932 +1403636690263555584.0000000000 1.6581521747 3.1053120386 -0.4870585345 0.3319309028 0.5065948590 0.6588211873 -0.446248997525 +1403636690313555456.0000000000 1.6477125032 3.0941609059 -0.4791385911 0.3342564153 0.5052406532 0.6595522619 -0.444966678503 +1403636690363555584.0000000000 1.6356560084 3.0832753261 -0.4696137028 0.3360495792 0.5045444708 0.6597681935 -0.44408500102 +1403636690413555456.0000000000 1.6226130190 3.0725497271 -0.4593183186 0.3369449247 0.5041707899 0.6598155817 -0.443760442588 +1403636690463555584.0000000000 1.6081973342 3.0618290820 -0.4487361439 0.3369267342 0.5043259033 0.6587552111 -0.44517112542 +1403636690513555456.0000000000 1.5927408814 3.0510881387 -0.4386273598 0.3353640764 0.5055587944 0.6563560143 -0.448484140321 +1403636690563555584.0000000000 1.5761800104 3.0408253030 -0.4298764067 0.3339534684 0.5066312747 0.6543113263 -0.45130535194 +1403636690613555456.0000000000 1.5586505776 3.0308480109 -0.4223107191 0.3297144543 0.5097190823 0.6516692031 -0.454754972957 +1403636690663555584.0000000000 1.5398475685 3.0217621148 -0.4159908614 0.3269575851 0.5117348538 0.6487527533 -0.458634976952 +1403636690713555456.0000000000 1.5198847353 3.0134512054 -0.4114611021 0.3228887370 0.5144522083 0.6437043149 -0.465538982169 +1403636690763555584.0000000000 1.4991315107 3.0065283628 -0.4108838719 0.3179588405 0.5178822216 0.6380359663 -0.472874492837 +1403636690813555456.0000000000 1.4775495138 3.0015777091 -0.4145148776 0.3147260969 0.5199528558 0.6332799243 -0.47911694714 +1403636690863555584.0000000000 1.4549955187 2.9991248718 -0.4214993567 0.3139891619 0.5202696965 0.6285939134 -0.485386383318 +1403636690913555456.0000000000 1.4317669929 2.9993793868 -0.4302282184 0.3149798769 0.5193520296 0.6238097199 -0.491856259347 +1403636690963555584.0000000000 1.4078781302 3.0026604598 -0.4383703382 0.3167556692 0.5177748469 0.6180363178 -0.499606008601 +1403636691013555456.0000000000 1.3832170823 3.0094513427 -0.4449660312 0.3201817970 0.5149268269 0.6123231464 -0.50734046188 +1403636691063555584.0000000000 1.3591596632 3.0204602155 -0.4495734191 0.3241853134 0.5115197185 0.6078680542 -0.513563909144 +1403636691113555456.0000000000 1.3364396554 3.0356361982 -0.4532284917 0.3277410810 0.5081834666 0.6060643522 -0.516741085109 +1403636691163555584.0000000000 1.3151777265 3.0552783601 -0.4541423955 0.3343883028 0.5030203781 0.6049062754 -0.518886654336 +1403636691213555456.0000000000 1.2953992085 3.0790701144 -0.4543118633 0.3430180368 0.4965658827 0.6066523213 -0.51743010309 +1403636691263555584.0000000000 1.2783248537 3.1066838702 -0.4530017437 0.3531069714 0.4891883520 0.6101099524 -0.51359134438 +1403636691313555456.0000000000 1.2649405888 3.1374114682 -0.4504492253 0.3609641175 0.4832411812 0.6146091833 -0.508368388528 +1403636691363555584.0000000000 1.2540989643 3.1700467359 -0.4460675477 0.3656728612 0.4793071267 0.6195227203 -0.502732171127 +1403636691413555456.0000000000 1.2459111814 3.2037960783 -0.4401683035 0.3640605472 0.4792957641 0.6256058958 -0.496339351247 +1403636691463555584.0000000000 1.2392166453 3.2384942316 -0.4318704322 0.3603781296 0.4808908343 0.6318581624 -0.489516978016 +1403636691513555456.0000000000 1.2339646200 3.2737581087 -0.4207328347 0.3551207515 0.4833244333 0.6365731584 -0.48483126754 +1403636691563555584.0000000000 1.2293458029 3.3096460180 -0.4066371372 0.3519318685 0.4843295630 0.6397428261 -0.481972977217 +1403636691613555456.0000000000 1.2264294620 3.3476641146 -0.3941064490 0.3498888450 0.4844527299 0.6434646588 -0.478368666959 +1403636691663555584.0000000000 1.2225280443 3.3852846031 -0.3773813302 0.3516194558 0.4825536744 0.6475489924 -0.473482852918 +1403636691713555456.0000000000 1.2191774519 3.4233237793 -0.3609737491 0.3537766187 0.4803696647 0.6520957306 -0.467822880343 +1403636691763555584.0000000000 1.2163239835 3.4609068432 -0.3450738577 0.3566449079 0.4777695547 0.6547887335 -0.464534580748 +1403636691813555456.0000000000 1.2141845789 3.4978641725 -0.3305308882 0.3565804126 0.4774279239 0.6560087732 -0.463212128836 +1403636691863555584.0000000000 1.2128757483 3.5342549473 -0.3176511919 0.3550410230 0.4782006650 0.6561225390 -0.463436306117 +1403636691913555456.0000000000 1.2120924319 3.5704448251 -0.3063196310 0.3534842591 0.4793193828 0.6549397771 -0.465140512365 +1403636691963555584.0000000000 1.2112992802 3.6065402807 -0.2954877610 0.3536818991 0.4790376885 0.6518211333 -0.469639454746 +1403636692013555456.0000000000 1.2109486641 3.6428004371 -0.2856858016 0.3545745556 0.4785362855 0.6488219759 -0.473613715599 +1403636692063555584.0000000000 1.2114286461 3.6792044751 -0.2766158741 0.3535142298 0.4793913326 0.6476579403 -0.475132436149 +1403636692113555456.0000000000 1.2127098601 3.7165473457 -0.2676233842 0.3543368795 0.4791513349 0.6485347714 -0.473563115492 +1403636692163555584.0000000000 1.2136564699 3.7538542949 -0.2573027502 0.3579706184 0.4771069905 0.6505059910 -0.470178595484 +1403636692213555456.0000000000 1.2152367559 3.7906760427 -0.2451216169 0.3591915702 0.4764919160 0.6522403211 -0.467460622221 +1403636692263555584.0000000000 1.2177695250 3.8270556442 -0.2314657972 0.3593611013 0.4768016710 0.6532533984 -0.465596137214 +1403636692313555456.0000000000 1.2214490039 3.8628156394 -0.2145809072 0.3584320701 0.4778287276 0.6532319817 -0.465289303813 +1403636692363555584.0000000000 1.2266720535 3.8983959439 -0.1957440596 0.3562975776 0.4796789390 0.6524520020 -0.466118586546 +1403636692413555456.0000000000 1.2318483907 3.9338275857 -0.1759578604 0.3558596062 0.4805941742 0.6529929174 -0.464750933554 +1403636692463555584.0000000000 1.2367876183 3.9687952763 -0.1543779716 0.3572422899 0.4800806488 0.6542290524 -0.462476879428 +1403636692513555456.0000000000 1.2421154100 4.0034512368 -0.1316015605 0.3604041397 0.4786414014 0.6556391358 -0.459509073355 +1403636692563555584.0000000000 1.2478665471 4.0370230190 -0.1069727537 0.3610132214 0.4787962144 0.6554721591 -0.459107708104 +1403636692613555456.0000000000 1.2534928247 4.0694321403 -0.0800445558 0.3601289851 0.4798255975 0.6550136302 -0.459381817624 +1403636692663555584.0000000000 1.2599270454 4.1016880774 -0.0521052083 0.3598690472 0.4808493328 0.6543573264 -0.459450408062 +1403636692713555456.0000000000 1.2666129057 4.1340213271 -0.0252144364 0.3606370710 0.4809890165 0.6561505696 -0.456132545597 +1403636692763555584.0000000000 1.2735761395 4.1664754494 -0.0001338090 0.3640293546 0.4791328746 0.6602923877 -0.449364306699 +1403636692813555456.0000000000 1.2806595288 4.1980987589 0.0233416754 0.3681627834 0.4767877792 0.6651032578 -0.441324410156 +1403636692863555584.0000000000 1.2876279619 4.2279514217 0.0459995191 0.3712657245 0.4747849964 0.6684669756 -0.435766992145 +1403636692913555456.0000000000 1.2947243490 4.2559097074 0.0677217667 0.3733564182 0.4733608671 0.6711374675 -0.431403493535 +1403636692963555584.0000000000 1.3016676071 4.2810399563 0.0890180102 0.3725436728 0.4739557114 0.6717452683 -0.430506085946 +1403636693013555456.0000000000 1.3084110661 4.3035685283 0.1098916952 0.3693770514 0.4761196533 0.6711210067 -0.431818554446 +1403636693063555584.0000000000 1.3148162916 4.3242147701 0.1299077615 0.3673687083 0.4775910143 0.6692137043 -0.434856382331 +1403636693113555456.0000000000 1.3208472829 4.3430159564 0.1486801493 0.3660367513 0.4782645547 0.6670859662 -0.438493359137 +1403636693163555584.0000000000 1.3269019026 4.3601838613 0.1655619466 0.3639790975 0.4793544426 0.6652251305 -0.441830352808 +1403636693213555456.0000000000 1.3328702808 4.3762548392 0.1801216111 0.3614932104 0.4806980404 0.6653916940 -0.442160543598 +1403636693263555584.0000000000 1.3387082082 4.3911295471 0.1930676482 0.3574731600 0.4831055863 0.6660185232 -0.441861131071 +1403636693313555456.0000000000 1.3443665320 4.4048912453 0.2044998172 0.3523309144 0.4862644251 0.6667980412 -0.441350436531 +1403636693363555584.0000000000 1.3495588662 4.4177702840 0.2146686016 0.3477902982 0.4889380123 0.6676169182 -0.440759774882 +1403636693413555456.0000000000 1.3539088236 4.4297531096 0.2239068239 0.3435127720 0.4913524384 0.6683222249 -0.440360262052 +1403636693463555584.0000000000 1.3572244883 4.4410576788 0.2321159235 0.3394067067 0.4934408399 0.6698245100 -0.438924083264 +1403636693513555456.0000000000 1.3593233519 4.4519523736 0.2393373741 0.3344088863 0.4968537511 0.6715056363 -0.436333848373 +1403636693563555584.0000000000 1.3598401630 4.4623545115 0.2454605106 0.3300331015 0.4993836974 0.6740378406 -0.432859173587 +1403636693613555456.0000000000 1.3584095470 4.4720022272 0.2510481848 0.3272582812 0.5006786212 0.6762422351 -0.43002252857 +1403636693663555584.0000000000 1.3546158841 4.4811647416 0.2562284150 0.3255538881 0.5015662920 0.6774384536 -0.428395917496 +1403636693713555456.0000000000 1.3483167907 4.4892553472 0.2614207807 0.3257618379 0.5011145138 0.6769127074 -0.429595921287 +1403636693763555584.0000000000 1.3395640374 4.4966373151 0.2664201554 0.3288119763 0.4986197431 0.6748832912 -0.433351565436 +1403636693813555456.0000000000 1.3290166447 4.5035675110 0.2705721448 0.3323233430 0.4961493656 0.6728638854 -0.436636226666 +1403636693863555584.0000000000 1.3166470203 4.5099653381 0.2743633515 0.3360448703 0.4934352365 0.6698645329 -0.441448774024 +1403636693913555456.0000000000 1.3030314524 4.5155826397 0.2777691240 0.3395445271 0.4908304175 0.6656580751 -0.447989221452 +1403636693963555584.0000000000 1.2882755706 4.5209892626 0.2800207879 0.3443042908 0.4874231983 0.6625790911 -0.452616978446 +1403636694013555456.0000000000 1.2730394282 4.5256822863 0.2818209220 0.3476033110 0.4846900894 0.6586200027 -0.458766986063 +1403636694063555584.0000000000 1.2578102468 4.5304664672 0.2824028736 0.3509151383 0.4822140735 0.6559219539 -0.46270351576 +1403636694113555456.0000000000 1.2433203182 4.5353526517 0.2823353898 0.3520770538 0.4809471043 0.6547136581 -0.464845842092 +1403636694163555584.0000000000 1.2291570027 4.5402748149 0.2831717484 0.3536268905 0.4796166305 0.6534725953 -0.466786329455 +1403636694213555456.0000000000 1.2158819750 4.5454319833 0.2856973818 0.3544052878 0.4789137911 0.6527200860 -0.467968975453 +1403636694263555584.0000000000 1.2032128793 4.5507580174 0.2886738908 0.3545574689 0.4784216439 0.6534553168 -0.46733059063 +1403636694313555456.0000000000 1.1908952312 4.5557423432 0.2937092246 0.3534194356 0.4787955086 0.6545411602 -0.466289001712 +1403636694363555584.0000000000 1.1794311253 4.5608139051 0.3000131203 0.3511338469 0.4804791540 0.6552485124 -0.465289362883 +1403636694413555456.0000000000 1.1682797448 4.5659351969 0.3061866012 0.3494368578 0.4812551972 0.6570986222 -0.463150859128 +1403636694463555584.0000000000 1.1571774684 4.5711643974 0.3120169176 0.3484286006 0.4822317399 0.6580713571 -0.461510723916 +1403636694513555456.0000000000 1.1459030325 4.5762987351 0.3169402758 0.3484148226 0.4824461357 0.6591314823 -0.459780954953 +1403636694563555584.0000000000 1.1345721769 4.5811852219 0.3205294765 0.3478351414 0.4828167497 0.6596658755 -0.459063866252 +1403636694613555456.0000000000 1.1232774493 4.5860632181 0.3227155913 0.3477303874 0.4832665326 0.6599386696 -0.458277196035 +1403636694663555584.0000000000 1.1116616321 4.5907030120 0.3231450966 0.3481856835 0.4832982652 0.6601325414 -0.457618339218 +1403636694713555456.0000000000 1.0999534794 4.5951759700 0.3223985956 0.3493820717 0.4827302209 0.6596773232 -0.457962368587 +1403636694763555584.0000000000 1.0883802714 4.5991893788 0.3208687207 0.3494049137 0.4832752299 0.6575222776 -0.460462498973 +1403636694813555456.0000000000 1.0770227336 4.6033229493 0.3177346606 0.3507252593 0.4831818366 0.6561810083 -0.461468947611 +1403636694863555584.0000000000 1.0661991648 4.6068965400 0.3133521110 0.3465308273 0.4863494605 0.6538096961 -0.46466490001 +1403636694913555456.0000000000 1.0552097096 4.6109688130 0.3076007212 0.3436652719 0.4889991046 0.6517085615 -0.466958250109 +1403636694963555584.0000000000 1.0443067872 4.6154985563 0.3013781489 0.3404071953 0.4918318401 0.6498515907 -0.468953401228 +1403636695013555456.0000000000 1.0333775755 4.6210224963 0.2943688416 0.3388218668 0.4933250850 0.6491840501 -0.469457316689 +1403636695063555584.0000000000 1.0220297286 4.6275350881 0.2871806293 0.3396884079 0.4933914343 0.6502973366 -0.467215209556 +1403636695113555456.0000000000 1.0108283118 4.6350418853 0.2815479222 0.3424308517 0.4922493248 0.6510420878 -0.465377173883 +1403636695163555584.0000000000 0.9995526052 4.6429750256 0.2776419223 0.3438686754 0.4921183150 0.6514369355 -0.463900654485 +1403636695213555456.0000000000 0.9876473458 4.6513366581 0.2757127628 0.3467415055 0.4911392786 0.6520177575 -0.461979849392 +1403636695263555584.0000000000 0.9757714898 4.6600133989 0.2756869153 0.3496327053 0.4899537767 0.6523700675 -0.460560053814 +1403636695313555456.0000000000 0.9643806437 4.6689200140 0.2776944587 0.3518232682 0.4892957628 0.6524231563 -0.459515037424 +1403636695363555584.0000000000 0.9528354719 4.6777322716 0.2816100633 0.3537682704 0.4889605880 0.6523057598 -0.458544163613 +1403636695413555456.0000000000 0.9417542484 4.6864775706 0.2868133805 0.3545783911 0.4890101959 0.6521023207 -0.458154729554 +1403636695463555584.0000000000 0.9308809214 4.6951906829 0.2928845130 0.3560376891 0.4886090660 0.6518829928 -0.457762939029 +1403636695513555456.0000000000 0.9202230490 4.7038518086 0.2985716985 0.3583354873 0.4875657414 0.6523551157 -0.456407854215 +1403636695563555584.0000000000 0.9094431000 4.7117832928 0.3039107086 0.3600311798 0.4869143150 0.6520838089 -0.456156448679 +1403636695613555456.0000000000 0.8992429830 4.7196352605 0.3076300004 0.3620823269 0.4860805416 0.6523429278 -0.45505032705 +1403636695663555584.0000000000 0.8894337126 4.7270733893 0.3099246487 0.3645662069 0.4849358513 0.6528562854 -0.453549745358 +1403636695713555456.0000000000 0.8800309746 4.7336775008 0.3111217786 0.3653522864 0.4848383719 0.6525928358 -0.453400540937 +1403636695763555584.0000000000 0.8713324067 4.7395374132 0.3113735720 0.3632114386 0.4870496588 0.6514516651 -0.454390590605 +1403636695813555456.0000000000 0.8631407424 4.7453027606 0.3102750090 0.3628547576 0.4875682484 0.6514225717 -0.454161052006 +1403636695863555584.0000000000 0.8554175583 4.7508146678 0.3081688428 0.3623641311 0.4882719916 0.6508602319 -0.45460274667 +1403636695913555456.0000000000 0.8481448120 4.7560428785 0.3047177990 0.3620811310 0.4890216653 0.6510878668 -0.453695553212 +1403636695963555584.0000000000 0.8413586356 4.7608763299 0.3002449894 0.3601259137 0.4906475505 0.6513765906 -0.453081498897 +1403636696013555456.0000000000 0.8347453336 4.7654842756 0.2948184553 0.3580095951 0.4926843434 0.6515363419 -0.452318099012 +1403636696063555584.0000000000 0.8282484460 4.7699868075 0.2882111069 0.3564350307 0.4942471385 0.6529915568 -0.449750888431 +1403636696113555456.0000000000 0.8211086591 4.7742972189 0.2808767171 0.3561058626 0.4950732247 0.6551706772 -0.445917593817 +1403636696163555584.0000000000 0.8137296170 4.7783349347 0.2731460296 0.3576383092 0.4944239601 0.6569647065 -0.442760840487 +1403636696213555456.0000000000 0.8063520721 4.7818276917 0.2647117693 0.3584475114 0.4942137631 0.6582989412 -0.440352860696 +1403636696263555584.0000000000 0.7986324654 4.7845516529 0.2563086269 0.3612993352 0.4925391044 0.6576471946 -0.440872077101 +1403636696313555456.0000000000 0.7906763414 4.7861977587 0.2477634797 0.3628287118 0.4915532251 0.6556544058 -0.44367561689 +1403636696363555584.0000000000 0.7820478448 4.7870712436 0.2399401237 0.3667896319 0.4892955370 0.6514366226 -0.449094166233 +1403636696413555456.0000000000 0.7737217546 4.7871031959 0.2332192938 0.3695114005 0.4876630537 0.6463192819 -0.455979667043 +1403636696463555584.0000000000 0.7662470504 4.7868681169 0.2271582859 0.3697572000 0.4878595270 0.6422153891 -0.461337283357 +1403636696513555456.0000000000 0.7599216695 4.7869599045 0.2221090557 0.3706147208 0.4877162415 0.6410481465 -0.46242282648 +1403636696563555584.0000000000 0.7546943322 4.7867548565 0.2187162987 0.3693833699 0.4891512216 0.6406746859 -0.462409942841 +1403636696613555456.0000000000 0.7517347846 4.7868217861 0.2166596604 0.3688574587 0.4896188687 0.6409190645 -0.461995986313 +1403636696663555584.0000000000 0.7497324647 4.7868969564 0.2159624325 0.3670322962 0.4912977156 0.6408948444 -0.461700819272 +1403636696713555456.0000000000 0.7484514189 4.7873139120 0.2164608063 0.3665619453 0.4916698623 0.6409631170 -0.461583545463 +1403636696763555584.0000000000 0.7478712757 4.7879209672 0.2163477940 0.3654237633 0.4925673764 0.6416175730 -0.460618869566 +1403636696813555456.0000000000 0.7478359339 4.7889263452 0.2148068892 0.3661806722 0.4923249929 0.6421474156 -0.459537281727 +1403636696863555584.0000000000 0.7486218769 4.7899512155 0.2122023186 0.3660284892 0.4923478055 0.6429732315 -0.458478142503 +1403636696913555456.0000000000 0.7498550647 4.7910674353 0.2081617053 0.3671948717 0.4916074787 0.6437827686 -0.457202099605 +1403636696963555584.0000000000 0.7514844262 4.7922540017 0.2026489359 0.3715442540 0.4885119022 0.6461636384 -0.453633708139 +1403636697013555456.0000000000 0.7535534717 4.7929685144 0.1966726752 0.3762062792 0.4852504566 0.6487492834 -0.449583359511 +1403636697063555584.0000000000 0.7562423680 4.7929856201 0.1911065667 0.3806311159 0.4821317035 0.6509230894 -0.446058410583 +1403636697113555456.0000000000 0.7598491610 4.7922100358 0.1866811992 0.3853617734 0.4789221080 0.6536937429 -0.44137785242 +1403636697163555584.0000000000 0.7647029128 4.7899164480 0.1844070949 0.3891309401 0.4763814967 0.6554314048 -0.438232192622 +1403636697213555456.0000000000 0.7702743352 4.7852666658 0.1853380157 0.3916857823 0.4746051796 0.6561235967 -0.43684550735 +1403636697263555584.0000000000 0.7773420948 4.7784661995 0.1880746255 0.3929580097 0.4741849704 0.6560113633 -0.436327523458 +1403636697313555456.0000000000 0.7859712156 4.7692735141 0.1928087333 0.3896864903 0.4765918251 0.6560904862 -0.436520269249 +1403636697363555584.0000000000 0.7954172680 4.7578363712 0.1999732135 0.3846094345 0.4807723857 0.6546002908 -0.438670668355 +1403636697413555456.0000000000 0.8053029772 4.7447232229 0.2087788307 0.3786745768 0.4850928487 0.6534300611 -0.440817023616 +1403636697463555584.0000000000 0.8158298400 4.7305084001 0.2195158681 0.3732289741 0.4888265548 0.6528749706 -0.442157217488 +1403636697513555456.0000000000 0.8265790272 4.7155361395 0.2323939299 0.3694169942 0.4920510537 0.6521901120 -0.442792166522 +1403636697563555584.0000000000 0.8370359665 4.7001443837 0.2472112648 0.3683245655 0.4948581135 0.6510279375 -0.442283943339 +1403636697613555456.0000000000 0.8470175247 4.6845750741 0.2619619314 0.3702863904 0.4972513268 0.6491964117 -0.440650798395 +1403636697663555584.0000000000 0.8563599602 4.6687728069 0.2754233776 0.3739665744 0.5007759189 0.6461768990 -0.437981615376 +1403636697713555456.0000000000 0.8656184240 4.6525211883 0.2873647461 0.3773378815 0.5067626944 0.6416894836 -0.434789950805 +1403636697763555584.0000000000 0.8748588202 4.6360977683 0.2972374082 0.3817359085 0.5137701290 0.6370785232 -0.429475151867 +1403636697813555456.0000000000 0.8839199938 4.6191960958 0.3059308881 0.3869225130 0.5207928334 0.6311114003 -0.4251637261 +1403636697863555584.0000000000 0.8928698200 4.6015645773 0.3131287087 0.3913424265 0.5275228517 0.6251637617 -0.421593426407 +1403636697913555456.0000000000 0.9019905454 4.5830557090 0.3188825499 0.3949302409 0.5340439148 0.6197123160 -0.418071581487 +1403636697963555584.0000000000 0.9111218287 4.5638125312 0.3234398385 0.3978287164 0.5400915842 0.6142536653 -0.415602968953 +1403636698013555456.0000000000 0.9203036150 4.5439443026 0.3263874150 0.4000699135 0.5452179434 0.6100094660 -0.413001101587 +1403636698063555584.0000000000 0.9293747196 4.5235298927 0.3282552073 0.4029933252 0.5487006642 0.6061416511 -0.411237473706 +1403636698113555456.0000000000 0.9386625231 4.5023412637 0.3288615312 0.4042102629 0.5525490944 0.6028946583 -0.40966033816 +1403636698163555584.0000000000 0.9477096083 4.4807644173 0.3280571216 0.4053422533 0.5556686627 0.5999652188 -0.408621745904 +1403636698213555456.0000000000 0.9565239363 4.4590768469 0.3260749567 0.4071113878 0.5582208091 0.5970750579 -0.407616512665 +1403636698263555584.0000000000 0.9653292450 4.4373172227 0.3226908771 0.4088029005 0.5619045965 0.5937241894 -0.405752387306 +1403636698313555456.0000000000 0.9737880974 4.4157564604 0.3180179752 0.4119539769 0.5656473230 0.5903470700 -0.402277719724 +1403636698363555584.0000000000 0.9819657296 4.3938018953 0.3127515534 0.4158023973 0.5698713976 0.5857046916 -0.399130267967 +1403636698413555456.0000000000 0.9900513978 4.3717996947 0.3064877646 0.4192847733 0.5753223164 0.5809298758 -0.394620058444 +1403636698463555584.0000000000 0.9980158222 4.3498190840 0.2992254476 0.4223660847 0.5816374305 0.5755195459 -0.389976976384 +1403636698513555456.0000000000 1.0056761315 4.3276803897 0.2910960859 0.4268046438 0.5874726494 0.5700181812 -0.384438493693 +1403636698563555584.0000000000 1.0127834476 4.3054349572 0.2827183834 0.4310894223 0.5941414033 0.5632358662 -0.379372194508 +1403636698613555456.0000000000 1.0195764094 4.2829624929 0.2734787304 0.4353682382 0.6012088606 0.5558840174 -0.374159541126 +1403636698663555584.0000000000 1.0261831247 4.2604625880 0.2633027365 0.4389900229 0.6091863968 0.5477357712 -0.369005716335 +1403636698713555456.0000000000 1.0323882726 4.2376281812 0.2521531109 0.4431967732 0.6170249428 0.5391705127 -0.363527163108 +1403636698763555584.0000000000 1.0380682598 4.2146843405 0.2400688044 0.4475046303 0.6251577957 0.5301800205 -0.357528295708 +1403636698813555456.0000000000 1.0433093219 4.1916301192 0.2269901073 0.4519346195 0.6333997683 0.5208813501 -0.351059043988 +1403636698863555584.0000000000 1.0481821000 4.1682798533 0.2133326002 0.4556719096 0.6421748530 0.5103971315 -0.345643366939 +1403636698913555456.0000000000 1.0523492799 4.1452724122 0.2002386579 0.4607341707 0.6497317381 0.5005390378 -0.339165688356 +1403636698963555584.0000000000 1.0563715927 4.1220597776 0.1889329792 0.4644670494 0.6579410800 0.4902110877 -0.333282139845 +1403636699013555456.0000000000 1.0602350321 4.0988526118 0.1789958297 0.4685114636 0.6652752593 0.4801156482 -0.327711461819 +1403636699063555584.0000000000 1.0631300226 4.0759730359 0.1709765083 0.4723235706 0.6726823638 0.4696069832 -0.322301355054 +1403636699113555456.0000000000 1.0660208339 4.0532080492 0.1650211203 0.4764882317 0.6798310696 0.4584879456 -0.317139536521 +1403636699163555584.0000000000 1.0690302099 4.0307565534 0.1610414923 0.4790585142 0.6879941063 0.4457688374 -0.313778892455 +1403636699213555456.0000000000 1.0725755137 4.0091891073 0.1583687992 0.4819597879 0.6958668343 0.4342189019 -0.308120199017 +1403636699263555584.0000000000 1.0761111871 3.9886513502 0.1573468044 0.4848155376 0.7039778987 0.4216390114 -0.302637665828 +1403636699313555456.0000000000 1.0792608944 3.9691042908 0.1575740476 0.4862504955 0.7127067725 0.4091470928 -0.296998600352 +1403636699363555584.0000000000 1.0820603867 3.9511369867 0.1596402242 0.4889148697 0.7200540182 0.3975000939 -0.290651228191 +1403636699413555456.0000000000 1.0850075625 3.9342706787 0.1627156206 0.4907421310 0.7276485595 0.3853044940 -0.285026632986 +1403636699463555584.0000000000 1.0880647680 3.9186511897 0.1662678046 0.4928055380 0.7342960550 0.3743587899 -0.278939960845 +1403636699513555456.0000000000 1.0911396163 3.9043997666 0.1693968658 0.4957474152 0.7400193529 0.3640097455 -0.272218226587 +1403636699563555584.0000000000 1.0944304981 3.8914724715 0.1714890453 0.4981977124 0.7457903414 0.3530035010 -0.266428854161 +1403636699613555456.0000000000 1.0979070132 3.8796940717 0.1722822374 0.5005860613 0.7511366617 0.3422479048 -0.260909337546 +1403636699663555584.0000000000 1.1016194124 3.8696967818 0.1716765808 0.5032313001 0.7562528928 0.3311406303 -0.25531491073 +1403636699713555456.0000000000 1.1056541499 3.8616029400 0.1699713747 0.5071160837 0.7602528995 0.3208793000 -0.248767524667 +1403636699763555584.0000000000 1.1103370745 3.8550188346 0.1668303150 0.5116953218 0.7628819705 0.3136455505 -0.240427671802 +1403636699813555456.0000000000 1.1154571924 3.8494472301 0.1623917120 0.5169840224 0.7641573959 0.3080080689 -0.232211163397 +1403636699863555584.0000000000 1.1207813885 3.8445863433 0.1574802881 0.5220514283 0.7645317294 0.3030719448 -0.226055164188 +1403636699913555456.0000000000 1.1262365333 3.8403402640 0.1525083196 0.5260250111 0.7647877338 0.2984919262 -0.222035987905 +1403636699963555584.0000000000 1.1318420929 3.8364294126 0.1468797930 0.5286795352 0.7651374821 0.2942423063 -0.220190934753 +1403636700013555456.0000000000 1.1375024614 3.8330168797 0.1399713783 0.5298113686 0.7660152322 0.2910713952 -0.218627584377 +1403636700063555584.0000000000 1.1439131091 3.8297643922 0.1320651138 0.5306652885 0.7665329629 0.2890071137 -0.217477485256 +1403636700113555456.0000000000 1.1505869423 3.8268268449 0.1234555119 0.5310003476 0.7668858570 0.2871378301 -0.217891210935 +1403636700163555584.0000000000 1.1579857822 3.8247173193 0.1137126599 0.5319090064 0.7668543917 0.2861836073 -0.21703938316 +1403636700213555456.0000000000 1.1651007238 3.8235705093 0.1031688137 0.5320925041 0.7668938260 0.2857053912 -0.21708029885 +1403636700263555584.0000000000 1.1730759029 3.8228480613 0.0915438892 0.5318144966 0.7674354338 0.2848766835 -0.216936560809 +1403636700313555456.0000000000 1.1818149722 3.8229545591 0.0780876071 0.5307068872 0.7691650794 0.2830969369 -0.215850422375 +1403636700363555584.0000000000 1.1906834771 3.8243254201 0.0631839395 0.5291663404 0.7716346618 0.2797220609 -0.215217335461 +1403636700413555456.0000000000 1.2003108699 3.8267569470 0.0466027733 0.5286824392 0.7739563898 0.2753392446 -0.213716366887 +1403636700463555584.0000000000 1.2102576171 3.8307446120 0.0289028371 0.5313088015 0.7744244734 0.2714016358 -0.210520413569 +1403636700513555456.0000000000 1.2207335559 3.8354717805 0.0102018827 0.5347323014 0.7739561794 0.2679192856 -0.208020322687 +1403636700563555584.0000000000 1.2317842702 3.8411162518 -0.0093812589 0.5385931113 0.7732760835 0.2650126272 -0.204278893843 +1403636700613555456.0000000000 1.2435513858 3.8475248216 -0.0291874935 0.5430865360 0.7725076673 0.2611560011 -0.200216036671 +1403636700663555584.0000000000 1.2562897620 3.8545388632 -0.0500259263 0.5470537792 0.7725421383 0.2572627244 -0.194233616652 +1403636700713555456.0000000000 1.2693717875 3.8615896644 -0.0707010084 0.5500206208 0.7731794385 0.2523496869 -0.18971164467 +1403636700763555584.0000000000 1.2828968404 3.8682240360 -0.0899882140 0.5527126577 0.7734875426 0.2486624729 -0.185452727131 +1403636700813555456.0000000000 1.2969133313 3.8744590631 -0.1076138401 0.5537813476 0.7745602411 0.2458638204 -0.181476262217 +1403636700863555584.0000000000 1.3113852759 3.8801382822 -0.1238967043 0.5525677339 0.7768479580 0.2438066374 -0.178141721727 +1403636700913555456.0000000000 1.3259136899 3.8858919615 -0.1379760782 0.5513590798 0.7788130581 0.2423752359 -0.175235928338 +1403636700963555584.0000000000 1.3406753765 3.8913442998 -0.1502560243 0.5490985653 0.7811824678 0.2418147649 -0.172540827181 +1403636701013555456.0000000000 1.3555705038 3.8966969833 -0.1607927148 0.5468399470 0.7832305847 0.2413728193 -0.171041180895 +1403636701063555584.0000000000 1.3704634810 3.9021206536 -0.1696475826 0.5432405227 0.7859006027 0.2422043880 -0.169076939791 +1403636701113555456.0000000000 1.3853031000 3.9077330014 -0.1765239387 0.5392031229 0.7886572976 0.2431402136 -0.167816851569 +1403636701163555584.0000000000 1.3994178208 3.9144025422 -0.1807751521 0.5379572145 0.7892510356 0.2448619169 -0.166515704568 +1403636701213555456.0000000000 1.4129383614 3.9220265976 -0.1825798861 0.5358969350 0.7902473807 0.2466790529 -0.165749802746 +1403636701263555584.0000000000 1.4259276614 3.9303680801 -0.1816887474 0.5352186869 0.7902512277 0.2477656622 -0.166301325959 +1403636701313555456.0000000000 1.4384495473 3.9393280929 -0.1794648028 0.5341254672 0.7904340957 0.2496413661 -0.166141848788 +1403636701363555584.0000000000 1.4501495584 3.9490283084 -0.1757051908 0.5343226566 0.7898488426 0.2501921527 -0.167457431245 +1403636701413555456.0000000000 1.4613826584 3.9595654627 -0.1715018845 0.5358323915 0.7882229684 0.2517542137 -0.167952422512 +1403636701463555584.0000000000 1.4715294011 3.9705139770 -0.1666666146 0.5379714873 0.7860512794 0.2528556718 -0.169629225845 +1403636701513555456.0000000000 1.4811443939 3.9821707317 -0.1614728130 0.5416023149 0.7829617213 0.2536020539 -0.171242149276 +1403636701563555584.0000000000 1.4903463977 3.9938456223 -0.1563711234 0.5447609142 0.7800576274 0.2544283918 -0.173239250132 +1403636701613555456.0000000000 1.4992616009 4.0055321523 -0.1517425647 0.5466444633 0.7779995382 0.2556899045 -0.174697515786 +1403636701663555584.0000000000 1.5077434173 4.0172975769 -0.1475397644 0.5486291195 0.7758726118 0.2573996502 -0.17542291637 +1403636701713555456.0000000000 1.5162621338 4.0291034355 -0.1436509425 0.5499093483 0.7748743528 0.2570775995 -0.176296777605 +1403636701763555584.0000000000 1.5246863634 4.0411790442 -0.1406633938 0.5503291135 0.7751128020 0.2555134700 -0.176212592524 +1403636701813555456.0000000000 1.5333700641 4.0534976386 -0.1394987144 0.5500501548 0.7766353234 0.2523023409 -0.175002658497 +1403636701863555584.0000000000 1.5424744881 4.0664482146 -0.1401054115 0.5508606571 0.7781701626 0.2482978647 -0.171323976141 +1403636701913555456.0000000000 1.5515441556 4.0795771620 -0.1422795899 0.5505841373 0.7808854727 0.2421893194 -0.168580307087 +1403636701963555584.0000000000 1.5607682384 4.0930670662 -0.1456888060 0.5518729792 0.7828721519 0.2354700268 -0.164624648957 +1403636702013555456.0000000000 1.5701317607 4.1066640268 -0.1504314079 0.5526990951 0.7855166279 0.2277705372 -0.160024747937 +1403636702063555584.0000000000 1.5797535978 4.1201890555 -0.1564202768 0.5541465253 0.7880003645 0.2189095357 -0.155098901321 +1403636702113555456.0000000000 1.5896467603 4.1341001726 -0.1640726632 0.5560435647 0.7903733477 0.2090461516 -0.149750565759 +1403636702163555584.0000000000 1.5999687775 4.1482941545 -0.1731206520 0.5584164376 0.7924504174 0.1989525986 -0.143566297429 +1403636702213555456.0000000000 1.6103483107 4.1626966979 -0.1835435969 0.5596452980 0.7948346147 0.1900823980 -0.137490937063 +1403636702263555584.0000000000 1.6208321880 4.1766463436 -0.1955605054 0.5599910761 0.7972206099 0.1829027156 -0.131893481489 +1403636702313555456.0000000000 1.6315732985 4.1902126691 -0.2089755169 0.5591895520 0.7999873605 0.1773097354 -0.126049695326 +1403636702363555584.0000000000 1.6420714588 4.2037891011 -0.2232961675 0.5585523639 0.8021856965 0.1731225746 -0.120606547491 +1403636702413555456.0000000000 1.6524567497 4.2173089415 -0.2387705285 0.5585798149 0.8036079781 0.1704991266 -0.114598672232 +1403636702463555584.0000000000 1.6623767448 4.2308284337 -0.2552344938 0.5574029787 0.8056648114 0.1677442672 -0.109854411619 +1403636702513555456.0000000000 1.6718131424 4.2445690758 -0.2725426595 0.5573858146 0.8066089668 0.1660718917 -0.105466369848 +1403636702563555584.0000000000 1.6804833390 4.2581149889 -0.2911378132 0.5571953988 0.8074161622 0.1646267371 -0.102520563326 +1403636702613555456.0000000000 1.6886325658 4.2720166730 -0.3110484893 0.5560251532 0.8087910453 0.1636275583 -0.0995946599357 +1403636702663555584.0000000000 1.6960899045 4.2861172946 -0.3320512983 0.5545660402 0.8101573676 0.1633106422 -0.0971142671766 +1403636702713555456.0000000000 1.7027649431 4.3004630249 -0.3540078311 0.5540611233 0.8107268344 0.1635317322 -0.0948453700228 +1403636702763555584.0000000000 1.7084170872 4.3148691045 -0.3767452541 0.5532298811 0.8114596562 0.1627573252 -0.0947627461797 +1403636702813555456.0000000000 1.7132872135 4.3298182144 -0.4006939626 0.5518535077 0.8123809617 0.1638553833 -0.0929854425743 +1403636702863555584.0000000000 1.7171080277 4.3453762894 -0.4251676026 0.5508491491 0.8130340143 0.1643164217 -0.0924176396115 +1403636702913555456.0000000000 1.7197106465 4.3616785249 -0.4488332292 0.5497149712 0.8137710935 0.1643219463 -0.092673382514 +1403636702963555584.0000000000 1.7214564856 4.3789413260 -0.4707861167 0.5499626078 0.8134896810 0.1646679845 -0.0930597858599 +1403636703013555456.0000000000 1.7222134986 4.3971871137 -0.4906731063 0.5509140397 0.8128109675 0.1633514006 -0.0956471221245 +1403636703063555584.0000000000 1.7224770528 4.4160741535 -0.5089034508 0.5526289296 0.8115692427 0.1626169109 -0.0975313837691 +1403636703113555456.0000000000 1.7217910407 4.4359379286 -0.5245656430 0.5546440101 0.8101738484 0.1600380679 -0.101863507943 +1403636703163555584.0000000000 1.7206876436 4.4561352793 -0.5373135583 0.5585801411 0.8073894980 0.1564463507 -0.107865489407 +1403636703213555456.0000000000 1.7195306008 4.4765646928 -0.5484081291 0.5603813430 0.8059516860 0.1534258452 -0.113468675431 +1403636703263555584.0000000000 1.7184997774 4.4982229401 -0.5578523484 0.5621585677 0.8045923274 0.1492742694 -0.119691787223 +1403636703313555456.0000000000 1.7184668191 4.5199329044 -0.5657943001 0.5636780762 0.8033233846 0.1460611772 -0.124918768406 +1403636703363555584.0000000000 1.7198255768 4.5417214792 -0.5726539918 0.5653483749 0.8020292740 0.1455522132 -0.126272767487 +1403636703413555456.0000000000 1.7227161363 4.5638748720 -0.5783109721 0.5671074426 0.8008419356 0.1475648376 -0.123555499345 +1403636703463555584.0000000000 1.7269148266 4.5859264791 -0.5829020283 0.5674026558 0.8006830855 0.1514485772 -0.118423608934 +1403636703513555456.0000000000 1.7316539597 4.6072559557 -0.5857747654 0.5672356487 0.8007674667 0.1560436038 -0.112541445069 +1403636703563555584.0000000000 1.7367625542 4.6285835454 -0.5865343888 0.5670689476 0.8008315021 0.1594754515 -0.108024507776 +1403636703613555456.0000000000 1.7412244157 4.6487239857 -0.5851250690 0.5651300434 0.8020697623 0.1616801086 -0.105696135071 +1403636703663555584.0000000000 1.7454586713 4.6689240678 -0.5826859025 0.5637270368 0.8029200104 0.1630198193 -0.10467006915 +1403636703713555456.0000000000 1.7495216696 4.6887552568 -0.5805559135 0.5628327887 0.8034235207 0.1638576746 -0.104309927135 +1403636703763555584.0000000000 1.7531421262 4.7085462659 -0.5788326453 0.5634153256 0.8028579806 0.1637718479 -0.105645708455 +1403636703813555456.0000000000 1.7562623028 4.7281600390 -0.5782886322 0.5642917439 0.8021127196 0.1629599519 -0.107861331876 +1403636703863555584.0000000000 1.7592017038 4.7477240413 -0.5788621023 0.5654778212 0.8011214331 0.1617894614 -0.110740477312 +1403636703913555456.0000000000 1.7619814575 4.7671686114 -0.5805603660 0.5663428568 0.8002684846 0.1608494472 -0.113813779787 +1403636703963555584.0000000000 1.7650402086 4.7864882533 -0.5835478825 0.5668404791 0.7997570577 0.1607305763 -0.115092144935 +1403636704013555456.0000000000 1.7681961621 4.8053578359 -0.5873679680 0.5667930551 0.7995391194 0.1599461610 -0.117898494062 +1403636704063555584.0000000000 1.7718234905 4.8240730495 -0.5923830212 0.5668132697 0.7992665405 0.1597404379 -0.119911246678 +1403636704113555456.0000000000 1.7762059489 4.8426067058 -0.5992372897 0.5653064449 0.8001143336 0.1605738112 -0.120256923571 +1403636704163555584.0000000000 1.7810966780 4.8611897410 -0.6075658883 0.5631175533 0.8014530607 0.1622275277 -0.11938945454 +1403636704213555456.0000000000 1.7863390487 4.8800118053 -0.6172327460 0.5604603705 0.8031227700 0.1643628136 -0.117740625924 +1403636704263555584.0000000000 1.7916952833 4.8993642541 -0.6274988316 0.5579622959 0.8047191523 0.1663660020 -0.115877158123 +1403636704313555456.0000000000 1.7970814058 4.9192641041 -0.6367977405 0.5565295616 0.8055558765 0.1684827970 -0.113877671303 +1403636704363555584.0000000000 1.8022680079 4.9398916099 -0.6445406813 0.5553279189 0.8062563551 0.1704205031 -0.111885854202 +1403636704413555456.0000000000 1.8068224332 4.9610326605 -0.6499816307 0.5539615244 0.8070582987 0.1710613682 -0.111899688352 +1403636704463555584.0000000000 1.8113834280 4.9820637617 -0.6532816871 0.5525814928 0.8078756774 0.1729185658 -0.109953413821 +1403636704513555456.0000000000 1.8153102247 5.0037249535 -0.6546410024 0.5510459605 0.8088089208 0.1746648941 -0.108021543357 +1403636704563555584.0000000000 1.8184615533 5.0258705447 -0.6539402182 0.5491566861 0.8100391678 0.1752674303 -0.107446770728 +1403636704613555456.0000000000 1.8209446931 5.0486550820 -0.6528848656 0.5476449753 0.8109486430 0.1763434828 -0.106537578062 +1403636704663555584.0000000000 1.8224853087 5.0721866074 -0.6524577139 0.5463711857 0.8117755338 0.1770282222 -0.105640990176 +1403636704713555456.0000000000 1.8235174042 5.0959511354 -0.6541303014 0.5431652731 0.8137703426 0.1789994451 -0.103481951781 +1403636704763555584.0000000000 1.8236445040 5.1204186136 -0.6571694771 0.5411377420 0.8149330766 0.1804890984 -0.102360686383 +1403636704813555456.0000000000 1.8226581846 5.1459457494 -0.6619059372 0.5380681254 0.8168212371 0.1812253544 -0.102191633838 +1403636704863555584.0000000000 1.8203087730 5.1724412072 -0.6682968650 0.5348766346 0.8187428748 0.1821044800 -0.102005142449 +1403636704913555456.0000000000 1.8168307094 5.2004013382 -0.6759035688 0.5322505803 0.8202109382 0.1829885722 -0.102364637742 +1403636704963555584.0000000000 1.8123526166 5.2300595468 -0.6849620436 0.5299260981 0.8215248549 0.1843001262 -0.101531802206 +1403636705013555456.0000000000 1.8068493573 5.2612730533 -0.6950530523 0.5284542564 0.8222815029 0.1855502076 -0.100798557596 +1403636705063555584.0000000000 1.7998615361 5.2944090122 -0.7055309011 0.5285431334 0.8220090010 0.1872044705 -0.0994879115025 +1403636705113555456.0000000000 1.7911371480 5.3298853043 -0.7161909181 0.5325956854 0.8192930734 0.1870669316 -0.100531880082 +1403636705163555584.0000000000 1.7810291267 5.3665752709 -0.7262336153 0.5399199880 0.8144006025 0.1866217291 -0.10203134551 +1403636705213555456.0000000000 1.7694387856 5.4045047800 -0.7352386813 0.5476873403 0.8091086296 0.1864237509 -0.103092132672 +1403636705263555584.0000000000 1.7567266869 5.4431094940 -0.7427255181 0.5537900858 0.8048274407 0.1865168684 -0.103830579573 +1403636705313555456.0000000000 1.7430650484 5.4814950704 -0.7482783575 0.5575260084 0.8022072884 0.1861328461 -0.104798759304 +1403636705363555584.0000000000 1.7287711548 5.5195535589 -0.7528906058 0.5599844422 0.8004661635 0.1857285279 -0.10571782956 +1403636705413555456.0000000000 1.7137014377 5.5573136120 -0.7565828493 0.5585288025 0.8014453018 0.1859797781 -0.10555816986 +1403636705463555584.0000000000 1.6978754133 5.5948486303 -0.7597879577 0.5564950419 0.8029180354 0.1857099089 -0.105582794058 +1403636705513555456.0000000000 1.6812049702 5.6322808070 -0.7638681853 0.5532286578 0.8052403952 0.1858032287 -0.104895749782 +1403636705563555584.0000000000 1.6637411950 5.6697383862 -0.7692707869 0.5504689361 0.8070985782 0.1865706168 -0.103765314359 +1403636705613555456.0000000000 1.6453685778 5.7074662607 -0.7758635873 0.5490894805 0.8081036320 0.1861739253 -0.103964089576 +1403636705663555584.0000000000 1.6263140995 5.7455783811 -0.7840694385 0.5479691886 0.8089526730 0.1861882757 -0.103243727008 +1403636705713555456.0000000000 1.6061472730 5.7847276547 -0.7927361488 0.5495981501 0.8079172412 0.1854829562 -0.103959982088 +1403636705763555584.0000000000 1.5850720705 5.8244868188 -0.8022298948 0.5515989951 0.8066587445 0.1842414427 -0.105334274312 +1403636705813555456.0000000000 1.5632015411 5.8644048443 -0.8114581654 0.5538008722 0.8051826306 0.1824681006 -0.108124546465 +1403636705863555584.0000000000 1.5407904231 5.9048303507 -0.8197138871 0.5568525772 0.8030901277 0.1806932612 -0.110956746137 +1403636705913555456.0000000000 1.5179941266 5.9452596779 -0.8260506285 0.5592352625 0.8014729232 0.1775134448 -0.115698105139 +1403636705963555584.0000000000 1.4949964712 5.9857926784 -0.8302874863 0.5611080652 0.8001108630 0.1743800938 -0.120714245153 +1403636706013555456.0000000000 1.4722255302 6.0256933028 -0.8321257793 0.5619340341 0.7993330603 0.1703304253 -0.12761013371 +1403636706063555584.0000000000 1.4505190659 6.0649716236 -0.8321150237 0.5617872543 0.7991416402 0.1665429497 -0.13428017617 +1403636706113555456.0000000000 1.4296405008 6.1051107626 -0.8314355358 0.5628741930 0.7981156851 0.1633736711 -0.139617475724 +1403636706163555584.0000000000 1.4108036455 6.1453511115 -0.8325036839 0.5647510998 0.7966320605 0.1650489625 -0.138536621043 +1403636706213555456.0000000000 1.3934802512 6.1859218476 -0.8358811358 0.5666980789 0.7951579897 0.1692218625 -0.133944092905 +1403636706263555584.0000000000 1.3771467614 6.2262961624 -0.8415152566 0.5671370890 0.7947265765 0.1731637066 -0.129535792765 +1403636706313555456.0000000000 1.3614912201 6.2662482581 -0.8492271349 0.5676634087 0.7941624015 0.1784134964 -0.123421872725 +1403636706363555584.0000000000 1.3462718376 6.3058410542 -0.8591954624 0.5667258520 0.7945993107 0.1824497384 -0.118936272872 +1403636706413555456.0000000000 1.3311552042 6.3448529001 -0.8700991464 0.5659279916 0.7949470752 0.1859317614 -0.114952321142 +1403636706463555584.0000000000 1.3158738036 6.3835920924 -0.8815041499 0.5644177554 0.7957934877 0.1887111254 -0.111952818279 +1403636706513555456.0000000000 1.2999342256 6.4223998496 -0.8914699016 0.5635773495 0.7962366637 0.1906143048 -0.109790406321 +1403636706563555584.0000000000 1.2838897051 6.4604351967 -0.8998971240 0.5624054611 0.7970726566 0.1916100292 -0.107985527464 +1403636706613555456.0000000000 1.2671243758 6.4980683319 -0.9060427161 0.5616534101 0.7975254609 0.1920039287 -0.107856744874 +1403636706663555584.0000000000 1.2499129400 6.5353837477 -0.9113455724 0.5607430193 0.7982422066 0.1923166771 -0.106728354308 +1403636706713555456.0000000000 1.2313342267 6.5735526915 -0.9146960337 0.5589303154 0.7995343385 0.1926652565 -0.105933201095 +1403636706763555584.0000000000 1.2117444121 6.6114894501 -0.9153141268 0.5564435902 0.8014190358 0.1918286795 -0.106300600806 +1403636706813555456.0000000000 1.1918973112 6.6491699666 -0.9154255289 0.5542450858 0.8030949295 0.1919429189 -0.104922995515 +1403636706863555584.0000000000 1.1713101704 6.6868676050 -0.9146021527 0.5527538024 0.8043712874 0.1913929022 -0.104013570697 +1403636706913555456.0000000000 1.1497891238 6.7246433670 -0.9125260328 0.5521378941 0.8050771030 0.1901044721 -0.104186821963 +1403636706963555584.0000000000 1.1274600550 6.7630907233 -0.9097878813 0.5525025312 0.8051636773 0.1892609975 -0.103114890569 +1403636707013555456.0000000000 1.1040193026 6.8016522151 -0.9059376733 0.5547305305 0.8039707776 0.1876273703 -0.10344562431 +1403636707063555584.0000000000 1.0800110132 6.8403256891 -0.9020574022 0.5573020153 0.8025060393 0.1866349455 -0.102790650592 +1403636707113555456.0000000000 1.0554691156 6.8789189863 -0.8980584223 0.5593790326 0.8014417938 0.1850586238 -0.102661846258 +1403636707163555584.0000000000 1.0303960904 6.9172031163 -0.8943119536 0.5598452654 0.8015117153 0.1838025317 -0.101827689479 +1403636707213555456.0000000000 1.0048589248 6.9552151246 -0.8903402552 0.5597270030 0.8020705597 0.1824721917 -0.100460931141 +1403636707263555584.0000000000 0.9786960530 6.9931783531 -0.8851373541 0.5597222792 0.8024780169 0.1814498744 -0.0990754544833 +1403636707313555456.0000000000 0.9518769911 7.0309264465 -0.8782499974 0.5593077001 0.8031069655 0.1810871265 -0.0969615964087 +1403636707363555584.0000000000 0.9240757244 7.0683419656 -0.8692689440 0.5588544147 0.8037347251 0.1802445404 -0.0959382117174 +1403636707413555456.0000000000 0.8953743019 7.1058186350 -0.8581598112 0.5582220011 0.8044320410 0.1793636557 -0.0954251951302 +1403636707463555584.0000000000 0.8655567565 7.1436579175 -0.8447846310 0.5577221000 0.8049042045 0.1794198019 -0.0942539944096 +1403636707513555456.0000000000 0.8349640691 7.1809379096 -0.8293776594 0.5572445687 0.8054189206 0.1782332582 -0.0949302832204 +1403636707563555584.0000000000 0.8033766580 7.2184724795 -0.8123327701 0.5568561684 0.8058433900 0.1770068289 -0.0958969293197 +1403636707613555456.0000000000 0.7711552679 7.2556961861 -0.7959595365 0.5552780267 0.8070760517 0.1755839158 -0.0972874520942 +1403636707663555584.0000000000 0.7380489880 7.2931935129 -0.7810065448 0.5526518487 0.8090256683 0.1717306012 -0.102771604757 +1403636707713555456.0000000000 0.7049819733 7.3312133142 -0.7691026397 0.5511762416 0.8100549975 0.1695482951 -0.106155674881 +1403636707763555584.0000000000 0.6718851219 7.3699197767 -0.7604122608 0.5495707378 0.8110978565 0.1677906286 -0.109263792311 +1403636707813555456.0000000000 0.6387020610 7.4097607978 -0.7547748678 0.5498949918 0.8108773710 0.1666592221 -0.110986894695 +1403636707863555584.0000000000 0.6056446347 7.4500398901 -0.7520660051 0.5508022934 0.8100858754 0.1664532956 -0.112565574162 +1403636707913555456.0000000000 0.5730500071 7.4905963022 -0.7522115078 0.5523158013 0.8088393054 0.1664453796 -0.114114719576 +1403636707963555584.0000000000 0.5405956984 7.5316709124 -0.7550862311 0.5536942553 0.8076086359 0.1676597192 -0.114372992443 +1403636708013555456.0000000000 0.5081558418 7.5733495297 -0.7604211504 0.5551701612 0.8062685716 0.1693134024 -0.114236834654 +1403636708063555584.0000000000 0.4759256993 7.6152157780 -0.7679840237 0.5567098197 0.8048475419 0.1714943944 -0.11350895828 +1403636708113555456.0000000000 0.4437313057 7.6574015906 -0.7767780563 0.5587380012 0.8030328992 0.1737307215 -0.112994005363 +1403636708163555584.0000000000 0.4115021538 7.6996109695 -0.7868471286 0.5605115242 0.8014364640 0.1757643960 -0.112397964998 +1403636708213555456.0000000000 0.3792022924 7.7414174567 -0.7979767974 0.5613883183 0.8005176830 0.1758978596 -0.114343947151 +1403636708263555584.0000000000 0.3469434442 7.7828174953 -0.8099879724 0.5620930544 0.7998251895 0.1745155291 -0.11779386452 +1403636708313555456.0000000000 0.3148760485 7.8240804610 -0.8224172496 0.5628897139 0.7990992938 0.1710944384 -0.123782800835 +1403636708363555584.0000000000 0.2835554109 7.8643980045 -0.8348923262 0.5626035490 0.7990942288 0.1662785955 -0.13144233986 +1403636708413555456.0000000000 0.2537191945 7.9048929139 -0.8464947137 0.5626520979 0.7988436311 0.1625982719 -0.137234368016 +1403636708463555584.0000000000 0.2251386078 7.9462443387 -0.8569848869 0.5628848736 0.7984593456 0.1598763615 -0.141643360434 +1403636708513555456.0000000000 0.1980585850 7.9889574303 -0.8655207782 0.5634591399 0.7979884811 0.1586577618 -0.143373276012 +1403636708563555584.0000000000 0.1727794150 8.0322633491 -0.8726010976 0.5650077093 0.7968707603 0.1590105416 -0.143104603244 +1403636708613555456.0000000000 0.1497950082 8.0757992732 -0.8786242967 0.5671972733 0.7955594050 0.1612339928 -0.139198009387 +1403636708663555584.0000000000 0.1284941669 8.1191481255 -0.8854620508 0.5685976596 0.7948316212 0.1652379263 -0.132799936268 +1403636708713555456.0000000000 0.1084186032 8.1622908974 -0.8930087862 0.5719153873 0.7927410182 0.1692558823 -0.125805064134 +1403636708763555584.0000000000 0.0890995699 8.2048677017 -0.9020037110 0.5740758390 0.7913786684 0.1734426843 -0.118635448193 +1403636708813555456.0000000000 0.0702433234 8.2467257488 -0.9119642889 0.5774536370 0.7891172931 0.1766854652 -0.112354088956 +1403636708863555584.0000000000 0.0512961292 8.2871294525 -0.9228834933 0.5781406746 0.7889069468 0.1776583573 -0.108704635463 +1403636708913555456.0000000000 0.0322231949 8.3265668455 -0.9330545158 0.5804747915 0.7876183051 0.1774089606 -0.105983406981 +1403636708963555584.0000000000 0.0130170232 8.3645183584 -0.9421307969 0.5822361066 0.7868090310 0.1769291167 -0.103095842125 +1403636709013555456.0000000000 -0.0067319939 8.4008164800 -0.9486713028 0.5844759211 0.7855684033 0.1751389085 -0.102939516562 +1403636709063555584.0000000000 -0.0262473660 8.4353254505 -0.9539041165 0.5869868416 0.7841386629 0.1749698506 -0.0997925673144 +1403636709113555456.0000000000 -0.0463237504 8.4679283239 -0.9573066848 0.5879974040 0.7838382491 0.1731755952 -0.0993320961694 +1403636709163555584.0000000000 -0.0666865868 8.4989391727 -0.9590188908 0.5875649706 0.7845650434 0.1725940813 -0.0971410368932 +1403636709213555456.0000000000 -0.0873373853 8.5278059745 -0.9588837528 0.5851681191 0.7867427777 0.1713295910 -0.0962301692087 +1403636709263555584.0000000000 -0.1081781438 8.5551233368 -0.9577030954 0.5824759629 0.7889472901 0.1716525022 -0.0939113653745 +1403636709313555456.0000000000 -0.1297923292 8.5809884801 -0.9547333274 0.5795821128 0.7912300625 0.1713733719 -0.0931167551508 +1403636709363555584.0000000000 -0.1519925241 8.6057290555 -0.9519213732 0.5768546746 0.7932958940 0.1712344551 -0.0927311727862 +1403636709413555456.0000000000 -0.1745190100 8.6296207303 -0.9502673818 0.5759108774 0.7940075798 0.1724597856 -0.0902011471309 +1403636709463555584.0000000000 -0.1980334941 8.6525421233 -0.9501361850 0.5750771907 0.7946277804 0.1720602516 -0.0908195200303 +1403636709513555456.0000000000 -0.2220352070 8.6746878258 -0.9523484999 0.5743933545 0.7950830934 0.1730386742 -0.0892903477865 +1403636709563555584.0000000000 -0.2469285333 8.6956978068 -0.9561257976 0.5734124210 0.7957500033 0.1731371403 -0.0894631674442 +1403636709613555456.0000000000 -0.2725472974 8.7160464810 -0.9612511236 0.5720405065 0.7966884818 0.1736295848 -0.0889375582639 +1403636709663555584.0000000000 -0.2989717241 8.7357949437 -0.9675316305 0.5712059193 0.7971766236 0.1741618095 -0.0888869654233 +1403636709713555456.0000000000 -0.3262759332 8.7552043236 -0.9741277590 0.5708081255 0.7972639225 0.1751786200 -0.0886609995179 +1403636709763555584.0000000000 -0.3547182955 8.7736950856 -0.9807805967 0.5700822233 0.7975760443 0.1753924902 -0.0900898808492 +1403636709813555456.0000000000 -0.3837861099 8.7915084340 -0.9872602048 0.5705471693 0.7969776416 0.1767616083 -0.0897658082634 +1403636709863555584.0000000000 -0.4141287130 8.8086819100 -0.9922827298 0.5704088997 0.7969147246 0.1766487212 -0.0914102733022 +1403636709913555456.0000000000 -0.4451997785 8.8256337837 -0.9956028913 0.5709584952 0.7963286090 0.1776122137 -0.0912197604577 +1403636709963555584.0000000000 -0.4770589551 8.8416420442 -0.9972248102 0.5715565743 0.7956500573 0.1784582882 -0.0917426185794 +1403636710013555456.0000000000 -0.5096959416 8.8568914114 -0.9973144727 0.5714104932 0.7955436127 0.1787255574 -0.0930461370226 +1403636710063555584.0000000000 -0.5428766464 8.8713178052 -0.9964362166 0.5718681191 0.7949791096 0.1794624890 -0.0936391198366 +1403636710113555456.0000000000 -0.5770788349 8.8854608606 -0.9958336764 0.5724504720 0.7942607281 0.1803206711 -0.094524115794 +1403636710163555584.0000000000 -0.6119402267 8.8989324274 -0.9969214348 0.5727635366 0.7937215342 0.1814679460 -0.0949602120926 +1403636710213555456.0000000000 -0.6475389065 8.9119016367 -1.0000627611 0.5731473512 0.7930811477 0.1826227294 -0.0957775843372 +1403636710263555584.0000000000 -0.6839131255 8.9239648429 -1.0055629613 0.5730486382 0.7928103900 0.1827306910 -0.0983688892122 +1403636710313555456.0000000000 -0.7210737027 8.9350281979 -1.0125859081 0.5727623253 0.7927484688 0.1802604511 -0.104877803937 +1403636710363555584.0000000000 -0.7586583794 8.9450938691 -1.0211309300 0.5711026371 0.7934642130 0.1774132118 -0.113052523034 +1403636710413555456.0000000000 -0.7963246566 8.9542654686 -1.0309173567 0.5694629407 0.7936898541 0.1763255491 -0.121151456557 +1403636710463555584.0000000000 -0.8337151953 8.9627421874 -1.0421107931 0.5671084740 0.7940155647 0.1768270921 -0.129071457965 +1403636710513555456.0000000000 -0.8707071809 8.9709030011 -1.0543917998 0.5650601787 0.7937362876 0.1785311926 -0.137172568424 +1403636710563555584.0000000000 -0.9066699791 8.9790010305 -1.0678008488 0.5634090889 0.7930342857 0.1816570894 -0.143762032847 +1403636710613555456.0000000000 -0.9415038580 8.9872507456 -1.0823183003 0.5625331822 0.7917602206 0.1854264224 -0.14929572638 +1403636710663555584.0000000000 -0.9752677884 8.9954592166 -1.0979665772 0.5615163924 0.7902124149 0.1908044770 -0.154458188282 +1403636710713555456.0000000000 -1.0077315271 9.0038152743 -1.1143872028 0.5613849376 0.7878472531 0.1977133805 -0.158281637629 +1403636710763555584.0000000000 -1.0390251963 9.0121444409 -1.1303113219 0.5610747528 0.7852526280 0.2053789944 -0.162458919698 +1403636710813555456.0000000000 -1.0689576092 9.0204987790 -1.1447630968 0.5618959643 0.7815531432 0.2161133582 -0.163531727942 +1403636710863555584.0000000000 -1.0977616926 9.0282381525 -1.1578701224 0.5615603027 0.7783147356 0.2275148763 -0.164660802204 +1403636710913555456.0000000000 -1.1260456788 9.0358676784 -1.1693151966 0.5608707811 0.7751748866 0.2386307715 -0.16608195868 +1403636710963555584.0000000000 -1.1537557718 9.0434722280 -1.1787902629 0.5608970346 0.7717145956 0.2486002098 -0.167478462011 +1403636711013555456.0000000000 -1.1809500944 9.0509167922 -1.1869050626 0.5602221729 0.7689195000 0.2595850052 -0.165920295908 +1403636711063555584.0000000000 -1.2081549502 9.0575067756 -1.1928016150 0.5598319249 0.7665080665 0.2660532071 -0.168134740105 +1403636711113555456.0000000000 -1.2353011934 9.0639138459 -1.1976875059 0.5601159539 0.7639797125 0.2727653981 -0.167940926132 +1403636711163555584.0000000000 -1.2626478129 9.0693586824 -1.2012924967 0.5607471886 0.7617248745 0.2770975283 -0.168981554571 +1403636711213555456.0000000000 -1.2903871261 9.0739990474 -1.2045801657 0.5611213654 0.7600344623 0.2804289985 -0.169852895682 +1403636711263555584.0000000000 -1.3179355224 9.0772205717 -1.2073980241 0.5612826260 0.7588944126 0.2826480198 -0.170737169853 +1403636711313555456.0000000000 -1.3458433295 9.0790294699 -1.2087335934 0.5611997157 0.7581978716 0.2825817898 -0.174179213965 +1403636711363555584.0000000000 -1.3736599958 9.0798125067 -1.2094870135 0.5613180721 0.7577278287 0.2817229778 -0.177208135617 +1403636711413555456.0000000000 -1.4021481024 9.0801527825 -1.2077740072 0.5642470870 0.7554229456 0.2794207955 -0.181343368096 +1403636711463555584.0000000000 -1.4297345297 9.0788966108 -1.2048040740 0.5690191455 0.7518943771 0.2764927869 -0.18553650997 +1403636711513555456.0000000000 -1.4565685477 9.0764645549 -1.2019070275 0.5736582960 0.7485934706 0.2740541232 -0.188197536736 +1403636711563555584.0000000000 -1.4829636927 9.0732620760 -1.1986613265 0.5783700800 0.7454182808 0.2731555010 -0.187685133905 +1403636711613555456.0000000000 -1.5086929746 9.0682162919 -1.1952860310 0.5814337278 0.7435045014 0.2726538285 -0.186536233317 +1403636711663555584.0000000000 -1.5335364572 9.0611236332 -1.1920016949 0.5831763119 0.7426441637 0.2724495888 -0.184814114335 +1403636711713555456.0000000000 -1.5574094660 9.0519623284 -1.1885387814 0.5834709534 0.7429657142 0.2729679537 -0.18180233866 +1403636711763555584.0000000000 -1.5806254013 9.0404274379 -1.1842116940 0.5829393358 0.7438965540 0.2722215553 -0.180817788465 +1403636711813555456.0000000000 -1.6031491207 9.0268096749 -1.1797511731 0.5806147031 0.7461523085 0.2708077497 -0.181125541608 +1403636711863555584.0000000000 -1.6249298932 9.0109012947 -1.1745627566 0.5766779309 0.7495167895 0.2687932325 -0.182804114801 +1403636711913555456.0000000000 -1.6462563919 8.9934130915 -1.1684215725 0.5717581605 0.7535800358 0.2659924718 -0.18562796253 +1403636711963555584.0000000000 -1.6665686405 8.9747600932 -1.1612574452 0.5670341681 0.7574108890 0.2631002777 -0.188624604189 +1403636712013555456.0000000000 -1.6857522218 8.9547718083 -1.1528981588 0.5627958763 0.7607862138 0.2596646236 -0.19245628523 +1403636712063555584.0000000000 -1.7039972268 8.9345042550 -1.1432397072 0.5592943156 0.7634824525 0.2564489058 -0.196260979431 +1403636712113555456.0000000000 -1.7210682484 8.9143748330 -1.1324131184 0.5580910941 0.7644210994 0.2542854433 -0.198830648771 +1403636712163555584.0000000000 -1.7368847957 8.8944415942 -1.1207806815 0.5580369532 0.7642864322 0.2535727947 -0.200404207151 +1403636712213555456.0000000000 -1.7511091220 8.8742914006 -1.1089630170 0.5590590684 0.7625549230 0.2580177097 -0.19846865988 +1403636712263555584.0000000000 -1.7643433522 8.8535038086 -1.0959770764 0.5601541688 0.7599023693 0.2649605603 -0.196396531942 +1403636712313555456.0000000000 -1.7769343571 8.8321004957 -1.0814527057 0.5619351203 0.7559907747 0.2728644789 -0.195580789845 +1403636712363555584.0000000000 -1.7888204509 8.8097078347 -1.0660960491 0.5628501036 0.7522133126 0.2815102318 -0.19526106279 +1403636712413555456.0000000000 -1.8000799495 8.7864316098 -1.0494956249 0.5634773902 0.7488250438 0.2885721712 -0.196164182444 +1403636712463555584.0000000000 -1.8107378119 8.7622451091 -1.0316886894 0.5644583080 0.7451535839 0.2950431620 -0.197692912071 +1403636712513555456.0000000000 -1.8211174754 8.7370112227 -1.0126337235 0.5644632747 0.7422306994 0.3007441591 -0.20006936594 +1403636712563555584.0000000000 -1.8311293385 8.7106307182 -0.9927586974 0.5641623957 0.7398582955 0.3049354022 -0.203334439689 +1403636712613555456.0000000000 -1.8407661305 8.6829020173 -0.9732833129 0.5647992818 0.7368667930 0.3078601023 -0.207969367994 +1403636712663555584.0000000000 -1.8498286513 8.6542408036 -0.9550616211 0.5654679714 0.7340869799 0.3093214795 -0.213734652479 +1403636712713555456.0000000000 -1.8579175483 8.6245879666 -0.9385779032 0.5660590289 0.7316760238 0.3105003664 -0.218670744634 +1403636712763555584.0000000000 -1.8651425244 8.5940747445 -0.9240222116 0.5654904603 0.7302507417 0.3121542940 -0.222517618158 +1403636712813555456.0000000000 -1.8712263148 8.5628189848 -0.9114554568 0.5640070952 0.7299958858 0.3138205078 -0.224763636343 +1403636712863555584.0000000000 -1.8760297061 8.5307401144 -0.9004726529 0.5616429525 0.7307846642 0.3156133282 -0.2256085005 +1403636712913555456.0000000000 -1.8796563477 8.4978134396 -0.8907068974 0.5594069528 0.7317250839 0.3172099193 -0.225876359582 +1403636712963555584.0000000000 -1.8819184162 8.4639405307 -0.8828137676 0.5570951450 0.7329973628 0.3190837482 -0.224823102002 +1403636713013555456.0000000000 -1.8834984824 8.4298595248 -0.8760062487 0.5563211783 0.7333802170 0.3209545941 -0.22281910246 +1403636713063555584.0000000000 -1.8843607299 8.3946330994 -0.8677417394 0.5560767518 0.7333533788 0.3205648145 -0.224075138478 +1403636713113555456.0000000000 -1.8837692735 8.3576634824 -0.8580461537 0.5552412285 0.7334738303 0.3201596952 -0.226320763312 +1403636713163555584.0000000000 -1.8821019563 8.3198974553 -0.8473535255 0.5536732012 0.7341738567 0.3206202221 -0.227238657918 +1403636713213555456.0000000000 -1.8793860338 8.2816084602 -0.8345048206 0.5519534054 0.7353279762 0.3205014528 -0.22785746535 +1403636713263555584.0000000000 -1.8758144243 8.2428711904 -0.8198463834 0.5496917534 0.7368535685 0.3210207674 -0.227665240381 +1403636713313555456.0000000000 -1.8713782784 8.2039118928 -0.8031691548 0.5489096280 0.7375002509 0.3214683925 -0.226825203504 +1403636713363555584.0000000000 -1.8664752610 8.1644208229 -0.7844266040 0.5472475531 0.7387825294 0.3218527461 -0.226122311372 +1403636713413555456.0000000000 -1.8618088022 8.1246907434 -0.7630944501 0.5461517228 0.7396877217 0.3206566626 -0.227507527024 +1403636713463555584.0000000000 -1.8563145798 8.0847323252 -0.7411879522 0.5450538884 0.7406789812 0.3197391593 -0.228205555618 +1403636713513555456.0000000000 -1.8494806256 8.0441315328 -0.7183226341 0.5435684777 0.7419149208 0.3185729615 -0.22936178525 +1403636713563555584.0000000000 -1.8422500380 8.0035551501 -0.6956324994 0.5426051983 0.7428473244 0.3168830819 -0.230960091394 +1403636713613555456.0000000000 -1.8340126751 7.9631964033 -0.6741947029 0.5398298411 0.7452533916 0.3148903050 -0.232433260917 +1403636713663555584.0000000000 -1.8252919720 7.9233444735 -0.6543917234 0.5375677030 0.7472490353 0.3132503118 -0.233482517816 +1403636713713555456.0000000000 -1.8158776494 7.8843316109 -0.6360745848 0.5356692092 0.7489766512 0.3112502090 -0.234980385766 +1403636713763555584.0000000000 -1.8057745363 7.8464651399 -0.6194826891 0.5340118483 0.7506464350 0.3091735774 -0.23616302525 +1403636713813555456.0000000000 -1.7948161988 7.8094846304 -0.6044188813 0.5327136219 0.7519203164 0.3078108050 -0.236821754185 +1403636713863555584.0000000000 -1.7829829990 7.7741329500 -0.5908536128 0.5327504007 0.7523957119 0.3069649429 -0.236326526358 +1403636713913555456.0000000000 -1.7701615907 7.7396149541 -0.5786674383 0.5333557325 0.7525256119 0.3073628211 -0.234019149255 +1403636713963555584.0000000000 -1.7564789036 7.7057186386 -0.5678557001 0.5341160812 0.7524529419 0.3080476209 -0.231605797117 +1403636714013555456.0000000000 -1.7420583565 7.6721555639 -0.5584945618 0.5341608999 0.7529985215 0.3083556990 -0.229307920985 +1403636714063555584.0000000000 -1.7269156523 7.6393121039 -0.5502487293 0.5368805752 0.7517244934 0.3099191259 -0.22498815387 +1403636714113555456.0000000000 -1.7114514555 7.6065517725 -0.5431311384 0.5373155929 0.7520142062 0.3096950361 -0.223283612947 +1403636714163555584.0000000000 -1.6955402065 7.5740820758 -0.5369855146 0.5382256144 0.7519582175 0.3095689791 -0.221447678371 +1403636714213555456.0000000000 -1.6792371259 7.5418568550 -0.5315498193 0.5395893190 0.7515255891 0.3083152517 -0.221346699113 +1403636714263555584.0000000000 -1.6627031613 7.5097059160 -0.5269081060 0.5397365443 0.7518763212 0.3059767896 -0.223035119831 +1403636714313555456.0000000000 -1.6457267485 7.4777827073 -0.5232350702 0.5393629181 0.7526046700 0.3038819811 -0.224342583819 +1403636714363555584.0000000000 -1.6279597640 7.4461732796 -0.5210182490 0.5385353551 0.7536637203 0.3029761837 -0.22400022343 +1403636714413555456.0000000000 -1.6094786801 7.4150238386 -0.5203531502 0.5361224082 0.7557676027 0.3034560789 -0.222041668083 +1403636714463555584.0000000000 -1.5906206283 7.3840264459 -0.5208402267 0.5324553841 0.7579576881 0.3052400483 -0.220952302458 +1403636714513555456.0000000000 -1.5715786422 7.3535140570 -0.5221544708 0.5285163453 0.7595948262 0.3082336053 -0.220631405957 +1403636714563555584.0000000000 -1.5526696369 7.3235395861 -0.5241657400 0.5241801836 0.7607077172 0.3116779266 -0.222296590412 +1403636714613555456.0000000000 -1.5340782695 7.2944252651 -0.5272015035 0.5201537707 0.7607136054 0.3169289062 -0.22430098927 +1403636714663555584.0000000000 -1.5157857615 7.2664705722 -0.5298793271 0.5173061369 0.7591823799 0.3236445473 -0.226474461602 +1403636714713555456.0000000000 -1.4978895688 7.2394138650 -0.5313641569 0.5141290787 0.7569757355 0.3312436682 -0.230079678699 +1403636714763555584.0000000000 -1.4801427611 7.2134124814 -0.5312602303 0.5113359430 0.7536763729 0.3403325242 -0.233840226013 +1403636714813555456.0000000000 -1.4629686453 7.1884835422 -0.5291355287 0.5097484373 0.7486341352 0.3509932722 -0.237712400292 +1403636714863555584.0000000000 -1.4462492844 7.1645936462 -0.5251263734 0.5084466748 0.7428042343 0.3622842547 -0.241813910156 +1403636714913555456.0000000000 -1.4302078174 7.1415016538 -0.5193520697 0.5060710277 0.7372946145 0.3734362648 -0.246645742801 +1403636714963555584.0000000000 -1.4150730767 7.1191748615 -0.5113266619 0.5026026801 0.7323379156 0.3840529473 -0.252140946827 +1403636715013555456.0000000000 -1.4007156994 7.0978708723 -0.5013383223 0.4999003406 0.7274489638 0.3936067703 -0.256887845008 +1403636715063555584.0000000000 -1.3873947592 7.0774847712 -0.4894024963 0.4970921022 0.7230834673 0.4022456445 -0.261243531524 +1403636715113555456.0000000000 -1.3744646272 7.0579187143 -0.4762147859 0.4948206808 0.7191997508 0.4103970097 -0.263587759062 +1403636715163555584.0000000000 -1.3628150762 7.0390625519 -0.4618393303 0.4923090689 0.7163536005 0.4159715444 -0.267276961225 +1403636715213555456.0000000000 -1.3522649307 7.0213728174 -0.4470684616 0.4910055961 0.7135995491 0.4208162064 -0.269449268841 +1403636715263555584.0000000000 -1.3429027608 7.0042495287 -0.4331429745 0.4900143011 0.7113078298 0.4236424776 -0.272862982447 +1403636715313555456.0000000000 -1.3346887524 6.9878304350 -0.4206847271 0.4896723771 0.7092902447 0.4247980853 -0.276902326961 +1403636715363555584.0000000000 -1.3275102075 6.9719967153 -0.4099513333 0.4897390468 0.7075307045 0.4259201656 -0.279549603369 +1403636715413555456.0000000000 -1.3216860257 6.9566518736 -0.4003766445 0.4900426502 0.7062063576 0.4241840744 -0.284953772416 +1403636715463555584.0000000000 -1.3163385559 6.9419061982 -0.3929989360 0.4905999763 0.7051561546 0.4221389501 -0.289594833434 +1403636715513555456.0000000000 -1.3113270128 6.9274327138 -0.3875504345 0.4898714736 0.7052091426 0.4184881616 -0.295928476396 +1403636715563555584.0000000000 -1.3061942198 6.9136405543 -0.3838222796 0.4878343426 0.7063862005 0.4137953464 -0.303000992101 +1403636715613555456.0000000000 -1.3005285949 6.9012574151 -0.3830674301 0.4867366529 0.7071085797 0.4120033301 -0.30551291811 +1403636715663555584.0000000000 -1.2945403802 6.8906352235 -0.3833623964 0.4901490930 0.7050542778 0.4107191437 -0.306532407679 +1403636715713555456.0000000000 -1.2880718174 6.8814287431 -0.3850905417 0.4968476918 0.7008779062 0.4104738482 -0.305652992427 +1403636715763555584.0000000000 -1.2807627272 6.8729673502 -0.3874082321 0.5032484515 0.6970371676 0.4106013227 -0.303787321895 +1403636715813555456.0000000000 -1.2726909498 6.8648257744 -0.3894223586 0.5089238367 0.6937660242 0.4104237873 -0.302055536213 +1403636715863555584.0000000000 -1.2643810231 6.8568289387 -0.3896668047 0.5134799105 0.6910151416 0.4097794936 -0.301524828515 +1403636715913555456.0000000000 -1.2546535554 6.8486351344 -0.3879120744 0.5184195878 0.6881400777 0.4095319263 -0.299979942263 +1403636715963555584.0000000000 -1.2437396506 6.8397607113 -0.3844998889 0.5211337266 0.6869943180 0.4082019563 -0.299715880421 +1403636716013555456.0000000000 -1.2310559949 6.8300352423 -0.3807014914 0.5225125666 0.6866423501 0.4072190928 -0.299458697023 +1403636716063555584.0000000000 -1.2176269923 6.8200331961 -0.3761650877 0.5226833970 0.6873632682 0.4065700583 -0.298386648056 +1403636716113555456.0000000000 -1.2028346533 6.8092997510 -0.3702142768 0.5212825010 0.6891895860 0.4051375167 -0.298573041541 +1403636716163555584.0000000000 -1.1866260456 6.7979944954 -0.3635004232 0.5175107723 0.6928722051 0.4049657723 -0.296839066089 +1403636716213555456.0000000000 -1.1690517152 6.7860232802 -0.3554212847 0.5125753082 0.6975033316 0.4048493396 -0.294707767214 +1403636716263555584.0000000000 -1.1506249130 6.7741767569 -0.3476319334 0.5101832715 0.7004248099 0.4045910509 -0.292274180693 +1403636716313555456.0000000000 -1.1315558301 6.7622841525 -0.3409698489 0.5078960614 0.7031172249 0.4043885046 -0.290064986178 +1403636716363555584.0000000000 -1.1121637943 6.7508208968 -0.3358702839 0.5063037739 0.7053340602 0.4037399505 -0.288365054069 +1403636716413555456.0000000000 -1.0927404056 6.7395677096 -0.3321431565 0.5063202904 0.7062369211 0.4027729050 -0.287477237046 +1403636716463555584.0000000000 -1.0730490655 6.7285078080 -0.3304684999 0.5061629208 0.7071519139 0.4024027714 -0.286019715871 +1403636716513555456.0000000000 -1.0535792316 6.7177525683 -0.3300928158 0.5068807668 0.7075015106 0.4013516213 -0.285360082962 +1403636716563555584.0000000000 -1.0339964790 6.7069782347 -0.3314333806 0.5082679805 0.7063979295 0.4023423261 -0.284229269791 +1403636716613555456.0000000000 -1.0143047592 6.6958680432 -0.3341804107 0.5083350651 0.7053741576 0.4041807749 -0.284043413149 +1403636716663555584.0000000000 -0.9944373826 6.6843126890 -0.3382418534 0.5080526759 0.7035369151 0.4066539868 -0.285571046747 +1403636716713555456.0000000000 -0.9743304644 6.6723049032 -0.3436521860 0.5069556771 0.7014010898 0.4103026726 -0.287548551576 +1403636716763555584.0000000000 -0.9539965884 6.6600646195 -0.3502436475 0.5056188729 0.6989207813 0.4138246077 -0.290875387122 +1403636716813555456.0000000000 -0.9330903832 6.6472709429 -0.3573847396 0.5034015314 0.6959386698 0.4187811861 -0.294751733193 +1403636716863555584.0000000000 -0.9120641500 6.6341988647 -0.3641103814 0.5004708731 0.6927514159 0.4244289565 -0.299139502311 +1403636716913555456.0000000000 -0.8906583196 6.6206654210 -0.3696769619 0.4971430298 0.6887797277 0.4310800253 -0.304304627746 +1403636716963555584.0000000000 -0.8687529236 6.6068095872 -0.3738167860 0.4931130981 0.6841262702 0.4397383748 -0.308935075117 +1403636717013555456.0000000000 -0.8466047621 6.5931504735 -0.3759624117 0.4897815459 0.6786721088 0.4477263466 -0.314736913271 +1403636717063555584.0000000000 -0.8245162559 6.5796264184 -0.3764274552 0.4857024462 0.6732913616 0.4565682627 -0.319870751398 +1403636717113555456.0000000000 -0.8024385504 6.5660861240 -0.3750743898 0.4822222470 0.6677137624 0.4646821077 -0.325100868695 +1403636717163555584.0000000000 -0.7805664322 6.5531026219 -0.3722875872 0.4796848292 0.6627685888 0.4718644350 -0.328609521116 +1403636717213555456.0000000000 -0.7589915378 6.5403970197 -0.3686046109 0.4772828417 0.6584045037 0.4782047786 -0.331699846692 +1403636717263555584.0000000000 -0.7370935685 6.5280866054 -0.3647721306 0.4764761686 0.6538995357 0.4843961060 -0.332785622311 +1403636717313555456.0000000000 -0.7150239720 6.5159166549 -0.3610439972 0.4766501456 0.6495606563 0.4906840276 -0.331820399491 +1403636717363555584.0000000000 -0.6930458269 6.5037598840 -0.3567960404 0.4787403950 0.6446126875 0.4965497698 -0.32972783229 +1403636717413555456.0000000000 -0.6712554027 6.4910036589 -0.3527840816 0.4805639977 0.6404477832 0.5014094589 -0.327831413568 +1403636717463555584.0000000000 -0.6494908946 6.4773358573 -0.3490016719 0.4814377133 0.6376715052 0.5045466857 -0.327147400551 +1403636717513555456.0000000000 -0.6280823175 6.4623406940 -0.3466826635 0.4809751575 0.6366295802 0.5061307354 -0.327410070238 +1403636717563555584.0000000000 -0.6072309901 6.4459688887 -0.3455358651 0.4798162623 0.6365116819 0.5058401560 -0.329780184106 +1403636717613555456.0000000000 -0.5867546955 6.4284959830 -0.3460880474 0.4773446490 0.6377683043 0.5048134510 -0.332501211642 +1403636717663555584.0000000000 -0.5665060424 6.4103963286 -0.3484616744 0.4769853314 0.6379528028 0.5038883665 -0.334062463039 +1403636717713555456.0000000000 -0.5465410300 6.3914119207 -0.3525414692 0.4765750906 0.6383414248 0.5028251038 -0.335504580264 +1403636717763555584.0000000000 -0.5264704489 6.3716339129 -0.3584785136 0.4773606063 0.6370509697 0.5050157747 -0.333544571134 +1403636717813555456.0000000000 -0.5064612075 6.3504340159 -0.3643616884 0.4768429707 0.6357727395 0.5070646752 -0.333615377581 +1403636717863555584.0000000000 -0.4866051851 6.3278688860 -0.3693693179 0.4760819490 0.6333609409 0.5106905163 -0.33375903435 +1403636717913555456.0000000000 -0.4671223288 6.3038152603 -0.3728270620 0.4748276511 0.6302117412 0.5148650100 -0.335090860081 +1403636717963555584.0000000000 -0.4477426174 6.2782772352 -0.3746781448 0.4736396843 0.6262905458 0.5195303403 -0.336918131491 +1403636718013555456.0000000000 -0.4286071093 6.2507909247 -0.3743488616 0.4711004329 0.6220630626 0.5245882894 -0.340454189171 +1403636718063555584.0000000000 -0.4098570998 6.2218115956 -0.3723349607 0.4674659766 0.6179820428 0.5298700308 -0.344690449487 +1403636718113555456.0000000000 -0.3913178061 6.1910210580 -0.3683998858 0.4621315087 0.6141454043 0.5342440079 -0.351913669933 +1403636718163555584.0000000000 -0.3732639905 6.1592541391 -0.3644400346 0.4560678879 0.6106147560 0.5388875856 -0.358820110106 +1403636718213555456.0000000000 -0.3556405114 6.1268985091 -0.3615553192 0.4506037951 0.6072974553 0.5429257311 -0.365209078715 +1403636718263555584.0000000000 -0.3376015143 6.0942335114 -0.3608824105 0.4455499507 0.6044768429 0.5467181217 -0.37039476693 +1403636718313555456.0000000000 -0.3195415138 6.0612414434 -0.3623557881 0.4405045845 0.6022051113 0.5499342790 -0.375335854602 +1403636718363555584.0000000000 -0.3016202871 6.0279076961 -0.3658535157 0.4362815743 0.5989061043 0.5537381351 -0.379926234907 +1403636718413555456.0000000000 -0.2838461020 5.9941098347 -0.3708725149 0.4312279247 0.5959721383 0.5578178952 -0.384316123936 +1403636718463555584.0000000000 -0.2665397801 5.9599955747 -0.3770339036 0.4259860608 0.5928852771 0.5612012172 -0.389969380768 +1403636718513555456.0000000000 -0.2491698373 5.9259441823 -0.3847716475 0.4215995801 0.5887235732 0.5653601909 -0.395001522699 +1403636718563555584.0000000000 -0.2320809016 5.8921977335 -0.3935000762 0.4165780230 0.5859971290 0.5682283027 -0.400233321494 +1403636718613555456.0000000000 -0.2154687418 5.8589646684 -0.4031859304 0.4114489776 0.5839153541 0.5708218873 -0.404864139067 +1403636718663555584.0000000000 -0.1992276984 5.8265165512 -0.4135541223 0.4054067962 0.5830674441 0.5720551702 -0.410402932996 +1403636718713555456.0000000000 -0.1833865069 5.7953762642 -0.4254270608 0.4001211175 0.5821407732 0.5738650751 -0.414359852208 +1403636718763555584.0000000000 -0.1681753601 5.7657664222 -0.4381328070 0.3976032354 0.5798799490 0.5757501452 -0.417328027046 +1403636718813555456.0000000000 -0.1529330531 5.7379211720 -0.4524979214 0.3976402448 0.5765757316 0.5793318285 -0.416914012605 +1403636718863555584.0000000000 -0.1384237724 5.7113500860 -0.4664287807 0.3998094667 0.5723521051 0.5835211735 -0.414811400824 +1403636718913555456.0000000000 -0.1244828453 5.6855740953 -0.4790272888 0.4022077970 0.5685137138 0.5867534006 -0.413208775528 +1403636718963555584.0000000000 -0.1103621876 5.6604685797 -0.4898795601 0.4050310841 0.5649012779 0.5893859418 -0.411655898486 +1403636719013555456.0000000000 -0.0969516269 5.6355540647 -0.4980913644 0.4068741923 0.5622528838 0.5913378807 -0.410663605833 +1403636719063555584.0000000000 -0.0833983769 5.6106933090 -0.5038178389 0.4086199042 0.5600462241 0.5918363594 -0.411227095956 +1403636719113555456.0000000000 -0.0697651557 5.5858654397 -0.5077583905 0.4107874666 0.5579698122 0.5917625396 -0.411995682832 +1403636719163555584.0000000000 -0.0569057114 5.5606823295 -0.5092322868 0.4126040081 0.5564101352 0.5904693888 -0.414139583774 +1403636719213555456.0000000000 -0.0437590411 5.5353731033 -0.5091770721 0.4143068201 0.5553249866 0.5887724540 -0.416306396276 +1403636719263555584.0000000000 -0.0302700658 5.5100611491 -0.5096988593 0.4161537133 0.5543546553 0.5869795601 -0.418284591075 +1403636719313555456.0000000000 -0.0161423252 5.4846257929 -0.5113672830 0.4161583740 0.5548402448 0.5844830189 -0.421122442016 +1403636719363555584.0000000000 -0.0013810136 5.4595847656 -0.5148835759 0.4174997678 0.5544207051 0.5827964568 -0.42268181356 +1403636719413555456.0000000000 0.0142803556 5.4346554162 -0.5201866023 0.4179143046 0.5546982701 0.5813409903 -0.423910505026 +1403636719463555584.0000000000 0.0306705050 5.4101713964 -0.5270651728 0.4179706251 0.5554165181 0.5799482292 -0.424821255862 +1403636719513555456.0000000000 0.0478346207 5.3862165182 -0.5357434516 0.4176897481 0.5564122052 0.5789752765 -0.42512158429 +1403636719563555584.0000000000 0.0658979343 5.3627111300 -0.5459238658 0.4162291026 0.5583760482 0.5794729842 -0.423297275601 +1403636719613555456.0000000000 0.0848870620 5.3394803233 -0.5556400812 0.4139508799 0.5608668229 0.5792312773 -0.422568578305 +1403636719663555584.0000000000 0.1039071671 5.3169973476 -0.5637412121 0.4126487108 0.5629806513 0.5802161767 -0.41967012759 +1403636719713555456.0000000000 0.1235482899 5.2950124878 -0.5696666105 0.4110009386 0.5655013260 0.5807107181 -0.417206832029 +1403636719763555584.0000000000 0.1437412186 5.2734898738 -0.5733577518 0.4100856801 0.5676194130 0.5806387654 -0.415327053229 +1403636719813555456.0000000000 0.1634927065 5.2524471679 -0.5747745837 0.4092552746 0.5696783952 0.5803972342 -0.413661331099 +1403636719863555584.0000000000 0.1834292123 5.2319831135 -0.5740897303 0.4093143573 0.5710462297 0.5795257642 -0.412938069248 +1403636719913555456.0000000000 0.2036365792 5.2119290525 -0.5722590665 0.4092319121 0.5724313462 0.5786896193 -0.41227408433 +1403636719963555584.0000000000 0.2237975948 5.1922747303 -0.5706536336 0.4084203292 0.5740568534 0.5785199060 -0.411055084186 +1403636720013555456.0000000000 0.2437608892 5.1733930296 -0.5699219783 0.4091902931 0.5747185349 0.5781693113 -0.409856263934 +1403636720063555584.0000000000 0.2632888405 5.1547727054 -0.5706036120 0.4087805469 0.5754748036 0.5779243143 -0.409549388711 +1403636720113555456.0000000000 0.2824348672 5.1366990051 -0.5728241385 0.4090847197 0.5757857813 0.5779489908 -0.408773030195 +1403636720163555584.0000000000 0.3015346745 5.1190783567 -0.5769652692 0.4086011557 0.5764575439 0.5782359384 -0.407903168927 +1403636720213555456.0000000000 0.3201833736 5.1018305790 -0.5821636130 0.4080436529 0.5768732750 0.5779298087 -0.408307161428 +1403636720263555584.0000000000 0.3384832105 5.0849116068 -0.5882602339 0.4080198272 0.5768472760 0.5777973723 -0.408555060381 +1403636720313555456.0000000000 0.3563610234 5.0683476285 -0.5952544644 0.4075944285 0.5770778558 0.5774603338 -0.409130166561 +1403636720363555584.0000000000 0.3739975765 5.0523268716 -0.6032551608 0.4076063429 0.5767317651 0.5777811637 -0.409153354072 +1403636720413555456.0000000000 0.3914934061 5.0367115841 -0.6120759387 0.4070663842 0.5765686423 0.5779600990 -0.409667772052 +1403636720463555584.0000000000 0.4087690048 5.0216263934 -0.6206848246 0.4059971750 0.5767156737 0.5782177739 -0.410157934854 +1403636720513555456.0000000000 0.4260117041 5.0072264131 -0.6279096700 0.4052090924 0.5767880354 0.5785111081 -0.410421797043 +1403636720563555584.0000000000 0.4429544668 4.9934803340 -0.6334447755 0.4043441738 0.5766638192 0.5786194247 -0.411295745323 +1403636720613555456.0000000000 0.4596057324 4.9805370499 -0.6376476887 0.4043880620 0.5761051537 0.5797853708 -0.410392581555 +1403636720663555584.0000000000 0.4759102621 4.9679958282 -0.6394946490 0.4034540743 0.5759161512 0.5799530066 -0.411339162704 +1403636720713555456.0000000000 0.4924554620 4.9563673658 -0.6394531870 0.4045209506 0.5752972399 0.5793777644 -0.41196758649 +1403636720763555584.0000000000 0.5083114581 4.9454625544 -0.6375643362 0.4044401940 0.5765861328 0.5784284015 -0.411578844608 +1403636720813555456.0000000000 0.5232064615 4.9355863589 -0.6347867448 0.4058032202 0.5785095055 0.5767981393 -0.409822406615 +1403636720863555584.0000000000 0.5373355170 4.9265577429 -0.6322640629 0.4083709353 0.5807218987 0.5748299140 -0.406897807237 +1403636720913555456.0000000000 0.5511785224 4.9182057375 -0.6307150474 0.4109563941 0.5842645222 0.5713278305 -0.404146409515 +1403636720963555584.0000000000 0.5644278065 4.9104720966 -0.6306587638 0.4142692249 0.5877156153 0.5669372326 -0.40193723277 +1403636721013555456.0000000000 0.5775661345 4.9029463159 -0.6321815661 0.4168085612 0.5913400495 0.5619933454 -0.400937712003 +1403636721063555584.0000000000 0.5903374959 4.8959726910 -0.6351472680 0.4201487938 0.5948608181 0.5567270237 -0.399588061948 +1403636721113555456.0000000000 0.6029910551 4.8897486136 -0.6397742187 0.4232511893 0.5991247423 0.5513567510 -0.397383576838 +1403636721163555584.0000000000 0.6153764012 4.8844558576 -0.6452772103 0.4283536405 0.6029605065 0.5453188127 -0.39443526557 +1403636721213555456.0000000000 0.6281218745 4.8794867613 -0.6505206026 0.4321360451 0.6074039264 0.5394058323 -0.39161238079 +1403636721263555584.0000000000 0.6411898071 4.8750485993 -0.6540508276 0.4363672587 0.6107827137 0.5331873465 -0.390178607407 +1403636721313555456.0000000000 0.6541818209 4.8712321869 -0.6561087404 0.4391070675 0.6143817471 0.5290652154 -0.387053032583 +1403636721363555584.0000000000 0.6682087160 4.8679539355 -0.6561615125 0.4419727921 0.6174998382 0.5252720628 -0.383983412284 +1403636721413555456.0000000000 0.6826820062 4.8651281207 -0.6541110973 0.4450289972 0.6194893023 0.5221784602 -0.381460157358 +1403636721463555584.0000000000 0.6976776284 4.8623198052 -0.6509319913 0.4466148074 0.6219519627 0.5196014440 -0.379111209741 +1403636721513555456.0000000000 0.7131288446 4.8600095910 -0.6473779144 0.4488435581 0.6244783904 0.5173377817 -0.375403542778 +1403636721563555584.0000000000 0.7287052199 4.8581290535 -0.6444587371 0.4507639298 0.6275946672 0.5144275421 -0.371888581807 +1403636721613555456.0000000000 0.7445331153 4.8564776601 -0.6430173172 0.4531403548 0.6303933722 0.5119356892 -0.367681744634 +1403636721663555584.0000000000 0.7606291578 4.8547649832 -0.6431502389 0.4546886247 0.6330085691 0.5099309904 -0.364045039848 +1403636721713555456.0000000000 0.7768018800 4.8531131137 -0.6442363092 0.4571906338 0.6340828917 0.5078998521 -0.361874772581 +1403636721763555584.0000000000 0.7934298933 4.8513648094 -0.6470531017 0.4590421041 0.6350871957 0.5071783565 -0.358768330994 +1403636721813555456.0000000000 0.8104049740 4.8492512840 -0.6509610951 0.4600836558 0.6358918796 0.5059047904 -0.357805659742 +1403636721863555584.0000000000 0.8274104357 4.8470461454 -0.6560616722 0.4606501437 0.6364805787 0.5046143184 -0.357852354653 +1403636721913555456.0000000000 0.8443480187 4.8446214380 -0.6622150436 0.4611878224 0.6366757452 0.5042428334 -0.357335910542 +1403636721963555584.0000000000 0.8613842541 4.8422438249 -0.6690552403 0.4628692797 0.6354943178 0.5054851212 -0.355504984645 +1403636722013555456.0000000000 0.8784471722 4.8397526716 -0.6750416993 0.4646964842 0.6340902437 0.5071487053 -0.353251937257 +1403636722063555584.0000000000 0.8954568760 4.8368447556 -0.6791935091 0.4661471276 0.6326678303 0.5088729041 -0.351406658188 +1403636722113555456.0000000000 0.9126188322 4.8332254736 -0.6810870331 0.4659464424 0.6320697818 0.5098844955 -0.351282656902 +1403636722163555584.0000000000 0.9299963074 4.8289191761 -0.6810891709 0.4645533279 0.6325010325 0.5098593763 -0.352386245305 +1403636722213555456.0000000000 0.9473590064 4.8241541319 -0.6790892045 0.4633481114 0.6326670229 0.5099583576 -0.353529969371 +1403636722263555584.0000000000 0.9647768752 4.8188579539 -0.6759219120 0.4617231573 0.6331213892 0.5100580230 -0.354696836433 +1403636722313555456.0000000000 0.9819960050 4.8131903417 -0.6726395302 0.4605546418 0.6331487274 0.5097421228 -0.356616150936 +1403636722363555584.0000000000 0.9993358627 4.8075065559 -0.6707618682 0.4597764404 0.6335194692 0.5097442421 -0.356958701554 +1403636722413555456.0000000000 1.0166166606 4.8021227150 -0.6703316310 0.4601787882 0.6342310918 0.5091335024 -0.356047022022 +1403636722463555584.0000000000 1.0338645953 4.7968248526 -0.6711172588 0.4614753463 0.6351309566 0.5074944542 -0.35510357883 +1403636722513555456.0000000000 1.0511292557 4.7913743951 -0.6730541069 0.4621908175 0.6365471321 0.5055647303 -0.354389193238 +1403636722563555584.0000000000 1.0684950881 4.7857760174 -0.6760707491 0.4629273633 0.6377920772 0.5042058078 -0.353123244582 +1403636722613555456.0000000000 1.0856061600 4.7800370396 -0.6798341141 0.4642800089 0.6381838075 0.5038005953 -0.351212843352 +1403636722663555584.0000000000 1.1026887258 4.7740908652 -0.6841172550 0.4649618212 0.6389881827 0.5031548723 -0.349771041892 +1403636722713555456.0000000000 1.1195713441 4.7678857968 -0.6886300246 0.4661668100 0.6391876224 0.5024753896 -0.348778112152 +1403636722763555584.0000000000 1.1363517920 4.7613774164 -0.6934387138 0.4670351530 0.6394729156 0.5025063863 -0.347044504015 +1403636722813555456.0000000000 1.1530245649 4.7545745617 -0.6969453334 0.4672834446 0.6398261855 0.5027629265 -0.345684935411 +1403636722863555584.0000000000 1.1698859280 4.7472014465 -0.6978851691 0.4681162759 0.6397223119 0.5027793892 -0.344725110292 +1403636722913555456.0000000000 1.1866977476 4.7391614058 -0.6971615174 0.4675594296 0.6404519751 0.5021433229 -0.345052938762 +1403636722963555584.0000000000 1.2035094456 4.7306317493 -0.6947114184 0.4666071406 0.6411639893 0.5017658643 -0.345568419425 +1403636723013555456.0000000000 1.2212584081 4.7215071303 -0.6911256318 0.4658280521 0.6416253737 0.5007923590 -0.347171598657 +1403636723063555584.0000000000 1.2375824740 4.7123793324 -0.6848919862 0.4651072362 0.6420844807 0.4994413445 -0.349229325592 +1403636723113555456.0000000000 1.2539424209 4.7032463416 -0.6788632763 0.4646844078 0.6423335768 0.4989398766 -0.350049963312 +1403636723163555584.0000000000 1.2702830057 4.6941981748 -0.6734926169 0.4647207784 0.6424136534 0.4986978791 -0.350199545168 +1403636723213555456.0000000000 1.2866240631 4.6850370286 -0.6692958266 0.4644245516 0.6427734494 0.4983970576 -0.350360530973 +1403636723263555584.0000000000 1.3030353643 4.6758972648 -0.6665346802 0.4645948921 0.6427460692 0.4992022551 -0.349036080328 +1403636723313555456.0000000000 1.3193631632 4.6669164603 -0.6649801606 0.4661832676 0.6419267763 0.4999211538 -0.347393170551 +1403636723363555584.0000000000 1.3355858242 4.6578382940 -0.6641976079 0.4673647957 0.6424149919 0.4992306391 -0.345892895201 +1403636723413555456.0000000000 1.3517811846 4.6489606566 -0.6645889147 0.4702243685 0.6429693503 0.4978127425 -0.343018849661 +1403636723463555584.0000000000 1.3677535726 4.6401744230 -0.6651846859 0.4746372105 0.6433116911 0.4952748650 -0.33995940137 +1403636723513555456.0000000000 1.3835577094 4.6309615789 -0.6655357415 0.4792014926 0.6444095174 0.4900047807 -0.33911298734 +1403636723563555584.0000000000 1.3982146170 4.6212672253 -0.6637126611 0.4840593775 0.6451209893 0.4828402097 -0.341131587682 +1403636723613555456.0000000000 1.4136572768 4.6109083060 -0.6605120592 0.4887947478 0.6454361368 0.4761133053 -0.343231712338 +1403636723663555584.0000000000 1.4304365748 4.6001927506 -0.6562631070 0.4904234771 0.6477152762 0.4719193267 -0.342406020911 +1403636723713555456.0000000000 1.4478954367 4.5887684297 -0.6513482348 0.4893564471 0.6514231151 0.4705466065 -0.33876848133 +1403636723763555584.0000000000 1.4665899828 4.5765727303 -0.6455011403 0.4875554721 0.6557195348 0.4692342658 -0.334874240691 +1403636723813555456.0000000000 1.4858073909 4.5637647465 -0.6401766367 0.4846607561 0.6601700515 0.4679847560 -0.332068852503 +1403636723863555584.0000000000 1.5054059010 4.5508401548 -0.6355269257 0.4827834929 0.6635706444 0.4668507208 -0.329612656634 +1403636723913555456.0000000000 1.5250198112 4.5377031338 -0.6324209293 0.4807017918 0.6668396185 0.4658956578 -0.327401812158 +1403636723963555584.0000000000 1.5446282126 4.5245346029 -0.6310260845 0.4780226319 0.6704050512 0.4652792857 -0.324910167586 +1403636724013555456.0000000000 1.5640600590 4.5117955302 -0.6311464322 0.4763267910 0.6738305958 0.4646480986 -0.321196607771 +1403636724063555584.0000000000 1.5828569335 4.4997467928 -0.6324006798 0.4754114606 0.6776537498 0.4626364311 -0.317390723204 +1403636724113555456.0000000000 1.6013498081 4.4882986134 -0.6353223872 0.4749595718 0.6819979206 0.4600477602 -0.312487279471 +1403636724163555584.0000000000 1.6190471743 4.4775773648 -0.6388711176 0.4775895417 0.6849063635 0.4558248676 -0.308277785496 +1403636724213555456.0000000000 1.6359594936 4.4672691012 -0.6437899201 0.4788133889 0.6893426292 0.4504840879 -0.304316553629 +1403636724263555584.0000000000 1.6518308153 4.4577884592 -0.6494681611 0.4818164213 0.6931957924 0.4444006092 -0.299734262576 +1403636724313555456.0000000000 1.6668899449 4.4487438081 -0.6556383051 0.4860919522 0.6963811825 0.4380217670 -0.294796191137 +1403636724363555584.0000000000 1.6807113922 4.4401675526 -0.6617927002 0.4906499566 0.6994396161 0.4307843405 -0.290640147652 +1403636724413555456.0000000000 1.6947681924 4.4314739078 -0.6664950335 0.4959828311 0.7018857540 0.4233060526 -0.286652063354 +1403636724463555584.0000000000 1.7084515563 4.4225462889 -0.6696304550 0.4997595850 0.7043905717 0.4168135711 -0.283444397923 +1403636724513555456.0000000000 1.7216966767 4.4135600747 -0.6708702462 0.5043865870 0.7054636276 0.4115409803 -0.280266413317 +1403636724563555584.0000000000 1.7351872410 4.4039346937 -0.6709390621 0.5078256192 0.7065662515 0.4067907264 -0.27820599838 +1403636724613555456.0000000000 1.7480347140 4.3943783304 -0.6694177642 0.5097802335 0.7082074487 0.4032776344 -0.275560288734 +1403636724663555584.0000000000 1.7604826348 4.3843944639 -0.6651330322 0.5114841917 0.7092274469 0.4005082868 -0.273812823713 +1403636724713555456.0000000000 1.7727179522 4.3739593825 -0.6589211009 0.5121762960 0.7105119941 0.3982884148 -0.272423359197 +1403636724763555584.0000000000 1.7845807151 4.3632435992 -0.6505391263 0.5123168005 0.7117328428 0.3967628340 -0.271195704306 +1403636724813555456.0000000000 1.7964077715 4.3520460337 -0.6402090628 0.5119692974 0.7127595457 0.3960120155 -0.270251275982 +1403636724863555584.0000000000 1.8078968596 4.3405431710 -0.6277908677 0.5110303861 0.7137706873 0.3954783519 -0.270141118067 +1403636724913555456.0000000000 1.8190289521 4.3286376280 -0.6134354534 0.5095656293 0.7147599566 0.3948378022 -0.271227181094 +1403636724963555584.0000000000 1.8298889575 4.3165284739 -0.5971756258 0.5077225836 0.7157902927 0.3941813802 -0.272915874444 +1403636725013555456.0000000000 1.8403011946 4.3044558820 -0.5789537369 0.5060056784 0.7164842919 0.3933971653 -0.27540367314 +1403636725063555584.0000000000 1.8506610265 4.2925893805 -0.5586379887 0.5050165447 0.7167065986 0.3926546421 -0.277690967 +1403636725113555456.0000000000 1.8610531426 4.2811010443 -0.5367737116 0.5036261393 0.7171593152 0.3924697608 -0.279303983651 +1403636725163555584.0000000000 1.8711224606 4.2703105920 -0.5142566804 0.5018828415 0.7179168592 0.3924369168 -0.280539236342 +1403636725213555456.0000000000 1.8812447830 4.2602391430 -0.4922907551 0.5021073233 0.7173839128 0.3932047141 -0.280425766121 +1403636725263555584.0000000000 1.8912273669 4.2504437458 -0.4713423747 0.5013789089 0.7174004792 0.3937392528 -0.280936190266 +1403636725313555456.0000000000 1.9012548528 4.2415640080 -0.4519694927 0.5019717900 0.7168804174 0.3951732453 -0.279186130262 +1403636725363555584.0000000000 1.9111346337 4.2331793310 -0.4338669197 0.5023020181 0.7164620622 0.3960210494 -0.27846386544 +1403636725413555456.0000000000 1.9208164334 4.2252223671 -0.4172451779 0.5033635106 0.7156096431 0.3969950684 -0.27734983415 +1403636725463555584.0000000000 1.9302190360 4.2174700484 -0.4021853135 0.5037507634 0.7153179826 0.3974079838 -0.2768072372 +1403636725513555456.0000000000 1.9396033191 4.2100706510 -0.3886963532 0.5043755761 0.7148332432 0.3982988665 -0.275638759137 +1403636725563555584.0000000000 1.9489922970 4.2028742194 -0.3769832022 0.5043307320 0.7150235716 0.3987973996 -0.27450398693 +1403636725613555456.0000000000 1.9580155648 4.1960001349 -0.3665409980 0.5051321150 0.7145235373 0.3993983786 -0.273456753697 +1403636725663555584.0000000000 1.9665440495 4.1891816150 -0.3574897743 0.5063990856 0.7137183580 0.3988466263 -0.274020875669 +1403636725713555456.0000000000 1.9746968407 4.1824192996 -0.3499839538 0.5064303663 0.7138339685 0.3983365382 -0.274403629451 +1403636725763555584.0000000000 1.9825921458 4.1755826019 -0.3442024321 0.5061074761 0.7139887651 0.3986011630 -0.274212287836 +1403636725813555456.0000000000 1.9903327090 4.1688716763 -0.3398345952 0.5064208627 0.7136584465 0.3987343537 -0.274299921023 +1403636725863555584.0000000000 1.9978584034 4.1621863345 -0.3369600588 0.5049360510 0.7145003609 0.3991092195 -0.274300290873 +1403636725913555456.0000000000 2.0048572330 4.1557069760 -0.3348849501 0.5040102318 0.7149248249 0.3983173331 -0.276042538688 +1403636725963555584.0000000000 2.0117221494 4.1494471512 -0.3343331950 0.5031765216 0.7151959688 0.3985561554 -0.276516012659 +1403636726013555456.0000000000 2.0183608582 4.1434618625 -0.3346928555 0.5033346467 0.7148207216 0.3981864746 -0.277728465887 +1403636726063555584.0000000000 2.0247772164 4.1378545509 -0.3363711005 0.5038159993 0.7141134593 0.3989011250 -0.277649596762 +1403636726113555456.0000000000 2.0311345389 4.1325044756 -0.3392936085 0.5044828990 0.7133569924 0.3996953078 -0.277240810449 +1403636726163555584.0000000000 2.0372376509 4.1273135368 -0.3431694166 0.5060555316 0.7119045799 0.3999184585 -0.2777856991 +1403636726213555456.0000000000 2.0434301501 4.1220995253 -0.3484905366 0.5065401158 0.7111892409 0.4002398617 -0.278271500275 +1403636726263555584.0000000000 2.0498460341 4.1167953841 -0.3543721824 0.5069655069 0.7104848131 0.4011504164 -0.277984979196 +1403636726313555456.0000000000 2.0561445196 4.1112705545 -0.3592081149 0.5070192493 0.7099508316 0.4015785965 -0.278632245873 +1403636726363555584.0000000000 2.0626502677 4.1057389645 -0.3627260654 0.5080567338 0.7088376676 0.4020187569 -0.278941634244 +1403636726413555456.0000000000 2.0684455920 4.1002429897 -0.3636118315 0.5081966014 0.7081803689 0.4025603353 -0.279574598126 +1403636726463555584.0000000000 2.0738259843 4.0946763906 -0.3621350598 0.5082088259 0.7076255801 0.4026086922 -0.28088443983 +1403636726513555456.0000000000 2.0789212661 4.0890728005 -0.3589682648 0.5072433532 0.7078932495 0.4016826331 -0.28327087779 +1403636726563555584.0000000000 2.0836249429 4.0833479583 -0.3532716122 0.5048263772 0.7090831487 0.3984017651 -0.289184112069 +1403636726613555456.0000000000 2.0894858187 4.0773652266 -0.3461052999 0.5013097917 0.7110488953 0.3941643225 -0.296196637491 +1403636726663555584.0000000000 2.0953734868 4.0725164333 -0.3375940865 0.4993941802 0.7118556271 0.3899695625 -0.302969898199 +1403636726713555456.0000000000 2.1030387143 4.0688494646 -0.3286142659 0.4989248575 0.7119675971 0.3897178606 -0.303802758982 +1403636726763555584.0000000000 2.1116634184 4.0665865416 -0.3179012436 0.5011789983 0.7103248381 0.3913933465 -0.301777209736 +1403636726813555456.0000000000 2.1206515253 4.0654796005 -0.3051526639 0.5037927207 0.7082239289 0.3946060665 -0.298157363591 +1403636726863555584.0000000000 2.1308846477 4.0643883590 -0.2905738347 0.5062562136 0.7053040533 0.3988580931 -0.295233907507 +1403636726913555456.0000000000 2.1420556813 4.0632552477 -0.2746590205 0.5075779569 0.7030767216 0.4026781168 -0.293083734512 +1403636726963555584.0000000000 2.1539548769 4.0619022492 -0.2572878335 0.5082472414 0.7012856431 0.4057615583 -0.291960179284 +1403636727013555456.0000000000 2.1655448575 4.0608239334 -0.2383168784 0.5085450582 0.7000522674 0.4075453088 -0.291917056471 +1403636727063555584.0000000000 2.1777223389 4.0597041250 -0.2185999223 0.5093980861 0.6986438235 0.4094974413 -0.291070856224 +1403636727113555456.0000000000 2.1901421965 4.0584104836 -0.1999374174 0.5096261825 0.6976754924 0.4116101910 -0.290012261925 +1403636727163555584.0000000000 2.2031353565 4.0569007286 -0.1827413365 0.5100917925 0.6967404683 0.4140277372 -0.287993256567 +1403636727213555456.0000000000 2.2161680592 4.0547433342 -0.1671251229 0.5106798359 0.6958329156 0.4161483943 -0.28608245794 +1403636727263555584.0000000000 2.2290259009 4.0519665628 -0.1530320665 0.5112909402 0.6949947927 0.4181054662 -0.284168315841 +1403636727313555456.0000000000 2.2418682268 4.0484698935 -0.1403980781 0.5120636543 0.6942137047 0.4199756649 -0.281919468983 +1403636727363555584.0000000000 2.2546362854 4.0441163880 -0.1284364873 0.5111925316 0.6946426186 0.4212213595 -0.280582241737 +1403636727413555456.0000000000 2.2669932891 4.0390415452 -0.1170833468 0.5114379374 0.6943114760 0.4219535157 -0.279853606562 +1403636727463555584.0000000000 2.2791355078 4.0333100573 -0.1063885662 0.5119939309 0.6938497467 0.4225184923 -0.279128764939 +1403636727513555456.0000000000 2.2910091474 4.0265211577 -0.0951043146 0.5121463095 0.6937414043 0.4210922990 -0.281265528041 +1403636727563555584.0000000000 2.3026544505 4.0187891556 -0.0828021762 0.5114490659 0.6942749641 0.4188391741 -0.28456260028 +1403636727613555456.0000000000 2.3146659358 4.0104661136 -0.0695425251 0.5119444435 0.6939418387 0.4177532357 -0.286076642537 +1403636727663555584.0000000000 2.3267228099 4.0013651468 -0.0552565055 0.5111051688 0.6945211530 0.4166114139 -0.287831208106 +1403636727713555456.0000000000 2.3384228346 3.9923133623 -0.0394496883 0.5102205678 0.6952285560 0.4172424529 -0.286776851584 +1403636727763555584.0000000000 2.3497393086 3.9828960703 -0.0216202882 0.5102600404 0.6951711137 0.4180102315 -0.285725848129 +1403636727813555456.0000000000 2.3611225229 3.9727246108 -0.0023261319 0.5104489573 0.6948772663 0.4191062910 -0.284494927221 +1403636727863555584.0000000000 2.3727819937 3.9621407647 0.0181182554 0.5122027891 0.6937451850 0.4217199819 -0.280210952763 +1403636727913555456.0000000000 2.3843620278 3.9505266395 0.0385266604 0.5143691249 0.6921982336 0.4239272993 -0.276715835454 +1403636727963555584.0000000000 2.3955039393 3.9377978467 0.0581163399 0.5148673671 0.6918226445 0.4245317511 -0.275800317731 +1403636728013555456.0000000000 2.4062215041 3.9238927610 0.0763559010 0.5140781154 0.6925351778 0.4238667130 -0.276506290095 +1403636728063555584.0000000000 2.4165258539 3.9091032550 0.0930055961 0.5131450876 0.6932916422 0.4230073305 -0.277657372037 +1403636728113555456.0000000000 2.4264213529 3.8932897972 0.1085171508 0.5126060767 0.6937762578 0.4207017312 -0.280926267259 +1403636728163555584.0000000000 2.4363001720 3.8771309806 0.1223932286 0.5127468683 0.6939752189 0.4192113297 -0.282402028345 +1403636728213555456.0000000000 2.4460927997 3.8602238727 0.1347776611 0.5126101074 0.6941011052 0.4178958681 -0.284284324117 +1403636728263555584.0000000000 2.4557922103 3.8429510515 0.1455425255 0.5125441647 0.6942547413 0.4169980486 -0.285344460021 +1403636728313555456.0000000000 2.4655972851 3.8249873623 0.1547449311 0.5117416690 0.6949325440 0.4162073749 -0.286287695547 +1403636728363555584.0000000000 2.4754973965 3.8066148783 0.1622201878 0.5117135133 0.6950868399 0.4163447511 -0.285763212287 +1403636728413555456.0000000000 2.4852483157 3.7873159382 0.1684655614 0.5094578516 0.6966565873 0.4145570251 -0.288556354564 +1403636728463555584.0000000000 2.4949295518 3.7678775604 0.1734938709 0.5069655886 0.6985572396 0.4111287230 -0.293218089723 +1403636728513555456.0000000000 2.5051506736 3.7484224945 0.1770632503 0.5033007989 0.7012190556 0.4074811290 -0.298226879099 +1403636728563555584.0000000000 2.5160969231 3.7292822333 0.1788583866 0.5010280989 0.7023617306 0.4062923769 -0.30097399863 +1403636728613555456.0000000000 2.5275513150 3.7106864355 0.1797407131 0.4997914626 0.7021317743 0.4062249406 -0.303645785472 +1403636728663555584.0000000000 2.5400730696 3.6927047968 0.1796616597 0.5001370488 0.6998837271 0.4106776089 -0.302274052157 +1403636728713555456.0000000000 2.5531245050 3.6749905313 0.1805268454 0.5012038838 0.6960791374 0.4165375356 -0.3012722736 +1403636728763555584.0000000000 2.5663417091 3.6572190351 0.1833067367 0.5011949895 0.6918926195 0.4234382179 -0.301310904582 +1403636728813555456.0000000000 2.5798857340 3.6393404556 0.1878460107 0.5007492675 0.6872059580 0.4311814996 -0.301795720414 +1403636728863555584.0000000000 2.5938948914 3.6208290208 0.1944077253 0.4998532142 0.6829368783 0.4377146769 -0.303561931196 +1403636728913555456.0000000000 2.6081169636 3.6023289930 0.2018205723 0.4997668177 0.6782532363 0.4433995370 -0.305945298831 +1403636728963555584.0000000000 2.6223303961 3.5835655878 0.2090382270 0.4989247590 0.6747894231 0.4476175989 -0.308823257676 +1403636729013555456.0000000000 2.6367265107 3.5644314989 0.2153511633 0.4984216629 0.6713441355 0.4513039178 -0.311765410811 +1403636729063555584.0000000000 2.6512749214 3.5451171039 0.2203622394 0.4985486020 0.6679452003 0.4545181040 -0.314184331091 +1403636729113555456.0000000000 2.6660310953 3.5254993561 0.2237970637 0.4979075440 0.6654933081 0.4570513838 -0.316718750728 +1403636729163555584.0000000000 2.6812431785 3.5056897121 0.2257011249 0.4970078889 0.6639056055 0.4595657351 -0.317823599639 +1403636729213555456.0000000000 2.6967200498 3.4853537120 0.2261267234 0.4945428453 0.6639012775 0.4618197059 -0.318410155518 +1403636729263555584.0000000000 2.7121048611 3.4643882772 0.2258285191 0.4921081286 0.6641072254 0.4626652061 -0.320518470588 +1403636729313555456.0000000000 2.7277242071 3.4434415523 0.2241065463 0.4914357893 0.6635300415 0.4638197426 -0.321076307724 +1403636729363555584.0000000000 2.7435520873 3.4218609481 0.2219596893 0.4906313863 0.6632941582 0.4641258163 -0.322349079495 +1403636729413555456.0000000000 2.7596434441 3.4002877091 0.2198572897 0.4910442242 0.6624319374 0.4645520575 -0.322879054848 +1403636729463555584.0000000000 2.7764318866 3.3782413651 0.2191375701 0.4910293021 0.6620412826 0.4648755695 -0.323237172 +1403636729513555456.0000000000 2.7940317499 3.3555885084 0.2199877068 0.4907076055 0.6618932077 0.4650937244 -0.323714774159 +1403636729563555584.0000000000 2.8118924152 3.3327724297 0.2223849633 0.4899219126 0.6622185134 0.4652280490 -0.324046327722 +1403636729613555456.0000000000 2.8293129147 3.3099321090 0.2270401346 0.4892264531 0.6625544113 0.4656455569 -0.32381066216 +1403636729663555584.0000000000 2.8474409906 3.2868463185 0.2334388485 0.4886934631 0.6629283871 0.4656996315 -0.323772305736 +1403636729713555456.0000000000 2.8656146311 3.2635683895 0.2408330628 0.4881526840 0.6632560263 0.4650123340 -0.324902954609 +1403636729763555584.0000000000 2.8836041509 3.2404614833 0.2483400529 0.4872399329 0.6641345796 0.4657146325 -0.323469301679 +1403636729813555456.0000000000 2.9018526761 3.2170805059 0.2552354961 0.4857333713 0.6655242654 0.4659182718 -0.32258442012 +1403636729863555584.0000000000 2.9205536528 3.1937726957 0.2609108409 0.4842642725 0.6667749600 0.4669190960 -0.320758203162 +1403636729913555456.0000000000 2.9393066282 3.1701348149 0.2654633770 0.4821977219 0.6684876539 0.4663576056 -0.321123336568 +1403636729963555584.0000000000 2.9579005431 3.1467036123 0.2684435853 0.4815590523 0.6689629762 0.4674324967 -0.319525079798 +1403636730013555456.0000000000 2.9758979636 3.1231177834 0.2706437120 0.4800790018 0.6701269168 0.4674218287 -0.319328829729 +1403636730063555584.0000000000 2.9936313507 3.0994314055 0.2719238797 0.4793438021 0.6704628579 0.4678118925 -0.319156871824 +1403636730113555456.0000000000 3.0108944327 3.0757225068 0.2721126608 0.4786847386 0.6705494289 0.4683455882 -0.319181444546 +1403636730163555584.0000000000 3.0278517048 3.0520563711 0.2714571230 0.4782717752 0.6708316507 0.4677788891 -0.320037367097 +1403636730213555456.0000000000 3.0447454680 3.0286477563 0.2693408726 0.4778459388 0.6710102019 0.4686817492 -0.318976465706 +1403636730263555584.0000000000 3.0612732014 3.0053273417 0.2664458769 0.4777519569 0.6707821139 0.4690411935 -0.319068616628 +1403636730313555456.0000000000 3.0775132701 2.9821510831 0.2629042168 0.4770667142 0.6711309048 0.4680617560 -0.320794095117 +1403636730363555584.0000000000 3.0938829619 2.9591755890 0.2578261781 0.4765031417 0.6712429415 0.4684051619 -0.320896048182 +1403636730413555456.0000000000 3.1101006074 2.9364504787 0.2519538615 0.4758959228 0.6714332188 0.4693870641 -0.319962946809 +1403636730463555584.0000000000 3.1254474348 2.9140235200 0.2470376384 0.4730795678 0.6730992002 0.4706568034 -0.318771646557 +1403636730513555456.0000000000 3.1411286220 2.8918170713 0.2436013503 0.4710516460 0.6743269835 0.4726720329 -0.316187626985 +1403636730563555584.0000000000 3.1555981715 2.8698287498 0.2426751659 0.4677225516 0.6764384485 0.4738181904 -0.314901512585 +1403636730613555456.0000000000 3.1685007361 2.8485453715 0.2434320315 0.4654062761 0.6778558142 0.4746670574 -0.314005856644 +1403636730663555584.0000000000 3.1796119183 2.8281967666 0.2464529616 0.4640857182 0.6787343755 0.4749402645 -0.313649229151 +1403636730713555456.0000000000 3.1889323455 2.8085490453 0.2528899575 0.4631550322 0.6790899038 0.4754038261 -0.313553058833 +1403636730763555584.0000000000 3.1964289752 2.7896146283 0.2616980439 0.4627108063 0.6794349425 0.4760531237 -0.31247446619 +1403636730813555456.0000000000 3.2035101879 2.7709297130 0.2718761987 0.4624792610 0.6793174584 0.4765849741 -0.312261887489 +1403636730863555584.0000000000 3.2102752831 2.7527580091 0.2830901574 0.4609589805 0.6804703166 0.4757169165 -0.313321531076 +1403636730913555456.0000000000 3.2158802245 2.7349466149 0.2943182452 0.4587468773 0.6821764373 0.4740595457 -0.315363533309 +1403636730963555584.0000000000 3.2206774217 2.7179267850 0.3048520926 0.4571064277 0.6834832845 0.4710180909 -0.31944682114 +1403636731013555456.0000000000 3.2244053310 2.7017356003 0.3139138807 0.4555436109 0.6848980488 0.4677069544 -0.323488618249 +1403636731063555584.0000000000 3.2269278006 2.6866234486 0.3226171933 0.4559215740 0.6849091769 0.4622891106 -0.330641370634 +1403636731113555456.0000000000 3.2289575854 2.6732387436 0.3301913318 0.4585880445 0.6834915013 0.4577370014 -0.336174375263 +1403636731163555584.0000000000 3.2310016912 2.6612907997 0.3360068376 0.4612126881 0.6819107669 0.4546982126 -0.339897187067 +1403636731213555456.0000000000 3.2332427009 2.6510640041 0.3401208233 0.4648970608 0.6797178226 0.4539249097 -0.340303659941 +1403636731263555584.0000000000 3.2359499723 2.6423175468 0.3429537517 0.4694012917 0.6768993702 0.4545017686 -0.338965798308 +1403636731313555456.0000000000 3.2391618017 2.6347913132 0.3443592983 0.4735548953 0.6744307902 0.4560984657 -0.335950978556 +1403636731363555584.0000000000 3.2426503667 2.6277998881 0.3447962236 0.4761687375 0.6728732868 0.4576755712 -0.333223565858 +1403636731413555456.0000000000 3.2466499659 2.6213485944 0.3436153645 0.4781914250 0.6716246694 0.4603865756 -0.32908580252 +1403636731463555584.0000000000 3.2506410675 2.6149900601 0.3420014882 0.4794112200 0.6708219409 0.4608847917 -0.328249926887 +1403636731513555456.0000000000 3.2550416525 2.6085953102 0.3393084129 0.4782473375 0.6716749293 0.4605980158 -0.328605753839 +1403636731563555584.0000000000 3.2595804416 2.6021535545 0.3360431166 0.4756614363 0.6732815737 0.4589178248 -0.331409943409 +1403636731613555456.0000000000 3.2642765103 2.5963694358 0.3320411784 0.4743107632 0.6742548863 0.4573234810 -0.333563909806 +1403636731663555584.0000000000 3.2694245712 2.5912388531 0.3269577291 0.4728679175 0.6751462781 0.4562171867 -0.335319719566 +1403636731713555456.0000000000 3.2747594557 2.5873597526 0.3205983452 0.4733600205 0.6749184759 0.4563121404 -0.334954582604 +1403636731763555584.0000000000 3.2806388748 2.5842768770 0.3129275990 0.4747298033 0.6739676543 0.4579670022 -0.332664154693 +1403636731813555456.0000000000 3.2869962233 2.5817136322 0.3044217520 0.4757615960 0.6731923144 0.4589500859 -0.33140282168 +1403636731863555584.0000000000 3.2936284545 2.5796468198 0.2948901156 0.4768156821 0.6722982445 0.4603848939 -0.32970839418 +1403636731913555456.0000000000 3.3003142001 2.5777858990 0.2846914314 0.4777094569 0.6712829158 0.4614441442 -0.329001859369 +1403636731963555584.0000000000 3.3070057890 2.5760583662 0.2738866938 0.4782945995 0.6706973306 0.4614757208 -0.329301572867 +1403636732013555456.0000000000 3.3137030216 2.5745471937 0.2620351191 0.4786274204 0.6701909864 0.4619357958 -0.329203819323 +1403636732063555584.0000000000 3.3204964437 2.5733673133 0.2493857889 0.4800069276 0.6689752603 0.4620574512 -0.329497135518 +1403636732113555456.0000000000 3.3274765581 2.5724277979 0.2354835755 0.4797235144 0.6690398277 0.4618453273 -0.330075676732 +1403636732163555584.0000000000 3.3346865218 2.5716519295 0.2205400824 0.4801992933 0.6683500813 0.4626145417 -0.329703796452 +1403636732213555456.0000000000 3.3420189811 2.5713714134 0.2065260770 0.4814158492 0.6672894293 0.4624737034 -0.330275144951 +1403636732263555584.0000000000 3.3499431559 2.5712879573 0.1935951605 0.4827562746 0.6660351579 0.4633633985 -0.32960265268 +1403636732313555456.0000000000 3.3587361474 2.5706764966 0.1823642500 0.4826574438 0.6657820859 0.4628083115 -0.331035455477 +1403636732363555584.0000000000 3.3681199869 2.5706317166 0.1721309624 0.4835653691 0.6650208547 0.4643680080 -0.329050375862 +1403636732413555456.0000000000 3.3777529695 2.5705542385 0.1646938104 0.4868411417 0.6626522680 0.4659626908 -0.326736048338 +1403636732463555584.0000000000 3.3877282378 2.5704383060 0.1595513531 0.4919895165 0.6587892926 0.4686434166 -0.322980389028 +1403636732513555456.0000000000 3.3990925811 2.5693620036 0.1563754065 0.4980574770 0.6541161964 0.4718437123 -0.31848746039 +1403636732563555584.0000000000 3.4107393643 2.5669177530 0.1545919201 0.5029592341 0.6502369362 0.4738614449 -0.315720234882 +1403636732613555456.0000000000 3.4224106535 2.5627964966 0.1542177878 0.5072683787 0.6467287672 0.4753113729 -0.313846765882 +1403636732663555584.0000000000 3.4343171548 2.5562721415 0.1557023696 0.5085195931 0.6454430182 0.4745488597 -0.315617669571 +1403636732713555456.0000000000 3.4465813494 2.5475375349 0.1589030849 0.5076969530 0.6458455050 0.4722981924 -0.319471133318 +1403636732763555584.0000000000 3.4596249555 2.5368994357 0.1635309422 0.5053585401 0.6473489365 0.4702339312 -0.323159635972 +1403636732813555456.0000000000 3.4720597152 2.5245708150 0.1702049750 0.5032488865 0.6486198337 0.4678201078 -0.32737931567 +1403636732863555584.0000000000 3.4856260825 2.5114267302 0.1761295618 0.5023024988 0.6491939178 0.4669534712 -0.328928430751 +1403636732913555456.0000000000 3.5002940716 2.4970472847 0.1806631861 0.5009261925 0.6499864767 0.4669484578 -0.329468765722 +1403636732963555584.0000000000 3.5159569336 2.4815108145 0.1834954197 0.4988795548 0.6512653264 0.4674051035 -0.32940117424 +1403636733013555456.0000000000 3.5323285844 2.4651578219 0.1847597981 0.4966387012 0.6525990932 0.4685050068 -0.328584057142 +1403636733063555584.0000000000 3.5492515169 2.4480708876 0.1857549095 0.4947509731 0.6538071198 0.4696325492 -0.327418682046 +1403636733113555456.0000000000 3.5667503513 2.4302786131 0.1882706931 0.4918237222 0.6556849974 0.4710400134 -0.326048947734 +1403636733163555584.0000000000 3.5847043346 2.4121410699 0.1931956411 0.4931477318 0.6546327878 0.4725315748 -0.323998670642 +1403636733213555456.0000000000 3.6028566558 2.3930005974 0.1998866346 0.4921493571 0.6550590352 0.4733101514 -0.323518425022 +1403636733263555584.0000000000 3.6212424282 2.3731248712 0.2084251632 0.4919306588 0.6547746838 0.4743906319 -0.32284341208 +1403636733313555456.0000000000 3.6407183312 2.3521040661 0.2183115307 0.4905264551 0.6555025783 0.4740443485 -0.324009447895 +1403636733363555584.0000000000 3.6610663181 2.3304898235 0.2289875554 0.4879541128 0.6570502654 0.4741862331 -0.324550687653 +1403636733413555456.0000000000 3.6810264315 2.3085613132 0.2408584670 0.4851607820 0.6585747625 0.4747164647 -0.32487316896 +1403636733463555584.0000000000 3.7007282091 2.2863408863 0.2545477265 0.4826550235 0.6603984391 0.4740929429 -0.325812693636 +1403636733513555456.0000000000 3.7199489335 2.2641117114 0.2688184806 0.4809435731 0.6614269618 0.4748185311 -0.325199963338 +1403636733563555584.0000000000 3.7392416503 2.2416461239 0.2823707681 0.4794508069 0.6624326488 0.4749763890 -0.325126651432 +1403636733613555456.0000000000 3.7586606551 2.2192104972 0.2948734182 0.4788156698 0.6624907402 0.4762243275 -0.324117206294 +1403636733663555584.0000000000 3.7778867861 2.1965517959 0.3059850931 0.4771110924 0.6637285116 0.4758077585 -0.324709786327 +1403636733713555456.0000000000 3.7969196717 2.1740520171 0.3153365753 0.4763341167 0.6640797747 0.4764834473 -0.324140997906 +1403636733763555584.0000000000 3.8154888837 2.1517010325 0.3231217792 0.4764432012 0.6638154415 0.4771447234 -0.323548835025 +1403636733813555456.0000000000 3.8338082001 2.1291965413 0.3290682922 0.4747737375 0.6648649862 0.4776960791 -0.323033905923 +1403636733863555584.0000000000 3.8519231705 2.1066962308 0.3338389274 0.4740799224 0.6651963154 0.4781474831 -0.322702763601 +1403636733913555456.0000000000 3.8694416067 2.0843907299 0.3374601809 0.4756070771 0.6640288786 0.4785832640 -0.322213618615 +1403636733963555584.0000000000 3.8865797541 2.0622243541 0.3399685843 0.4786553413 0.6618801388 0.4793163990 -0.32102887066 +1403636734013555456.0000000000 3.9030955182 2.0397835424 0.3420050904 0.4814202671 0.6599045880 0.4787860867 -0.321751992052 +1403636734063555584.0000000000 3.9195427589 2.0170484655 0.3431597015 0.4832907826 0.6588879807 0.4777075954 -0.322633075972 +1403636734113555456.0000000000 3.9355354269 1.9939495502 0.3442882013 0.4841457015 0.6587232987 0.4759255151 -0.324316912219 +1403636734163555584.0000000000 3.9518775792 1.9704469761 0.3458065303 0.4845370081 0.6586515599 0.4753362135 -0.324742197016 +1403636734213555456.0000000000 3.9679566718 1.9464793154 0.3489806412 0.4838110116 0.6590369304 0.4746047632 -0.326109718152 +1403636734263555584.0000000000 3.9845297454 1.9220679141 0.3542898266 0.4833473555 0.6589120666 0.4741484904 -0.327709370494 +1403636734313555456.0000000000 4.0015608205 1.8974105013 0.3604913523 0.4815696060 0.6599047821 0.4740239091 -0.328508335814 +1403636734363555584.0000000000 4.0184480605 1.8728842419 0.3685492827 0.4798858794 0.6607981946 0.4742863385 -0.328797441824 +1403636734413555456.0000000000 4.0354330012 1.8482350466 0.3787048486 0.4778514072 0.6618628716 0.4744282205 -0.32941377528 +1403636734463555584.0000000000 4.0524834611 1.8237963362 0.3896301069 0.4762494848 0.6625849491 0.4753524623 -0.328949312136 +1403636734513555456.0000000000 4.0693656011 1.7995162067 0.4003943680 0.4746923757 0.6632658240 0.4760191968 -0.328863679165 +1403636734563555584.0000000000 4.0860867831 1.7753887854 0.4099786062 0.4728513350 0.6641804135 0.4770231542 -0.32821472191 +1403636734613555456.0000000000 4.1025780360 1.7514052349 0.4183317488 0.4710838152 0.6649761273 0.4779082950 -0.327857363432 +1403636734663555584.0000000000 4.1188732008 1.7278032926 0.4250330298 0.4701258855 0.6653054268 0.4792623990 -0.326585201369 +1403636734713555456.0000000000 4.1347104497 1.7044154418 0.4302947225 0.4697205395 0.6650751431 0.4803379135 -0.326056985102 +1403636734763555584.0000000000 4.1501999032 1.6814236967 0.4342089290 0.4703119175 0.6640974538 0.4812806514 -0.32580700835 +1403636734813555456.0000000000 4.1653601162 1.6584806052 0.4364028533 0.4692637075 0.6643919755 0.4819107032 -0.325786663233 +1403636734863555584.0000000000 4.1799809551 1.6357266476 0.4371689304 0.4688558966 0.6641299948 0.4823664712 -0.326233176672 +1403636734913555456.0000000000 4.1939133347 1.6132328491 0.4366787025 0.4681906115 0.6641207487 0.4826116448 -0.326844278968 +1403636734963555584.0000000000 4.2073133077 1.5911326598 0.4351238356 0.4676095624 0.6643355190 0.4825276350 -0.327363249178 +1403636735013555456.0000000000 4.2201850888 1.5694609588 0.4323708493 0.4681749731 0.6637368634 0.4831365807 -0.326870945725 +1403636735063555584.0000000000 4.2323856126 1.5478750629 0.4290659071 0.4681394549 0.6636560444 0.4826869958 -0.327748942862 +1403636735113555456.0000000000 4.2448568179 1.5264318204 0.4250351048 0.4678043139 0.6639971875 0.4821855631 -0.328274186797 +1403636735163555584.0000000000 4.2571950780 1.5053645048 0.4218345724 0.4670504226 0.6645451768 0.4816238207 -0.329062465128 +1403636735213555456.0000000000 4.2688526604 1.4848243755 0.4196415888 0.4660924966 0.6654810997 0.4813146429 -0.32898161808 +1403636735263555584.0000000000 4.2795698508 1.4646966153 0.4195651799 0.4646607638 0.6668025663 0.4807451590 -0.329163795539 +1403636735313555456.0000000000 4.2895803800 1.4451371460 0.4217900216 0.4632946841 0.6682880265 0.4801259621 -0.328980561388 +1403636735363555584.0000000000 4.2982422527 1.4263355160 0.4271343544 0.4623783384 0.6695837084 0.4794152469 -0.328671493714 +1403636735413555456.0000000000 4.3058934706 1.4083836426 0.4360782164 0.4639936461 0.6693245551 0.4781950257 -0.328700553222 +1403636735463555584.0000000000 4.3135273880 1.3908531047 0.4475845878 0.4647238249 0.6699640869 0.4762262499 -0.329224008319 +1403636735513555456.0000000000 4.3205586713 1.3741874648 0.4601061744 0.4664960137 0.6700077380 0.4750986154 -0.328256615867 +1403636735563555584.0000000000 4.3274145006 1.3582708539 0.4742018463 0.4683471846 0.6699580398 0.4736636480 -0.327795497505 +1403636735613555456.0000000000 4.3336534250 1.3429011586 0.4892545467 0.4700821888 0.6698471400 0.4726141466 -0.327052615373 +1403636735663555584.0000000000 4.3397347150 1.3280050527 0.5036238584 0.4713176928 0.6702319272 0.4716288752 -0.325906428808 +1403636735713555456.0000000000 4.3456287858 1.3131687020 0.5164859618 0.4709211652 0.6714195285 0.4707878934 -0.325250414886 +1403636735763555584.0000000000 4.3510695968 1.2989467639 0.5278756525 0.4715802898 0.6717990637 0.4706620724 -0.323690070814 +1403636735813555456.0000000000 4.3559536993 1.2849457000 0.5382942379 0.4716361788 0.6724689748 0.4694707935 -0.323947475444 +1403636735863555584.0000000000 4.3606175857 1.2715031082 0.5472927671 0.4724331649 0.6722947388 0.4690091955 -0.323816403952 +1403636735913555456.0000000000 4.3649119744 1.2584165363 0.5550112360 0.4727500847 0.6721872635 0.4686749533 -0.324060840455 +1403636735963555584.0000000000 4.3687611291 1.2459367762 0.5614495500 0.4733222357 0.6719389746 0.4687683628 -0.323605156965 +1403636736013555456.0000000000 4.3722363250 1.2333619280 0.5680614615 0.4738683185 0.6703737969 0.4700242628 -0.32422982833 +1403636736063555584.0000000000 4.3754542277 1.2207600754 0.5756847389 0.4736828989 0.6681964964 0.4723236632 -0.325650595966 +1403636736113555456.0000000000 4.3785143715 1.2079582824 0.5855165758 0.4731887229 0.6652473728 0.4743404670 -0.329453315283 +1403636736163555584.0000000000 4.3816645915 1.1950674908 0.5968809447 0.4725511307 0.6613210424 0.4777879248 -0.333269570549 +1403636736213555456.0000000000 4.3851459660 1.1821664959 0.6102902860 0.4713912379 0.6573959599 0.4812897841 -0.337610717386 +1403636736263555584.0000000000 4.3886656352 1.1694185906 0.6242089613 0.4699061157 0.6538641615 0.4852366680 -0.340874282843 +1403636736313555456.0000000000 4.3921987744 1.1571423025 0.6378114642 0.4687076771 0.6505340642 0.4891430990 -0.343303908274 +1403636736363555584.0000000000 4.3957346276 1.1449946691 0.6499377522 0.4677079661 0.6475450667 0.4928170112 -0.345059471008 +1403636736413555456.0000000000 4.3993388211 1.1329179725 0.6605766165 0.4665199739 0.6451814385 0.4959701476 -0.346574144969 +1403636736463555584.0000000000 4.4027891786 1.1212609079 0.6696146292 0.4673872604 0.6418177990 0.4999357725 -0.345952720941 +1403636736513555456.0000000000 4.4059543324 1.1095295087 0.6766763004 0.4692033347 0.6381671989 0.5036786697 -0.344816842165 +1403636736563555584.0000000000 4.4091771428 1.0975066218 0.6819512930 0.4707117557 0.6350320939 0.5069818028 -0.34370646539 +1403636736613555456.0000000000 4.4124472457 1.0851917894 0.6860119742 0.4720106594 0.6325504786 0.5096031284 -0.34262294282 +1403636736663555584.0000000000 4.4159766011 1.0718367516 0.6892071599 0.4725088014 0.6309894661 0.5107826529 -0.343058023869 +1403636736713555456.0000000000 4.4194054234 1.0578245726 0.6915313743 0.4730816396 0.6296098255 0.5118649303 -0.343190214169 +1403636736763555584.0000000000 4.4229920135 1.0429491576 0.6924966923 0.4725367358 0.6292442688 0.5130598761 -0.342826847093 +1403636736813555456.0000000000 4.4266074283 1.0271271870 0.6929763793 0.4732202464 0.6279111532 0.5137762152 -0.343255273473 +1403636736863555584.0000000000 4.4303484664 1.0104024570 0.6928146235 0.4722555917 0.6278926618 0.5135837945 -0.344901648765 +1403636736913555456.0000000000 4.4344768097 0.9929471185 0.6916073540 0.4715828641 0.6275561379 0.5149573182 -0.344386202583 +1403636736963555584.0000000000 4.4383802152 0.9744271843 0.6900808443 0.4699823434 0.6279238141 0.5146518202 -0.346354997816 +1403636737013555456.0000000000 4.4424549598 0.9548892034 0.6880143002 0.4673496647 0.6289393918 0.5138675077 -0.349227313988 +1403636737063555584.0000000000 4.4464217166 0.9349429912 0.6854603285 0.4653585367 0.6293114021 0.5131484879 -0.3522601608 +1403636737113555456.0000000000 4.4505204911 0.9144548867 0.6824821519 0.4630390412 0.6298773892 0.5117992687 -0.35624546234 +1403636737163555584.0000000000 4.4548676415 0.8941185033 0.6782272690 0.4616612212 0.6297434191 0.5122520466 -0.35761709104 +1403636737213555456.0000000000 4.4594323063 0.8736122217 0.6731379411 0.4603305305 0.6296014301 0.5125848255 -0.359102545976 +1403636737263555584.0000000000 4.4644361683 0.8529012091 0.6671412041 0.4579550158 0.6302359972 0.5125137020 -0.361122550656 +1403636737313555456.0000000000 4.4696077680 0.8324856789 0.6603722131 0.4563773129 0.6303495317 0.5144111225 -0.360222727207 +1403636737363555584.0000000000 4.4744082979 0.8121508401 0.6550788452 0.4540194176 0.6310379331 0.5153370253 -0.360673322838 +1403636737413555456.0000000000 4.4804035354 0.7918709502 0.6512559266 0.4521897073 0.6312770854 0.5171044792 -0.36002314892 +1403636737463555584.0000000000 4.4863632921 0.7718242431 0.6494244840 0.4501236723 0.6317863933 0.5186844013 -0.359445579499 +1403636737513555456.0000000000 4.4915891728 0.7522150307 0.6498654315 0.4491412474 0.6316790431 0.5204777359 -0.358268967091 +1403636737563555584.0000000000 4.4963555989 0.7327828563 0.6519092282 0.4473106601 0.6324011273 0.5205051759 -0.359244136274 +1403636737613555456.0000000000 4.5004896690 0.7136854909 0.6556789037 0.4451715343 0.6334933177 0.5202134962 -0.360397613549 +1403636737663555584.0000000000 4.5049998499 0.6948063281 0.6605595157 0.4420659399 0.6352139151 0.5193938844 -0.362368568908 +1403636737713555456.0000000000 4.5096485476 0.6765917193 0.6665654855 0.4392563847 0.6370604028 0.5185859150 -0.363698392279 +1403636737763555584.0000000000 4.5133755649 0.6592482245 0.6743162169 0.4374499706 0.6381754996 0.5177746004 -0.365073990006 +1403636737813555456.0000000000 4.5164526756 0.6428761043 0.6835337118 0.4356110120 0.6395751129 0.5166823852 -0.366368713065 +1403636737863555584.0000000000 4.5193410732 0.6275443887 0.6951189903 0.4348062735 0.6403483074 0.5158411590 -0.367158614832 +1403636737913555456.0000000000 4.5218321659 0.6134136181 0.7082532905 0.4345532914 0.6406624010 0.5155388159 -0.36733479866 +1403636737963555584.0000000000 4.5236740581 0.6006432594 0.7236361469 0.4345816927 0.6409225190 0.5149219969 -0.36771240678 +1403636738013555456.0000000000 4.5250046086 0.5891986174 0.7409929128 0.4353017992 0.6410027041 0.5144197727 -0.367423698856 +1403636738063555584.0000000000 4.5265702860 0.5788918724 0.7594874378 0.4358580442 0.6412205486 0.5144282555 -0.366370772963 +1403636738113555456.0000000000 4.5275903455 0.5699972135 0.7779911065 0.4387505378 0.6397265795 0.5150212488 -0.364692997416 +1403636738163555584.0000000000 4.5282066797 0.5615779891 0.7956642342 0.4404920440 0.6391298227 0.5145926748 -0.36424470901 +1403636738213555456.0000000000 4.5287900463 0.5540129053 0.8117852136 0.4425399578 0.6383873632 0.5143928789 -0.363345464192 +1403636738263555584.0000000000 4.5293393086 0.5469667833 0.8261765335 0.4431133962 0.6386995396 0.5138470205 -0.362870025871 +1403636738313555456.0000000000 4.5296079533 0.5403865335 0.8388418404 0.4437509270 0.6388231453 0.5137693010 -0.361982332633 +1403636738363555584.0000000000 4.5295004693 0.5342991199 0.8501385976 0.4439053284 0.6395538263 0.5131211368 -0.361421722606 +1403636738413555456.0000000000 4.5289860758 0.5286929615 0.8599236977 0.4439788168 0.6401024597 0.5127461158 -0.360892050355 +1403636738463555584.0000000000 4.5281833793 0.5239669568 0.8681031552 0.4447092929 0.6410508970 0.5119236036 -0.359474082961 +1403636738513555456.0000000000 4.5269218744 0.5202049133 0.8748798049 0.4450979188 0.6435578271 0.5097889671 -0.357542130308 +1403636738563555584.0000000000 4.5252770367 0.5173995916 0.8797115882 0.4456720334 0.6470944290 0.5069024801 -0.35453506764 +1403636738613555456.0000000000 4.5230143779 0.5154342474 0.8829038293 0.4461881552 0.6516494065 0.5027149983 -0.351492263997 +1403636738663555584.0000000000 4.5201007041 0.5145552291 0.8846495577 0.4485145840 0.6561074461 0.4972753069 -0.347958268034 +1403636738713555456.0000000000 4.5167743472 0.5146713674 0.8849952759 0.4513848705 0.6610608785 0.4902357422 -0.344846532156 +1403636738763555584.0000000000 4.5132744139 0.5155861236 0.8838616514 0.4561831495 0.6654090451 0.4816931020 -0.342198030776 +1403636738813555456.0000000000 4.5098538030 0.5172613570 0.8813354252 0.4606796986 0.6705520165 0.4720710801 -0.339533656333 +1403636738863555584.0000000000 4.5063910395 0.5201451284 0.8775259524 0.4654516289 0.6757719900 0.4614449996 -0.337276609141 +1403636738913555456.0000000000 4.5034420626 0.5240044918 0.8718529648 0.4697398719 0.6816609127 0.4511575029 -0.3333763045 +1403636738963555584.0000000000 4.5007586789 0.5287883900 0.8648752973 0.4731983417 0.6882479403 0.4399664364 -0.329890340683 +1403636739013555456.0000000000 4.4983702508 0.5347246421 0.8564501199 0.4767762480 0.6949769150 0.4280907614 -0.326235799755 +1403636739063555584.0000000000 4.4965632368 0.5421200856 0.8465251924 0.4800539961 0.7020320582 0.4164958159 -0.321294857509 +1403636739113555456.0000000000 4.4953276531 0.5511430400 0.8353140077 0.4852561781 0.7078169841 0.4063693275 -0.313664674966 +1403636739163555584.0000000000 4.4949736107 0.5612889424 0.8223539632 0.4908269445 0.7131274619 0.3979310611 -0.303626422287 +1403636739213555456.0000000000 4.4952136884 0.5725352693 0.8087066815 0.4971420128 0.7178761696 0.3886709819 -0.294004238355 +1403636739263555584.0000000000 4.4963175839 0.5846670824 0.7939249031 0.5034119675 0.7224612487 0.3802554728 -0.282899117216 +1403636739313555456.0000000000 4.4979381992 0.5972791589 0.7784905114 0.5100827123 0.7263553045 0.3720437934 -0.27167446316 +1403636739363555584.0000000000 4.4999756722 0.6101913395 0.7630685794 0.5165487371 0.7300480265 0.3643513054 -0.259721788527 +1403636739413555456.0000000000 4.5027022897 0.6228130755 0.7492495677 0.5215081541 0.7341208349 0.3562086887 -0.24942176137 +1403636739463555584.0000000000 4.5056447243 0.6353320699 0.7373791800 0.5261215469 0.7380996190 0.3476118063 -0.239939789135 +1403636739513555456.0000000000 4.5085014655 0.6472960884 0.7279320675 0.5289649484 0.7428465211 0.3381193309 -0.232487521227 +1403636739563555584.0000000000 4.5111530849 0.6588031152 0.7216192519 0.5317033347 0.7467137926 0.3282188747 -0.227996592286 +1403636739613555456.0000000000 4.5138701838 0.6696958974 0.7168832038 0.5331574425 0.7503754456 0.3198235373 -0.22448326707 +1403636739663555584.0000000000 4.5167672038 0.6803844161 0.7136261516 0.5341900539 0.7534409791 0.3142141457 -0.219629569659 +1403636739713555456.0000000000 4.5196038313 0.6906301779 0.7115104999 0.5358091738 0.7551598274 0.3091810624 -0.216908356381 +1403636739763555584.0000000000 4.5220223460 0.7005459765 0.7090666492 0.5355693313 0.7575486009 0.3039206582 -0.216605268041 +1403636739813555456.0000000000 4.5246852537 0.7102934030 0.7050721347 0.5358175822 0.7589404663 0.3004307047 -0.215986756312 +1403636739863555584.0000000000 4.5273264002 0.7201864176 0.6996969197 0.5357345316 0.7601749475 0.2981700173 -0.214981863404 +1403636739913555456.0000000000 4.5300583673 0.7303779955 0.6932360804 0.5359597589 0.7606876615 0.2970340482 -0.214177946332 +1403636739963555584.0000000000 4.5330095924 0.7407708176 0.6852897296 0.5364855136 0.7607010590 0.2966436746 -0.213353516063 +1403636740013555456.0000000000 4.5363116302 0.7510405752 0.6762776039 0.5364078280 0.7608428504 0.2972533428 -0.212191539038 +1403636740063555584.0000000000 4.5397413024 0.7613660885 0.6661264921 0.5366385080 0.7604480251 0.2987241805 -0.21095444255 +1403636740113555456.0000000000 4.5434821368 0.7714459360 0.6548929176 0.5380531839 0.7591132961 0.3007855894 -0.209221901686 +1403636740163555584.0000000000 4.5475384080 0.7817653671 0.6425917750 0.5392828203 0.7577994194 0.3036408282 -0.206679285627 +1403636740213555456.0000000000 4.5515786989 0.7917567675 0.6293329954 0.5411545363 0.7558461372 0.3066475786 -0.204488746153 +1403636740263555584.0000000000 4.5554459078 0.8012370665 0.6152906563 0.5421795656 0.7545103893 0.3093361261 -0.202648839757 +1403636740313555456.0000000000 4.5588533568 0.8099864711 0.6013216628 0.5428733266 0.7534893683 0.3093190496 -0.204607059287 +1403636740363555584.0000000000 4.5619416865 0.8179724186 0.5860728607 0.5422702428 0.7531741259 0.3092610117 -0.207435162247 +1403636740413555456.0000000000 4.5646825191 0.8255544503 0.5697702376 0.5412954774 0.7533830365 0.3079828425 -0.211091864098 +1403636740463555584.0000000000 4.5675216250 0.8327643864 0.5518775223 0.5397435173 0.7539487949 0.3077345078 -0.213395461367 +1403636740513555456.0000000000 4.5704219573 0.8398007100 0.5343034894 0.5400543666 0.7531047668 0.3068063882 -0.216897052889 +1403636740563555584.0000000000 4.5738013468 0.8466264024 0.5173162495 0.5401583140 0.7525058880 0.3073964439 -0.217879119238 +1403636740613555456.0000000000 4.5773589618 0.8532476546 0.5019218403 0.5400702559 0.7519553574 0.3081552451 -0.218923740423 +1403636740663555584.0000000000 4.5810125434 0.8596725859 0.4882051997 0.5383242700 0.7527268962 0.3082587162 -0.220421786706 +1403636740713555456.0000000000 4.5851392693 0.8659954758 0.4760367020 0.5360661579 0.7539158511 0.3088613621 -0.221017245395 +1403636740763555584.0000000000 4.5897974573 0.8725341938 0.4647516281 0.5342521768 0.7546748679 0.3108462954 -0.220034169921 +1403636740813555456.0000000000 4.5946459313 0.8791998068 0.4539093755 0.5334555241 0.7548136313 0.3113830568 -0.220731007728 +1403636740863555584.0000000000 4.5995587552 0.8859207585 0.4421677206 0.5338506979 0.7542111889 0.3115550609 -0.221590520979 +1403636740913555456.0000000000 4.6049151289 0.8929185518 0.4286365468 0.5358348994 0.7524279819 0.3134045809 -0.220251359285 +1403636740963555584.0000000000 4.6104520991 0.9000320765 0.4136163940 0.5390051847 0.7499603589 0.3156557082 -0.217702422679 +1403636741013555456.0000000000 4.6162489554 0.9068165004 0.3966662153 0.5424208414 0.7472482544 0.3196146623 -0.212711411823 +1403636741063555584.0000000000 4.6220421494 0.9133135760 0.3781232722 0.5464395898 0.7446812298 0.3220546341 -0.207688356325 +1403636741113555456.0000000000 4.6273230997 0.9190440608 0.3581610248 0.5489603256 0.7438525783 0.3211322780 -0.205426295066 +1403636741163555584.0000000000 4.6327910768 0.9237814948 0.3367473237 0.5508911523 0.7442887302 0.3174728217 -0.204362990324 +1403636741213555456.0000000000 4.6379912593 0.9274411920 0.3140799850 0.5514707393 0.7459984926 0.3117384437 -0.205390884555 +1403636741263555584.0000000000 4.6429836053 0.9298426555 0.2900902431 0.5505866550 0.7485647340 0.3055750915 -0.207675318127 +1403636741313555456.0000000000 4.6482770247 0.9310764912 0.2648156373 0.5487622002 0.7513001689 0.3009360765 -0.209393365943 +1403636741363555584.0000000000 4.6541914482 0.9314062804 0.2392915202 0.5445669517 0.7557088197 0.2971693242 -0.209860448036 +1403636741413555456.0000000000 4.6603600165 0.9314353813 0.2150367316 0.5411878508 0.7593776002 0.2946093330 -0.208965813798 +1403636741463555584.0000000000 4.6666425570 0.9312780896 0.1922182061 0.5378070107 0.7627965679 0.2932405859 -0.207159296152 +1403636741513555456.0000000000 4.6730796152 0.9313241201 0.1706483612 0.5324237041 0.7673877483 0.2932973924 -0.204004124236 +1403636741563555584.0000000000 4.6791101651 0.9315789732 0.1516284577 0.5279793070 0.7710829491 0.2908048843 -0.205186393714 +1403636741613555456.0000000000 4.6857200679 0.9325584842 0.1336499856 0.5263767226 0.7726256110 0.2924591380 -0.201109083864 +1403636741663555584.0000000000 4.6917964966 0.9341710196 0.1178468523 0.5252309873 0.7736246996 0.2926896205 -0.199925036515 +1403636741713555456.0000000000 4.6973278504 0.9367830286 0.1042896634 0.5259511184 0.7732224727 0.2928976137 -0.199282253635 +1403636741763555584.0000000000 4.7019838821 0.9405721421 0.0927916745 0.5283313040 0.7714848585 0.2933529157 -0.199050780425 +1403636741813555456.0000000000 4.7062897112 0.9450284506 0.0820254413 0.5308912512 0.7694321481 0.2943718083 -0.198680364796 +1403636741863555584.0000000000 4.7105656981 0.9497543891 0.0705494828 0.5340591250 0.7668088649 0.2959976226 -0.197915191976 +1403636741913555456.0000000000 4.7147052756 0.9545800952 0.0571553099 0.5362903050 0.7646964117 0.2983602708 -0.196502558264 +1403636741963555584.0000000000 4.7184904388 0.9595216387 0.0419504092 0.5389163847 0.7620991038 0.3018739975 -0.194026225023 +1403636742013555456.0000000000 4.7217393901 0.9642898487 0.0250383804 0.5393316540 0.7610611205 0.3055567795 -0.191160645513 +1403636742063555584.0000000000 4.7242753158 0.9685289667 0.0079998390 0.5374603910 0.7615066075 0.3084024336 -0.190084070559 +1403636742113555456.0000000000 4.7258567816 0.9722762844 -0.0080774593 0.5329238429 0.7638592367 0.3103348154 -0.190272295618 +1403636742163555584.0000000000 4.7262915938 0.9759056945 -0.0221532619 0.5289800805 0.7659548930 0.3106943367 -0.192255573142 +1403636742213555456.0000000000 4.7255675656 0.9800036377 -0.0346709098 0.5266621715 0.7669070361 0.3109251681 -0.194437894815 +1403636742263555584.0000000000 4.7237597397 0.9844757530 -0.0446512506 0.5242612765 0.7679333896 0.3099723624 -0.198357146605 +1403636742313555456.0000000000 4.7216869182 0.9892373550 -0.0530539532 0.5249603740 0.7666668670 0.3099323601 -0.201445905603 +1403636742363555584.0000000000 4.7193371022 0.9941193626 -0.0599344521 0.5270024689 0.7648962903 0.3086457080 -0.204792309122 +1403636742413555456.0000000000 4.7161656233 0.9998318635 -0.0645148005 0.5297678712 0.7623399893 0.3083946882 -0.207548692159 +1403636742463555584.0000000000 4.7128530721 1.0059672081 -0.0673784360 0.5313596652 0.7608133632 0.3080235176 -0.209622148365 +1403636742513555456.0000000000 4.7095483351 1.0122183921 -0.0696813916 0.5327209058 0.7593907533 0.3083416095 -0.210854386019 +1403636742563555584.0000000000 4.7055480304 1.0191834381 -0.0714456081 0.5331934437 0.7586047361 0.3087193634 -0.211933859238 +1403636742613555456.0000000000 4.7014776375 1.0263709508 -0.0721231952 0.5348351940 0.7571056625 0.3090015604 -0.212744839329 +1403636742663555584.0000000000 4.6974466798 1.0336141873 -0.0739483134 0.5367942492 0.7554882614 0.3087384007 -0.213939292358 +1403636742713555456.0000000000 4.6934529954 1.0406735521 -0.0778205112 0.5383899754 0.7539120780 0.3086376500 -0.215628416391 +1403636742763555584.0000000000 4.6895206631 1.0476436709 -0.0842391492 0.5397774157 0.7525262323 0.3087888666 -0.216781104082 +1403636742813555456.0000000000 4.6859750204 1.0543514015 -0.0924751785 0.5406799275 0.7516463044 0.3087797734 -0.217596187185 +1403636742863555584.0000000000 4.6828091958 1.0605309865 -0.1024754911 0.5410069826 0.7510009054 0.3085977337 -0.219263593698 +1403636742913555456.0000000000 4.6804243767 1.0662046945 -0.1144856256 0.5409521681 0.7507493568 0.3085130333 -0.22037663958 +1403636742963555584.0000000000 4.6787133270 1.0717232359 -0.1284644861 0.5408698316 0.7512176681 0.3075432927 -0.220338293329 +1403636743013555456.0000000000 4.6772293143 1.0773916083 -0.1448426130 0.5397929428 0.7529920688 0.3065758658 -0.218260765705 +1403636743063555584.0000000000 4.6762811966 1.0829664337 -0.1631229546 0.5359382073 0.7572250255 0.3050590971 -0.215219529803 +1403636743113555456.0000000000 4.6756417773 1.0885080713 -0.1819003230 0.5295116676 0.7633851283 0.3036793586 -0.211280351494 +1403636743163555584.0000000000 4.6749392029 1.0944740957 -0.2002809876 0.5211680049 0.7705482959 0.3033758692 -0.206403285553 +1403636743213555456.0000000000 4.6736743693 1.1015243754 -0.2174045044 0.5152906798 0.7756793606 0.3031136510 -0.202284847395 +1403636743263555584.0000000000 4.6719243954 1.1097147085 -0.2337294968 0.5096719356 0.7804891852 0.3038742531 -0.196803425298 +1403636743313555456.0000000000 4.6687740727 1.1191128335 -0.2466981915 0.5068014435 0.7832544272 0.3024462699 -0.195425313177 +1403636743363555584.0000000000 4.6643838100 1.1301583450 -0.2574785887 0.5049226313 0.7851524751 0.3008261027 -0.195172700657 +1403636743413555456.0000000000 4.6584327502 1.1433927528 -0.2658249082 0.5048389806 0.7857852685 0.2992786628 -0.195221406157 +1403636743463555584.0000000000 4.6506907502 1.1587124415 -0.2724940249 0.5078534829 0.7842278030 0.2976698507 -0.196123055395 +1403636743513555456.0000000000 4.6424746101 1.1753314265 -0.2797230025 0.5110417598 0.7825020848 0.2964618741 -0.196563384994 +1403636743563555584.0000000000 4.6336098046 1.1930884361 -0.2879675253 0.5154041007 0.7798912289 0.2951001444 -0.197596024399 +1403636743613555456.0000000000 4.6238233649 1.2121929274 -0.2980770952 0.5204358042 0.7765418652 0.2953260962 -0.197260746585 +1403636743663555584.0000000000 4.6134687714 1.2320460882 -0.3100520210 0.5240407794 0.7741290535 0.2956192079 -0.196760651435 +1403636743713555456.0000000000 4.6025745235 1.2526680534 -0.3234088434 0.5288628705 0.7709745652 0.2953837995 -0.196597800004 +1403636743763555584.0000000000 4.5910906868 1.2740992832 -0.3380998253 0.5341728820 0.7681228081 0.2937427308 -0.19586192055 +1403636743813555456.0000000000 4.5793828996 1.2954686929 -0.3542689768 0.5369851893 0.7675526279 0.2904704658 -0.1952864009 +1403636743863555584.0000000000 4.5673137157 1.3166756966 -0.3713838289 0.5391943399 0.7675354304 0.2854325428 -0.19669034138 +1403636743913555456.0000000000 4.5552715007 1.3379234002 -0.3900412287 0.5428130267 0.7663217282 0.2831156833 -0.194808974905 +1403636743963555584.0000000000 4.5432001693 1.3590547136 -0.4102040884 0.5458557054 0.7652490411 0.2809825579 -0.193608512673 +1403636744013555456.0000000000 4.5307883625 1.3800340701 -0.4317919903 0.5472297892 0.7652146871 0.2787061740 -0.19315514223 +1403636744063555584.0000000000 4.5182819016 1.4011686822 -0.4547429536 0.5497824063 0.7648583460 0.2768208917 -0.190003184748 +1403636744113555456.0000000000 4.5056543067 1.4220315982 -0.4793359247 0.5512181140 0.7656432454 0.2734232522 -0.18758661112 +1403636744163555584.0000000000 4.4931466529 1.4421912320 -0.5043404841 0.5528480202 0.7663046901 0.2696593434 -0.185526351167 +1403636744213555456.0000000000 4.4810941821 1.4609399802 -0.5310142017 0.5539770236 0.7670187239 0.2654420718 -0.185289614163 +1403636744263555584.0000000000 4.4691720193 1.4790051202 -0.5586888185 0.5551234719 0.7674918219 0.2609755029 -0.186241835071 +1403636744313555456.0000000000 4.4577330375 1.4961891820 -0.5879932628 0.5554027097 0.7683518145 0.2580443965 -0.1859473279 +1403636744363555584.0000000000 4.4463266661 1.5129865938 -0.6186808910 0.5548768858 0.7695846543 0.2545877328 -0.187179560206 +1403636744413555456.0000000000 4.4353499494 1.5291775519 -0.6506667522 0.5541850169 0.7705325949 0.2516556316 -0.189282673286 +1403636744463555584.0000000000 4.4248155045 1.5449273867 -0.6836603726 0.5532619844 0.7715046064 0.2487086435 -0.191900571792 +1403636744513555456.0000000000 4.4148621518 1.5601592751 -0.7175955591 0.5516809134 0.7725015188 0.2453890515 -0.196656519291 +1403636744563555584.0000000000 4.4058697218 1.5760718484 -0.7530724295 0.5525007244 0.7717878027 0.2442873861 -0.198520049945 +1403636744613555456.0000000000 4.3974740781 1.5918455963 -0.7898421827 0.5524463775 0.7715623589 0.2425456019 -0.20165851675 +1403636744663555584.0000000000 4.3904330728 1.6080126841 -0.8276252795 0.5534128136 0.7706786536 0.2420586801 -0.202968632939 +1403636744713555456.0000000000 4.3849663856 1.6244344148 -0.8669019185 0.5558203610 0.7689036844 0.2432404268 -0.20170509456 +1403636744763555584.0000000000 4.3811198314 1.6406735977 -0.9068053662 0.5582070087 0.7672993866 0.2461048705 -0.197709330877 +1403636744813555456.0000000000 4.3785756909 1.6563514389 -0.9453417837 0.5592432459 0.7666461611 0.2484774973 -0.194318267319 +1403636744863555584.0000000000 4.3774600442 1.6709988057 -0.9821538072 0.5590569713 0.7667919379 0.2511177526 -0.190854135879 +1403636744913555456.0000000000 4.3774192655 1.6848432365 -1.0172714797 0.5571695823 0.7681096686 0.2541917998 -0.186965565068 +1403636744963555584.0000000000 4.3778625512 1.6978141431 -1.0494783893 0.5552522782 0.7691555052 0.2562383951 -0.185571013873 +1403636745013555456.0000000000 4.3785588573 1.7104770083 -1.0792355649 0.5517367718 0.7712615904 0.2581666663 -0.184640369803 +1403636745063555584.0000000000 4.3788866863 1.7234831939 -1.1066466425 0.5488921136 0.7726858903 0.2606108353 -0.183727937957 +1403636745113555456.0000000000 4.3791450250 1.7362227873 -1.1322739075 0.5447935872 0.7748320493 0.2630189808 -0.183456420936 +1403636745163555584.0000000000 4.3791824778 1.7489482884 -1.1555717228 0.5421954388 0.7758941249 0.2635806367 -0.185843108756 +1403636745213555456.0000000000 4.3789195575 1.7625594693 -1.1779382042 0.5416671041 0.7753320525 0.2663618075 -0.185764216835 +1403636745263555584.0000000000 4.3782627836 1.7765297710 -1.1994977801 0.5406002201 0.7750615016 0.2687793589 -0.186517363967 +1403636745313555456.0000000000 4.3772727717 1.7908911466 -1.2200319277 0.5411471476 0.7736737527 0.2711809871 -0.187215280494 +1403636745363555584.0000000000 4.3754829502 1.8060424069 -1.2373287298 0.5444561958 0.7702861277 0.2729675592 -0.188985300963 +1403636745413555456.0000000000 4.3739967043 1.8210960839 -1.2514635003 0.5483457480 0.7668119917 0.2737367532 -0.190747214983 +1403636745463555584.0000000000 4.3727556479 1.8357617277 -1.2631870472 0.5519003713 0.7638471510 0.2745851762 -0.191171366034 +1403636745513555456.0000000000 4.3712129977 1.8500564969 -1.2729016339 0.5540259395 0.7622935010 0.2735937673 -0.192640409179 +1403636745563555584.0000000000 4.3699356617 1.8637693885 -1.2812193882 0.5552538720 0.7616950380 0.2725785339 -0.192911247979 +1403636745613555456.0000000000 4.3689130469 1.8769101491 -1.2880505319 0.5564758439 0.7615474973 0.2708612737 -0.192390786985 +1403636745663555584.0000000000 4.3682348249 1.8892087117 -1.2932103878 0.5575026511 0.7617654808 0.2690106664 -0.19114760686 +1403636745713555456.0000000000 4.3673116470 1.9011059074 -1.2960020448 0.5588067425 0.7618946072 0.2673475415 -0.189147889622 +1403636745763555584.0000000000 4.3665158186 1.9124989607 -1.2974343731 0.5599157874 0.7623837218 0.2659765820 -0.185800510098 +1403636745813555456.0000000000 4.3657428467 1.9230026278 -1.2974039914 0.5599851281 0.7635828656 0.2645699698 -0.182648828782 +1403636745863555584.0000000000 4.3646596522 1.9331587853 -1.2953750980 0.5610111370 0.7641981501 0.2633364387 -0.178666201235 +1403636745913555456.0000000000 4.3634521647 1.9423848846 -1.2920669369 0.5623093841 0.7647027476 0.2613751200 -0.175273816905 +1403636745963555584.0000000000 4.3622760269 1.9505329431 -1.2875003758 0.5637857370 0.7649840028 0.2607145091 -0.170214755544 +1403636746013555456.0000000000 4.3601674493 1.9578528855 -1.2807991227 0.5647520907 0.7655305859 0.2596946884 -0.166062238204 +1403636746063555584.0000000000 4.3579752123 1.9636304591 -1.2725240810 0.5656286236 0.7660060018 0.2588671897 -0.16213217881 +1403636746113555456.0000000000 4.3552009987 1.9682237227 -1.2626454004 0.5659027729 0.7667929220 0.2586135101 -0.157802784524 +1403636746163555584.0000000000 4.3516817163 1.9713118779 -1.2507321324 0.5671415872 0.7666979011 0.2573157258 -0.155927437586 +1403636746213555456.0000000000 4.3476924886 1.9725314795 -1.2368191323 0.5691099633 0.7658710314 0.2560552517 -0.154890674236 +1403636746263555584.0000000000 4.3425774506 1.9727469004 -1.2212779084 0.5726714498 0.7638776969 0.2536065125 -0.15563422394 +1403636746313555456.0000000000 4.3365043378 1.9719312578 -1.2055059857 0.5793925089 0.7592842801 0.2511027491 -0.157286719462 +1403636746363555584.0000000000 4.3301149278 1.9688692423 -1.1915035984 0.5835380790 0.7564562679 0.2484012658 -0.15985629888 +1403636746413555456.0000000000 4.3235406609 1.9639015265 -1.1798292528 0.5856996771 0.7549540727 0.2472437897 -0.160843852586 +1403636746463555584.0000000000 4.3168789939 1.9566369070 -1.1710823193 0.5829482737 0.7570253622 0.2462059179 -0.162685454895 +1403636746513555456.0000000000 4.3104942134 1.9474005849 -1.1648815348 0.5780044862 0.7605546506 0.2464543535 -0.163486051512 +1403636746563555584.0000000000 4.3040029243 1.9364579556 -1.1608803870 0.5697086441 0.7663071158 0.2472584561 -0.164525745594 +1403636746613555456.0000000000 4.2975031965 1.9245830877 -1.1593170120 0.5597051596 0.7730528487 0.2489893205 -0.164692882838 +1403636746663555584.0000000000 4.2905398932 1.9122036037 -1.1587657641 0.5488870710 0.7800440191 0.2503455412 -0.1660765534 +1403636746713555456.0000000000 4.2828258900 1.8999094157 -1.1590081372 0.5382966774 0.7867186758 0.2505494349 -0.168924222302 +1403636746763555584.0000000000 4.2745172947 1.8883749244 -1.1599551435 0.5308175374 0.7911448171 0.2500823335 -0.172573018956 +1403636746813555456.0000000000 4.2654363348 1.8788232047 -1.1608337063 0.5269798608 0.7931048840 0.2488653092 -0.177039337731 +1403636746863555584.0000000000 4.2562748724 1.8704753943 -1.1623035494 0.5249998581 0.7938904517 0.2476456884 -0.181065492851 +1403636746913555456.0000000000 4.2470450512 1.8639077449 -1.1638461638 0.5249931846 0.7933405072 0.2472455594 -0.184018012873 +1403636746963555584.0000000000 4.2383836664 1.8588271957 -1.1652200232 0.5259755129 0.7921839685 0.2481777458 -0.184938169015 +1403636747013555456.0000000000 4.2297467460 1.8556305402 -1.1643759849 0.5277925239 0.7905727838 0.2485940940 -0.186093260579 +1403636747063555584.0000000000 4.2214234015 1.8543625263 -1.1609791793 0.5326100282 0.7870155961 0.2515046181 -0.183516855716 +1403636747113555456.0000000000 4.2131421767 1.8542637011 -1.1552246449 0.5378751929 0.7833420396 0.2542010427 -0.180131495938 +1403636747163555584.0000000000 4.2041134485 1.8553500487 -1.1476080808 0.5425554583 0.7800956847 0.2551907783 -0.178779092774 +1403636747213555456.0000000000 4.1944770452 1.8578023084 -1.1384115868 0.5472165132 0.7768707588 0.2575967480 -0.175128031146 +1403636747263555584.0000000000 4.1841283339 1.8607251826 -1.1266303642 0.5507150297 0.7745364807 0.2586937434 -0.172869150723 +1403636747313555456.0000000000 4.1735354653 1.8631548203 -1.1125624925 0.5524573008 0.7734758751 0.2596094162 -0.170672061111 +1403636747363555584.0000000000 4.1630618539 1.8646362585 -1.0977353959 0.5536396923 0.7728577769 0.2595060179 -0.169795684533 +1403636747413555456.0000000000 4.1516752685 1.8662058246 -1.0830667830 0.5547795559 0.7724286372 0.2589638032 -0.168853171487 +1403636747463555584.0000000000 4.1402245793 1.8672314197 -1.0705636184 0.5554627462 0.7724105505 0.2584016525 -0.167546008649 +1403636747513555456.0000000000 4.1282254485 1.8677608939 -1.0595847575 0.5543770951 0.7737323897 0.2569708292 -0.16724299228 +1403636747563555584.0000000000 4.1157098625 1.8679234190 -1.0498589124 0.5534368807 0.7747750504 0.2562968986 -0.166562721141 +1403636747613555456.0000000000 4.1026923534 1.8677945018 -1.0409958577 0.5524988022 0.7759285500 0.2548289739 -0.166559757816 +1403636747663555584.0000000000 4.0893472283 1.8673788747 -1.0310714469 0.5520621597 0.7766760302 0.2540610061 -0.165694662494 +1403636747713555456.0000000000 4.0757402061 1.8664542004 -1.0196635311 0.5519944239 0.7772560157 0.2527711598 -0.165172585175 +1403636747763555584.0000000000 4.0618490114 1.8653250859 -1.0065184687 0.5516581491 0.7780088855 0.2519800210 -0.163955876858 +1403636747813555456.0000000000 4.0470805009 1.8643029610 -0.9909187056 0.5515038797 0.7785803253 0.2507889651 -0.163588027295 +1403636747863555584.0000000000 4.0313625290 1.8635466047 -0.9728025680 0.5519161695 0.7787888364 0.2487640157 -0.164295327583 +1403636747913555456.0000000000 4.0148316114 1.8625085191 -0.9523611144 0.5504606740 0.7803476875 0.2436683534 -0.169340681707 +1403636747963555584.0000000000 3.9978329316 1.8617712317 -0.9307943916 0.5503366171 0.7809048687 0.2372797738 -0.176112188161 +1403636748013555456.0000000000 3.9812842971 1.8612956213 -0.9102657094 0.5488204591 0.7823168187 0.2316780103 -0.18193899668 +1403636748063555584.0000000000 3.9659411555 1.8612685499 -0.8917541546 0.5477050928 0.7834728468 0.2273618441 -0.185731046247 +1403636748113555456.0000000000 3.9516226930 1.8618308774 -0.8753581393 0.5468518417 0.7843614562 0.2254319039 -0.186843854263 +1403636748163555584.0000000000 3.9380821840 1.8629535223 -0.8605518702 0.5453550250 0.7856902667 0.2229967152 -0.188550169796 +1403636748213555456.0000000000 3.9258658027 1.8649235853 -0.8479683329 0.5454093516 0.7860026874 0.2234881421 -0.186497895375 +1403636748263555584.0000000000 3.9148893913 1.8677834699 -0.8376237782 0.5465017715 0.7854521463 0.2269649352 -0.181349546035 +1403636748313555456.0000000000 3.9047062846 1.8716897689 -0.8289263825 0.5484311491 0.7843237381 0.2311966740 -0.174950411232 +1403636748363555584.0000000000 3.8948547830 1.8762548241 -0.8212164630 0.5506475507 0.7828013839 0.2360390685 -0.168210660911 +1403636748413555456.0000000000 3.8847930145 1.8812332542 -0.8136944788 0.5528164953 0.7810957481 0.2403376696 -0.162853183566 +1403636748463555584.0000000000 3.8742510739 1.8861431592 -0.8048209015 0.5543050104 0.7799707584 0.2418437418 -0.16094463658 +1403636748513555456.0000000000 3.8635199382 1.8906906106 -0.7945387944 0.5559987704 0.7786074092 0.2436706197 -0.158935517716 +1403636748563555584.0000000000 3.8524490161 1.8946387074 -0.7827942096 0.5563169281 0.7784199328 0.2436061014 -0.158839387475 +1403636748613555456.0000000000 3.8409486975 1.8982057838 -0.7689016933 0.5559803668 0.7787683552 0.2410058629 -0.162240114545 +1403636748663555584.0000000000 3.8294659219 1.9016907113 -0.7537796053 0.5555939508 0.7791548229 0.2384325085 -0.165478284661 +1403636748713555456.0000000000 3.8179346914 1.9052797877 -0.7380064554 0.5547723486 0.7798979760 0.2348638214 -0.169781546757 +1403636748763555584.0000000000 3.8069946948 1.9087724900 -0.7232230797 0.5537373297 0.7807742092 0.2317341721 -0.173395147885 +1403636748813555456.0000000000 3.7964167300 1.9126038592 -0.7098397162 0.5527613718 0.7817003668 0.2289541032 -0.176009718668 +1403636748863555584.0000000000 3.7863622866 1.9168549248 -0.6978678136 0.5526989265 0.7820729191 0.2267280208 -0.177426746622 +1403636748913555456.0000000000 3.7768792811 1.9215253028 -0.6871712142 0.5526756209 0.7825782512 0.2240088510 -0.178720377849 +1403636748963555584.0000000000 3.7683920995 1.9267914031 -0.6776671334 0.5529367321 0.7829919193 0.2219914294 -0.17861811201 +1403636749013555456.0000000000 3.7607715979 1.9325097601 -0.6690325958 0.5532683400 0.7833400404 0.2200237295 -0.178499533706 +1403636749063555584.0000000000 3.7538466516 1.9384320933 -0.6608581550 0.5528090097 0.7840872360 0.2169291389 -0.180419383158 +1403636749113555456.0000000000 3.7479456502 1.9447746461 -0.6530548791 0.5524274931 0.7846851501 0.2133650166 -0.183216947283 +1403636749163555584.0000000000 3.7433518423 1.9517761356 -0.6462621813 0.5526424440 0.7848644843 0.2114952889 -0.183966880731 +1403636749213555456.0000000000 3.7402518683 1.9595424559 -0.6392859165 0.5534586680 0.7847523093 0.2114311027 -0.18205549917 +1403636749263555584.0000000000 3.7389862591 1.9678424209 -0.6311095123 0.5560296877 0.7835438493 0.2140174562 -0.176313785496 +1403636749313555456.0000000000 3.7386590725 1.9764158496 -0.6212601653 0.5585072772 0.7822206078 0.2164638464 -0.171300745313 +1403636749363555584.0000000000 3.7390508720 1.9851977417 -0.6095239999 0.5598620119 0.7815727675 0.2189759951 -0.166577460534 +1403636749413555456.0000000000 3.7401056957 1.9934329365 -0.5959961041 0.5613178563 0.7807172592 0.2213052202 -0.162563294967 +1403636749463555584.0000000000 3.7415794301 2.0015024988 -0.5812621415 0.5629957788 0.7796146080 0.2238051464 -0.158581437981 +1403636749513555456.0000000000 3.7432055123 2.0090090899 -0.5657410140 0.5638805611 0.7789625146 0.2263767053 -0.154950640253 +1403636749563555584.0000000000 3.7448553797 2.0161549099 -0.5499235106 0.5646539801 0.7782584046 0.2296435994 -0.150809666988 +1403636749613555456.0000000000 3.7462809362 2.0233133730 -0.5343772557 0.5664805394 0.7767623140 0.2321943957 -0.147735806867 +1403636749663555584.0000000000 3.7470373833 2.0295909482 -0.5202940482 0.5667109155 0.7763722707 0.2334171830 -0.146973651224 +1403636749713555456.0000000000 3.7469711800 2.0350829666 -0.5074684216 0.5672302240 0.7757576957 0.2333956313 -0.148244223313 +1403636749763555584.0000000000 3.7463757331 2.0399606512 -0.4958466739 0.5689935158 0.7742042883 0.2328440844 -0.150458403639 +1403636749813555456.0000000000 3.7455792718 2.0441179820 -0.4856802053 0.5717434299 0.7718656160 0.2320410497 -0.153264061034 +1403636749863555584.0000000000 3.7445861901 2.0474645286 -0.4769527394 0.5745089220 0.7694845680 0.2307351119 -0.156825719239 +1403636749913555456.0000000000 3.7437793975 2.0498353148 -0.4700798405 0.5764353026 0.7675808677 0.2306698199 -0.15916465591 +1403636749963555584.0000000000 3.7432234222 2.0510304229 -0.4644800146 0.5782376543 0.7656566903 0.2308841588 -0.161565939889 +1403636750013555456.0000000000 3.7431053063 2.0507978558 -0.4604085697 0.5788855927 0.7645246709 0.2316279978 -0.163529718296 +1403636750063555584.0000000000 3.7435320525 2.0489857745 -0.4574627803 0.5787817399 0.7640327122 0.2323565477 -0.165154918332 +1403636750113555456.0000000000 3.7445677688 2.0457522664 -0.4550637574 0.5770718115 0.7647104076 0.2336800192 -0.166131771669 +1403636750163555584.0000000000 3.7462235702 2.0412385209 -0.4519057227 0.5751347712 0.7656533393 0.2351298013 -0.166460011966 +1403636750213555456.0000000000 3.7487165153 2.0349815705 -0.4475469902 0.5732094426 0.7665392524 0.2361513666 -0.167573988268 +1403636750263555584.0000000000 3.7514298030 2.0281199752 -0.4420321093 0.5705214010 0.7680126231 0.2382879637 -0.166975411688 +1403636750313555456.0000000000 3.7537289357 2.0210605404 -0.4337304715 0.5680966377 0.7691993762 0.2395429606 -0.167981248469 +1403636750363555584.0000000000 3.7568978479 2.0129143886 -0.4234484641 0.5658633588 0.7702260358 0.2420732263 -0.167185723235 +1403636750413555456.0000000000 3.7595445015 2.0047056743 -0.4100535789 0.5637635066 0.7712643541 0.2424197168 -0.168981317418 +1403636750463555584.0000000000 3.7626768884 1.9955795376 -0.3948753240 0.5626817192 0.7713344485 0.2446332614 -0.169076961537 +1403636750513555456.0000000000 3.7659049503 1.9860299498 -0.3762574121 0.5625325429 0.7706803301 0.2461581036 -0.170338354253 +1403636750563555584.0000000000 3.7691963556 1.9760872083 -0.3556799976 0.5617242240 0.7705183564 0.2481665067 -0.170823720606 +1403636750613555456.0000000000 3.7725301387 1.9658208527 -0.3333482118 0.5607084698 0.7705368841 0.2497470496 -0.171771165902 +1403636750663555584.0000000000 3.7759943390 1.9560745964 -0.3097471983 0.5609543059 0.7698056451 0.2518798325 -0.17113177821 +1403636750713555456.0000000000 3.7793993726 1.9460183673 -0.2842902025 0.5599956094 0.7699600256 0.2532728043 -0.171520736489 +1403636750763555584.0000000000 3.7829420708 1.9354426533 -0.2579497174 0.5588595405 0.7702750225 0.2546428002 -0.171783142331 +1403636750813555456.0000000000 3.7862145718 1.9248860793 -0.2300733525 0.5583606193 0.7702841463 0.2560180107 -0.171319966494 +1403636750863555584.0000000000 3.7895967572 1.9135844361 -0.2001642003 0.5577396976 0.7703802693 0.2570015660 -0.17143764309 +1403636750913555456.0000000000 3.7934068970 1.9014959375 -0.1690612324 0.5567141434 0.7709075100 0.2588127984 -0.169667053232 +1403636750963555584.0000000000 3.7969475779 1.8890582442 -0.1381948362 0.5564001977 0.7709500120 0.2603951802 -0.168075129354 +1403636751013555456.0000000000 3.8000542663 1.8767752937 -0.1080832433 0.5557451183 0.7714330736 0.2612757221 -0.166653453145 +1403636751063555584.0000000000 3.8025341194 1.8643323360 -0.0788771547 0.5556656836 0.7715547149 0.2614074500 -0.166147871098 +1403636751113555456.0000000000 3.8043003962 1.8516476717 -0.0515528460 0.5553149119 0.7719147494 0.2609425061 -0.166379015553 +1403636751163555584.0000000000 3.8053865412 1.8387419126 -0.0260396114 0.5530413080 0.7737791605 0.2602613784 -0.166358460103 +1403636751213555456.0000000000 3.8059421379 1.8259432734 -0.0020657473 0.5498634148 0.7762034765 0.2613464142 -0.16387934566 +1403636751263555584.0000000000 3.8056548775 1.8130852521 0.0214017172 0.5457217620 0.7793384858 0.2610366847 -0.1633374796 +1403636751313555456.0000000000 3.8048429713 1.8003500892 0.0447682960 0.5432813634 0.7812944913 0.2598976798 -0.163943509043 +1403636751363555584.0000000000 3.8032229404 1.7881929728 0.0682936844 0.5419294135 0.7825849730 0.2570962650 -0.166657676986 +1403636751413555456.0000000000 3.8008390453 1.7768258094 0.0918979348 0.5424619640 0.7825616957 0.2536790854 -0.170232581244 +1403636751463555584.0000000000 3.7981233581 1.7661688233 0.1154787206 0.5431542562 0.7823969630 0.2493531942 -0.175104057096 +1403636751513555456.0000000000 3.7953995887 1.7560824978 0.1386774497 0.5443538048 0.7814612914 0.2465035489 -0.179536028774 +1403636751563555584.0000000000 3.7929713423 1.7464923128 0.1612407820 0.5459685024 0.7795990435 0.2454072152 -0.18417118242 +1403636751613555456.0000000000 3.7910099380 1.7372465406 0.1827668344 0.5453381983 0.7789707609 0.2454571278 -0.188577839495 +1403636751663555584.0000000000 3.7899861622 1.7286361084 0.2034311300 0.5439987559 0.7787941338 0.2464360879 -0.191870543158 +1403636751713555456.0000000000 3.7898002143 1.7205526554 0.2226430554 0.5405425335 0.7800686662 0.2485493100 -0.193726317186 +1403636751763555584.0000000000 3.7906140134 1.7133296237 0.2408841681 0.5363823402 0.7819324886 0.2509628709 -0.194661772764 +1403636751813555456.0000000000 3.7920768403 1.7072452749 0.2583919079 0.5319655189 0.7840062667 0.2534241822 -0.195251234082 +1403636751863555584.0000000000 3.7941948749 1.7029906372 0.2752447000 0.5287257700 0.7855272329 0.2577083790 -0.192308132537 +1403636751913555456.0000000000 3.7966833210 1.7000656186 0.2923488824 0.5278789410 0.7853646525 0.2624127723 -0.188906652209 +1403636751963555584.0000000000 3.7989777730 1.6986201788 0.3092535813 0.5278423504 0.7847502473 0.2668696863 -0.1852837637 +1403636752013555456.0000000000 3.8007696518 1.6986257069 0.3258752144 0.5283052031 0.7839634125 0.2704908484 -0.182015606841 +1403636752063555584.0000000000 3.8018853880 1.6995708934 0.3425577869 0.5296914599 0.7826907319 0.2723720310 -0.180653403541 +1403636752113555456.0000000000 3.8022455287 1.7016533911 0.3590816421 0.5317519069 0.7810124280 0.2732463662 -0.180543402255 +1403636752163555584.0000000000 3.8017370378 1.7043984785 0.3756332709 0.5354572827 0.7777833214 0.2741569092 -0.182144427604 +1403636752213555456.0000000000 3.8006664453 1.7075354470 0.3915974371 0.5392547284 0.7739930614 0.2756749009 -0.184776697186 +1403636752263555584.0000000000 3.7994844945 1.7103918451 0.4079148174 0.5419878121 0.7702646395 0.2780466102 -0.188763553816 +1403636752313555456.0000000000 3.7979480990 1.7134208331 0.4255957212 0.5451503809 0.7656913107 0.2809905306 -0.193835499019 +1403636752363555584.0000000000 3.7964412693 1.7160858804 0.4444697200 0.5472978685 0.7611787830 0.2852023925 -0.199327616639 +1403636752413555456.0000000000 3.7952449384 1.7182274872 0.4646152057 0.5475791810 0.7574089833 0.2907742777 -0.204790116924 +1403636752463555584.0000000000 3.7944121286 1.7198174362 0.4860912529 0.5458263604 0.7544684796 0.2976842950 -0.210321083342 +1403636752513555456.0000000000 3.7939998661 1.7210980312 0.5082418401 0.5441023877 0.7510407270 0.3058529610 -0.215277458871 +1403636752563555584.0000000000 3.7939567914 1.7221326464 0.5295554166 0.5409745765 0.7482883859 0.3145828872 -0.220110440768 +1403636752613555456.0000000000 3.7940395006 1.7229782259 0.5495122827 0.5379354210 0.7451010315 0.3236968267 -0.225100644435 +1403636752663555584.0000000000 3.7946377287 1.7234717461 0.5675175993 0.5337101792 0.7425466782 0.3332015752 -0.229683664155 +1403636752713555456.0000000000 3.7951429844 1.7239715033 0.5844205855 0.5307618553 0.7388678880 0.3417070273 -0.235801621094 +1403636752763555584.0000000000 3.7957597746 1.7243889515 0.5996069568 0.5272996364 0.7352151805 0.3507148777 -0.241687414605 +1403636752813555456.0000000000 3.7966831890 1.7246682466 0.6126312866 0.5246800572 0.7307813329 0.3607165799 -0.246075252859 +1403636752863555584.0000000000 3.7978693723 1.7243714227 0.6240510412 0.5209506318 0.7267651567 0.3705973475 -0.251158221522 +1403636752913555456.0000000000 3.7990900960 1.7240883936 0.6340239791 0.5198852022 0.7206389973 0.3809716553 -0.255459214027 +1403636752963555584.0000000000 3.8002368789 1.7234399305 0.6418147316 0.5177993321 0.7148728527 0.3918360829 -0.259432342488 +1403636753013555456.0000000000 3.8013105990 1.7222682489 0.6479889328 0.5151946527 0.7092151863 0.4025891553 -0.263647987561 +1403636753063555584.0000000000 3.8022700177 1.7205509945 0.6524749731 0.5123038582 0.7034129535 0.4133071822 -0.268201690636 +1403636753113555456.0000000000 3.8028042313 1.7181149732 0.6553748910 0.5091482273 0.6974754134 0.4236616665 -0.27350854214 +1403636753163555584.0000000000 3.8028916928 1.7149136019 0.6568278402 0.5056346748 0.6915090217 0.4338080201 -0.279212195803 +1403636753213555456.0000000000 3.8025476701 1.7110098252 0.6566805440 0.5021093955 0.6852803713 0.4439876547 -0.284871778486 +1403636753263555584.0000000000 3.8017308388 1.7064078495 0.6547390170 0.4991048362 0.6784892721 0.4545841582 -0.28965481727 +1403636753313555456.0000000000 3.8003117742 1.7009728936 0.6512488324 0.4970031872 0.6708375211 0.4655243195 -0.293686840077 +1403636753363555584.0000000000 3.7983018369 1.6944894691 0.6471461956 0.4944868889 0.6643177063 0.4735215733 -0.299903353495 +1403636753413555456.0000000000 3.7955129177 1.6870959901 0.6435405969 0.4913452532 0.6594500737 0.4793509498 -0.306476931058 +1403636753463555584.0000000000 3.7915705655 1.6788705930 0.6409441987 0.4872825272 0.6565023364 0.4828939663 -0.313646039761 +1403636753513555456.0000000000 3.7874274351 1.6699895412 0.6399214524 0.4837157213 0.6544773656 0.4853826510 -0.319502990558 +1403636753563555584.0000000000 3.7834586560 1.6604508210 0.6409956320 0.4803657299 0.6531268714 0.4869320520 -0.324917269695 +1403636753613555456.0000000000 3.7796239192 1.6505977992 0.6435160232 0.4790068349 0.6513828430 0.4876993654 -0.329244852451 +1403636753663555584.0000000000 3.7767050789 1.6402412550 0.6475202502 0.4774568208 0.6507326158 0.4881888044 -0.33204478344 +1403636753713555456.0000000000 3.7733276444 1.6300193266 0.6509354121 0.4761642337 0.6506448628 0.4882879885 -0.333921735456 +1403636753763555584.0000000000 3.7697369114 1.6198683838 0.6540564332 0.4768163276 0.6496598231 0.4884744456 -0.33463565251 +1403636753813555456.0000000000 3.7663818975 1.6093904816 0.6557309852 0.4775116027 0.6490384629 0.4886810040 -0.334548381149 +1403636753863555584.0000000000 3.7635969469 1.5985374323 0.6558891010 0.4782707226 0.6489118700 0.4882115931 -0.334394888268 +1403636753913555456.0000000000 3.7609340628 1.5871868624 0.6545697207 0.4777928439 0.6499057822 0.4872336208 -0.334574164222 +1403636753963555584.0000000000 3.7587690586 1.5755324086 0.6520952088 0.4786494195 0.6500331198 0.4865790871 -0.334054588912 +1403636754013555456.0000000000 3.7568444276 1.5636187427 0.6500572474 0.4799251457 0.6501311605 0.4857796160 -0.333195878517 +1403636754063555584.0000000000 3.7546070913 1.5513250977 0.6499628034 0.4823034647 0.6494885931 0.4834721628 -0.334368962598 +1403636754113555456.0000000000 3.7524776794 1.5386888509 0.6517590549 0.4848776324 0.6485618777 0.4812193088 -0.335692045244 +1403636754163555584.0000000000 3.7510750554 1.5254396936 0.6550116015 0.4873326015 0.6478607734 0.4795327879 -0.335904240986 +1403636754213555456.0000000000 3.7506008423 1.5115516359 0.6589700938 0.4903553387 0.6467754166 0.4784506547 -0.33513903579 +1403636754263555584.0000000000 3.7515891468 1.4967015797 0.6646585429 0.4922023665 0.6464959223 0.4776694311 -0.334083473715 +1403636754313555456.0000000000 3.7526575765 1.4812110744 0.6717982357 0.4932178390 0.6467463711 0.4771648079 -0.332819832367 +1403636754363555584.0000000000 3.7541992935 1.4650577576 0.6804245053 0.4943023625 0.6463978885 0.4774985274 -0.331406246961 +1403636754413555456.0000000000 3.7566082537 1.4474345579 0.6903114959 0.4938299462 0.6463080137 0.4778340891 -0.331801927199 +1403636754463555584.0000000000 3.7599823155 1.4284366702 0.7004717643 0.4926799381 0.6456784528 0.4791750047 -0.332801936763 +1403636754513555456.0000000000 3.7641202773 1.4084064670 0.7098178718 0.4913701185 0.6444826253 0.4816213303 -0.333524281848 +1403636754563555584.0000000000 3.7689954313 1.3872026632 0.7174122410 0.4894240232 0.6426712423 0.4858513804 -0.333745765429 +1403636754613555456.0000000000 3.7743632751 1.3647607786 0.7234160124 0.4868330131 0.6403601933 0.4906233747 -0.334994245421 +1403636754663555584.0000000000 3.7801960651 1.3411745415 0.7282887995 0.4842199441 0.6371052497 0.4952843514 -0.338114415335 +1403636754713555456.0000000000 3.7865998579 1.3165570845 0.7319984738 0.4804450546 0.6340267879 0.5003204517 -0.341850884778 +1403636754763555584.0000000000 3.7932869658 1.2910067418 0.7349467215 0.4773574126 0.6296357632 0.5055436898 -0.346575077112 +1403636754813555456.0000000000 3.8004765492 1.2651519677 0.7364334000 0.4744417623 0.6253615355 0.5110950149 -0.350156893238 +1403636754863555584.0000000000 3.8079563666 1.2386915481 0.7368334631 0.4709782601 0.6220612065 0.5152924817 -0.354532075009 +1403636754913555456.0000000000 3.8158620533 1.2119568973 0.7359372526 0.4693979273 0.6182332309 0.5194142322 -0.357298353557 +1403636754963555584.0000000000 3.8241193936 1.1846239796 0.7340929168 0.4664778591 0.6157670966 0.5227461042 -0.360507697944 +1403636755013555456.0000000000 3.8325543553 1.1570479360 0.7311694862 0.4653213237 0.6126447409 0.5268268913 -0.361380566455 +1403636755063555584.0000000000 3.8413660499 1.1287609704 0.7282884101 0.4634545721 0.6110655973 0.5284693627 -0.3640450908 +1403636755113555456.0000000000 3.8508232726 1.1000812350 0.7264119891 0.4620596300 0.6094014402 0.5307337257 -0.36531150446 +1403636755163555584.0000000000 3.8616448763 1.0706122350 0.7255615442 0.4599529426 0.6088431319 0.5320723074 -0.366950120645 +1403636755213555456.0000000000 3.8732552171 1.0406134692 0.7261627725 0.4586396216 0.6080828348 0.5331284597 -0.368319167224 +1403636755263555584.0000000000 3.8850152752 1.0103293458 0.7284660436 0.4563544981 0.6087025711 0.5348312419 -0.367664649727 +1403636755313555456.0000000000 3.8967147668 0.9796252885 0.7323395491 0.4525126231 0.6105709080 0.5372497192 -0.365784405864 +1403636755363555584.0000000000 3.9091615849 0.9485989863 0.7381112207 0.4480347146 0.6132313017 0.5397026938 -0.363226193272 +1403636755413555456.0000000000 3.9209784977 0.9177267710 0.7453273975 0.4449905703 0.6151216074 0.5421633690 -0.360093990277 +1403636755463555584.0000000000 3.9316509666 0.8867207583 0.7538958141 0.4425901179 0.6168740726 0.5431798696 -0.358519170011 +1403636755513555456.0000000000 3.9414021842 0.8557192416 0.7624644466 0.4426214806 0.6172369524 0.5436059064 -0.35720776598 +1403636755563555584.0000000000 3.9504133171 0.8245195319 0.7698480451 0.4436440516 0.6169886933 0.5440086025 -0.355752088282 +1403636755613555456.0000000000 3.9585982166 0.7930069655 0.7760352974 0.4455667754 0.6161235710 0.5434711244 -0.355669974784 +1403636755663555584.0000000000 3.9660531847 0.7608764807 0.7808527722 0.4459611715 0.6165511038 0.5417276788 -0.357091713628 +1403636755713555456.0000000000 3.9733764389 0.7285360530 0.7839729945 0.4465039988 0.6167382768 0.5407634451 -0.357551357815 +1403636755763555584.0000000000 3.9803681223 0.6958432796 0.7860267708 0.4470307072 0.6169571497 0.5390587490 -0.359086462304 +1403636755813555456.0000000000 3.9869545226 0.6629868795 0.7869126408 0.4485977006 0.6163705915 0.5371507927 -0.360993660343 +1403636755863555584.0000000000 3.9936898754 0.6298368101 0.7863423903 0.4493620511 0.6161204224 0.5358615791 -0.36238341598 +1403636755913555456.0000000000 4.0001280793 0.5965322338 0.7851547883 0.4511168292 0.6150744881 0.5346429780 -0.363777221094 +1403636755963555584.0000000000 4.0065599767 0.5628665248 0.7842524628 0.4510326168 0.6152455901 0.5336514525 -0.36504598296 +1403636756013555456.0000000000 4.0133469525 0.5290418117 0.7845548808 0.4514977820 0.6149510641 0.5328509125 -0.366135011645 +1403636756063555584.0000000000 4.0195508967 0.4952061889 0.7862562708 0.4518114959 0.6147395729 0.5322307246 -0.367004203487 +1403636756113555456.0000000000 4.0256623290 0.4615044266 0.7894359800 0.4530526688 0.6138280657 0.5325311266 -0.36656375182 +1403636756163555584.0000000000 4.0310498999 0.4275254003 0.7947199056 0.4540000647 0.6130005477 0.5324335684 -0.366917926863 +1403636756213555456.0000000000 4.0375830304 0.3933802974 0.8012706531 0.4545299114 0.6125439283 0.5318458956 -0.367875575189 +1403636756263555584.0000000000 4.0445058898 0.3589267427 0.8082922911 0.4543293282 0.6124507364 0.5317191236 -0.368461301377 +1403636756313555456.0000000000 4.0518016354 0.3243222031 0.8147784421 0.4541873052 0.6122668259 0.5318181923 -0.368798909855 +1403636756363555584.0000000000 4.0590532859 0.2897366126 0.8203795063 0.4545854305 0.6115108481 0.5321159221 -0.369133058032 +1403636756413555456.0000000000 4.0665565158 0.2551521452 0.8246860546 0.4552802609 0.6106972118 0.5325164153 -0.369046158263 +1403636756463555584.0000000000 4.0744641186 0.2203324267 0.8275211186 0.4550718257 0.6104256925 0.5325204146 -0.369746014736 +1403636756513555456.0000000000 4.0827225908 0.1853534589 0.8286596371 0.4546415112 0.6102649615 0.5326027690 -0.370421467382 +1403636756563555584.0000000000 4.0911573586 0.1503665728 0.8285146739 0.4547558468 0.6097551273 0.5330113906 -0.370532943266 +1403636756613555456.0000000000 4.0996917760 0.1149377470 0.8273851959 0.4548173808 0.6093809507 0.5328619002 -0.371287223575 +1403636756663555584.0000000000 4.1086507440 0.0792555006 0.8262883650 0.4544415494 0.6091430632 0.5329413078 -0.372023076081 +1403636756713555456.0000000000 4.1182492033 0.0435463999 0.8262136093 0.4549524593 0.6082724778 0.5328052464 -0.373016651 +1403636756763555584.0000000000 4.1286238251 0.0076629447 0.8275306857 0.4551375962 0.6077107377 0.5328171933 -0.373688729163 +1403636756813555456.0000000000 4.1399173319 -0.0283927048 0.8297660797 0.4548999537 0.6073941839 0.5326714934 -0.374699102874 +1403636756863555584.0000000000 4.1515841363 -0.0645413678 0.8335549646 0.4543089244 0.6073399463 0.5329225973 -0.37514676607 +1403636756913555456.0000000000 4.1639311440 -0.1007491430 0.8389654591 0.4542019236 0.6071630256 0.5333759966 -0.374918283254 +1403636756963555584.0000000000 4.1770178314 -0.1372351304 0.8465935520 0.4532970159 0.6073718222 0.5334455771 -0.37557569314 +1403636757013555456.0000000000 4.1908147976 -0.1735293107 0.8542301997 0.4534817278 0.6068730031 0.5338723714 -0.375552621886 +1403636757063555584.0000000000 4.2048618239 -0.2102109725 0.8615417068 0.4518065629 0.6077356227 0.5333290534 -0.376946101419 +1403636757113555456.0000000000 4.2191577932 -0.2467584662 0.8678170546 0.4521174460 0.6072866338 0.5334180275 -0.377171005558 +1403636757163555584.0000000000 4.2336197371 -0.2833564208 0.8724584564 0.4514136172 0.6076788433 0.5337405564 -0.376925971577 +1403636757213555456.0000000000 4.2486672537 -0.3198312373 0.8757966452 0.4515038625 0.6075562185 0.5334567109 -0.377417065211 +1403636757263555584.0000000000 4.2642005223 -0.3561960718 0.8775401009 0.4515839182 0.6072166540 0.5341289551 -0.376916647661 +1403636757313555456.0000000000 4.2802201344 -0.3922616954 0.8772612036 0.4524117966 0.6064719206 0.5356912554 -0.374900326283 +1403636757363555584.0000000000 4.2965546439 -0.4287125978 0.8759040128 0.4514136206 0.6069425250 0.5361197366 -0.374729425792 +1403636757413555456.0000000000 4.3132827953 -0.4651635372 0.8728395203 0.4511088370 0.6068713793 0.5377647516 -0.372849860013 +1403636757463555584.0000000000 4.3300330482 -0.5017769520 0.8694534215 0.4507499599 0.6068928795 0.5396231979 -0.370556757686 +1403636757513555456.0000000000 4.3473304957 -0.5388922697 0.8670159988 0.4494568786 0.6062685714 0.5425136900 -0.368925235998 +1403636757563555584.0000000000 4.3647088937 -0.5767839213 0.8662540411 0.4461685978 0.6061766097 0.5462082543 -0.367613986538 +1403636757613555456.0000000000 4.3821722177 -0.6150808770 0.8660949506 0.4412645481 0.6063947226 0.5510776501 -0.365902258355 +1403636757663555584.0000000000 4.3992701433 -0.6537305827 0.8681596885 0.4360701464 0.6069411231 0.5558896351 -0.363939574832 +1403636757713555456.0000000000 4.4155342356 -0.6926717553 0.8716949346 0.4304449919 0.6075586876 0.5604265902 -0.36264526344 +1403636757763555584.0000000000 4.4303509920 -0.7317082094 0.8775425366 0.4254266097 0.6080233887 0.5641155279 -0.362068266752 +1403636757813555456.0000000000 4.4434222528 -0.7708308889 0.8856891056 0.4213463695 0.6079284292 0.5674658010 -0.361763495403 +1403636757863555584.0000000000 4.4544799593 -0.8098118558 0.8968320403 0.4179032972 0.6078443978 0.5693311613 -0.362965633372 +1403636757913555456.0000000000 4.4639797227 -0.8487440339 0.9109348426 0.4162998113 0.6068322919 0.5704406981 -0.364755324327 +1403636757963555584.0000000000 4.4718440129 -0.8877540417 0.9265045379 0.4158533514 0.6052927985 0.5698131124 -0.368781283688 +1403636758013555456.0000000000 4.4774812932 -0.9261075748 0.9427973061 0.4201074858 0.6010428345 0.5676937170 -0.374140421687 +1403636758063555584.0000000000 4.4821256104 -0.9642346529 0.9576117040 0.4232867681 0.5974830426 0.5655532983 -0.379462504796 +1403636758113555456.0000000000 4.4861601058 -1.0021931888 0.9709943503 0.4259609969 0.5946765616 0.5629924463 -0.384651168586 +1403636758163555584.0000000000 4.4899472875 -1.0399107564 0.9826718366 0.4285184698 0.5921315445 0.5610405863 -0.388568675545 +1403636758213555456.0000000000 4.4940557799 -1.0771396827 0.9925995608 0.4307359132 0.5898720566 0.5593937581 -0.391913451204 +1403636758263555584.0000000000 4.4987163671 -1.1141589327 1.0007585959 0.4311673001 0.5891743241 0.5582241287 -0.394149968014 +1403636758313555456.0000000000 4.5035789068 -1.1509163370 1.0071156749 0.4313897921 0.5888078249 0.5568732798 -0.396358856262 +1403636758363555584.0000000000 4.5090472965 -1.1872166182 1.0106521476 0.4296487361 0.5898791137 0.5570630208 -0.396390445997 +1403636758413555456.0000000000 4.5154520095 -1.2233969301 1.0116286631 0.4241510202 0.5936730843 0.5584607537 -0.39467678888 +1403636758463555584.0000000000 4.5219836333 -1.2592573654 1.0107094857 0.4164495377 0.5990127136 0.5603381087 -0.392141244408 +1403636758513555456.0000000000 4.5282187778 -1.2948508190 1.0086220309 0.4062315899 0.6060073291 0.5619783749 -0.389758025707 +1403636758563555584.0000000000 4.5335239762 -1.3295123306 1.0061120241 0.3955794282 0.6131925300 0.5629242311 -0.388108421903 +1403636758613555456.0000000000 4.5375125105 -1.3624872660 1.0031879135 0.3868710276 0.6189582474 0.5634554208 -0.386961864827 +1403636758663555584.0000000000 4.5388640273 -1.3931918983 1.0005299283 0.3850973543 0.6204556732 0.5632555927 -0.386623748136 +1403636758713555456.0000000000 4.5375209273 -1.4217437232 0.9985674354 0.3898006402 0.6178669370 0.5609203416 -0.389440983338 +1403636758763555584.0000000000 4.5344010068 -1.4481180448 0.9961461210 0.3979166217 0.6132370667 0.5588393160 -0.391537074916 +1403636758813555456.0000000000 4.5302264644 -1.4733775912 0.9935356933 0.4036921330 0.6095609898 0.5559636785 -0.395439565198 +1403636758863555584.0000000000 4.5254542206 -1.4970994617 0.9901379713 0.4110316380 0.6046402841 0.5542119587 -0.397884687121 +1403636758913555456.0000000000 4.5209620773 -1.5193952049 0.9852844006 0.4179217326 0.6001536985 0.5545643105 -0.397008046699 +1403636758963555584.0000000000 4.5167580852 -1.5410610618 0.9799748347 0.4222611802 0.5972503489 0.5538566079 -0.397781817561 +1403636759013555456.0000000000 4.5131996880 -1.5621284293 0.9737090942 0.4248124495 0.5954579145 0.5539510705 -0.39762100835 +1403636759063555584.0000000000 4.5099098320 -1.5832208565 0.9674450074 0.4249970668 0.5951673879 0.5520479060 -0.400495172339 +1403636759113555456.0000000000 4.5070092452 -1.6040300386 0.9609519953 0.4216080945 0.5974384786 0.5483191395 -0.405783193645 +1403636759163555584.0000000000 4.5044887965 -1.6243321692 0.9542778370 0.4154717024 0.6012949009 0.5433008947 -0.413100283876 +1403636759213555456.0000000000 4.5024370804 -1.6430010213 0.9468304074 0.4093375157 0.6050778487 0.5385191966 -0.419905549126 +1403636759263555584.0000000000 4.5009292361 -1.6594039540 0.9381353440 0.4040787693 0.6082627178 0.5344635270 -0.425541481681 +1403636759313555456.0000000000 4.4999593478 -1.6729919892 0.9276381561 0.4026579937 0.6089008495 0.5336037456 -0.427051915209 +1403636759363555584.0000000000 4.4995955138 -1.6834415159 0.9152817902 0.4071991151 0.6057527384 0.5365052458 -0.423573632149 +1403636759413555456.0000000000 4.4999385564 -1.6914721477 0.9014617555 0.4119145197 0.6025592452 0.5405587404 -0.418383834084 +1403636759463555584.0000000000 4.5008636836 -1.6978320245 0.8870342425 0.4171490127 0.5988190673 0.5439426835 -0.414160334762 +1403636759513555456.0000000000 4.5026902807 -1.7028643193 0.8714864228 0.4218594655 0.5955505623 0.5476487395 -0.409188192871 +1403636759563555584.0000000000 4.5051838763 -1.7072793785 0.8559124071 0.4250228866 0.5927542036 0.5502395664 -0.406490368273 +1403636759613555456.0000000000 4.5083630008 -1.7108597988 0.8416829343 0.4285546848 0.5898204224 0.5531941281 -0.403024823278 +1403636759663555584.0000000000 4.5130499497 -1.7141039963 0.8302865887 0.4302462911 0.5882089877 0.5551501123 -0.400882362555 +1403636759713555456.0000000000 4.5179299881 -1.7173071791 0.8215431749 0.4309786121 0.5872863115 0.5566740230 -0.399332262988 +1403636759763555584.0000000000 4.5233150203 -1.7208138190 0.8158563303 0.4307056815 0.5869845713 0.5564447190 -0.400388565772 +1403636759813555456.0000000000 4.5285109484 -1.7239590716 0.8125894137 0.4322844151 0.5857482337 0.5568668009 -0.399910686465 +1403636759863555584.0000000000 4.5342468533 -1.7270646300 0.8105433868 0.4313744836 0.5864644504 0.5569554094 -0.399720121136 +1403636759913555456.0000000000 4.5409822916 -1.7302096025 0.8074970667 0.4282554653 0.5885625145 0.5591527134 -0.396912668209 +1403636759963555584.0000000000 4.5483068245 -1.7332243609 0.8036736603 0.4251121527 0.5908237579 0.5615807204 -0.393489566795 +1403636760013555456.0000000000 4.5557640694 -1.7363938348 0.7994937678 0.4220465372 0.5931026340 0.5630795377 -0.391212755759 +1403636760063555584.0000000000 4.5630048130 -1.7394996547 0.7948027719 0.4185285224 0.5957528213 0.5637719739 -0.389966169437 +1403636760113555456.0000000000 4.5699698469 -1.7423413367 0.7891481849 0.4162243298 0.5975439771 0.5657829420 -0.386766292759 +1403636760163555584.0000000000 4.5760908295 -1.7452926285 0.7835387650 0.4142028387 0.5990400050 0.5671929333 -0.384550721297 +1403636760213555456.0000000000 4.5805851978 -1.7479959844 0.7788471060 0.4162818269 0.5977080296 0.5650905294 -0.387462573087 +1403636760263555584.0000000000 4.5843196243 -1.7502537943 0.7740566520 0.4207558444 0.5949114057 0.5618789226 -0.391582705337 +1403636760313555456.0000000000 4.5878189959 -1.7524358043 0.7689416320 0.4241743783 0.5925144717 0.5583845046 -0.396496459786 +1403636760363555584.0000000000 4.5915270411 -1.7539392881 0.7623680081 0.4275045226 0.5902524198 0.5572726030 -0.397855765316 +1403636760413555456.0000000000 4.5955914091 -1.7553140765 0.7550704147 0.4308228412 0.5877542999 0.5565779798 -0.398945503632 +1403636760463555584.0000000000 4.6002863620 -1.7566217786 0.7468985013 0.4325062754 0.5865587107 0.5567847401 -0.398594974707 +1403636760513555456.0000000000 4.6060707537 -1.7579746694 0.7382911988 0.4325121074 0.5865253611 0.5582719484 -0.396552278286 +1403636760563555584.0000000000 4.6125129986 -1.7597615641 0.7294771130 0.4297837098 0.5881763444 0.5609224396 -0.393319930129 +1403636760613555456.0000000000 4.6190802690 -1.7615460193 0.7205953782 0.4269430373 0.5899965579 0.5636945529 -0.389707782269 +1403636760663555584.0000000000 4.6254977990 -1.7634839800 0.7121056476 0.4256873172 0.5906299543 0.5664455909 -0.386116507754 +1403636760713555456.0000000000 4.6317294230 -1.7656811177 0.7041994755 0.4244442309 0.5911141141 0.5688045024 -0.383265752447 +1403636760763555584.0000000000 4.6371647915 -1.7681674869 0.6971826205 0.4256320442 0.5900160168 0.5698039029 -0.382154386522 +1403636760813555456.0000000000 4.6418871815 -1.7712528560 0.6905736658 0.4275811492 0.5883822443 0.5693850845 -0.383120504685 +1403636760863555584.0000000000 4.6463224855 -1.7746998066 0.6840983001 0.4307902858 0.5858968881 0.5689066529 -0.384043990211 +1403636760913555456.0000000000 4.6509499800 -1.7787905315 0.6777571849 0.4332348358 0.5837034742 0.5685577889 -0.38514915529 +1403636760963555584.0000000000 4.6557782595 -1.7836339018 0.6711544243 0.4330139400 0.5837144141 0.5687764434 -0.385058135835 +1403636761013555456.0000000000 4.6609271796 -1.7894886413 0.6645128356 0.4296373324 0.5858384105 0.5695839256 -0.384420695563 +1403636761063555584.0000000000 4.6659382567 -1.7956574474 0.6575054976 0.4254220545 0.5887364661 0.5705327369 -0.383272546916 +1403636761113555456.0000000000 4.6704479782 -1.8024086877 0.6504253726 0.4199942097 0.5922601755 0.5722132186 -0.381319788134 +1403636761163555584.0000000000 4.6742712300 -1.8093721481 0.6429026730 0.4145311681 0.5958215829 0.5747783177 -0.377876219852 +1403636761213555456.0000000000 4.6771664400 -1.8164665742 0.6357590376 0.4105954400 0.5980249487 0.5780411693 -0.373692322621 +1403636761263555584.0000000000 4.6787531162 -1.8238579659 0.6297835013 0.4069710447 0.6004041007 0.5792112152 -0.372026683006 +1403636761313555456.0000000000 4.6783914995 -1.8312127338 0.6248345004 0.4065737167 0.6005951417 0.5799857103 -0.370944557176 +1403636761363555584.0000000000 4.6759852647 -1.8386432036 0.6212310412 0.4079752390 0.5995275735 0.5788021618 -0.372975804164 +1403636761413555456.0000000000 4.6720079491 -1.8460109327 0.6191515748 0.4124125232 0.5966263163 0.5760608887 -0.376970558463 +1403636761463555584.0000000000 4.6670085420 -1.8533245744 0.6179948691 0.4177837114 0.5931647384 0.5731441920 -0.380943695129 +1403636761513555456.0000000000 4.6613529742 -1.8608318940 0.6177802568 0.4220414344 0.5904594260 0.5698651801 -0.38534707786 +1403636761563555584.0000000000 4.6556095404 -1.8684222818 0.6181589713 0.4258885661 0.5881543837 0.5670456954 -0.388783396777 +1403636761613555456.0000000000 4.6499134445 -1.8762092956 0.6190411172 0.4284683625 0.5867048169 0.5644912676 -0.391844266245 +1403636761663555584.0000000000 4.6447391411 -1.8842178370 0.6202782547 0.4276282856 0.5876465826 0.5615519214 -0.395556548315 +1403636761713555456.0000000000 4.6398658449 -1.8922985134 0.6222686191 0.4250510796 0.5898554922 0.5576866922 -0.400484246187 +1403636761763555584.0000000000 4.6354523869 -1.8999387685 0.6244137135 0.4218939072 0.5922292229 0.5547646584 -0.404359063692 +1403636761813555456.0000000000 4.6314373911 -1.9068070033 0.6270354835 0.4192468296 0.5943523439 0.5522283777 -0.407456999013 +1403636761863555584.0000000000 4.6279896241 -1.9126570836 0.6298910022 0.4175134575 0.5956509547 0.5508213646 -0.409241099104 +1403636761913555456.0000000000 4.6252223207 -1.9168292074 0.6325958983 0.4178276964 0.5956690132 0.5515443057 -0.407918278278 +1403636761963555584.0000000000 4.6228831689 -1.9196366142 0.6354585651 0.4197610749 0.5946374824 0.5532060413 -0.405178948509 +1403636762013555456.0000000000 4.6205844255 -1.9212906778 0.6383167401 0.4256335931 0.5907517464 0.5568299571 -0.399735934502 +1403636762063555584.0000000000 4.6184727639 -1.9226147022 0.6415230003 0.4316675744 0.5869165766 0.5603431274 -0.393963979208 +1403636762113555456.0000000000 4.6171653892 -1.9238031618 0.6448626708 0.4390891466 0.5817316305 0.5653706156 -0.386193084263 +1403636762163555584.0000000000 4.6163425234 -1.9260091585 0.6485812144 0.4433184346 0.5788322505 0.5693945265 -0.379752372539 +1403636762213555456.0000000000 4.6160979062 -1.9298100955 0.6523218399 0.4422542738 0.5798602210 0.5724969970 -0.374727193989 +1403636762263555584.0000000000 4.6157990791 -1.9353059562 0.6556403698 0.4370819415 0.5837376640 0.5749405011 -0.371016355716 +1403636762313555456.0000000000 4.6146644188 -1.9420462023 0.6576024338 0.4307303524 0.5884730423 0.5766760666 -0.36826017474 +1403636762363555584.0000000000 4.6136050924 -1.9495607641 0.6574803399 0.4245345347 0.5929500810 0.5778253811 -0.366467541901 +1403636762413555456.0000000000 4.6105858049 -1.9579484608 0.6555296062 0.4198470028 0.5964182810 0.5772138037 -0.367202877382 +1403636762463555584.0000000000 4.6063367822 -1.9672802646 0.6521215536 0.4144238873 0.6003904806 0.5741345411 -0.371690248984 +1403636762513555456.0000000000 4.6003152754 -1.9773819195 0.6483332017 0.4088785752 0.6045631397 0.5660916742 -0.383225700106 +1403636762563555584.0000000000 4.5935815995 -1.9870368859 0.6425383094 0.4046877865 0.6076417455 0.5577300103 -0.394888009648 +1403636762613555456.0000000000 4.5864396718 -1.9957258291 0.6347560171 0.4008246534 0.6102372604 0.5493906385 -0.406349615036 +1403636762663555584.0000000000 4.5789525221 -2.0024570552 0.6244682677 0.4004289446 0.6102942535 0.5435098790 -0.414481116572 +1403636762713555456.0000000000 4.5716951912 -2.0065929182 0.6104925102 0.4055113263 0.6066729508 0.5434930556 -0.414878046608 diff --git a/data/euroc_groundtruth/MH_02_easy.txt b/data/euroc_groundtruth/MH_02_easy.txt new file mode 100755 index 00000000..702c7f2a --- /dev/null +++ b/data/euroc_groundtruth/MH_02_easy.txt @@ -0,0 +1,3000 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403636859551666432.0000000000 4.6007251330 -1.8992266135 0.7254218941 0.4553496982 0.6652088523 0.4806972609 -0.345085465526 +1403636859601666560.0000000000 4.5986132409 -1.8957845851 0.7476130289 0.4578604366 0.6661437955 0.4802166833 -0.340599767178 +1403636859651666432.0000000000 4.5960790067 -1.8926073207 0.7705000109 0.4624068450 0.6658715875 0.4786942508 -0.33711534057 +1403636859701666560.0000000000 4.5932628122 -1.8903267716 0.7940387527 0.4673689069 0.6646097000 0.4756961562 -0.337006555515 +1403636859751666432.0000000000 4.5905739813 -1.8879864657 0.8175848138 0.4738624301 0.6620928672 0.4732541966 -0.33633004313 +1403636859801666560.0000000000 4.5883869808 -1.8860577519 0.8402761439 0.4802112544 0.6594949047 0.4715534337 -0.33481484585 +1403636859851666432.0000000000 4.5867636625 -1.8844915355 0.8622409401 0.4858023464 0.6571830669 0.4706510208 -0.332556932742 +1403636859901666560.0000000000 4.5860565127 -1.8839241257 0.8831788284 0.4889187907 0.6559270013 0.4698856203 -0.33155043196 +1403636859951666432.0000000000 4.5860467146 -1.8836141293 0.9021344939 0.4907032984 0.6555303130 0.4687546958 -0.331299436868 +1403636860001666560.0000000000 4.5867605505 -1.8827386843 0.9170741102 0.4917685232 0.6558961233 0.4678833602 -0.330225917025 +1403636860051666432.0000000000 4.5873967418 -1.8810180258 0.9263528689 0.4918892338 0.6571993132 0.4671897297 -0.328432338196 +1403636860101666560.0000000000 4.5882292257 -1.8787878358 0.9278415538 0.4904044646 0.6598095820 0.4659323709 -0.327202998673 +1403636860151666432.0000000000 4.5891755842 -1.8764623463 0.9211182081 0.4880116279 0.6621457515 0.4658908619 -0.326118628134 +1403636860201666560.0000000000 4.5907776864 -1.8745791881 0.9060767797 0.4846225920 0.6647731418 0.4664992160 -0.3249555273 +1403636860251666432.0000000000 4.5928801063 -1.8739484164 0.8847568274 0.4791198408 0.6681090846 0.4675566709 -0.324754043478 +1403636860301666560.0000000000 4.5953053145 -1.8738760549 0.8587300054 0.4722389992 0.6726900331 0.4689491326 -0.323365363228 +1403636860351666432.0000000000 4.5979561124 -1.8734197831 0.8294532968 0.4646976572 0.6783317812 0.4709599194 -0.319560379929 +1403636860401666560.0000000000 4.6009032293 -1.8736109762 0.7999149085 0.4561419063 0.6848722254 0.4727842984 -0.315213583874 +1403636860451666432.0000000000 4.6041696804 -1.8742072936 0.7707819998 0.4474409662 0.6912571226 0.4749813310 -0.310407647084 +1403636860501666560.0000000000 4.6072545695 -1.8750770763 0.7434868878 0.4380260768 0.6975416711 0.4770071398 -0.306647944227 +1403636860551666432.0000000000 4.6100552722 -1.8762165399 0.7195651896 0.4291716999 0.7023640488 0.4793990700 -0.304422283426 +1403636860601666560.0000000000 4.6129975649 -1.8770004728 0.6991733468 0.4222902498 0.7063530274 0.4813475007 -0.301729894501 +1403636860651666432.0000000000 4.6157729415 -1.8779571913 0.6826182664 0.4171681133 0.7080534120 0.4834497069 -0.301508726102 +1403636860701666560.0000000000 4.6179924359 -1.8784334210 0.6685783310 0.4146381379 0.7078010246 0.4860098444 -0.301475298033 +1403636860751666432.0000000000 4.6201836764 -1.8786693575 0.6611674105 0.4152340195 0.7063254235 0.4885342181 -0.300032369776 +1403636860801666560.0000000000 4.6219347314 -1.8786362172 0.6597550726 0.4168594273 0.7039402596 0.4914868648 -0.298558186167 +1403636860851666432.0000000000 4.6229967627 -1.8783765721 0.6651911615 0.4182496400 0.7017227154 0.4942209594 -0.297318200996 +1403636860901666560.0000000000 4.6233121159 -1.8778027308 0.6775860961 0.4188659597 0.6997897782 0.4965897029 -0.29705932271 +1403636860951666432.0000000000 4.6230756935 -1.8769846469 0.6963656488 0.4193750601 0.6978553397 0.4985029024 -0.297686647473 +1403636861001666560.0000000000 4.6218727666 -1.8755941006 0.7202896893 0.4218198496 0.6954813115 0.4990660434 -0.298842507218 +1403636861051666432.0000000000 4.6197797471 -1.8738751236 0.7478137832 0.4257000318 0.6928182829 0.4976826447 -0.301818314487 +1403636861101666560.0000000000 4.6167828148 -1.8717432087 0.7775421884 0.4317269700 0.6893374233 0.4949858023 -0.305638341397 +1403636861151666432.0000000000 4.6133092988 -1.8692395931 0.8080543505 0.4392490650 0.6850481124 0.4913280599 -0.31042886491 +1403636861201666560.0000000000 4.6095237190 -1.8664509270 0.8393565887 0.4477734366 0.6795519629 0.4878967506 -0.315697386712 +1403636861251666432.0000000000 4.6061386731 -1.8637047544 0.8704068236 0.4564913913 0.6738085647 0.4840230040 -0.321433289142 +1403636861301666560.0000000000 4.6031024282 -1.8611831738 0.9009661133 0.4642180279 0.6686707404 0.4795039649 -0.327806362227 +1403636861351666432.0000000000 4.6077357258 -1.8616316080 0.9331627599 0.4713334528 0.6644234483 0.4750385865 -0.332753059946 +1403636861401666560.0000000000 4.6062444069 -1.8593691560 0.9571163232 0.4769946456 0.6614985834 0.4700324423 -0.337587374418 +1403636861451666432.0000000000 4.6051334750 -1.8570311073 0.9741852060 0.4822384764 0.6586561201 0.4666316457 -0.340401343322 +1403636861501666560.0000000000 4.6042096483 -1.8551822270 0.9830963842 0.4855708053 0.6572228518 0.4637325399 -0.342390489819 +1403636861551666432.0000000000 4.6034989209 -1.8533161351 0.9830590642 0.4873767661 0.6571633930 0.4625637647 -0.34151855937 +1403636861601666560.0000000000 4.6031617789 -1.8520765419 0.9745049976 0.4858029561 0.6584391783 0.4632666480 -0.34034886387 +1403636861651666432.0000000000 4.6031376316 -1.8516556825 0.9584918130 0.4818493410 0.6608222260 0.4649882842 -0.339000138342 +1403636861701666560.0000000000 4.6032778567 -1.8518703248 0.9365410985 0.4775263089 0.6632593451 0.4675277426 -0.336858242086 +1403636861751666432.0000000000 4.6038124948 -1.8525121201 0.9110132842 0.4733446022 0.6654518903 0.4705064829 -0.334278804038 +1403636861801666560.0000000000 4.6047365188 -1.8536311372 0.8835868833 0.4697508807 0.6674682305 0.4735087436 -0.331073618754 +1403636861851666432.0000000000 4.6060475251 -1.8557537263 0.8554024216 0.4647905089 0.6697266650 0.4761673344 -0.329697811114 +1403636861901666560.0000000000 4.6075257592 -1.8586579808 0.8267914316 0.4581952473 0.6728868043 0.4794124363 -0.327786790216 +1403636861951666432.0000000000 4.6090950028 -1.8618925170 0.7980015929 0.4501117017 0.6775435472 0.4825424943 -0.324787528822 +1403636862001666560.0000000000 4.6105810039 -1.8654619496 0.7695507435 0.4413105570 0.6826352331 0.4855388788 -0.321723682784 +1403636862051666432.0000000000 4.6119951176 -1.8693284349 0.7429237139 0.4332730880 0.6875698012 0.4875018915 -0.319161566512 +1403636862101666560.0000000000 4.6144829334 -1.8721934567 0.7155465186 0.4272987511 0.6913625638 0.4888715353 -0.316919871088 +1403636862151666432.0000000000 4.6154803373 -1.8751953647 0.6944550621 0.4220300027 0.6940244316 0.4897533259 -0.316800323321 +1403636862201666560.0000000000 4.6169867540 -1.8772280629 0.6776676886 0.4190724282 0.6946189528 0.4923527314 -0.315391182776 +1403636862251666432.0000000000 4.6184128837 -1.8779953780 0.6672518363 0.4181567945 0.6944725973 0.4958284949 -0.311459163331 +1403636862301666560.0000000000 4.6196143191 -1.8784104477 0.6641775135 0.4169055298 0.6944860532 0.4991105506 -0.30784340074 +1403636862351666432.0000000000 4.6201439888 -1.8780276390 0.6695560814 0.4149744404 0.6947221134 0.5022835601 -0.304743538316 +1403636862401666560.0000000000 4.6200793584 -1.8774882495 0.6837827021 0.4132492350 0.6950986885 0.5036570197 -0.303961329092 +1403636862451666432.0000000000 4.6195601867 -1.8765777957 0.7049616054 0.4135075890 0.6945451336 0.5037784180 -0.304673328003 +1403636862501666560.0000000000 4.6182124321 -1.8746441523 0.7306395871 0.4167667004 0.6930499321 0.5029454122 -0.305013477344 +1403636862551666432.0000000000 4.6155579611 -1.8713553217 0.7596185636 0.4227409001 0.6915330872 0.5005217050 -0.304220550841 +1403636862601666560.0000000000 4.6121870579 -1.8670209054 0.7907733128 0.4315275036 0.6889792999 0.4981414344 -0.301573621545 +1403636862651666432.0000000000 4.6087701156 -1.8633713658 0.8235490459 0.4395552418 0.6865649089 0.4946406207 -0.301248189535 +1403636862701666560.0000000000 4.6054156116 -1.8604541513 0.8574274173 0.4467628632 0.6838331508 0.4916302072 -0.301786191434 +1403636862751666432.0000000000 4.6020178316 -1.8588818680 0.8918010380 0.4499755866 0.6836111397 0.4863475882 -0.306045428938 +1403636862801666560.0000000000 4.5989975726 -1.8567762240 0.9261958768 0.4525228628 0.6837250026 0.4829582069 -0.307399658111 +1403636862851666432.0000000000 4.5963534149 -1.8552814098 0.9598407326 0.4535619001 0.6854364221 0.4777748645 -0.310144632336 +1403636862901666560.0000000000 4.5946748158 -1.8539609999 0.9910915600 0.4551999578 0.6859042825 0.4738763912 -0.312681114706 +1403636862951666432.0000000000 4.5936622849 -1.8533794838 1.0175920982 0.4567245995 0.6858315849 0.4695055422 -0.317178535151 +1403636863001666560.0000000000 4.5986771696 -1.8574039087 1.0372940235 0.4595558310 0.6834106687 0.4676459553 -0.321038247943 +1403636863051666432.0000000000 4.5993688698 -1.8565030888 1.0463283558 0.4645850564 0.6795983619 0.4674563267 -0.322166687476 +1403636863101666560.0000000000 4.5998857062 -1.8550831824 1.0459570323 0.4702874606 0.6759457806 0.4679087655 -0.320918047607 +1403636863151666432.0000000000 4.6003077330 -1.8540553534 1.0370488107 0.4750632127 0.6726024496 0.4692419429 -0.3189559337 +1403636863201666560.0000000000 4.6007316073 -1.8537473846 1.0199693059 0.4776842972 0.6708214239 0.4710373392 -0.316133127821 +1403636863251666432.0000000000 4.6008997402 -1.8543502862 0.9964592282 0.4780714938 0.6703119607 0.4727500812 -0.314065093275 +1403636863301666560.0000000000 4.6011523059 -1.8546846716 0.9678042050 0.4791518280 0.6699282465 0.4747451744 -0.310204270971 +1403636863351666432.0000000000 4.6015910639 -1.8554167734 0.9362818716 0.4790965549 0.6706145724 0.4754250931 -0.307755693893 +1403636863401666560.0000000000 4.6016933434 -1.8555208614 0.9036997322 0.4797514466 0.6719267730 0.4756174054 -0.303547434377 +1403636863451666432.0000000000 4.6024121966 -1.8565444601 0.8702294426 0.4784338737 0.6740969896 0.4752569132 -0.301372101535 +1403636863501666560.0000000000 4.6036072180 -1.8579943372 0.8356191279 0.4739294749 0.6784074808 0.4744137184 -0.30014291038 +1403636863551666432.0000000000 4.6057745030 -1.8608701082 0.8018806550 0.4660129986 0.6822275226 0.4753033774 -0.302463538106 +1403636863601666560.0000000000 4.6087707123 -1.8634885357 0.7696588864 0.4575196366 0.6865844832 0.4765366728 -0.303628603653 +1403636863651666432.0000000000 4.6119661555 -1.8661785498 0.7394207873 0.4489926459 0.6908923950 0.4780410308 -0.304220438597 +1403636863701666560.0000000000 4.6154802010 -1.8667938983 0.7103942970 0.4409229411 0.6950934211 0.4792491265 -0.304552738795 +1403636863751666432.0000000000 4.6174843619 -1.8680799155 0.6882941743 0.4341365175 0.6997062462 0.4793820405 -0.303528437555 +1403636863801666560.0000000000 4.6195019504 -1.8688424769 0.6726648754 0.4280777609 0.7032738759 0.4811403093 -0.3010968097 +1403636863851666432.0000000000 4.6215597678 -1.8692760797 0.6654059853 0.4235692582 0.7058081948 0.4832636160 -0.298127746439 +1403636863901666560.0000000000 4.6233373459 -1.8693198020 0.6673085009 0.4200181663 0.7071055476 0.4854387349 -0.296539574351 +1403636863951666432.0000000000 4.6245645262 -1.8689966766 0.6787760340 0.4172509404 0.7073661363 0.4872435550 -0.296864481014 +1403636864001666560.0000000000 4.6250386263 -1.8682235276 0.6989575322 0.4170752233 0.7062784153 0.4884910546 -0.297650042406 +1403636864051666432.0000000000 4.6251040047 -1.8675570508 0.7256468433 0.4186719202 0.7039610500 0.4891252664 -0.299848523589 +1403636864101666560.0000000000 4.6244962067 -1.8659413273 0.7573005591 0.4229968054 0.7004905981 0.4906243263 -0.299456833173 +1403636864151666432.0000000000 4.6230858401 -1.8638721106 0.7919484387 0.4286783760 0.6976143998 0.4906465460 -0.298051952016 +1403636864201666560.0000000000 4.6207807065 -1.8617681674 0.8282647684 0.4340882282 0.6954946497 0.4896426645 -0.296824297338 +1403636864251666432.0000000000 4.6182364869 -1.8605461014 0.8636726224 0.4376463472 0.6941709529 0.4884199916 -0.296712444345 +1403636864301666560.0000000000 4.6156671321 -1.8601742527 0.8976967209 0.4390144745 0.6930696448 0.4876973197 -0.298449464785 +1403636864351666432.0000000000 4.6133314965 -1.8602235507 0.9294722134 0.4403643713 0.6922698613 0.4863190373 -0.300558569428 +1403636864401666560.0000000000 4.6107541253 -1.8601698146 0.9590796834 0.4433457812 0.6912573751 0.4832725799 -0.303406284116 +1403636864451666432.0000000000 4.6102646170 -1.8613458704 0.9883650269 0.4486352807 0.6897373740 0.4780933009 -0.30727111068 +1403636864501666560.0000000000 4.6073560571 -1.8611338473 1.0126726216 0.4554033423 0.6874101400 0.4711870777 -0.313141873547 +1403636864551666432.0000000000 4.6044125314 -1.8615760590 1.0317990062 0.4608107711 0.6845809246 0.4642904356 -0.321615892509 +1403636864601666560.0000000000 4.6020921742 -1.8614447524 1.0433393592 0.4673694879 0.6811406626 0.4597171796 -0.325995819425 +1403636864651666432.0000000000 4.6007829464 -1.8610639022 1.0462176933 0.4729466334 0.6777672697 0.4577123976 -0.327799284864 +1403636864701666560.0000000000 4.6006136076 -1.8605461792 1.0398161657 0.4771092877 0.6749334077 0.4591788902 -0.325555478273 +1403636864751666432.0000000000 4.6009141963 -1.8600430034 1.0254970228 0.4786789898 0.6737737828 0.4619672846 -0.32168547122 +1403636864801666560.0000000000 4.6014584088 -1.8604207395 1.0045794062 0.4770841788 0.6742334460 0.4649869123 -0.318727341169 +1403636864851666432.0000000000 4.6019694521 -1.8614000303 0.9788185957 0.4743795336 0.6758045818 0.4673132670 -0.316022998854 +1403636864901666560.0000000000 4.6020668840 -1.8623091705 0.9502380908 0.4716856867 0.6782182411 0.4684912154 -0.313127148995 +1403636864951666432.0000000000 4.6022315190 -1.8624225956 0.9202050304 0.4696744380 0.6806755764 0.4701876768 -0.308237295929 +1403636865001666560.0000000000 4.6024896216 -1.8624733206 0.8889463027 0.4677547385 0.6836834550 0.4714060559 -0.302586794811 +1403636865051666432.0000000000 4.6028551023 -1.8629713670 0.8579407473 0.4637943775 0.6863577039 0.4737499708 -0.298946220854 +1403636865101666560.0000000000 4.6024287002 -1.8618899588 0.8269197611 0.4590908843 0.6899103199 0.4749157196 -0.296166118502 +1403636865151666432.0000000000 4.6021476723 -1.8630780572 0.7988339533 0.4516057656 0.6950300917 0.4727538541 -0.299147451159 +1403636865201666560.0000000000 4.6021535673 -1.8647125017 0.7736766357 0.4438953585 0.6991923615 0.4706949338 -0.30419275398 +1403636865251666432.0000000000 4.6026679869 -1.8662974002 0.7516140347 0.4369393258 0.7026605250 0.4683982965 -0.309766441081 +1403636865301666560.0000000000 4.6031522602 -1.8673036223 0.7323388248 0.4329717245 0.7043907800 0.4671990553 -0.313199868383 +1403636865351666432.0000000000 4.6034053786 -1.8675669036 0.7168912801 0.4322565029 0.7054426232 0.4660260347 -0.31356778529 +1403636865401666560.0000000000 4.6036327784 -1.8677777196 0.7049569619 0.4321339477 0.7054104097 0.4674771282 -0.31164328914 +1403636865451666432.0000000000 4.6039002864 -1.8678287899 0.6980747046 0.4316561887 0.7051880540 0.4709399745 -0.307568339868 +1403636865501666560.0000000000 4.6041133467 -1.8677045895 0.6971970521 0.4302445103 0.7057337377 0.4752217850 -0.301651799081 +1403636865551666432.0000000000 4.6041891707 -1.8676791218 0.7039513666 0.4272273069 0.7063248418 0.4800466311 -0.296879231471 +1403636865601666560.0000000000 4.6039002134 -1.8683121231 0.7181467814 0.4243769042 0.7069287193 0.4832867714 -0.294261661848 +1403636865651666432.0000000000 4.6034689728 -1.8699719340 0.7387578851 0.4222607256 0.7066385267 0.4850260126 -0.295140033185 +1403636865701666560.0000000000 4.6027489077 -1.8718506741 0.7644667069 0.4227515885 0.7048576449 0.4854053606 -0.298057764265 +1403636865751666432.0000000000 4.6013277300 -1.8733188685 0.7935373579 0.4258001222 0.7026374992 0.4836672818 -0.301762756338 +1403636865801666560.0000000000 4.5993107087 -1.8740261457 0.8252349965 0.4304004575 0.6997478919 0.4809957889 -0.306188479455 +1403636865851666432.0000000000 4.5970330412 -1.8740379559 0.8584234819 0.4356613211 0.6969826126 0.4770992322 -0.311112156154 +1403636865901666560.0000000000 4.5949050929 -1.8737209323 0.8926101641 0.4420836269 0.6931392916 0.4730412118 -0.316783839876 +1403636865951666432.0000000000 4.5931217645 -1.8736252397 0.9270066687 0.4492073659 0.6887684780 0.4677508285 -0.324067722055 +1403636866001666560.0000000000 4.5915631538 -1.8732675916 0.9608775817 0.4578036844 0.6836263220 0.4621269072 -0.330922287048 +1403636866051666432.0000000000 4.5904025890 -1.8730808592 0.9930424367 0.4677131228 0.6783340007 0.4553565380 -0.337280064062 +1403636866101666560.0000000000 4.5901513337 -1.8735641894 1.0273479234 0.4774954548 0.6727722934 0.4500708334 -0.34177737893 +1403636866151666432.0000000000 4.5904434574 -1.8734759403 1.0526136161 0.4858408966 0.6676313272 0.4465366475 -0.344720258467 +1403636866201666560.0000000000 4.5914709725 -1.8736507815 1.0709095460 0.4913836921 0.6639849067 0.4449046643 -0.346014378876 +1403636866251666432.0000000000 4.5923488271 -1.8736736473 1.0819070600 0.4946192785 0.6623942051 0.4443855143 -0.34511911141 +1403636866301666560.0000000000 4.5933931274 -1.8737311276 1.0841122563 0.4957429355 0.6624976244 0.4458926570 -0.341343782759 +1403636866351666432.0000000000 4.5938220699 -1.8736707574 1.0784456656 0.4953760010 0.6645123626 0.4474379220 -0.335894691159 +1403636866401666560.0000000000 4.5940682385 -1.8733462804 1.0654141151 0.4934520512 0.6667654923 0.4504649348 -0.330166918237 +1403636866451666432.0000000000 4.5937714431 -1.8731061043 1.0461796668 0.4906306646 0.6694745087 0.4525894964 -0.325957329839 +1403636866501666560.0000000000 4.5940448919 -1.8730587132 1.0215876891 0.4876354676 0.6714458917 0.4554436702 -0.322402122297 +1403636866551666432.0000000000 4.5942675219 -1.8722176928 0.9936692700 0.4848155443 0.6737349357 0.4575753023 -0.318841601914 +1403636866601666560.0000000000 4.5946494235 -1.8707478695 0.9649446974 0.4816283656 0.6766043229 0.4592965793 -0.315098968462 +1403636866651666432.0000000000 4.5958591200 -1.8687256109 0.9370524879 0.4789084718 0.6795805519 0.4613515563 -0.309792980282 +1403636866701666560.0000000000 4.5978922247 -1.8668804355 0.9117119458 0.4753250040 0.6824895153 0.4634831295 -0.305708342607 +1403636866751666432.0000000000 4.6015158853 -1.8660924682 0.8895830837 0.4709397711 0.6839581582 0.4669325114 -0.303958878142 +1403636866801666560.0000000000 4.6033423276 -1.8632665820 0.8690730324 0.4661705699 0.6852476843 0.4699662787 -0.30373065019 +1403636866851666432.0000000000 4.6074047632 -1.8641178197 0.8512700491 0.4594071567 0.6866047768 0.4730247793 -0.306213165942 +1403636866901666560.0000000000 4.6111841270 -1.8653321237 0.8349255348 0.4513618833 0.6894195331 0.4754878279 -0.308033250052 +1403636866951666432.0000000000 4.6149711122 -1.8671148651 0.8203436099 0.4420679918 0.6930775352 0.4779602565 -0.309472800118 +1403636867001666560.0000000000 4.6186500634 -1.8685315810 0.8080771037 0.4348771143 0.6967425367 0.4800791251 -0.308148935791 +1403636867051666432.0000000000 4.6218337476 -1.8695309191 0.7982844983 0.4300093128 0.7002314424 0.4812318047 -0.305260328355 +1403636867101666560.0000000000 4.6252020132 -1.8708405982 0.7909811085 0.4262056437 0.7019312716 0.4834752347 -0.303138477628 +1403636867151666432.0000000000 4.6291915463 -1.8726119010 0.7863605468 0.4220533661 0.7034250745 0.4846817293 -0.303558465466 +1403636867201666560.0000000000 4.6341609494 -1.8752345323 0.7836058241 0.4176737434 0.7033281044 0.4872277521 -0.30575699375 +1403636867251666432.0000000000 4.6396981965 -1.8786072029 0.7822552228 0.4127417128 0.7023302318 0.4908673362 -0.308910638197 +1403636867301666560.0000000000 4.6444193349 -1.8807740737 0.7826198014 0.4089471707 0.7017714019 0.4936582302 -0.31077429548 +1403636867351666432.0000000000 4.6485814474 -1.8824326131 0.7839531887 0.4057187447 0.7023748095 0.4956589298 -0.310457972325 +1403636867401666560.0000000000 4.6519627794 -1.8833581917 0.7859830078 0.4038588200 0.7033612186 0.4975804224 -0.307562632506 +1403636867451666432.0000000000 4.6554979869 -1.8848997888 0.7886318977 0.4008279334 0.7054298784 0.4994560702 -0.30372567939 +1403636867501666560.0000000000 4.6591316787 -1.8862301594 0.7911233635 0.3965688821 0.7085861410 0.5019780504 -0.29775298401 +1403636867551666432.0000000000 4.6639430627 -1.8876559000 0.7920193817 0.3890932501 0.7127257266 0.5072288216 -0.288699504532 +1403636867601666560.0000000000 4.6692752520 -1.8890454551 0.7916886599 0.3766868470 0.7190832961 0.5136083389 -0.277907730709 +1403636867651666432.0000000000 4.6752201245 -1.8908323357 0.7900856900 0.3588475163 0.7277994679 0.5206778823 -0.265388276799 +1403636867701666560.0000000000 4.6814488293 -1.8928706937 0.7878380380 0.3365457290 0.7384865020 0.5276455837 -0.250927871356 +1403636867751666432.0000000000 4.6878839406 -1.8946102031 0.7848777057 0.3130332755 0.7493642023 0.5343561380 -0.234365054044 +1403636867801666560.0000000000 4.6934708234 -1.8955364388 0.7823180832 0.2919964031 0.7591988596 0.5394973455 -0.21748058851 +1403636867851666432.0000000000 4.6973363415 -1.8959656328 0.7805743707 0.2753882138 0.7676747155 0.5413291664 -0.204449496364 +1403636867901666560.0000000000 4.6991888999 -1.8961209462 0.7804776358 0.2655086407 0.7726732638 0.5419972759 -0.196774342844 +1403636867951666432.0000000000 4.6990759334 -1.8962982821 0.7817667503 0.2622644916 0.7757448384 0.5400016897 -0.194513385761 +1403636868001666560.0000000000 4.6984038463 -1.8966255629 0.7839051416 0.2643808444 0.7757511447 0.5383538545 -0.196183735358 +1403636868051666432.0000000000 4.6973113624 -1.8968363375 0.7867013794 0.2700139669 0.7744610019 0.5359291333 -0.200206339293 +1403636868101666560.0000000000 4.6969586084 -1.8972769229 0.7891071170 0.2764521504 0.7720694073 0.5343701442 -0.204772038803 +1403636868151666432.0000000000 4.6970838904 -1.8979207387 0.7909805579 0.2816996712 0.7700375874 0.5329554275 -0.208916063157 +1403636868201666560.0000000000 4.6982987353 -1.8992019099 0.7922385979 0.2838364955 0.7688919534 0.5321691722 -0.212221535006 +1403636868251666432.0000000000 4.7000449496 -1.9006804415 0.7929331205 0.2843325942 0.7683498987 0.5322866066 -0.213223773296 +1403636868301666560.0000000000 4.7022204985 -1.9033286159 0.7934165753 0.2828702218 0.7697160149 0.5307839661 -0.213986156827 +1403636868351666432.0000000000 4.7047542625 -1.9067680006 0.7937126267 0.2803578158 0.7712124184 0.5301683596 -0.213430108673 +1403636868401666560.0000000000 4.7070062142 -1.9106831371 0.7940293365 0.2793559911 0.7725607255 0.5286565394 -0.213617459413 +1403636868451666432.0000000000 4.7090450698 -1.9152362935 0.7944519722 0.2811129308 0.7729376000 0.5267071391 -0.214761673234 +1403636868501666560.0000000000 4.7107859852 -1.9193775563 0.7955680843 0.2860892049 0.7720092182 0.5250716409 -0.215533073589 +1403636868551666432.0000000000 4.7122792259 -1.9232154184 0.7975305979 0.2922375845 0.7713258832 0.5223136050 -0.216430298684 +1403636868601666560.0000000000 4.7136704758 -1.9269405613 0.8002109444 0.2964074398 0.7716700879 0.5189822221 -0.217543922549 +1403636868651666432.0000000000 4.7156823815 -1.9302054981 0.8028646077 0.2979467620 0.7723474867 0.5170744317 -0.21758014349 +1403636868701666560.0000000000 4.7185711173 -1.9334508064 0.8046495887 0.2972288544 0.7731723387 0.5169083323 -0.21602156995 +1403636868751666432.0000000000 4.7220382845 -1.9370810504 0.8056269252 0.2943779915 0.7729659936 0.5195962645 -0.214207592677 +1403636868801666560.0000000000 4.7253353479 -1.9407050980 0.8055895174 0.2913403507 0.7727671684 0.5225771707 -0.21181313503 +1403636868851666432.0000000000 4.7279278748 -1.9436216336 0.8054732117 0.2900713501 0.7721071078 0.5253846831 -0.208997992052 +1403636868901666560.0000000000 4.7291070632 -1.9460863554 0.8057007639 0.2917331762 0.7709059373 0.5268570096 -0.207406559838 +1403636868951666432.0000000000 4.7292803179 -1.9487880709 0.8062013518 0.2940740494 0.7698171096 0.5266611277 -0.20863874946 +1403636869001666560.0000000000 4.7287855213 -1.9512584435 0.8072544915 0.2954288958 0.7680320609 0.5270584783 -0.212268418021 +1403636869051666432.0000000000 4.7284314926 -1.9533680030 0.8082154465 0.2957934991 0.7670122035 0.5267209439 -0.216248775184 +1403636869101666560.0000000000 4.7278452735 -1.9552951297 0.8091407973 0.2959285342 0.7657842723 0.5270709771 -0.219538005995 +1403636869151666432.0000000000 4.7277724991 -1.9574218397 0.8090922049 0.2954868324 0.7651970512 0.5271457509 -0.221987301444 +1403636869201666560.0000000000 4.7277042587 -1.9588006531 0.8084137432 0.2949316180 0.7641535584 0.5287216343 -0.222571591415 +1403636869251666432.0000000000 4.7268588133 -1.9595881150 0.8076613676 0.2946332215 0.7638158803 0.5293944524 -0.222526581621 +1403636869301666560.0000000000 4.7263147428 -1.9599684772 0.8067899455 0.2945278483 0.7632059773 0.5303843918 -0.222401393492 +1403636869351666432.0000000000 4.7254542368 -1.9604215401 0.8062275171 0.2941011420 0.7630582169 0.5304387098 -0.223341556683 +1403636869401666560.0000000000 4.7247911017 -1.9604755076 0.8056957209 0.2940906679 0.7625940748 0.5309582251 -0.223705876776 +1403636869451666432.0000000000 4.7242368462 -1.9601679316 0.8052719962 0.2938416204 0.7625000088 0.5310294703 -0.224184166139 +1403636869501666560.0000000000 4.7240979940 -1.9587520390 0.8048602450 0.2940660466 0.7625897204 0.5308159554 -0.224090383694 +1403636869551666432.0000000000 4.7243481140 -1.9557266868 0.8044280776 0.2943858038 0.7626499012 0.5306148485 -0.223941977599 +1403636869601666560.0000000000 4.7250378133 -1.9506692237 0.8039665233 0.2940890861 0.7631812470 0.5301771040 -0.223558117614 +1403636869651666432.0000000000 4.7263205438 -1.9431546696 0.8035143800 0.2931878596 0.7635951184 0.5306221317 -0.222269042873 +1403636869701666560.0000000000 4.7280658668 -1.9330313776 0.8027992700 0.2920125027 0.7650086963 0.5301462107 -0.220080412743 +1403636869751666432.0000000000 4.7298872088 -1.9204828333 0.8023792916 0.2909959206 0.7663842868 0.5295681159 -0.21802318622 +1403636869801666560.0000000000 4.7313439001 -1.9054514263 0.8020899451 0.2913935817 0.7678369221 0.5277372403 -0.216817081325 +1403636869851666432.0000000000 4.7323028588 -1.8879392063 0.8021962635 0.2936763007 0.7691094814 0.5248250962 -0.216294832137 +1403636869901666560.0000000000 4.7329511542 -1.8683075909 0.8024931325 0.2971895878 0.7704056578 0.5209026822 -0.216365124383 +1403636869951666432.0000000000 4.7338095196 -1.8471559032 0.8027012223 0.3007038411 0.7715729209 0.5169018014 -0.216944590414 +1403636870001666560.0000000000 4.7348089959 -1.8242698804 0.8025449486 0.3033150787 0.7730698798 0.5132955555 -0.216542367063 +1403636870051666432.0000000000 4.7361907145 -1.8003947070 0.8020857984 0.3042303625 0.7754859358 0.5096192766 -0.21529896156 +1403636870101666560.0000000000 4.7376655515 -1.7753018969 0.8014834307 0.3038680838 0.7784985942 0.5065212008 -0.212227235766 +1403636870151666432.0000000000 4.7396343229 -1.7493527947 0.8010059090 0.3031969521 0.7813128026 0.5044533750 -0.207722664324 +1403636870201666560.0000000000 4.7417609140 -1.7228919442 0.8009205315 0.3030370150 0.7828858779 0.5039150943 -0.20329251708 +1403636870251666432.0000000000 4.7438572047 -1.6967621091 0.8012535403 0.3032630293 0.7841768574 0.5025147054 -0.201437737702 +1403636870301666560.0000000000 4.7455792580 -1.6706242761 0.8018071436 0.3053655799 0.7847984147 0.5002312826 -0.201524129788 +1403636870351666432.0000000000 4.7472820917 -1.6445492496 0.8021316272 0.3091299354 0.7852369635 0.4969709653 -0.202142162254 +1403636870401666560.0000000000 4.7490962756 -1.6185031724 0.8017348136 0.3140968211 0.7848879451 0.4947819687 -0.201208608215 +1403636870451666432.0000000000 4.7512785756 -1.5938277817 0.8006200928 0.3176168350 0.7849413400 0.4931031683 -0.199589339318 +1403636870501666560.0000000000 4.7535955884 -1.5724820096 0.7988668053 0.3166250910 0.7872759553 0.4900269626 -0.199546230036 +1403636870551666432.0000000000 4.7557398936 -1.5536079687 0.7969184773 0.3134944655 0.7907906427 0.4866789254 -0.19878381018 +1403636870601666560.0000000000 4.7586458931 -1.5350916338 0.7941908433 0.3120455713 0.7932323716 0.4859517021 -0.193030850827 +1403636870651666432.0000000000 4.7612524313 -1.5182584107 0.7918273086 0.3117082543 0.7954729306 0.4846005803 -0.187678071182 +1403636870701666560.0000000000 4.7629171111 -1.5033458321 0.7901393714 0.3137736454 0.7962983159 0.4829172977 -0.185056680718 +1403636870751666432.0000000000 4.7630112479 -1.4909236941 0.7890290679 0.3166812084 0.7958900782 0.4811172949 -0.186542607267 +1403636870801666560.0000000000 4.7626969492 -1.4816893773 0.7871951459 0.3192632673 0.7960084274 0.4772312225 -0.191551324481 +1403636870851666432.0000000000 4.7625906668 -1.4742091451 0.7851753815 0.3220309070 0.7952289261 0.4747250565 -0.196324147266 +1403636870901666560.0000000000 4.7633142484 -1.4685189352 0.7829934631 0.3255698622 0.7935294847 0.4737338309 -0.199728513734 +1403636870951666432.0000000000 4.7636144305 -1.4647366637 0.7810501005 0.3271812682 0.7926702570 0.4723743344 -0.203687922148 +1403636871001666560.0000000000 4.7642332877 -1.4630650334 0.7790125769 0.3267484225 0.7929423879 0.4710270156 -0.206425261184 +1403636871051666432.0000000000 4.7643921733 -1.4628477445 0.7765956958 0.3234907439 0.7949313854 0.4693297854 -0.207767619104 +1403636871101666560.0000000000 4.7650466000 -1.4628216236 0.7740215901 0.3199273563 0.7973107159 0.4694083404 -0.203955678712 +1403636871151666432.0000000000 4.7655398251 -1.4633833413 0.7723315492 0.3173018418 0.7995109370 0.4702229831 -0.197464297938 +1403636871201666560.0000000000 4.7653331591 -1.4660005258 0.7722324850 0.3154095120 0.8017320095 0.4694748801 -0.193225157653 +1403636871251666432.0000000000 4.7644264521 -1.4702297013 0.7735669294 0.3151647724 0.8025907037 0.4688459215 -0.191579827968 +1403636871301666560.0000000000 4.7628230337 -1.4767333868 0.7754878394 0.3157291732 0.8023125652 0.4683890568 -0.192928298656 +1403636871351666432.0000000000 4.7612179201 -1.4853516085 0.7772088991 0.3166222703 0.8011385912 0.4695369191 -0.193552001499 +1403636871401666560.0000000000 4.7593484473 -1.4964929337 0.7787963772 0.3174036471 0.7996389578 0.4717033169 -0.193205700678 +1403636871451666432.0000000000 4.7566135049 -1.5103945809 0.7803170332 0.3176289758 0.7981183075 0.4737136280 -0.19420195593 +1403636871501666560.0000000000 4.7529664259 -1.5268147252 0.7815879688 0.3175074664 0.7971421971 0.4749744783 -0.195326832336 +1403636871551666432.0000000000 4.7489291865 -1.5456435864 0.7829397879 0.3165558820 0.7967236501 0.4758560968 -0.196430074187 +1403636871601666560.0000000000 4.7445038632 -1.5666149410 0.7844393524 0.3152202813 0.7964560375 0.4770579278 -0.196747777801 +1403636871651666432.0000000000 4.7398642161 -1.5899573016 0.7865797077 0.3124943812 0.7963308801 0.4782170317 -0.198778423846 +1403636871701666560.0000000000 4.7349189764 -1.6151077149 0.7890790697 0.3091773729 0.7958368788 0.4799167408 -0.201824023315 +1403636871751666432.0000000000 4.7293157126 -1.6415371464 0.7915383177 0.3063374953 0.7949434206 0.4815931020 -0.205646252426 +1403636871801666560.0000000000 4.7234438703 -1.6682906001 0.7931673839 0.3044907642 0.7936863507 0.4838309957 -0.207978169178 +1403636871851666432.0000000000 4.7173127771 -1.6952681921 0.7939612034 0.3041076146 0.7914719983 0.4872463053 -0.209001609222 +1403636871901666560.0000000000 4.7101759640 -1.7230292598 0.7945608249 0.3039061082 0.7894422414 0.4894395367 -0.211827676872 +1403636871951666432.0000000000 4.7024517584 -1.7514981132 0.7951071154 0.3039212982 0.7871240199 0.4913759729 -0.215910340242 +1403636872001666560.0000000000 4.6938273208 -1.7804665791 0.7953930544 0.3037711157 0.7845028027 0.4929361888 -0.222018863127 +1403636872051666432.0000000000 4.6851114679 -1.8092885137 0.7952875049 0.3035540602 0.7818373983 0.4944385107 -0.228288795682 +1403636872101666560.0000000000 4.6768588947 -1.8373226642 0.7945147531 0.3034019581 0.7788126425 0.4970168664 -0.233178803254 +1403636872151666432.0000000000 4.6692519614 -1.8640385503 0.7934424820 0.3031732545 0.7765822568 0.4992983685 -0.236023548257 +1403636872201666560.0000000000 4.6624771224 -1.8895778266 0.7915747963 0.3017751338 0.7749568691 0.5021344750 -0.237138332191 +1403636872251666432.0000000000 4.6564790587 -1.9142292647 0.7895975974 0.2984626707 0.7735254366 0.5059157227 -0.237965784766 +1403636872301666560.0000000000 4.6514548334 -1.9378467129 0.7870815385 0.2939432053 0.7725761929 0.5099549956 -0.238053188651 +1403636872351666432.0000000000 4.6469754019 -1.9591353141 0.7845438008 0.2895534736 0.7713650896 0.5143950581 -0.237807503474 +1403636872401666560.0000000000 4.6431364332 -1.9775770784 0.7822905078 0.2856914421 0.7705608978 0.5177978510 -0.237700837697 +1403636872451666432.0000000000 4.6396256221 -1.9922541351 0.7806850257 0.2834063424 0.7697555565 0.5201766561 -0.237851791593 +1403636872501666560.0000000000 4.6370690365 -2.0031091653 0.7799989676 0.2822911694 0.7686589460 0.5220189156 -0.238686765849 +1403636872551666432.0000000000 4.6356188761 -2.0100644165 0.7800167459 0.2825787571 0.7671119667 0.5236251311 -0.239802415978 +1403636872601666560.0000000000 4.6352346425 -2.0135981458 0.7806477623 0.2838123083 0.7650389085 0.5251596522 -0.241605839916 +1403636872651666432.0000000000 4.6357053941 -2.0141613109 0.7815877430 0.2859913445 0.7634292555 0.5257579367 -0.242823628672 +1403636872701666560.0000000000 4.6365266467 -2.0121645926 0.7825305402 0.2882444845 0.7619636546 0.5264668114 -0.24322664888 +1403636872751666432.0000000000 4.6377481879 -2.0077502468 0.7832129646 0.2899112349 0.7618650586 0.5260978362 -0.242351346564 +1403636872801666560.0000000000 4.6394918815 -2.0002913461 0.7834249764 0.2908292856 0.7623829306 0.5259631885 -0.23990272614 +1403636872851666432.0000000000 4.6415255683 -1.9897607115 0.7834091743 0.2903787992 0.7641624113 0.5242819650 -0.238462540571 +1403636872901666560.0000000000 4.6440262130 -1.9753575976 0.7828753460 0.2901195617 0.7661140741 0.5223438381 -0.236763130754 +1403636872951666432.0000000000 4.6470946777 -1.9570807139 0.7818518814 0.2909066904 0.7680716481 0.5201751471 -0.234215834632 +1403636873001666560.0000000000 4.6510701183 -1.9359747110 0.7806278054 0.2921609853 0.7698297031 0.5179288045 -0.231848960271 +1403636873051666432.0000000000 4.6553729718 -1.9121834111 0.7792782816 0.2940868495 0.7713627557 0.5156029340 -0.229490824408 +1403636873101666560.0000000000 4.6600359668 -1.8865763630 0.7780943831 0.2953221140 0.7728805150 0.5133454990 -0.227852928711 +1403636873151666432.0000000000 4.6649892424 -1.8594916672 0.7771898470 0.2955529640 0.7751675782 0.5105719653 -0.226008715409 +1403636873201666560.0000000000 4.6699659319 -1.8305560175 0.7765295264 0.2959531420 0.7776596332 0.5075612877 -0.223693477467 +1403636873251666432.0000000000 4.6752675832 -1.8007911502 0.7760517891 0.2964004410 0.7802673309 0.5042881012 -0.221411792699 +1403636873301666560.0000000000 4.6806328728 -1.7703302452 0.7756723071 0.2971212618 0.7828775539 0.5008273720 -0.219074496312 +1403636873351666432.0000000000 4.6864103360 -1.7397134879 0.7750029354 0.2978777139 0.7851165751 0.4978322764 -0.216849845578 +1403636873401666560.0000000000 4.6924579624 -1.7093251840 0.7740601911 0.2985507743 0.7871544978 0.4951421724 -0.214684561437 +1403636873451666432.0000000000 4.6988556216 -1.6799904468 0.7727049024 0.2984977527 0.7894175627 0.4921018137 -0.213435723893 +1403636873501666560.0000000000 4.7056812636 -1.6513560270 0.7708646061 0.2985928621 0.7912302458 0.4903212020 -0.21067064297 +1403636873551666432.0000000000 4.7126074351 -1.6240067469 0.7686479312 0.2987480441 0.7938446607 0.4877558955 -0.206529531284 +1403636873601666560.0000000000 4.7196263561 -1.5987212179 0.7659166191 0.2989457988 0.7963940441 0.4853183789 -0.20212374204 +1403636873651666432.0000000000 4.7261739985 -1.5753099955 0.7628411493 0.2995267576 0.7984168643 0.4833773956 -0.197890186156 +1403636873701666560.0000000000 4.7322424048 -1.5548693496 0.7596719971 0.2987783767 0.8007449775 0.4810084198 -0.195371089733 +1403636873751666432.0000000000 4.7380590658 -1.5374163463 0.7567329307 0.2975899054 0.8020720936 0.4800016070 -0.19421395972 +1403636873801666560.0000000000 4.7433929139 -1.5233651141 0.7543856707 0.2965752255 0.8023735198 0.4805183552 -0.19324073249 +1403636873851666432.0000000000 4.7473140105 -1.5128922865 0.7524233107 0.2961985886 0.8031177203 0.4794979860 -0.193261493676 +1403636873901666560.0000000000 4.7501409119 -1.5053727731 0.7505890570 0.2964579850 0.8036037620 0.4785175672 -0.193273367774 +1403636873951666432.0000000000 4.7516837754 -1.5002145498 0.7489467781 0.2977456376 0.8040200135 0.4771598780 -0.192919164465 +1403636874001666560.0000000000 4.7523948669 -1.4977480681 0.7475243801 0.2987460633 0.8047012477 0.4756013432 -0.192379972704 +1403636874051666432.0000000000 4.7520120604 -1.4969810963 0.7464560935 0.2993803171 0.8051908376 0.4746391581 -0.191720657246 +1403636874101666560.0000000000 4.7512892477 -1.4983226380 0.7458627755 0.2990083640 0.8053126353 0.4746684338 -0.191717071838 +1403636874151666432.0000000000 4.7499563898 -1.5013177988 0.7459429511 0.2981937157 0.8055327819 0.4748142036 -0.191700071099 +1403636874201666560.0000000000 4.7484409511 -1.5064390011 0.7465621724 0.2972470171 0.8053233529 0.4759116162 -0.191328621935 +1403636874251666432.0000000000 4.7461256223 -1.5142682404 0.7474388694 0.2961734616 0.8050932633 0.4770685937 -0.191080284212 +1403636874301666560.0000000000 4.7430165466 -1.5252699846 0.7483232007 0.2946583933 0.8035588038 0.4804491079 -0.191411427855 +1403636874351666432.0000000000 4.7385856570 -1.5398894782 0.7491955773 0.2925761158 0.8027031676 0.4825670970 -0.192862225564 +1403636874401666560.0000000000 4.7329397504 -1.5576853880 0.7502398720 0.2901878120 0.8011644199 0.4856090408 -0.195219019227 +1403636874451666432.0000000000 4.7262196508 -1.5783466657 0.7514169058 0.2885785527 0.7998173901 0.4875911563 -0.19816514747 +1403636874501666560.0000000000 4.7188758282 -1.6009044913 0.7526456642 0.2888594821 0.7977899938 0.4897357116 -0.20062466991 +1403636874551666432.0000000000 4.7110781019 -1.6250012301 0.7540670647 0.2903558212 0.7957268832 0.4912913182 -0.202842463641 +1403636874601666560.0000000000 4.7032705837 -1.6516539431 0.7552682181 0.2909450498 0.7934722066 0.4935620685 -0.20530299533 +1403636874651666432.0000000000 4.6952184506 -1.6805435836 0.7561570072 0.2905102991 0.7911484564 0.4960322633 -0.208901603141 +1403636874701666560.0000000000 4.6871292157 -1.7101922225 0.7564927856 0.2898655118 0.7886201896 0.4990650623 -0.212109040861 +1403636874751666432.0000000000 4.6785149099 -1.7397372571 0.7561329169 0.2886823804 0.7867638068 0.5015078188 -0.214837387964 +1403636874801666560.0000000000 4.6701623258 -1.7688424743 0.7550638204 0.2870628710 0.7849474428 0.5041711971 -0.217402447344 +1403636874851666432.0000000000 4.6617451749 -1.7972848353 0.7535332802 0.2840449713 0.7842850337 0.5054682360 -0.220719964231 +1403636874901666560.0000000000 4.6541701486 -1.8241393524 0.7518874554 0.2804248296 0.7832303275 0.5078263107 -0.223661814169 +1403636874951666432.0000000000 4.6466820976 -1.8481997350 0.7505211176 0.2780309881 0.7825948501 0.5090275355 -0.226130578073 +1403636875001666560.0000000000 4.6398310284 -1.8690430664 0.7492841153 0.2782207027 0.7808519792 0.5104541485 -0.22869190935 +1403636875051666432.0000000000 4.6321599967 -1.8865792452 0.7482049686 0.2821818748 0.7801953869 0.5080774586 -0.231356529682 +1403636875101666560.0000000000 4.6240108076 -1.9008370834 0.7470729800 0.2896948104 0.7797309558 0.5034581153 -0.233723082932 +1403636875151666432.0000000000 4.6162800739 -1.9132718653 0.7458245554 0.2995429138 0.7811876520 0.4947707879 -0.234993111807 +1403636875201666560.0000000000 4.6101718259 -1.9247104290 0.7444021620 0.3089408672 0.7829547024 0.4855275652 -0.236221205448 +1403636875251666432.0000000000 4.6052055622 -1.9351081341 0.7426415531 0.3165545745 0.7869071232 0.4741760460 -0.23606663942 +1403636875301666560.0000000000 4.6019272583 -1.9451215864 0.7407528689 0.3213733592 0.7921456298 0.4623432448 -0.235506240425 +1403636875351666432.0000000000 4.6005623877 -1.9552906894 0.7392888194 0.3228900860 0.7987394257 0.4499543104 -0.23515620496 +1403636875401666560.0000000000 4.6021050697 -1.9654309488 0.7380583071 0.3216706069 0.8055171937 0.4388223516 -0.234744573955 +1403636875451666432.0000000000 4.6073189827 -1.9753416509 0.7373038215 0.3188841037 0.8115486022 0.4296609747 -0.234719495468 +1403636875501666560.0000000000 4.6164117931 -1.9844448361 0.7366874875 0.3149465816 0.8169163851 0.4225613040 -0.234303680882 +1403636875551666432.0000000000 4.6291816069 -1.9920973704 0.7363460352 0.3108901742 0.8219812252 0.4157475074 -0.234196872354 +1403636875601666560.0000000000 4.6453737625 -1.9978787450 0.7360560158 0.3075847222 0.8257377576 0.4110900561 -0.233567463663 +1403636875651666432.0000000000 4.6636619441 -2.0010118358 0.7361848520 0.3065090960 0.8292190551 0.4055436038 -0.232340952538 +1403636875701666560.0000000000 4.6836857808 -2.0014975489 0.7358422795 0.3080128281 0.8321027761 0.4000633357 -0.229526458715 +1403636875751666432.0000000000 4.7042089056 -1.9991039850 0.7355022787 0.3115466077 0.8352315218 0.3929824226 -0.225592180167 +1403636875801666560.0000000000 4.7259299275 -1.9954523528 0.7345447703 0.3145650928 0.8385170437 0.3861836880 -0.220907512223 +1403636875851666432.0000000000 4.7477669137 -1.9899797682 0.7338142238 0.3165453695 0.8426216007 0.3788971491 -0.214999575485 +1403636875901666560.0000000000 4.7696405440 -1.9828344209 0.7333259964 0.3178566684 0.8474472031 0.3706636305 -0.208347904413 +1403636875951666432.0000000000 4.7910429038 -1.9734437112 0.7338516522 0.3199141069 0.8524532870 0.3613068735 -0.201086302144 +1403636876001666560.0000000000 4.8117583490 -1.9615367897 0.7350632728 0.3234714591 0.8571738446 0.3504555065 -0.194422615146 +1403636876051666432.0000000000 4.8315560439 -1.9462047426 0.7368206296 0.3298842535 0.8608124113 0.3399514037 -0.186041433563 +1403636876101666560.0000000000 4.8495180571 -1.9284980416 0.7391678810 0.3372910810 0.8640134402 0.3284218314 -0.178478577075 +1403636876151666432.0000000000 4.8649521047 -1.9086185042 0.7412791954 0.3445111657 0.8665648258 0.3176426823 -0.171699113842 +1403636876201666560.0000000000 4.8777927856 -1.8871058529 0.7431965245 0.3498476535 0.8690997174 0.3077182647 -0.166077602655 +1403636876251666432.0000000000 4.8880773100 -1.8638498513 0.7440633832 0.3531367205 0.8719491738 0.2987535169 -0.160453828711 +1403636876301666560.0000000000 4.8954501289 -1.8385610474 0.7443426182 0.3538567398 0.8748475399 0.2921268315 -0.155206649169 +1403636876351666432.0000000000 4.9000503849 -1.8111369702 0.7434369576 0.3533692734 0.8781515228 0.2855725017 -0.149761162935 +1403636876401666560.0000000000 4.9016076958 -1.7813552865 0.7424174736 0.3523732058 0.8807872637 0.2813880536 -0.144456509767 +1403636876451666432.0000000000 4.9001544312 -1.7495575342 0.7409538566 0.3534656439 0.8825264590 0.2774983411 -0.138577625845 +1403636876501666560.0000000000 4.8956163027 -1.7164819330 0.7397949311 0.3569315964 0.8821682961 0.2767331097 -0.133408091681 +1403636876551666432.0000000000 4.8872871833 -1.6833115630 0.7394776635 0.3625131304 0.8801791893 0.2768031119 -0.13133492395 +1403636876601666560.0000000000 4.8758342403 -1.6504467312 0.7396359771 0.3691386979 0.8765962564 0.2800519158 -0.129948256966 +1403636876651666432.0000000000 4.8606738750 -1.6191769330 0.7405299502 0.3755518206 0.8723503581 0.2842432779 -0.131039847855 +1403636876701666560.0000000000 4.8423219309 -1.5913350487 0.7420325425 0.3798335148 0.8680243925 0.2902268433 -0.134270378087 +1403636876751666432.0000000000 4.8212119666 -1.5671396485 0.7438900216 0.3825952492 0.8634925963 0.2980263774 -0.138497977261 +1403636876801666560.0000000000 4.7978457869 -1.5473570534 0.7454979286 0.3848386498 0.8582765942 0.3080976603 -0.142605515867 +1403636876851666432.0000000000 4.7724287620 -1.5327779104 0.7466505132 0.3863724974 0.8525534752 0.3196794326 -0.147220669561 +1403636876901666560.0000000000 4.7446872296 -1.5233545349 0.7475823726 0.3879286759 0.8459856140 0.3319407097 -0.153736946268 +1403636876951666432.0000000000 4.7152813261 -1.5192708665 0.7477712573 0.3890283748 0.8387767180 0.3447876429 -0.161963027277 +1403636877001666560.0000000000 4.6848175583 -1.5205845403 0.7477747188 0.3887923369 0.8310958083 0.3585020320 -0.172036534729 +1403636877051666432.0000000000 4.6544466440 -1.5271249637 0.7473696181 0.3873048070 0.8225558046 0.3743949573 -0.182278223287 +1403636877101666560.0000000000 4.6244334289 -1.5388238869 0.7473225805 0.3844052467 0.8137113740 0.3905893144 -0.193768918022 +1403636877151666432.0000000000 4.5959867890 -1.5554996331 0.7471241226 0.3804964089 0.8038783123 0.4088927954 -0.204472060882 +1403636877201666560.0000000000 4.5688313154 -1.5768879308 0.7473307857 0.3747229789 0.7946857671 0.4257481042 -0.216323305149 +1403636877251666432.0000000000 4.5437266946 -1.6019463533 0.7478406485 0.3686817743 0.7853355882 0.4423894516 -0.22718568669 +1403636877301666560.0000000000 4.5220996921 -1.6309386048 0.7485494878 0.3626118088 0.7763923333 0.4576256120 -0.23728973863 +1403636877351666432.0000000000 4.5039115289 -1.6623153087 0.7490570616 0.3565204331 0.7667140420 0.4736932194 -0.246287418448 +1403636877401666560.0000000000 4.4895155610 -1.6953149933 0.7495668744 0.3498529283 0.7575426500 0.4887887731 -0.254593003176 +1403636877451666432.0000000000 4.4791147832 -1.7295527022 0.7494510127 0.3424812236 0.7491243214 0.5027785330 -0.262170000591 +1403636877501666560.0000000000 4.4726511682 -1.7638325967 0.7487436736 0.3341020948 0.7420828934 0.5152075157 -0.268793573728 +1403636877551666432.0000000000 4.4704588791 -1.7979082818 0.7476103847 0.3250061084 0.7372748809 0.5249114369 -0.274344241671 +1403636877601666560.0000000000 4.4727295206 -1.8308014688 0.7460862683 0.3155118410 0.7338878588 0.5334105584 -0.278090030552 +1403636877651666432.0000000000 4.4793859212 -1.8620211134 0.7445209908 0.3070796690 0.7315683487 0.5401172069 -0.280683506632 +1403636877701666560.0000000000 4.4896053906 -1.8912683646 0.7433020289 0.2984543931 0.7309187280 0.5442866001 -0.283610446274 +1403636877751666432.0000000000 4.5031617611 -1.9179412464 0.7424548367 0.2914836640 0.7316969529 0.5463496319 -0.284884050913 +1403636877801666560.0000000000 4.5197609021 -1.9419270625 0.7414331889 0.2863813619 0.7338029763 0.5466765999 -0.284013384664 +1403636877851666432.0000000000 4.5382118514 -1.9632039756 0.7401758811 0.2821441767 0.7379482945 0.5443919039 -0.281894365253 +1403636877901666560.0000000000 4.5585141034 -1.9810142517 0.7382938933 0.2794076286 0.7424770652 0.5416874226 -0.277909915113 +1403636877951666432.0000000000 4.5803878635 -1.9954508304 0.7358691376 0.2775276680 0.7482998281 0.5376627442 -0.271927442923 +1403636878001666560.0000000000 4.6034677757 -2.0065175743 0.7330423081 0.2772203496 0.7542670443 0.5325376168 -0.265770183074 +1403636878051666432.0000000000 4.6271833335 -2.0133046362 0.7296257031 0.2790741005 0.7605952910 0.5262135146 -0.258286249843 +1403636878101666560.0000000000 4.6506092905 -2.0159600048 0.7262266582 0.2822415451 0.7677405228 0.5173489992 -0.251523781802 +1403636878151666432.0000000000 4.6740547652 -2.0142001792 0.7227373423 0.2872369253 0.7749692169 0.5070354726 -0.244607218155 +1403636878201666560.0000000000 4.6974904331 -2.0086056794 0.7197505004 0.2922061062 0.7815539351 0.4964346174 -0.239461288443 +1403636878251666432.0000000000 4.7206570990 -1.9988924164 0.7166515701 0.2976040344 0.7881165014 0.4853364228 -0.233993110449 +1403636878301666560.0000000000 4.7428798143 -1.9861057975 0.7140103893 0.3016535757 0.7947897629 0.4733103566 -0.230849863301 +1403636878351666432.0000000000 4.7640859408 -1.9699015027 0.7116899869 0.3056675102 0.8015083379 0.4607088255 -0.227813817759 +1403636878401666560.0000000000 4.7840559419 -1.9500432190 0.7098480669 0.3099383153 0.8081117906 0.4484066089 -0.223215339109 +1403636878451666432.0000000000 4.8024701437 -1.9271642386 0.7086608972 0.3142413014 0.8145944784 0.4362751714 -0.217605641072 +1403636878501666560.0000000000 4.8186859546 -1.9012981280 0.7086800804 0.3193006798 0.8201348755 0.4255069337 -0.210641190735 +1403636878551666432.0000000000 4.8318358433 -1.8732704795 0.7099556952 0.3243384852 0.8256409703 0.4142047196 -0.203852852536 +1403636878601666560.0000000000 4.8420119970 -1.8432189908 0.7121408183 0.3299692950 0.8300890282 0.4044655711 -0.19616337961 +1403636878651666432.0000000000 4.8490346096 -1.8118977563 0.7151024526 0.3357765247 0.8338123133 0.3951213379 -0.189447301523 +1403636878701666560.0000000000 4.8532716384 -1.7794108648 0.7184487714 0.3423805916 0.8363939404 0.3875190142 -0.18179582154 +1403636878751666432.0000000000 4.8546058677 -1.7468719969 0.7223010785 0.3492848463 0.8376968835 0.3813925484 -0.175509975454 +1403636878801666560.0000000000 4.8531587076 -1.7151696236 0.7261584404 0.3552725591 0.8386903046 0.3754108237 -0.171600393858 +1403636878851666432.0000000000 4.8494038085 -1.6837791704 0.7298038957 0.3596090472 0.8392240410 0.3714564612 -0.168536167203 +1403636878901666560.0000000000 4.8439297662 -1.6543357560 0.7324308616 0.3612112559 0.8401263204 0.3683510475 -0.167426701025 +1403636878951666432.0000000000 4.8363066444 -1.6263784177 0.7347369082 0.3613044907 0.8409690626 0.3666980308 -0.166621292083 +1403636879001666560.0000000000 4.8267266197 -1.6006878925 0.7364605096 0.3602762971 0.8416732940 0.3664029297 -0.165939594343 +1403636879051666432.0000000000 4.8145587740 -1.5773235951 0.7386524459 0.3598501260 0.8420261889 0.3657509874 -0.166511258575 +1403636879101666560.0000000000 4.7996691963 -1.5562572300 0.7416087602 0.3616336024 0.8408718897 0.3655738243 -0.168853136394 +1403636879151666432.0000000000 4.7825678239 -1.5382825890 0.7452973280 0.3653952612 0.8381901451 0.3657469568 -0.173645464204 +1403636879201666560.0000000000 4.7636040717 -1.5230292486 0.7492062613 0.3709765534 0.8343326881 0.3667422862 -0.178228667335 +1403636879251666432.0000000000 4.7436811319 -1.5115078839 0.7530908921 0.3766519882 0.8295517821 0.3696729787 -0.182534953961 +1403636879301666560.0000000000 4.7226916288 -1.5043169806 0.7567765138 0.3813428831 0.8245598262 0.3733262875 -0.187899392008 +1403636879351666432.0000000000 4.7017461568 -1.5013419212 0.7604367578 0.3848073337 0.8183966299 0.3805506233 -0.193213600123 +1403636879401666560.0000000000 4.6807333244 -1.5030002132 0.7636767256 0.3867463489 0.8121524806 0.3887057156 -0.199357659905 +1403636879451666432.0000000000 4.6599416707 -1.5095378028 0.7667657379 0.3864717223 0.8049544228 0.3998887079 -0.206826029272 +1403636879501666560.0000000000 4.6400171163 -1.5204753008 0.7696665110 0.3847623579 0.7978767145 0.4116401328 -0.214250035073 +1403636879551666432.0000000000 4.6220233454 -1.5356904322 0.7723700051 0.3813171920 0.7909234539 0.4245749650 -0.220846979293 +1403636879601666560.0000000000 4.6047280977 -1.5546014801 0.7756283960 0.3765856767 0.7850542502 0.4356409859 -0.228232302096 +1403636879651666432.0000000000 4.5893289840 -1.5769565263 0.7794171871 0.3713424925 0.7797359456 0.4452406583 -0.236383934661 +1403636879701666560.0000000000 4.5761887309 -1.6025747929 0.7833672955 0.3654378458 0.7749742822 0.4540411231 -0.244370008973 +1403636879751666432.0000000000 4.5652680374 -1.6305212501 0.7871171731 0.3589459628 0.7707823526 0.4623089142 -0.251640276259 +1403636879801666560.0000000000 4.5575855253 -1.6600676351 0.7897108110 0.3523181210 0.7669274784 0.4707680605 -0.257043999438 +1403636879851666432.0000000000 4.5531960325 -1.6900453883 0.7913997585 0.3454702798 0.7642395705 0.4779943327 -0.260978126666 +1403636879901666560.0000000000 4.5526196207 -1.7196643304 0.7922262912 0.3392398860 0.7622791601 0.4847446130 -0.262429880278 +1403636879951666432.0000000000 4.5561809459 -1.7483073619 0.7931107706 0.3331263547 0.7614456985 0.4897159461 -0.263449373189 +1403636880001666560.0000000000 4.5638500742 -1.7744586045 0.7938068691 0.3280064514 0.7609142417 0.4940526289 -0.263312142841 +1403636880051666432.0000000000 4.5752528155 -1.7967326260 0.7944914592 0.3237156949 0.7605525976 0.4974334380 -0.263301860829 +1403636880101666560.0000000000 4.5900925669 -1.8144614296 0.7950980104 0.3213960317 0.7608082541 0.4991989741 -0.262060633289 +1403636880151666432.0000000000 4.6077968843 -1.8271269265 0.7958372092 0.3210367508 0.7612722386 0.4996064891 -0.260371541248 +1403636880201666560.0000000000 4.6277319666 -1.8350366095 0.7963532436 0.3232824053 0.7636123014 0.4959947629 -0.257631393052 +1403636880251666432.0000000000 4.6493225109 -1.8386029651 0.7969344535 0.3279864112 0.7665588318 0.4902651847 -0.253875008767 +1403636880301666560.0000000000 4.6724044403 -1.8389872646 0.7971888035 0.3342248436 0.7710556477 0.4815175923 -0.248812681188 +1403636880351666432.0000000000 4.6960229389 -1.8370321241 0.7977248364 0.3412537476 0.7758723863 0.4717853120 -0.242871445815 +1403636880401666560.0000000000 4.7201022919 -1.8341828623 0.7993307350 0.3490542044 0.7805418938 0.4618510791 -0.235815807764 +1403636880451666432.0000000000 4.7446119068 -1.8318839654 0.8019117982 0.3567338989 0.7855048475 0.4512151420 -0.228315473879 +1403636880501666560.0000000000 4.7688466420 -1.8318043534 0.8059085539 0.3631999371 0.7897828573 0.4419880163 -0.221303948262 +1403636880551666432.0000000000 4.7923106809 -1.8344199041 0.8098312177 0.3681882659 0.7946352837 0.4327370296 -0.213847679518 +1403636880601666560.0000000000 4.8148298802 -1.8403438519 0.8140691102 0.3706794926 0.7986930883 0.4263565193 -0.207138077002 +1403636880651666432.0000000000 4.8356971957 -1.8501899842 0.8175468061 0.3704140438 0.8030413047 0.4211829427 -0.201303323286 +1403636880701666560.0000000000 4.8543099873 -1.8636503573 0.8209593906 0.3678601578 0.8068582186 0.4181899588 -0.196915915298 +1403636880751666432.0000000000 4.8699430742 -1.8799941805 0.8238359851 0.3644000978 0.8102587416 0.4159765968 -0.194053629939 +1403636880801666560.0000000000 4.8821704551 -1.8985779582 0.8260619631 0.3606862549 0.8120803557 0.4158313786 -0.193688373324 +1403636880851666432.0000000000 4.8906670784 -1.9185530978 0.8279059080 0.3572631501 0.8124373045 0.4171075186 -0.19578045271 +1403636880901666560.0000000000 4.8950298092 -1.9389075652 0.8294376070 0.3551600146 0.8107139765 0.4201196903 -0.200258977789 +1403636880951666432.0000000000 4.8953622048 -1.9588630526 0.8306356086 0.3552156697 0.8074264864 0.4236529787 -0.205918553532 +1403636881001666560.0000000000 4.8918958466 -1.9774893814 0.8318309624 0.3573926673 0.8027126914 0.4278345121 -0.211850057103 +1403636881051666432.0000000000 4.8850778331 -1.9949564108 0.8329984009 0.3607210773 0.7967946345 0.4328571206 -0.218250608243 +1403636881101666560.0000000000 4.8754051548 -2.0114084591 0.8341141403 0.3637256755 0.7898978890 0.4393667848 -0.225214978094 +1403636881151666432.0000000000 4.8634858293 -2.0269736756 0.8350322450 0.3644760212 0.7829487169 0.4467329291 -0.233619833838 +1403636881201666560.0000000000 4.8494651877 -2.0408566987 0.8363225198 0.3633726529 0.7757994538 0.4549879148 -0.243066904308 +1403636881251666432.0000000000 4.8341964936 -2.0522234792 0.8377117349 0.3608608630 0.7685970222 0.4641619916 -0.25217394908 +1403636881301666560.0000000000 4.8171703972 -2.0599066874 0.8395188680 0.3584682464 0.7616641330 0.4732291517 -0.259658303859 +1403636881351666432.0000000000 4.7993214092 -2.0634489470 0.8410943969 0.3568287917 0.7551040358 0.4820964544 -0.264715162256 +1403636881401666560.0000000000 4.7800200984 -2.0624434603 0.8424439191 0.3559417279 0.7497433735 0.4892043298 -0.268084844555 +1403636881451666432.0000000000 4.7597522453 -2.0565665739 0.8432806791 0.3570169368 0.7441889872 0.4960233763 -0.269596862746 +1403636881501666560.0000000000 4.7389233755 -2.0464263751 0.8438347997 0.3596530106 0.7393917239 0.5007334858 -0.270583752015 +1403636881551666432.0000000000 4.7185420426 -2.0318977053 0.8438816802 0.3635888457 0.7339129909 0.5059946744 -0.270451959868 +1403636881601666560.0000000000 4.6985480033 -2.0139126065 0.8436648834 0.3669806890 0.7296835849 0.5093793902 -0.270960655082 +1403636881651666432.0000000000 4.6800652366 -1.9922043424 0.8426220166 0.3697609229 0.7249459610 0.5142688077 -0.270661794297 +1403636881701666560.0000000000 4.6625705815 -1.9673419006 0.8408841612 0.3718542449 0.7218718465 0.5177424047 -0.269384966486 +1403636881751666432.0000000000 4.6463412059 -1.9400186843 0.8382847100 0.3725547330 0.7201321853 0.5208146489 -0.267141737631 +1403636881801666560.0000000000 4.6312283800 -1.9108363370 0.8351252574 0.3737216215 0.7204076430 0.5214610310 -0.26348315056 +1403636881851666432.0000000000 4.6177672716 -1.8809510611 0.8317034778 0.3743842685 0.7226795309 0.5193928785 -0.260387697203 +1403636881901666560.0000000000 4.6071900756 -1.8512606103 0.8277503954 0.3741690231 0.7261871525 0.5158672644 -0.257935509782 +1403636881951666432.0000000000 4.5997575121 -1.8218080153 0.8237045709 0.3739026962 0.7300574187 0.5117071223 -0.255673150917 +1403636882001666560.0000000000 4.5953554319 -1.7932318160 0.8195094967 0.3740698639 0.7341685068 0.5063632205 -0.254292409489 +1403636882051666432.0000000000 4.5943013411 -1.7654161714 0.8148150002 0.3754100642 0.7374489713 0.5012606593 -0.252930919237 +1403636882101666560.0000000000 4.5964638357 -1.7398811998 0.8090051936 0.3770686990 0.7406298576 0.4959402998 -0.251654185984 +1403636882151666432.0000000000 4.6015148880 -1.7171347803 0.8022650893 0.3794154057 0.7429502065 0.4914384835 -0.250114289075 +1403636882201666560.0000000000 4.6090389149 -1.6978619230 0.7947223460 0.3829700772 0.7450053521 0.4866422462 -0.247952151752 +1403636882251666432.0000000000 4.6184138308 -1.6828804577 0.7871347793 0.3872485454 0.7461803314 0.4824409061 -0.245976115393 +1403636882301666560.0000000000 4.6292144954 -1.6728062839 0.7793864423 0.3908982315 0.7465662036 0.4792655633 -0.245238651459 +1403636882351666432.0000000000 4.6406385665 -1.6680182964 0.7719478889 0.3928716390 0.7462825131 0.4772774304 -0.246820866872 +1403636882401666560.0000000000 4.6517246672 -1.6678653633 0.7642921177 0.3936204836 0.7449294820 0.4776445348 -0.248995341535 +1403636882451666432.0000000000 4.6611100659 -1.6721372660 0.7571558558 0.3925798817 0.7437752710 0.4779083555 -0.253540897168 +1403636882501666560.0000000000 4.6684460982 -1.6792558542 0.7500613516 0.3910863064 0.7418928368 0.4794525748 -0.258402299017 +1403636882551666432.0000000000 4.6722676651 -1.6880292244 0.7441090869 0.3894396007 0.7393516742 0.4812333677 -0.264783581756 +1403636882601666560.0000000000 4.6725206088 -1.6968691599 0.7385312855 0.3901884811 0.7353764017 0.4833601058 -0.270808982662 +1403636882651666432.0000000000 4.6685770642 -1.7053073519 0.7337861495 0.3931284711 0.7297825946 0.4847615096 -0.279058504177 +1403636882701666560.0000000000 4.6611005243 -1.7133040137 0.7292287611 0.3983627387 0.7217204025 0.4857777291 -0.290597293477 +1403636882751666432.0000000000 4.6512387304 -1.7206851401 0.7240887280 0.4040580436 0.7110540774 0.4878265152 -0.305228582252 +1403636882801666560.0000000000 4.6397936976 -1.7270745346 0.7173936723 0.4104036093 0.6989610349 0.4907111103 -0.31972637578 +1403636882851666432.0000000000 4.6275533636 -1.7327368885 0.7092381348 0.4157435622 0.6865797816 0.4942927022 -0.333826629387 +1403636882901666560.0000000000 4.6150389938 -1.7379527239 0.6996030601 0.4191024103 0.6756201558 0.4983822005 -0.34569604723 +1403636882951666432.0000000000 4.6030746092 -1.7433117910 0.6888609825 0.4182713131 0.6665664714 0.5038644217 -0.356172559912 +1403636883001666560.0000000000 4.5919682469 -1.7487077001 0.6769816987 0.4146333772 0.6593517977 0.5106835548 -0.364055869663 +1403636883051666432.0000000000 4.5813542992 -1.7537375662 0.6649294818 0.4092547863 0.6533062381 0.5184443814 -0.370022840581 +1403636883101666560.0000000000 4.5708562969 -1.7578223748 0.6529217700 0.4072101494 0.6473518927 0.5248746122 -0.373660357479 +1403636883151666432.0000000000 4.5607361046 -1.7612778066 0.6411034821 0.4074851051 0.6411225203 0.5303586812 -0.376347541879 +1403636883201666560.0000000000 4.5508915658 -1.7643524241 0.6295596500 0.4103832691 0.6345582773 0.5343217130 -0.378710538804 +1403636883251666432.0000000000 4.5417925717 -1.7672984484 0.6184928568 0.4132010530 0.6285386230 0.5373008105 -0.381460257729 +1403636883301666560.0000000000 4.5338093922 -1.7703704335 0.6086132042 0.4142078343 0.6239597074 0.5389856728 -0.385487480996 +1403636883351666432.0000000000 4.5268484060 -1.7725878020 0.5998536893 0.4147486467 0.6208127346 0.5401865929 -0.388295703574 +1403636883401666560.0000000000 4.5208172853 -1.7744016621 0.5924298303 0.4143130291 0.6185245694 0.5407373082 -0.391631503465 +1403636883451666432.0000000000 4.5157845899 -1.7755970532 0.5864153917 0.4149705026 0.6155127178 0.5413910124 -0.394764927354 +1403636883501666560.0000000000 4.5119302439 -1.7764049060 0.5819536848 0.4160585718 0.6115364395 0.5420015323 -0.398939578043 +1403636883551666432.0000000000 4.5084927920 -1.7771442840 0.5785258031 0.4182114438 0.6066737100 0.5425058772 -0.403402492616 +1403636883601666560.0000000000 4.5055328022 -1.7778265959 0.5752534457 0.4199040220 0.6019582167 0.5433501016 -0.407550714437 +1403636883651666432.0000000000 4.5029645826 -1.7784436591 0.5721486965 0.4198979672 0.5981838489 0.5449063651 -0.411021694384 +1403636883701666560.0000000000 4.5009793547 -1.7785291658 0.5693963309 0.4203584066 0.5945698077 0.5481675825 -0.411458205902 +1403636883751666432.0000000000 4.4993025189 -1.7788555869 0.5675504883 0.4195209942 0.5928627718 0.5497884092 -0.412611892999 +1403636883801666560.0000000000 4.4979446083 -1.7789014121 0.5655666677 0.4188217758 0.5916677651 0.5509686648 -0.413462339632 +1403636883851666432.0000000000 4.4968474875 -1.7793590984 0.5639894287 0.4158482152 0.5915845537 0.5502999946 -0.417454061739 +1403636883901666560.0000000000 4.4960639403 -1.7792716531 0.5619652182 0.4143570483 0.5900967472 0.5511505904 -0.419913196045 +1403636883951666432.0000000000 4.4951040922 -1.7790311131 0.5602715542 0.4145124208 0.5888229064 0.5520449076 -0.420372998578 +1403636884001666560.0000000000 4.4944257252 -1.7789186226 0.5598006276 0.4157608683 0.5859956879 0.5522572828 -0.422804739441 +1403636884051666432.0000000000 4.4942680488 -1.7787953411 0.5594766388 0.4163311302 0.5834626556 0.5518657440 -0.426243967961 +1403636884101666560.0000000000 4.4943921125 -1.7782967043 0.5588809494 0.4160348221 0.5815562119 0.5510216093 -0.430212256104 +1403636884151666432.0000000000 4.4947255599 -1.7774049393 0.5584312850 0.4187939455 0.5794220162 0.5515205448 -0.429775344808 +1403636884201666560.0000000000 4.4948769770 -1.7772173874 0.5585259050 0.4213750572 0.5771154961 0.5509250029 -0.431117624923 +1403636884251666432.0000000000 4.4951409369 -1.7772810782 0.5586735112 0.4241221055 0.5756372776 0.5499551918 -0.431638102114 +1403636884301666560.0000000000 4.4956007153 -1.7778734692 0.5587626133 0.4245910928 0.5753820607 0.5490892032 -0.43261869475 +1403636884351666432.0000000000 4.4958724807 -1.7783662780 0.5588680967 0.4244614492 0.5752506287 0.5485869196 -0.433556898191 +1403636884401666560.0000000000 4.4960433935 -1.7785288488 0.5587852824 0.4242925645 0.5753875043 0.5483443024 -0.433847398975 +1403636884451666432.0000000000 4.4960861241 -1.7783030274 0.5587038416 0.4248246745 0.5749379073 0.5487478875 -0.433412222619 +1403636884501666560.0000000000 4.4962008481 -1.7782721337 0.5586806623 0.4249389754 0.5749524323 0.5487651040 -0.433259077713 +1403636884551666432.0000000000 4.4962118417 -1.7784055406 0.5586892115 0.4245875496 0.5751112858 0.5486582925 -0.433527968874 +1403636884601666560.0000000000 4.4963469607 -1.7785153186 0.5587416245 0.4246811030 0.5749885856 0.5485684173 -0.433712783733 +1403636884651666432.0000000000 4.4962549299 -1.7784331844 0.5586394407 0.4244048486 0.5752923116 0.5486118066 -0.433525508307 +1403636884701666560.0000000000 4.4964074679 -1.7784989048 0.5585892252 0.4244151744 0.5752036317 0.5486693428 -0.433560254296 +1403636884751666432.0000000000 4.4964693091 -1.7785383096 0.5585538527 0.4242002301 0.5754111614 0.5485403159 -0.433658485349 +1403636884801666560.0000000000 4.4964395667 -1.7783654351 0.5584732732 0.4244839754 0.5752077578 0.5487117244 -0.433433770573 +1403636884851666432.0000000000 4.4964201543 -1.7784905763 0.5584947015 0.4241263494 0.5754150708 0.5484817040 -0.43379967309 +1403636884901666560.0000000000 4.4963965080 -1.7783132301 0.5584154397 0.4244232061 0.5752405992 0.5486807789 -0.433488867212 +1403636884951666432.0000000000 4.4964013725 -1.7784403755 0.5584413683 0.4241409412 0.5754136958 0.5485151869 -0.433744890894 +1403636885001666560.0000000000 4.4963782995 -1.7783970777 0.5583646532 0.4242397419 0.5753235931 0.5486529042 -0.433593583056 +1403636885051666432.0000000000 4.4963991809 -1.7784560949 0.5584154685 0.4241745464 0.5753760777 0.5485903713 -0.433666839705 +1403636885101666560.0000000000 4.4963633138 -1.7784608377 0.5584066591 0.4241709936 0.5754033619 0.5485203443 -0.433722689242 +1403636885151666432.0000000000 4.4963032472 -1.7783716154 0.5583937035 0.4242410642 0.5754154403 0.5485972744 -0.433540795126 +1403636885201666560.0000000000 4.4962876866 -1.7784945357 0.5584829153 0.4240899966 0.5755011516 0.5484619694 -0.433745971134 +1403636885251666432.0000000000 4.4962087081 -1.7784227979 0.5584950945 0.4242180225 0.5754547231 0.5485340494 -0.433591198783 +1403636885301666560.0000000000 4.4961704557 -1.7784886722 0.5585439700 0.4241187037 0.5754889593 0.5484768261 -0.433715291595 +1403636885351666432.0000000000 4.4960522370 -1.7785020430 0.5585722438 0.4241423069 0.5755236317 0.5484931562 -0.433625541791 +1403636885401666560.0000000000 4.4960207799 -1.7784905073 0.5586257650 0.4242044468 0.5755188657 0.5484142899 -0.433670830425 +1403636885451666432.0000000000 4.4959589427 -1.7784783087 0.5586561497 0.4242262069 0.5755126465 0.5483743996 -0.433708239388 +1403636885501666560.0000000000 4.4959063310 -1.7784490676 0.5586330869 0.4242030477 0.5755355909 0.5483956029 -0.433673633802 +1403636885551666432.0000000000 4.4959278907 -1.7784395323 0.5587007106 0.4241717321 0.5755781723 0.5484011928 -0.433640681846 +1403636885601666560.0000000000 4.4959991345 -1.7783776619 0.5587273498 0.4242288452 0.5755298429 0.5483780259 -0.433678253532 +1403636885651666432.0000000000 4.4960457113 -1.7783339233 0.5587104029 0.4242408143 0.5755038247 0.5484827910 -0.433568572699 +1403636885701666560.0000000000 4.4959670036 -1.7783726535 0.5587321023 0.4240510336 0.5756716974 0.5483802850 -0.433661020512 +1403636885751666432.0000000000 4.4960075245 -1.7783402265 0.5587307591 0.4242172223 0.5755234502 0.5484264279 -0.433636898516 +1403636885801666560.0000000000 4.4959469532 -1.7783030036 0.5587519064 0.4240653026 0.5756993530 0.5483659490 -0.433628481561 +1403636885851666432.0000000000 4.4959334394 -1.7782675008 0.5587308914 0.4242458586 0.5755567624 0.5483948459 -0.433604609981 +1403636885901666560.0000000000 4.4959174031 -1.7782567593 0.5586974765 0.4239818020 0.5757841047 0.5483373820 -0.433633730084 +1403636885951666432.0000000000 4.4959948865 -1.7781597605 0.5586868683 0.4242737143 0.5755916357 0.5484535325 -0.433456810924 +1403636886001666560.0000000000 4.4959066106 -1.7782928771 0.5587164202 0.4239863473 0.5757971437 0.5482785325 -0.433686381401 +1403636886051666432.0000000000 4.4959198594 -1.7782701206 0.5586415698 0.4241229388 0.5757221934 0.5483771715 -0.433527584632 +1403636886101666560.0000000000 4.4959336924 -1.7782958591 0.5586941458 0.4240848186 0.5757902986 0.5483050828 -0.433565606292 +1403636886151666432.0000000000 4.4959644001 -1.7783140034 0.5587057631 0.4240987450 0.5757954012 0.5482611280 -0.433600790978 +1403636886201666560.0000000000 4.4959559004 -1.7782856432 0.5586676522 0.4241569941 0.5757936681 0.5483161776 -0.43347648782 +1403636886251666432.0000000000 4.4960025804 -1.7783602329 0.5587702154 0.4240653100 0.5758425653 0.5482047160 -0.433642182275 +1403636886301666560.0000000000 4.4960161237 -1.7783035711 0.5587696293 0.4241852516 0.5757873225 0.5483110328 -0.433463773404 +1403636886351666432.0000000000 4.4959818422 -1.7783917333 0.5587215737 0.4239994691 0.5758928548 0.5482226732 -0.433617078191 +1403636886401666560.0000000000 4.4960000503 -1.7783698866 0.5587158908 0.4241089952 0.5758272316 0.5482598854 -0.433550063458 +1403636886451666432.0000000000 4.4960175438 -1.7783482461 0.5586786704 0.4240970127 0.5758457641 0.5482793874 -0.433512506336 +1403636886501666560.0000000000 4.4960472550 -1.7783836351 0.5587394618 0.4240918241 0.5758247484 0.5482412414 -0.433593732786 +1403636886551666432.0000000000 4.4960346522 -1.7783647667 0.5588095886 0.4240834089 0.5758645822 0.5482294646 -0.433563950757 +1403636886601666560.0000000000 4.4960374917 -1.7783564382 0.5587763374 0.4240940124 0.5758461447 0.5482333002 -0.433573217314 +1403636886651666432.0000000000 4.4960104069 -1.7783398283 0.5587881598 0.4240760552 0.5758668022 0.5482129130 -0.433589122949 +1403636886701666560.0000000000 4.4959966067 -1.7783117683 0.5587447942 0.4240787535 0.5758795426 0.5482278186 -0.433550714614 +1403636886751666432.0000000000 4.4959702089 -1.7783190647 0.5587330490 0.4240119125 0.5759116040 0.5482149013 -0.433589834346 +1403636886801666560.0000000000 4.4960188551 -1.7783092168 0.5587266606 0.4240785110 0.5758491384 0.5482320447 -0.433585990843 +1403636886851666432.0000000000 4.4960105212 -1.7783168603 0.5587176064 0.4240155564 0.5758989703 0.5482437141 -0.433566619891 +1403636886901666560.0000000000 4.4960291781 -1.7783520087 0.5587436588 0.4239836098 0.5758767714 0.5482419551 -0.433629567106 +1403636886951666432.0000000000 4.4960097564 -1.7783231488 0.5587500070 0.4240405186 0.5758610501 0.5482488281 -0.433586106964 +1403636887001666560.0000000000 4.4960106822 -1.7783142133 0.5588009162 0.4240455203 0.5758635069 0.5482630552 -0.43355996184 +1403636887051666432.0000000000 4.4959527214 -1.7783157701 0.5587445275 0.4239974994 0.5758880501 0.5482263071 -0.433620791077 +1403636887101666560.0000000000 4.4959575228 -1.7782710517 0.5587618589 0.4240262514 0.5758660427 0.5482424326 -0.433601515349 +1403636887151666432.0000000000 4.4959735657 -1.7782725543 0.5588188078 0.4239476441 0.5759321085 0.5481999905 -0.433644291923 +1403636887201666560.0000000000 4.4959860579 -1.7782869277 0.5588619261 0.4239741921 0.5758903189 0.5482257162 -0.433641313961 +1403636887251666432.0000000000 4.4959948606 -1.7783014468 0.5588800112 0.4239473410 0.5759147911 0.5482107573 -0.433653976204 +1403636887301666560.0000000000 4.4960092481 -1.7783012204 0.5589624656 0.4239424399 0.5759519800 0.5481817203 -0.433646083812 +1403636887351666432.0000000000 4.4960146391 -1.7782996024 0.5589224270 0.4239713344 0.5759379473 0.5481466831 -0.433680760836 +1403636887401666560.0000000000 4.4960072705 -1.7782539657 0.5588557074 0.4239950166 0.5759353853 0.5482253933 -0.43356150199 +1403636887451666432.0000000000 4.4960477678 -1.7782983364 0.5588554588 0.4239348283 0.5759641185 0.5481596197 -0.433665339818 +1403636887501666560.0000000000 4.4960598854 -1.7782356115 0.5587850312 0.4239823347 0.5759348648 0.5482480445 -0.43354595256 +1403636887551666432.0000000000 4.4960863664 -1.7782705267 0.5587815032 0.4238999071 0.5759660704 0.5482167424 -0.433624673895 +1403636887601666560.0000000000 4.4960567015 -1.7782610277 0.5587679900 0.4239651178 0.5759526290 0.5481824756 -0.433622095341 +1403636887651666432.0000000000 4.4960257239 -1.7782841282 0.5587511885 0.4239730158 0.5759581353 0.5481912064 -0.433596021161 +1403636887701666560.0000000000 4.4960101117 -1.7783349267 0.5587600310 0.4239283172 0.5759741481 0.5481716370 -0.433643193289 +1403636887751666432.0000000000 4.4960225383 -1.7783300959 0.5587480280 0.4239540713 0.5759628385 0.5482338679 -0.433554356687 +1403636887801666560.0000000000 4.4960452727 -1.7783661202 0.5587615265 0.4238735579 0.5759952392 0.5481747897 -0.433664722222 +1403636887851666432.0000000000 4.4960539517 -1.7782968838 0.5587566272 0.4239865456 0.5759329134 0.5482154937 -0.433585586518 +1403636887901666560.0000000000 4.4960454382 -1.7783196341 0.5587725877 0.4238470299 0.5760420353 0.5481717756 -0.433632301844 +1403636887951666432.0000000000 4.4960270400 -1.7782722986 0.5587715727 0.4238916752 0.5760149143 0.5482086898 -0.433578019088 +1403636888001666560.0000000000 4.4960162495 -1.7782601031 0.5587671830 0.4238032643 0.5760996203 0.5481844154 -0.433582595794 +1403636888051666432.0000000000 4.4960395227 -1.7782488035 0.5588034255 0.4238233360 0.5760655362 0.5482066305 -0.433580174993 +1403636888101666560.0000000000 4.4960410095 -1.7782456676 0.5587546666 0.4237878710 0.5760755003 0.5481778045 -0.433638043838 +1403636888151666432.0000000000 4.4960709236 -1.7782353251 0.5587847354 0.4237944071 0.5760785535 0.5481766764 -0.433629025844 +1403636888201666560.0000000000 4.4960569559 -1.7782720445 0.5587393946 0.4237597427 0.5760843048 0.5481521213 -0.433686299207 +1403636888251666432.0000000000 4.4960503051 -1.7782855519 0.5587216336 0.4237458282 0.5760795762 0.5481586972 -0.433697864515 +1403636888301666560.0000000000 4.4960550489 -1.7783079412 0.5587061699 0.4237564172 0.5760715550 0.5481415570 -0.433719835651 +1403636888351666432.0000000000 4.4960762868 -1.7783306997 0.5586879259 0.4237102984 0.5760910584 0.5481227596 -0.433762741452 +1403636888401666560.0000000000 4.4960753296 -1.7783239099 0.5586594913 0.4237399085 0.5760935818 0.5481734636 -0.433666379441 +1403636888451666432.0000000000 4.4961267120 -1.7783553602 0.5586958472 0.4236109040 0.5761822419 0.5481110716 -0.433753477598 +1403636888501666560.0000000000 4.4961295979 -1.7783434029 0.5586529312 0.4236919129 0.5761424069 0.5481492482 -0.433679019001 +1403636888551666432.0000000000 4.4961594095 -1.7784308500 0.5587055890 0.4236303054 0.5761790495 0.5481019820 -0.433750255971 +1403636888601666560.0000000000 4.4960883561 -1.7784949781 0.5587853346 0.4237314303 0.5761648052 0.5480582774 -0.433725623841 +1403636888651666432.0000000000 4.4959795021 -1.7785860182 0.5588813618 0.4237306680 0.5762176869 0.5479659078 -0.433772823239 +1403636888701666560.0000000000 4.4958964409 -1.7787304751 0.5589841204 0.4238460246 0.5760118381 0.5480324409 -0.433849459493 +1403636888751666432.0000000000 4.4958566841 -1.7788145144 0.5590413407 0.4239511171 0.5760206443 0.5479302678 -0.433864136898 +1403636888801666560.0000000000 4.4958630717 -1.7788107987 0.5589672118 0.4238346080 0.5759634910 0.5480830746 -0.433860836537 +1403636888851666432.0000000000 4.4957971002 -1.7787091340 0.5588960313 0.4238755278 0.5762300098 0.5479053787 -0.433691374886 +1403636888901666560.0000000000 4.4958405252 -1.7785869046 0.5589347489 0.4237199293 0.5764240286 0.5477942713 -0.433725946947 +1403636888951666432.0000000000 4.4959090695 -1.7784231352 0.5589580599 0.4239366470 0.5762913859 0.5477844206 -0.433702878045 +1403636889001666560.0000000000 4.4960566698 -1.7783918951 0.5590175549 0.4236947849 0.5762450969 0.5477477609 -0.434046896064 +1403636889051666432.0000000000 4.4960920303 -1.7781451442 0.5589900198 0.4239229088 0.5762974503 0.5477065283 -0.433806610193 +1403636889101666560.0000000000 4.4960495185 -1.7780782555 0.5590414269 0.4238300524 0.5765351452 0.5475632979 -0.433762317173 +1403636889151666432.0000000000 4.4959760557 -1.7781795194 0.5590216196 0.4238612121 0.5764483930 0.5476302156 -0.43376268861 +1403636889201666560.0000000000 4.4960101496 -1.7782765921 0.5589170164 0.4237844670 0.5766141095 0.5475709011 -0.433692290143 +1403636889251666432.0000000000 4.4960106070 -1.7782880186 0.5588375382 0.4237503811 0.5767146312 0.5474850884 -0.433700272757 +1403636889301666560.0000000000 4.4959355176 -1.7782752629 0.5587928196 0.4237924510 0.5766970190 0.5474623164 -0.433711331232 +1403636889351666432.0000000000 4.4959217155 -1.7783375225 0.5587673360 0.4238088407 0.5765984344 0.5475065330 -0.433770571029 +1403636889401666560.0000000000 4.4959831602 -1.7784603139 0.5587439474 0.4236938485 0.5763970856 0.5477367075 -0.433859910121 +1403636889451666432.0000000000 4.4960750518 -1.7784668384 0.5587297884 0.4237514098 0.5765254125 0.5475992346 -0.43380671926 +1403636889501666560.0000000000 4.4961541221 -1.7783707038 0.5586130736 0.4238749870 0.5764728515 0.5476894910 -0.433641866429 +1403636889551666432.0000000000 4.4961254256 -1.7783691200 0.5586309051 0.4238408912 0.5765654498 0.5475851530 -0.43368384942 +1403636889601666560.0000000000 4.4961302437 -1.7782232126 0.5586312674 0.4241003205 0.5765882537 0.5475244744 -0.433476474255 +1403636889651666432.0000000000 4.4961589682 -1.7783162678 0.5587076387 0.4239466464 0.5765521520 0.5474669399 -0.433747399792 +1403636889701666560.0000000000 4.4961853431 -1.7783316236 0.5587119376 0.4241909634 0.5763577056 0.5476098650 -0.433586505177 +1403636889751666432.0000000000 4.4961438838 -1.7784486897 0.5587428771 0.4241533926 0.5764471486 0.5474963725 -0.433647675594 +1403636889801666560.0000000000 4.4962239225 -1.7785943962 0.5587372735 0.4241212191 0.5762709615 0.5477127233 -0.433640108021 +1403636889851666432.0000000000 4.4962033336 -1.7785565165 0.5587596810 0.4241394840 0.5764655538 0.5475302492 -0.433594037804 +1403636889901666560.0000000000 4.4962311688 -1.7785319742 0.5588196674 0.4241105525 0.5765976524 0.5474458450 -0.433553264611 +1403636889951666432.0000000000 4.4962757307 -1.7784851353 0.5588400484 0.4240347708 0.5763498273 0.5477128004 -0.433619739044 +1403636890001666560.0000000000 4.4963013033 -1.7783990646 0.5588335319 0.4239182464 0.5765085238 0.5476604608 -0.433588816687 +1403636890051666432.0000000000 4.4962670555 -1.7782678384 0.5588327785 0.4239892106 0.5767658688 0.5474862956 -0.433397090459 +1403636890101666560.0000000000 4.4962144553 -1.7782811654 0.5589471259 0.4241484123 0.5769087492 0.5471379656 -0.433491021798 +1403636890151666432.0000000000 4.4961978250 -1.7784154958 0.5590965296 0.4243022046 0.5765725868 0.5471804470 -0.433734077356 +1403636890201666560.0000000000 4.4962978536 -1.7787109299 0.5591579566 0.4241065621 0.5762705167 0.5474231873 -0.434020471265 +1403636890251666432.0000000000 4.4963402660 -1.7789309953 0.5590936170 0.4239303586 0.5760828204 0.5478011593 -0.433964889154 +1403636890301666560.0000000000 4.4964234201 -1.7790786849 0.5589357824 0.4236121857 0.5762890508 0.5479623119 -0.433798283463 +1403636890351666432.0000000000 4.4964703703 -1.7790946134 0.5587609406 0.4235746396 0.5766108346 0.5478571734 -0.433540064751 +1403636890401666560.0000000000 4.4965200742 -1.7789934589 0.5586413265 0.4238257653 0.5768894244 0.5474882483 -0.433390044612 +1403636890451666432.0000000000 4.4964716988 -1.7788808140 0.5585694689 0.4242068262 0.5769500489 0.5470365025 -0.433506948738 +1403636890501666560.0000000000 4.4965284741 -1.7787575077 0.5585746198 0.4244339185 0.5766929890 0.5469491913 -0.433736818205 +1403636890551666432.0000000000 4.4966768972 -1.7787299123 0.5585956599 0.4243355451 0.5763787881 0.5471330308 -0.434018760447 +1403636890601666560.0000000000 4.4968180894 -1.7786753673 0.5585182110 0.4241590210 0.5761181045 0.5475603466 -0.433998526914 +1403636890651666432.0000000000 4.4969060222 -1.7786175538 0.5585043691 0.4237722516 0.5762206884 0.5478370598 -0.433890945882 +1403636890701666560.0000000000 4.4969516672 -1.7784873335 0.5584964472 0.4236524290 0.5764643213 0.5478655798 -0.433648258643 +1403636890751666432.0000000000 4.4969324329 -1.7783951356 0.5585959557 0.4237156947 0.5767378230 0.5476474034 -0.433498344958 +1403636890801666560.0000000000 4.4968607154 -1.7783412751 0.5588190475 0.4239873184 0.5768395320 0.5472851190 -0.433554963907 +1403636890851666432.0000000000 4.4968426809 -1.7783628611 0.5589749146 0.4241901517 0.5767073319 0.5472146971 -0.433621313832 +1403636890901666560.0000000000 4.4969245621 -1.7785908707 0.5590311522 0.4240376937 0.5765475488 0.5473738276 -0.433782031731 +1403636890951666432.0000000000 4.4969487347 -1.7787032348 0.5589661840 0.4239570355 0.5765112651 0.5475429500 -0.433695643455 +1403636891001666560.0000000000 4.4969531446 -1.7788866142 0.5589510476 0.4237303589 0.5765275633 0.5475592915 -0.433874836819 +1403636891051666432.0000000000 4.4969088240 -1.7788529148 0.5588418105 0.4237834723 0.5765049243 0.5476837658 -0.433695899859 +1403636891101666560.0000000000 4.4968868441 -1.7789144686 0.5588159180 0.4237790774 0.5765112370 0.5476279497 -0.433762280338 +1403636891151666432.0000000000 4.4968925645 -1.7789416641 0.5587984826 0.4238192191 0.5764738627 0.5476177322 -0.433785632005 +1403636891201666560.0000000000 4.4969270483 -1.7789229969 0.5587548229 0.4238333756 0.5764660732 0.5476429761 -0.433750281637 +1403636891251666432.0000000000 4.4969310296 -1.7789268030 0.5587348244 0.4237655731 0.5764763507 0.5476520908 -0.433791359424 +1403636891301666560.0000000000 4.4968622645 -1.7788752075 0.5586748663 0.4237430070 0.5764961297 0.5477048329 -0.433720523369 +1403636891351666432.0000000000 4.4968808794 -1.7788699121 0.5586122935 0.4237664322 0.5764603358 0.5476787780 -0.43377810957 +1403636891401666560.0000000000 4.4968684782 -1.7788043169 0.5585822748 0.4238393025 0.5764526432 0.5476578706 -0.433743533183 +1403636891451666432.0000000000 4.4968753021 -1.7787916854 0.5585824304 0.4237843633 0.5764750161 0.5476565754 -0.433769114434 +1403636891501666560.0000000000 4.4968759756 -1.7787786511 0.5585968178 0.4237558866 0.5764521170 0.5477005807 -0.433771805539 +1403636891551666432.0000000000 4.4968975008 -1.7787708262 0.5586598581 0.4236919957 0.5764923218 0.5477282152 -0.433745890949 +1403636891601666560.0000000000 4.4969217764 -1.7787771289 0.5586470358 0.4236603529 0.5764982844 0.5477547280 -0.433735393416 +1403636891651666432.0000000000 4.4968849870 -1.7788085418 0.5586468820 0.4236428143 0.5765563248 0.5477156747 -0.433724693764 +1403636891701666560.0000000000 4.4968466429 -1.7788283462 0.5586131517 0.4236803472 0.5765267666 0.5477136767 -0.433729845781 +1403636891751666432.0000000000 4.4968268604 -1.7788403147 0.5586236141 0.4236756185 0.5765155253 0.5477250366 -0.433735061577 +1403636891801666560.0000000000 4.4968216797 -1.7788454516 0.5586565905 0.4236486314 0.5765259637 0.5477025512 -0.433775939578 +1403636891851666432.0000000000 4.4968481947 -1.7787838529 0.5586792154 0.4237154884 0.5764577901 0.5477848424 -0.433697322473 +1403636891901666560.0000000000 4.4969005501 -1.7787949854 0.5587497653 0.4236215936 0.5765091503 0.5477064885 -0.43381971775 +1403636891951666432.0000000000 4.4969268969 -1.7787585083 0.5587477185 0.4236840467 0.5765030485 0.5477395117 -0.433725132847 +1403636892001666560.0000000000 4.4969319960 -1.7787700164 0.5588038555 0.4236561283 0.5765497171 0.5476927768 -0.433749387126 +1403636892051666432.0000000000 4.4969600046 -1.7787842396 0.5587862593 0.4236781943 0.5765265314 0.5476959904 -0.433754594624 +1403636892101666560.0000000000 4.4969705256 -1.7787609318 0.5587620792 0.4236514464 0.5765363710 0.5477062725 -0.433754658611 +1403636892151666432.0000000000 4.4969778344 -1.7787766580 0.5587433216 0.4236202947 0.5765592968 0.5476693348 -0.433801248059 +1403636892201666560.0000000000 4.4969660940 -1.7787269294 0.5586902062 0.4236528987 0.5765635950 0.5477146455 -0.433706478565 +1403636892251666432.0000000000 4.4969548981 -1.7787174866 0.5586579100 0.4236458046 0.5765615879 0.5477110547 -0.433720610691 +1403636892301666560.0000000000 4.4968679121 -1.7785820950 0.5586185205 0.4237999129 0.5765468526 0.5478224556 -0.433448864001 +1403636892351666432.0000000000 4.4968883808 -1.7787319257 0.5586535350 0.4237097080 0.5766063533 0.5476524924 -0.433672623411 +1403636892401666560.0000000000 4.4968038639 -1.7787404490 0.5586821633 0.4237567615 0.5767210592 0.5475558158 -0.433596189546 +1403636892451666432.0000000000 4.4967942064 -1.7788086962 0.5587260988 0.4239224452 0.5765520446 0.5475756660 -0.433633935843 +1403636892501666560.0000000000 4.4967871114 -1.7788640501 0.5587300004 0.4237864823 0.5766492846 0.5475644260 -0.433651725798 +1403636892551666432.0000000000 4.4968265158 -1.7788860322 0.5587287362 0.4237537761 0.5766681012 0.5476161366 -0.433593363975 +1403636892601666560.0000000000 4.4969167496 -1.7789562158 0.5587657848 0.4237507660 0.5766416830 0.5475824212 -0.433674013216 +1403636892651666432.0000000000 4.4969326298 -1.7789191576 0.5587440981 0.4236754388 0.5767200789 0.5475878794 -0.433636469236 +1403636892701666560.0000000000 4.4970173888 -1.7788885031 0.5587098152 0.4237457757 0.5766487960 0.5475782867 -0.433674651869 +1403636892751666432.0000000000 4.4970345537 -1.7788101242 0.5587322681 0.4236779223 0.5767107235 0.5476128642 -0.433614933531 +1403636892801666560.0000000000 4.4970713939 -1.7788190969 0.5587777653 0.4237266867 0.5765906325 0.5476592125 -0.433668449872 +1403636892851666432.0000000000 4.4970120838 -1.7788012640 0.5587508667 0.4236282991 0.5767002531 0.5476713570 -0.433603467441 +1403636892901666560.0000000000 4.4969385632 -1.7787639879 0.5587266026 0.4235725174 0.5767419995 0.5476992184 -0.433567243537 +1403636892951666432.0000000000 4.4968896367 -1.7787569580 0.5587387599 0.4236052071 0.5766897646 0.5477095963 -0.433591676724 +1403636893001666560.0000000000 4.4968689753 -1.7787160685 0.5587411650 0.4236729550 0.5766439586 0.5476963885 -0.433603088321 +1403636893051666432.0000000000 4.4968710865 -1.7787290150 0.5587646650 0.4235882096 0.5767133268 0.5476486810 -0.433653882175 +1403636893101666560.0000000000 4.4968930400 -1.7787207539 0.5587432239 0.4236890084 0.5766474142 0.5476608734 -0.433627664812 +1403636893151666432.0000000000 4.4968906499 -1.7787264296 0.5587789700 0.4236440469 0.5766942623 0.5476070129 -0.433677309481 +1403636893201666560.0000000000 4.4968848957 -1.7787023719 0.5587569766 0.4236476853 0.5767216041 0.5476140603 -0.433628494384 +1403636893251666432.0000000000 4.4968921655 -1.7787345512 0.5586923463 0.4236210452 0.5767056167 0.5476479464 -0.433632988298 +1403636893301666560.0000000000 4.4968909695 -1.7787772878 0.5586402184 0.4236296380 0.5767453920 0.5476027932 -0.433628716188 +1403636893351666432.0000000000 4.4969583110 -1.7788147809 0.5586715524 0.4236129859 0.5767271077 0.5475965111 -0.433677233082 +1403636893401666560.0000000000 4.4970003252 -1.7788080955 0.5586804547 0.4235846446 0.5767806292 0.5476194549 -0.433604759281 +1403636893451666432.0000000000 4.4970334467 -1.7788202883 0.5587246642 0.4236269191 0.5767439822 0.5475838576 -0.433657158793 +1403636893501666560.0000000000 4.4969900903 -1.7788144574 0.5587677109 0.4235695074 0.5767999822 0.5476194926 -0.433593754796 +1403636893551666432.0000000000 4.4969472185 -1.7787969946 0.5588062092 0.4235800143 0.5767738212 0.5476529143 -0.433576078872 +1403636893601666560.0000000000 4.4968973413 -1.7788005415 0.5587641896 0.4235743426 0.5768242948 0.5476233639 -0.433551796844 +1403636893651666432.0000000000 4.4968882671 -1.7788287858 0.5587406464 0.4236269309 0.5766807323 0.5476928938 -0.433603563739 +1403636893701666560.0000000000 4.4968736445 -1.7788489696 0.5587062800 0.4235379539 0.5767553182 0.5477102387 -0.433569370409 +1403636893751666432.0000000000 4.4968767565 -1.7788576084 0.5587094654 0.4235583784 0.5767052487 0.5477184780 -0.433605609966 +1403636893801666560.0000000000 4.4968380409 -1.7788355298 0.5587210753 0.4234083216 0.5768308074 0.5477196654 -0.433583649355 +1403636893851666432.0000000000 4.4968414973 -1.7788564127 0.5587005925 0.4234503898 0.5767577905 0.5477764315 -0.433567987292 +1403636893901666560.0000000000 4.4968551226 -1.7788685720 0.5586884525 0.4233528690 0.5768453339 0.5477071775 -0.433634243025 +1403636893951666432.0000000000 4.4969079337 -1.7788684068 0.5586858724 0.4232924134 0.5768396211 0.5477372544 -0.433662869522 +1403636894001666560.0000000000 4.4969159521 -1.7788500369 0.5586720795 0.4232923918 0.5768973670 0.5476732598 -0.433666899305 +1403636894051666432.0000000000 4.4969273254 -1.7788104543 0.5586556231 0.4232864622 0.5768660255 0.5476851960 -0.433699303267 +1403636894101666560.0000000000 4.4969598108 -1.7787951992 0.5586206277 0.4232736653 0.5769634283 0.5476600809 -0.433613932508 +1403636894151666432.0000000000 4.4969678180 -1.7788012703 0.5586301925 0.4232418650 0.5769307096 0.5476646510 -0.433682729719 +1403636894201666560.0000000000 4.4969743614 -1.7788039829 0.5586509482 0.4232787316 0.5769364641 0.5476490869 -0.433658747616 +1403636894251666432.0000000000 4.4969487758 -1.7788319878 0.5586892804 0.4232000875 0.5770036043 0.5476165020 -0.433687321994 +1403636894301666560.0000000000 4.4969097620 -1.7788107883 0.5587179365 0.4232923788 0.5769637522 0.5476023967 -0.433668082502 +1403636894351666432.0000000000 4.4969317263 -1.7788768978 0.5587416383 0.4232109660 0.5769993081 0.5476308743 -0.433664273715 +1403636894401666560.0000000000 4.4968981845 -1.7788723546 0.5587784236 0.4232391974 0.5769969461 0.5476575316 -0.43360619693 +1403636894451666432.0000000000 4.4969103767 -1.7788815798 0.5587773842 0.4231894939 0.5770415268 0.5476201383 -0.433642609491 +1403636894501666560.0000000000 4.4969733675 -1.7788772624 0.5587689763 0.4231756378 0.5769660970 0.5476784966 -0.433682795222 +1403636894551666432.0000000000 4.4969784788 -1.7788524103 0.5587154451 0.4232191511 0.5770109092 0.5476271743 -0.433645522182 +1403636894601666560.0000000000 4.4970485727 -1.7788831329 0.5586750430 0.4231914429 0.5770495955 0.5476243086 -0.43362470368 +1403636894651666432.0000000000 4.4970613003 -1.7788842636 0.5586489470 0.4231860847 0.5770335644 0.5476349682 -0.433637803831 +1403636894701666560.0000000000 4.4970690626 -1.7789108301 0.5586775932 0.4231782395 0.5770221037 0.5475909001 -0.43371635377 +1403636894751666432.0000000000 4.4970317914 -1.7788956179 0.5586753885 0.4231855373 0.5770175622 0.5476122690 -0.433688294533 +1403636894801666560.0000000000 4.4970072512 -1.7788424075 0.5586910793 0.4231496150 0.5770788975 0.5475838969 -0.433677559147 +1403636894851666432.0000000000 4.4969395950 -1.7788027043 0.5587268915 0.4231707246 0.5770874966 0.5475944928 -0.43363213746 +1403636894901666560.0000000000 4.4968590890 -1.7787365963 0.5587447945 0.4233252487 0.5771302480 0.5475138005 -0.433526295608 +1403636894951666432.0000000000 4.4967861572 -1.7787693425 0.5587532566 0.4232041476 0.5771690681 0.5475034719 -0.433605886149 +1403636895001666560.0000000000 4.4966858485 -1.7787388004 0.5587608175 0.4232107428 0.5771458296 0.5475646799 -0.433553087682 +1403636895051666432.0000000000 4.4966843266 -1.7788167302 0.5587295380 0.4230933659 0.5771688718 0.5475987252 -0.433593972786 +1403636895101666560.0000000000 4.4966849485 -1.7788129386 0.5587031548 0.4231104575 0.5771640219 0.5475994683 -0.433582812007 +1403636895151666432.0000000000 4.4967016418 -1.7787861334 0.5586469208 0.4232945682 0.5770042663 0.5476640110 -0.433534215834 +1403636895201666560.0000000000 4.4966735697 -1.7788531016 0.5586493457 0.4231585148 0.5771644583 0.5475405678 -0.433609716242 +1403636895251666432.0000000000 4.4966865421 -1.7788488204 0.5586071111 0.4232387404 0.5771053696 0.5476194095 -0.433510488166 +1403636895301666560.0000000000 4.4967368125 -1.7788903261 0.5586478142 0.4231362116 0.5771572479 0.5475415871 -0.433639790693 +1403636895351666432.0000000000 4.4968365540 -1.7788944647 0.5585756587 0.4232244567 0.5771351092 0.5476071526 -0.433500324604 +1403636895401666560.0000000000 4.4969079582 -1.7789257471 0.5585699258 0.4231606253 0.5771792921 0.5475620283 -0.433560809094 +1403636895451666432.0000000000 4.4969287999 -1.7788840880 0.5585740867 0.4232207123 0.5771486528 0.5475909327 -0.43350643795 +1403636895501666560.0000000000 4.4969464724 -1.7788850716 0.5586093053 0.4231905336 0.5771471618 0.5475354915 -0.433607900489 +1403636895551666432.0000000000 4.4969309071 -1.7787803648 0.5586600739 0.4231961012 0.5772170377 0.5475351614 -0.433509859534 +1403636895601666560.0000000000 4.4969461220 -1.7787364447 0.5586869366 0.4230935285 0.5772448093 0.5475466420 -0.433558497922 +1403636895651666432.0000000000 4.4969343765 -1.7786271726 0.5587507343 0.4232155792 0.5771108869 0.5476353115 -0.433505666996 +1403636895701666560.0000000000 4.4968554633 -1.7785561240 0.5588116560 0.4231201088 0.5771854407 0.5475741621 -0.433576841577 +1403636895751666432.0000000000 4.4968291560 -1.7785555765 0.5588186949 0.4231939737 0.5770966750 0.5476347611 -0.433546372097 +1403636895801666560.0000000000 4.4966498367 -1.7785880412 0.5588131852 0.4232583636 0.5770901489 0.5475990743 -0.433537278103 +1403636895851666432.0000000000 4.4964508444 -1.7786548511 0.5587868716 0.4232135331 0.5770778356 0.5476149720 -0.433577351207 +1403636895901666560.0000000000 4.4962131704 -1.7785920462 0.5587884179 0.4231790791 0.5770420379 0.5477121596 -0.433535862103 +1403636895951666432.0000000000 4.4961032219 -1.7786159343 0.5588369283 0.4231782260 0.5769800965 0.5477673809 -0.433549367134 +1403636896001666560.0000000000 4.4959721339 -1.7786363841 0.5588696455 0.4231259534 0.5770566414 0.5477811010 -0.433481170982 +1403636896051666432.0000000000 4.4960216622 -1.7786107612 0.5587666530 0.4229101019 0.5771899502 0.5479339905 -0.433321069362 +1403636896101666560.0000000000 4.4960655541 -1.7786080496 0.5586550594 0.4224988188 0.5774097866 0.5481121073 -0.43320411386 +1403636896151666432.0000000000 4.4960989118 -1.7785492965 0.5585246660 0.4221099551 0.5776650936 0.5483393519 -0.432955171561 +1403636896201666560.0000000000 4.4961790306 -1.7784924266 0.5583963047 0.4216217167 0.5780106874 0.5485031804 -0.432762099098 +1403636896251666432.0000000000 4.4963420034 -1.7784910306 0.5583762940 0.4216118917 0.5779806813 0.5485600742 -0.43273963272 +1403636896301666560.0000000000 4.4964610989 -1.7785716134 0.5585297430 0.4217704493 0.5778230348 0.5485991512 -0.432746114748 +1403636896351666432.0000000000 4.4967323274 -1.7788083705 0.5586978412 0.4220534890 0.5776598225 0.5484497871 -0.432877364855 +1403636896401666560.0000000000 4.4968601812 -1.7788215445 0.5587691658 0.4222547110 0.5774314549 0.5484594367 -0.432973579091 +1403636896451666432.0000000000 4.4965440374 -1.7786206381 0.5588387896 0.4224756401 0.5772673547 0.5484410985 -0.433000111155 +1403636896501666560.0000000000 4.4967366844 -1.7784847745 0.5588625087 0.4224638245 0.5772393665 0.5483737582 -0.433134219361 +1403636896551666432.0000000000 4.4969060610 -1.7784091402 0.5587553496 0.4224935641 0.5772270868 0.5483826927 -0.433110264203 +1403636896601666560.0000000000 4.4970139841 -1.7785320261 0.5586938278 0.4225131245 0.5772194509 0.5483892463 -0.433093061297 +1403636896651666432.0000000000 4.4971391893 -1.7786785743 0.5586640084 0.4223238401 0.5772766262 0.5484067466 -0.433179305974 +1403636896701666560.0000000000 4.4972433006 -1.7786149587 0.5584978770 0.4221278724 0.5773823838 0.5486396130 -0.432934426016 +1403636896751666432.0000000000 4.4971151890 -1.7785005695 0.5584526320 0.4216110135 0.5776483910 0.5488166781 -0.432858803224 +1403636896801666560.0000000000 4.4972503063 -1.7785728886 0.5586771743 0.4217538376 0.5774629883 0.5488467375 -0.432928927584 +1403636896851666432.0000000000 4.4969301591 -1.7786470531 0.5590212793 0.4219141777 0.5773839169 0.5486070476 -0.433181886181 +1403636896901666560.0000000000 4.4965633847 -1.7784368157 0.5591464766 0.4218540210 0.5772892474 0.5490414868 -0.432816075985 +1403636896951666432.0000000000 4.4962011650 -1.7784838441 0.5591981933 0.4218103982 0.5772672153 0.5489192946 -0.433042905637 +1403636897001666560.0000000000 4.4958355601 -1.7785677978 0.5593232009 0.4222392976 0.5768524117 0.5487389080 -0.433406139193 +1403636897051666432.0000000000 4.4954892659 -1.7784776512 0.5595318920 0.4222409083 0.5762976226 0.5491297454 -0.433647539142 +1403636897101666560.0000000000 4.4957107318 -1.7785105985 0.5595978671 0.4217841977 0.5752188165 0.5501718064 -0.434203163477 +1403636897151666432.0000000000 4.4966524414 -1.7789148047 0.5593607666 0.4212359788 0.5737690515 0.5515820074 -0.434863903824 +1403636897201666560.0000000000 4.4977702970 -1.7791473476 0.5586435164 0.4200528620 0.5735398840 0.5524690919 -0.435184440273 +1403636897251666432.0000000000 4.4993885290 -1.7788967576 0.5581102646 0.4196554478 0.5738237241 0.5527293241 -0.434863119845 +1403636897301666560.0000000000 4.5016471633 -1.7777761594 0.5576082950 0.4198824459 0.5748521558 0.5521067047 -0.434075934861 +1403636897351666432.0000000000 4.5048683235 -1.7757633205 0.5574508411 0.4202078765 0.5766613981 0.5513829366 -0.432277491542 +1403636897401666560.0000000000 4.5093941628 -1.7725946613 0.5567827577 0.4204275421 0.5791394714 0.5518938432 -0.428078661418 +1403636897451666432.0000000000 4.5150469448 -1.7689489615 0.5562726949 0.4202885475 0.5819531648 0.5523764951 -0.423754950924 +1403636897501666560.0000000000 4.5212583281 -1.7647825211 0.5553393708 0.4206658372 0.5844639668 0.5534026576 -0.418554206121 +1403636897551666432.0000000000 4.5279701049 -1.7603179160 0.5547507573 0.4199789027 0.5878039317 0.5544023371 -0.413209762558 +1403636897601666560.0000000000 4.5360594383 -1.7557650928 0.5544658084 0.4181306823 0.5914299160 0.5574175639 -0.405786947002 +1403636897651666432.0000000000 4.5446051153 -1.7507336168 0.5555563978 0.4166178148 0.5945377723 0.5612772322 -0.397394391497 +1403636897701666560.0000000000 4.5535390882 -1.7453109014 0.5580489219 0.4143312863 0.5976875953 0.5661484983 -0.38803994833 +1403636897751666432.0000000000 4.5623565088 -1.7399938449 0.5625478365 0.4119462094 0.5997221383 0.5706862653 -0.380724131076 +1403636897801666560.0000000000 4.5705345969 -1.7347018096 0.5688082187 0.4097336128 0.6014086817 0.5745199395 -0.374636895174 +1403636897851666432.0000000000 4.5778506063 -1.7297628200 0.5767842429 0.4071899473 0.6029849597 0.5776444077 -0.370043812779 +1403636897901666560.0000000000 4.5838487942 -1.7252022246 0.5865702897 0.4053026042 0.6037283553 0.5800434980 -0.36713950004 +1403636897951666432.0000000000 4.5876163429 -1.7209918967 0.5980951309 0.4072715045 0.6016952541 0.5798019437 -0.368676618265 +1403636898001666560.0000000000 4.5894980539 -1.7171077856 0.6088640409 0.4108116643 0.5984699993 0.5782473492 -0.372421051476 +1403636898051666432.0000000000 4.5904323927 -1.7137448555 0.6175987990 0.4137589731 0.5953866872 0.5764569151 -0.376849611913 +1403636898101666560.0000000000 4.5911386404 -1.7108729277 0.6242356858 0.4150165122 0.5930758125 0.5751323951 -0.381110355822 +1403636898151666432.0000000000 4.5915194377 -1.7079882971 0.6300324530 0.4159187738 0.5911989727 0.5745448389 -0.383918710716 +1403636898201666560.0000000000 4.5914623356 -1.7052948036 0.6361357964 0.4162759034 0.5894882339 0.5745465811 -0.386153104951 +1403636898251666432.0000000000 4.5908422600 -1.7028255896 0.6428736125 0.4160488500 0.5881218339 0.5753788424 -0.38724055904 +1403636898301666560.0000000000 4.5896540345 -1.7005680589 0.6505466633 0.4156243177 0.5871405108 0.5761058951 -0.388103651955 +1403636898351666432.0000000000 4.5879663244 -1.6985689683 0.6590353098 0.4148313679 0.5861616034 0.5773423532 -0.388594027388 +1403636898401666560.0000000000 4.5857445808 -1.6969476326 0.6685360337 0.4139994347 0.5851016219 0.5782347687 -0.389750063885 +1403636898451666432.0000000000 4.5830174788 -1.6956606676 0.6786539101 0.4125534328 0.5843978119 0.5794613486 -0.390516847251 +1403636898501666560.0000000000 4.5797398032 -1.6946537955 0.6893403540 0.4109817537 0.5838678508 0.5803720971 -0.391612767753 +1403636898551666432.0000000000 4.5758153488 -1.6936842887 0.7002960713 0.4101406380 0.5831390222 0.5810391033 -0.392590242155 +1403636898601666560.0000000000 4.5714648865 -1.6927367435 0.7108320344 0.4096804034 0.5821866939 0.5824458729 -0.392399573969 +1403636898651666432.0000000000 4.5666723838 -1.6919977559 0.7211511538 0.4094647214 0.5812995952 0.5834465328 -0.392453265893 +1403636898701666560.0000000000 4.5614315004 -1.6915923140 0.7309432659 0.4088473193 0.5807417284 0.5846022360 -0.392202932238 +1403636898751666432.0000000000 4.5556089545 -1.6915227524 0.7404021488 0.4077693976 0.5805911935 0.5850817068 -0.392832509912 +1403636898801666560.0000000000 4.5492491975 -1.6915585715 0.7494613996 0.4071025297 0.5801498820 0.5852139018 -0.393977580461 +1403636898851666432.0000000000 4.5423405317 -1.6918833024 0.7579723509 0.4055674843 0.5806426510 0.5851655785 -0.394905524505 +1403636898901666560.0000000000 4.5349542633 -1.6923480621 0.7659715862 0.4036133298 0.5814583641 0.5851315999 -0.395756821306 +1403636898951666432.0000000000 4.5268989286 -1.6928364251 0.7735937021 0.4009499807 0.5826921113 0.5843593076 -0.397785389494 +1403636899001666560.0000000000 4.5179365822 -1.6929334040 0.7804216111 0.3986318754 0.5847867657 0.5825362560 -0.399710616523 +1403636899051666432.0000000000 4.5078642272 -1.6921940807 0.7865051680 0.3981195368 0.5869944561 0.5796726062 -0.401145874301 +1403636899101666560.0000000000 4.4967866273 -1.6903492796 0.7921849961 0.3995967986 0.5896880590 0.5756809103 -0.401474633327 +1403636899151666432.0000000000 4.4851574754 -1.6872779423 0.7975921558 0.4035841550 0.5920128594 0.5713810583 -0.400205310302 +1403636899201666560.0000000000 4.4729169205 -1.6831517971 0.8029582060 0.4094870258 0.5942233918 0.5660427463 -0.39851542718 +1403636899251666432.0000000000 4.4602615619 -1.6782980849 0.8084868396 0.4166848997 0.5969756255 0.5582014779 -0.398001139321 +1403636899301666560.0000000000 4.4477734716 -1.6726653146 0.8136159215 0.4240480639 0.6006902656 0.5498764886 -0.396220003934 +1403636899351666432.0000000000 4.4356313317 -1.6661303626 0.8181519037 0.4325092166 0.6049221317 0.5410230326 -0.392809203558 +1403636899401666560.0000000000 4.4233435514 -1.6588593745 0.8227982903 0.4405370947 0.6100387369 0.5321820825 -0.388023245182 +1403636899451666432.0000000000 4.4126504598 -1.6515126830 0.8271297082 0.4459054537 0.6164118875 0.5236512848 -0.383398021939 +1403636899501666560.0000000000 4.4033537715 -1.6444892362 0.8309369107 0.4464481346 0.6249053828 0.5160564124 -0.379292901193 +1403636899551666432.0000000000 4.3953962108 -1.6373818479 0.8340691258 0.4453107429 0.6330087887 0.5105624819 -0.37459867554 +1403636899601666560.0000000000 4.3879583345 -1.6299278458 0.8370782782 0.4441703240 0.6399605352 0.5059340944 -0.370396988085 +1403636899651666432.0000000000 4.3806205739 -1.6217757985 0.8403130870 0.4435726251 0.6454489879 0.5016133466 -0.367454732902 +1403636899701666560.0000000000 4.3733243566 -1.6126111200 0.8435356898 0.4436588275 0.6496274605 0.4985764707 -0.36410508111 +1403636899751666432.0000000000 4.3659601115 -1.6024969708 0.8464215730 0.4438654358 0.6532375904 0.4962555504 -0.360547575374 +1403636899801666560.0000000000 4.3585497880 -1.5914114964 0.8487406983 0.4450565971 0.6553794156 0.4951076159 -0.356750466936 +1403636899851666432.0000000000 4.3511730815 -1.5794058203 0.8501875251 0.4477196699 0.6558671053 0.4949830159 -0.352671591348 +1403636899901666560.0000000000 4.3434284980 -1.5666495732 0.8510160623 0.4508687268 0.6554982365 0.4949889044 -0.349321396015 +1403636899951666432.0000000000 4.3354454341 -1.5534762712 0.8513081788 0.4546976944 0.6541395316 0.4942901887 -0.347891778046 +1403636900001666560.0000000000 4.3272299668 -1.5399982362 0.8509197901 0.4590004686 0.6520761911 0.4936609533 -0.347007311148 +1403636900051666432.0000000000 4.3190261490 -1.5265696637 0.8505078976 0.4624856685 0.6501609690 0.4922046492 -0.348040664534 +1403636900101666560.0000000000 4.3112056142 -1.5132269826 0.8508012244 0.4661203028 0.6477275869 0.4909090122 -0.349555686842 +1403636900151666432.0000000000 4.3040490419 -1.4999572453 0.8530599568 0.4693254504 0.6455206304 0.4896332014 -0.351135394732 +1403636900201666560.0000000000 4.2976044839 -1.4868243518 0.8574117039 0.4710565482 0.6438080030 0.4898355592 -0.351678985133 +1403636900251666432.0000000000 4.2922091513 -1.4739603047 0.8639186222 0.4713243661 0.6431603741 0.4906927489 -0.351309978806 +1403636900301666560.0000000000 4.2877511560 -1.4614486643 0.8727449565 0.4705740044 0.6429764465 0.4921870148 -0.350561461168 +1403636900351666432.0000000000 4.2838144631 -1.4494091958 0.8838379133 0.4669854219 0.6444455395 0.4941610090 -0.349884923161 +1403636900401666560.0000000000 4.2808266601 -1.4375583972 0.8964033219 0.4637309467 0.6455887625 0.4967453135 -0.348443470852 +1403636900451666432.0000000000 4.2777599963 -1.4257497054 0.9092415972 0.4603346762 0.6466536176 0.4994567799 -0.347093661236 +1403636900501666560.0000000000 4.2748114089 -1.4139741122 0.9216649979 0.4583209746 0.6466425463 0.5018547144 -0.346319429407 +1403636900551666432.0000000000 4.2716156841 -1.4021882637 0.9331421244 0.4563043259 0.6469763207 0.5032500172 -0.346334264524 +1403636900601666560.0000000000 4.2682323035 -1.3903977999 0.9435029693 0.4545343519 0.6470523496 0.5047036652 -0.346404373774 +1403636900651666432.0000000000 4.2646541769 -1.3784973940 0.9521392130 0.4515684500 0.6480318694 0.5067608337 -0.345447664011 +1403636900701666560.0000000000 4.2606971089 -1.3665366226 0.9591032822 0.4475758893 0.6500092400 0.5086400031 -0.34416443528 +1403636900751666432.0000000000 4.2560175561 -1.3544515519 0.9645607454 0.4436230092 0.6515982197 0.5107692488 -0.343122660711 +1403636900801666560.0000000000 4.2504433838 -1.3420892026 0.9688692980 0.4403754505 0.6530224808 0.5112473604 -0.343885502258 +1403636900851666432.0000000000 4.2437654578 -1.3293060213 0.9723858478 0.4396431932 0.6530226199 0.5099882270 -0.346680442086 +1403636900901666560.0000000000 4.2364098668 -1.3163190211 0.9748677763 0.4374117420 0.6539699082 0.5072206196 -0.351740771148 +1403636900951666432.0000000000 4.2282322129 -1.3023557521 0.9760761528 0.4373580475 0.6535737051 0.5050782091 -0.355605614305 +1403636901001666560.0000000000 4.2194957425 -1.2871416241 0.9759657754 0.4378157977 0.6533047630 0.5030863436 -0.358349472825 +1403636901051666432.0000000000 4.2104701909 -1.2709630798 0.9743878106 0.4373241194 0.6533860607 0.5018302202 -0.360556098728 +1403636901101666560.0000000000 4.2012771275 -1.2536216887 0.9719924065 0.4369794626 0.6534835458 0.5003176148 -0.36289184192 +1403636901151666432.0000000000 4.1920452873 -1.2350170820 0.9687120226 0.4369008093 0.6535443359 0.4995670703 -0.363909640186 +1403636901201666560.0000000000 4.1824116420 -1.2151766160 0.9656710777 0.4374016468 0.6532203772 0.4990280983 -0.36462843459 +1403636901251666432.0000000000 4.1728790105 -1.1939037413 0.9638162765 0.4387509977 0.6523594814 0.4997472214 -0.363562076854 +1403636901301666560.0000000000 4.1643891435 -1.1716860312 0.9635279970 0.4406712375 0.6510632005 0.5007334119 -0.362203836984 +1403636901351666432.0000000000 4.1563292559 -1.1486116066 0.9639677462 0.4419750250 0.6502718897 0.5013693215 -0.361155576222 +1403636901401666560.0000000000 4.1468355619 -1.1243583287 0.9658963651 0.4434768775 0.6493922972 0.5023206612 -0.359571768642 +1403636901451666432.0000000000 4.1363461853 -1.0990898411 0.9703451668 0.4454141688 0.6482278977 0.5033769494 -0.357796670934 +1403636901501666560.0000000000 4.1262015133 -1.0732575170 0.9759785274 0.4475788039 0.6468562426 0.5045802635 -0.355877750504 +1403636901551666432.0000000000 4.1159981049 -1.0470458563 0.9811983648 0.4492196675 0.6459443212 0.5056025724 -0.354010823293 +1403636901601666560.0000000000 4.1056948614 -1.0207966443 0.9854108856 0.4505170049 0.6450907591 0.5059170940 -0.35346885981 +1403636901651666432.0000000000 4.0954176311 -0.9945270852 0.9881376609 0.4523586549 0.6439472191 0.5055734681 -0.353693503957 +1403636901701666560.0000000000 4.0854061490 -0.9682098215 0.9890672973 0.4532027102 0.6435496641 0.5048572322 -0.354359010675 +1403636901751666432.0000000000 4.0755448357 -0.9419507020 0.9882462511 0.4528346945 0.6436526894 0.5039475769 -0.355933694081 +1403636901801666560.0000000000 4.0658539429 -0.9153355013 0.9857184986 0.4531768057 0.6435707998 0.5039389042 -0.355658529112 +1403636901851666432.0000000000 4.0563498376 -0.8886791461 0.9819119376 0.4534281395 0.6433570387 0.5042957179 -0.35521890709 +1403636901901666560.0000000000 4.0471371392 -0.8621102783 0.9769683591 0.4535767854 0.6430867802 0.5045231266 -0.355195590733 +1403636901951666432.0000000000 4.0383234904 -0.8355215615 0.9706712144 0.4538106591 0.6428393915 0.5050478474 -0.354598468954 +1403636902001666560.0000000000 4.0295996741 -0.8091661337 0.9640499042 0.4546082199 0.6420338391 0.5055071884 -0.354381712849 +1403636902051666432.0000000000 4.0208375390 -0.7827905614 0.9581900477 0.4547825053 0.6414697911 0.5061632741 -0.354243023946 +1403636902101666560.0000000000 4.0126755109 -0.7567091270 0.9540572045 0.4554230618 0.6408065013 0.5060783122 -0.354741602603 +1403636902151666432.0000000000 4.0032496717 -0.7304972620 0.9515974773 0.4556068065 0.6403310870 0.5068039861 -0.354327893978 +1403636902201666560.0000000000 3.9946626289 -0.7046875358 0.9507031768 0.4554163116 0.6402740395 0.5071726672 -0.35414830672 +1403636902251666432.0000000000 3.9861410300 -0.6789751917 0.9507586259 0.4546955618 0.6409824337 0.5064269504 -0.354859422458 +1403636902301666560.0000000000 3.9778605308 -0.6533469242 0.9506603482 0.4537544792 0.6419593305 0.5054019526 -0.355758284417 +1403636902351666432.0000000000 3.9700953032 -0.6277573832 0.9473535537 0.4531276469 0.6427814420 0.5047854181 -0.355948079125 +1403636902401666560.0000000000 3.9622659141 -0.6018601194 0.9405725449 0.4527400637 0.6437503528 0.5042124514 -0.355502070086 +1403636902451666432.0000000000 3.9547979033 -0.5757220261 0.9300124435 0.4529466530 0.6444195046 0.5040195376 -0.354298091076 +1403636902501666560.0000000000 3.9475100801 -0.5494260151 0.9164866356 0.4536656875 0.6446420513 0.5043790737 -0.35245683384 +1403636902551666432.0000000000 3.9397281032 -0.5228152095 0.9017730888 0.4561097675 0.6439957942 0.5044426833 -0.350386752529 +1403636902601666560.0000000000 3.9317292226 -0.4963924240 0.8871397820 0.4576791500 0.6438514040 0.5053367999 -0.347303734309 +1403636902651666432.0000000000 3.9235981591 -0.4701979942 0.8737952238 0.4602775948 0.6429938663 0.5056639075 -0.344974544293 +1403636902701666560.0000000000 3.9151195663 -0.4444699080 0.8625549249 0.4620157190 0.6427484277 0.5050715357 -0.343974821661 +1403636902751666432.0000000000 3.9068754417 -0.4194270513 0.8533808228 0.4633613311 0.6426720199 0.5041838129 -0.343609712522 +1403636902801666560.0000000000 3.8986791780 -0.3950898642 0.8463258260 0.4631010555 0.6433002708 0.5033171106 -0.344055315678 +1403636902851666432.0000000000 3.8904414220 -0.3713638874 0.8413665632 0.4639461850 0.6425125554 0.5025477988 -0.345510149629 +1403636902901666560.0000000000 3.8825060604 -0.3483523053 0.8385763246 0.4645230144 0.6415522536 0.5018863078 -0.347475479743 +1403636902951666432.0000000000 3.8749463802 -0.3257886863 0.8378530003 0.4648173862 0.6407233794 0.5019190628 -0.348562193807 +1403636903001666560.0000000000 3.8684680816 -0.3037889573 0.8381525423 0.4634810457 0.6410446329 0.5026453540 -0.348704383526 +1403636903051666432.0000000000 3.8616331026 -0.2822272145 0.8402339068 0.4629958823 0.6407199779 0.5028673864 -0.349624247742 +1403636903101666560.0000000000 3.8545779191 -0.2611579965 0.8445813681 0.4616197090 0.6407776943 0.5037291203 -0.350097363613 +1403636903151666432.0000000000 3.8463832877 -0.2401495702 0.8521016890 0.4605234420 0.6407221506 0.5045703853 -0.350431179312 +1403636903201666560.0000000000 3.8383633950 -0.2194208253 0.8617340741 0.4593899315 0.6407108707 0.5052373824 -0.350978145087 +1403636903251666432.0000000000 3.8318107122 -0.1991470570 0.8732010990 0.4578752184 0.6408168550 0.5067219662 -0.35062357552 +1403636903301666560.0000000000 3.8258087907 -0.1788752909 0.8854551895 0.4573623554 0.6404152899 0.5082225534 -0.349853924643 +1403636903351666432.0000000000 3.8197951069 -0.1587307817 0.8976027510 0.4569280873 0.6401749264 0.5095139643 -0.348981814471 +1403636903401666560.0000000000 3.8138099654 -0.1386494954 0.9081140444 0.4573357501 0.6391839116 0.5111974103 -0.347800440678 +1403636903451666432.0000000000 3.8078466907 -0.1188297318 0.9166790280 0.4570299802 0.6388763527 0.5124375741 -0.346941401147 +1403636903501666560.0000000000 3.8017057353 -0.0992893816 0.9239325733 0.4571693695 0.6384411615 0.5127136490 -0.347150925347 +1403636903551666432.0000000000 3.7955175990 -0.0802274995 0.9294525610 0.4571158723 0.6380230951 0.5132714510 -0.34716570538 +1403636903601666560.0000000000 3.7893183205 -0.0615729813 0.9331983224 0.4562226255 0.6382958991 0.5136228161 -0.347319541588 +1403636903651666432.0000000000 3.7832105002 -0.0435238379 0.9347110205 0.4533797871 0.6400474275 0.5141464798 -0.347043882768 +1403636903701666560.0000000000 3.7769306993 -0.0258099644 0.9345817190 0.4504850163 0.6417889289 0.5140371080 -0.347758641077 +1403636903751666432.0000000000 3.7703587112 -0.0081605303 0.9331880683 0.4478024650 0.6434134830 0.5145850443 -0.347410815072 +1403636903801666560.0000000000 3.7631673068 0.0095185998 0.9324999749 0.4449795809 0.6451831645 0.5136738217 -0.349100360467 +1403636903851666432.0000000000 3.7545246520 0.0277538468 0.9328926317 0.4420455246 0.6470395251 0.5125794594 -0.350995591067 +1403636903901666560.0000000000 3.7450240118 0.0467279770 0.9356490849 0.4420945081 0.6470544006 0.5115861740 -0.352352998005 +1403636903951666432.0000000000 3.7349267618 0.0657771629 0.9403925271 0.4414357183 0.6473496516 0.5098536532 -0.355136857456 +1403636904001666560.0000000000 3.7244489160 0.0855147683 0.9469709754 0.4420539123 0.6469972347 0.5086180698 -0.356778048566 +1403636904051666432.0000000000 3.7139521284 0.1058106360 0.9558864194 0.4427181694 0.6464846313 0.5070379591 -0.35912498104 +1403636904101666560.0000000000 3.7027610851 0.1269940541 0.9661599615 0.4429111560 0.6464907082 0.5059482855 -0.360410605453 +1403636904151666432.0000000000 3.6913185811 0.1489279912 0.9781296293 0.4418697645 0.6472303664 0.5053390185 -0.361215227242 +1403636904201666560.0000000000 3.6802608893 0.1715915004 0.9914772693 0.4417989235 0.6473877432 0.5039008114 -0.363024507999 +1403636904251666432.0000000000 3.6702128946 0.1952258835 1.0060822257 0.4429661405 0.6470163752 0.5035942755 -0.362689418509 +1403636904301666560.0000000000 3.6601617859 0.2193259938 1.0198771503 0.4430292304 0.6472049116 0.5027504673 -0.36344582951 +1403636904351666432.0000000000 3.6501198841 0.2441862665 1.0325926968 0.4441165650 0.6467674569 0.5023470747 -0.363455293072 +1403636904401666560.0000000000 3.6401113583 0.2697488069 1.0440356075 0.4457329027 0.6462737195 0.5020422024 -0.362775531028 +1403636904451666432.0000000000 3.6302208003 0.2958298266 1.0541519868 0.4475768119 0.6452746763 0.5029332376 -0.361045354611 +1403636904501666560.0000000000 3.6206011835 0.3221558532 1.0632015465 0.4481480443 0.6453839667 0.5026144074 -0.360585112596 +1403636904551666432.0000000000 3.6111183211 0.3491218014 1.0707092636 0.4494110620 0.6451117941 0.5030115099 -0.358942741104 +1403636904601666560.0000000000 3.6016949585 0.3763903999 1.0771792575 0.4508885334 0.6444516791 0.5036016283 -0.357445049966 +1403636904651666432.0000000000 3.5923456666 0.4039940422 1.0829041792 0.4519874758 0.6443453706 0.5042151296 -0.355377922926 +1403636904701666560.0000000000 3.5830170967 0.4317747104 1.0884543701 0.4533200655 0.6441196279 0.5044794305 -0.353710796261 +1403636904751666432.0000000000 3.5737496645 0.4596825605 1.0936958139 0.4545215399 0.6438882150 0.5045298791 -0.35251629387 +1403636904801666560.0000000000 3.5645299437 0.4876398643 1.0984016005 0.4557829347 0.6436510902 0.5048312494 -0.350885451731 +1403636904851666432.0000000000 3.5555183287 0.5155306982 1.1023497943 0.4567569014 0.6436456574 0.5050699194 -0.349281802008 +1403636904901666560.0000000000 3.5465442956 0.5432751485 1.1048910785 0.4579669596 0.6434333040 0.5057850544 -0.347046576134 +1403636904951666432.0000000000 3.5376529819 0.5705839007 1.1059948188 0.4589512232 0.6434222997 0.5060765810 -0.345337535064 +1403636905001666560.0000000000 3.5287412585 0.5976420516 1.1057800674 0.4599587461 0.6434362582 0.5057174911 -0.344496085019 +1403636905051666432.0000000000 3.5198013752 0.6241875022 1.1049851464 0.4601825965 0.6439869358 0.5048832582 -0.34439178264 +1403636905101666560.0000000000 3.5108219105 0.6506337596 1.1041233233 0.4623225611 0.6432829852 0.5050703753 -0.342562062062 +1403636905151666432.0000000000 3.5016625623 0.6764270834 1.1045828732 0.4630751434 0.6435668885 0.5039188557 -0.342708124195 +1403636905201666560.0000000000 3.4920970819 0.7022848733 1.1058444592 0.4643520460 0.6433260714 0.5041564108 -0.34107925289 +1403636905251666432.0000000000 3.4822869798 0.7275315261 1.1085395627 0.4645215330 0.6439043439 0.5042227611 -0.339656220888 +1403636905301666560.0000000000 3.4723309045 0.7521501222 1.1125068279 0.4649792623 0.6443130245 0.5045278144 -0.337796827366 +1403636905351666432.0000000000 3.4622895507 0.7758535264 1.1181008125 0.4637061420 0.6458964399 0.5045513184 -0.336485318937 +1403636905401666560.0000000000 3.4524090859 0.7986385011 1.1251539551 0.4627804076 0.6467783184 0.5056923447 -0.334346158474 +1403636905451666432.0000000000 3.4421487535 0.8203769122 1.1337060069 0.4625933451 0.6458675400 0.5075200581 -0.333595426228 +1403636905501666560.0000000000 3.4316907122 0.8409424517 1.1435161027 0.4618103705 0.6442095126 0.5103665767 -0.333543464805 +1403636905551666432.0000000000 3.4207041155 0.8607759781 1.1528992735 0.4616350626 0.6421864915 0.5130689987 -0.333541274444 +1403636905601666560.0000000000 3.4093332640 0.8799173713 1.1610464589 0.4616462710 0.6401564608 0.5156100183 -0.333509722881 +1403636905651666432.0000000000 3.3974446786 0.8981624918 1.1676221828 0.4601074652 0.6392830103 0.5170832042 -0.335027331856 +1403636905701666560.0000000000 3.3852185076 0.9156332290 1.1723248337 0.4581533029 0.6390735690 0.5179344778 -0.336785393376 +1403636905751666432.0000000000 3.3720928254 0.9324827171 1.1756031915 0.4565631305 0.6386495882 0.5181609118 -0.339390749495 +1403636905801666560.0000000000 3.3583995634 0.9488837685 1.1764464810 0.4547412845 0.6387430002 0.5185762659 -0.341022580264 +1403636905851666432.0000000000 3.3445773556 0.9647045658 1.1752436496 0.4532440761 0.6386623653 0.5192377069 -0.342158434623 +1403636905901666560.0000000000 3.3305659792 0.9798718018 1.1724232263 0.4515363253 0.6387653757 0.5200291982 -0.343020953781 +1403636905951666432.0000000000 3.3160439022 0.9945971873 1.1680419007 0.4493949237 0.6393369623 0.5210022471 -0.343291581269 +1403636906001666560.0000000000 3.3009839682 1.0091085540 1.1624633252 0.4474174936 0.6397434874 0.5226188516 -0.342659295441 +1403636906051666432.0000000000 3.2852372679 1.0235873711 1.1556991111 0.4465263118 0.6395317747 0.5249722820 -0.34061336603 +1403636906101666560.0000000000 3.2683696875 1.0375053519 1.1485355042 0.4456603740 0.6394026290 0.5262635831 -0.339996691377 +1403636906151666432.0000000000 3.2505072982 1.0508234969 1.1421190482 0.4450152006 0.6390509643 0.5270858219 -0.340229147146 +1403636906201666560.0000000000 3.2312570460 1.0640996927 1.1378336606 0.4461262140 0.6378938096 0.5267672960 -0.34143682388 +1403636906251666432.0000000000 3.2107727061 1.0768553898 1.1363148619 0.4479978448 0.6360122995 0.5252292844 -0.344848495381 +1403636906301666560.0000000000 3.1892078274 1.0891668355 1.1370717448 0.4505666379 0.6339525473 0.5230034170 -0.34865641884 +1403636906351666432.0000000000 3.1679050804 1.1008379184 1.1392956498 0.4515940920 0.6331425009 0.5203371086 -0.352764288271 +1403636906401666560.0000000000 3.1467626576 1.1121653291 1.1429117611 0.4515882371 0.6330758958 0.5178317004 -0.35655757509 +1403636906451666432.0000000000 3.1256918925 1.1230649695 1.1481783911 0.4488300875 0.6351125121 0.5138989873 -0.362065574679 +1403636906501666560.0000000000 3.1048709215 1.1342678040 1.1540975937 0.4453163257 0.6376801063 0.5105128054 -0.366652597892 +1403636906551666432.0000000000 3.0845749330 1.1459768130 1.1591019181 0.4416471129 0.6401567273 0.5089064210 -0.369000605366 +1403636906601666560.0000000000 3.0648082735 1.1585311004 1.1624051153 0.4385299098 0.6425070113 0.5090330115 -0.368458480437 +1403636906651666432.0000000000 3.0451109453 1.1720890333 1.1643176891 0.4386065092 0.6425074062 0.5100772082 -0.366919343676 +1403636906701666560.0000000000 3.0254793988 1.1865148709 1.1647533382 0.4414745313 0.6406390615 0.5118047364 -0.36433191322 +1403636906751666432.0000000000 3.0059876314 1.2017816701 1.1635724586 0.4446239198 0.6385752482 0.5137771352 -0.361336792485 +1403636906801666560.0000000000 2.9866807926 1.2174989102 1.1610285979 0.4469915901 0.6368045103 0.5161337920 -0.35816817669 +1403636906851666432.0000000000 2.9671375030 1.2331231260 1.1573708121 0.4481172659 0.6356762686 0.5178413035 -0.356296199717 +1403636906901666560.0000000000 2.9476799615 1.2485604889 1.1533357362 0.4491771392 0.6343806963 0.5199183371 -0.354239964619 +1403636906951666432.0000000000 2.9280144214 1.2635576870 1.1504670205 0.4499347142 0.6332318888 0.5213248964 -0.353265453006 +1403636907001666560.0000000000 2.9080838727 1.2781061892 1.1492423573 0.4502990938 0.6321485480 0.5227822078 -0.352587156183 +1403636907051666432.0000000000 2.8876292039 1.2923931073 1.1498253640 0.4500902414 0.6315871933 0.5234648120 -0.352846967585 +1403636907101666560.0000000000 2.8672894673 1.3064643939 1.1515720970 0.4492521706 0.6315846559 0.5244884654 -0.352399147679 +1403636907151666432.0000000000 2.8470327834 1.3203194615 1.1530135464 0.4483684166 0.6315909853 0.5263871423 -0.350678152546 +1403636907201666560.0000000000 2.8264955956 1.3337285916 1.1531255355 0.4458914483 0.6327510211 0.5277723799 -0.349661660044 +1403636907251666432.0000000000 2.8053560643 1.3469187169 1.1513724333 0.4431852868 0.6341750010 0.5288835815 -0.348842409824 +1403636907301666560.0000000000 2.7836120575 1.3598644750 1.1477809880 0.4408029339 0.6350840766 0.5300391085 -0.34845305646 +1403636907351666432.0000000000 2.7610665915 1.3724207701 1.1443571640 0.4385506857 0.6361457075 0.5295712171 -0.350066080669 +1403636907401666560.0000000000 2.7379593891 1.3849107266 1.1417924282 0.4358543346 0.6376068816 0.5286734214 -0.352126223272 +1403636907451666432.0000000000 2.7140200826 1.3975257517 1.1410024661 0.4337745589 0.6387465985 0.5281218517 -0.353453992341 +1403636907501666560.0000000000 2.6894218065 1.4105192184 1.1419420669 0.4318373994 0.6396876226 0.5264081968 -0.356665973035 +1403636907551666432.0000000000 2.6642566956 1.4239825051 1.1453474089 0.4288342718 0.6417581279 0.5246861052 -0.359099100089 +1403636907601666560.0000000000 2.6387274478 1.4381976296 1.1508496596 0.4285609375 0.6416343652 0.5240656666 -0.360549637908 +1403636907651666432.0000000000 2.6123083325 1.4534124817 1.1577440899 0.4277533344 0.6422226984 0.5231133622 -0.36184181745 +1403636907701666560.0000000000 2.5848765937 1.4695141612 1.1669163606 0.4268891699 0.6427879759 0.5222484669 -0.363105760861 +1403636907751666432.0000000000 2.5575704127 1.4865189786 1.1777722328 0.4268257175 0.6426920733 0.5219741604 -0.363743978171 +1403636907801666560.0000000000 2.5297742581 1.5044425845 1.1893796084 0.4261586339 0.6432509054 0.5210747262 -0.364826289012 +1403636907851666432.0000000000 2.5020044701 1.5232959863 1.1990027193 0.4262004007 0.6432770543 0.5204242914 -0.36565886662 +1403636907901666560.0000000000 2.4730434884 1.5430595471 1.2053053813 0.4274501680 0.6422986195 0.5202448069 -0.366175064889 +1403636907951666432.0000000000 2.4425864170 1.5639705427 1.2079505820 0.4313715968 0.6393926898 0.5207249776 -0.365979550642 +1403636908001666560.0000000000 2.4115080399 1.5858522863 1.2077723170 0.4352910180 0.6364487898 0.5219184388 -0.364768160557 +1403636908051666432.0000000000 2.3803326549 1.6082713336 1.2061023225 0.4397886770 0.6327284177 0.5240214101 -0.362825344688 +1403636908101666560.0000000000 2.3490361530 1.6307138185 1.2052051980 0.4423810884 0.6301780060 0.5246299006 -0.36323287394 +1403636908151666432.0000000000 2.3179660232 1.6533081842 1.2054973963 0.4438832637 0.6283773370 0.5254867362 -0.363281241858 +1403636908201666560.0000000000 2.2877862802 1.6755924638 1.2076194934 0.4456313724 0.6261616551 0.5259682959 -0.364268600625 +1403636908251666432.0000000000 2.2585694965 1.6977008583 1.2101448092 0.4460447545 0.6248909323 0.5271146735 -0.364287689511 +1403636908301666560.0000000000 2.2296970602 1.7194971493 1.2124169211 0.4460025383 0.6240517354 0.5278122674 -0.364767566656 +1403636908351666432.0000000000 2.2010679885 1.7411178815 1.2132858992 0.4455390014 0.6234385816 0.5292657497 -0.364276130715 +1403636908401666560.0000000000 2.1726202381 1.7623125798 1.2129302193 0.4445557557 0.6232491096 0.5298594520 -0.364937924398 +1403636908451666432.0000000000 2.1441401873 1.7833405416 1.2110611773 0.4433871808 0.6231228173 0.5309882525 -0.364934566884 +1403636908501666560.0000000000 2.1152182107 1.8042084951 1.2079571444 0.4422373244 0.6230282832 0.5319455785 -0.365096985272 +1403636908551666432.0000000000 2.0861550505 1.8248996244 1.2040110117 0.4414900695 0.6227170326 0.5327307856 -0.365387364162 +1403636908601666560.0000000000 2.0571179633 1.8454979560 1.1999744180 0.4407537859 0.6222900924 0.5337149658 -0.36556733494 +1403636908651666432.0000000000 2.0287080075 1.8658181113 1.1969357566 0.4401481942 0.6216537923 0.5351884188 -0.365225253802 +1403636908701666560.0000000000 2.0006024242 1.8859335905 1.1956252910 0.4384863614 0.6221868589 0.5360554400 -0.365044913325 +1403636908751666432.0000000000 1.9721301014 1.9058966371 1.1963035756 0.4358633783 0.6233535214 0.5371047710 -0.364653215815 +1403636908801666560.0000000000 1.9431896227 1.9257638008 1.1994385561 0.4334753466 0.6244214889 0.5376182770 -0.364915766218 +1403636908851666432.0000000000 1.9134915649 1.9457184671 1.2050093611 0.4302871900 0.6263407977 0.5380694160 -0.364734756908 +1403636908901666560.0000000000 1.8828267683 1.9659619134 1.2127718265 0.4289178595 0.6269647846 0.5392342188 -0.363553415522 +1403636908951666432.0000000000 1.8521413957 1.9860283924 1.2222929421 0.4274497602 0.6274841135 0.5395497251 -0.363918238019 +1403636909001666560.0000000000 1.8202198606 2.0063154094 1.2334737906 0.4268521525 0.6276627659 0.5393846982 -0.364555674087 +1403636909051666432.0000000000 1.7878501498 2.0268341396 1.2448164123 0.4259877524 0.6283126375 0.5385755033 -0.365642026555 +1403636909101666560.0000000000 1.7547029095 2.0476084805 1.2550734331 0.4246420835 0.6293082099 0.5381807248 -0.366076201614 +1403636909151666432.0000000000 1.7213652438 2.0686774554 1.2642447074 0.4241413117 0.6297413446 0.5374202543 -0.367027869303 +1403636909201666560.0000000000 1.6874195656 2.0903754725 1.2714474092 0.4241075920 0.6300201427 0.5375681229 -0.366371237224 +1403636909251666432.0000000000 1.6532035787 2.1124569401 1.2773231924 0.4238452192 0.6304057146 0.5375323744 -0.366063944647 +1403636909301666560.0000000000 1.6183216206 2.1349600156 1.2819555926 0.4235334714 0.6310207834 0.5370644503 -0.366051834812 +1403636909351666432.0000000000 1.5825856336 2.1578661031 1.2857010573 0.4248844363 0.6305206340 0.5364812951 -0.36620317562 +1403636909401666560.0000000000 1.5461163714 2.1811608534 1.2880739977 0.4261664826 0.6299911347 0.5361855484 -0.366057860114 +1403636909451666432.0000000000 1.5086840862 2.2050849383 1.2894599297 0.4291895759 0.6285071131 0.5355983113 -0.365936559591 +1403636909501666560.0000000000 1.4707628996 2.2292562920 1.2895240813 0.4320250394 0.6270334490 0.5349309701 -0.366104187909 +1403636909551666432.0000000000 1.4329099221 2.2533779225 1.2877334757 0.4329320184 0.6267591273 0.5340567645 -0.36677818363 +1403636909601666560.0000000000 1.3949956655 2.2776245984 1.2843806663 0.4332030046 0.6273424103 0.5325479917 -0.367653768626 +1403636909651666432.0000000000 1.3568979115 2.3017190059 1.2802065834 0.4326214246 0.6281948325 0.5300237111 -0.370519663455 +1403636909701666560.0000000000 1.3188379283 2.3264677119 1.2744640704 0.4338731648 0.6280206791 0.5280908875 -0.372107670042 +1403636909751666432.0000000000 1.2806035535 2.3518344897 1.2674848274 0.4375594265 0.6259577889 0.5263628699 -0.373712087053 +1403636909801666560.0000000000 1.2426337291 2.3779378547 1.2584632634 0.4425430527 0.6228399348 0.5268616872 -0.372347720185 +1403636909851666432.0000000000 1.2051762198 2.4043468521 1.2479587333 0.4491543742 0.6186253581 0.5283387311 -0.369352405758 +1403636909901666560.0000000000 1.1685264795 2.4304861085 1.2357637752 0.4548815893 0.6146859125 0.5312521201 -0.364712425879 +1403636909951666432.0000000000 1.1324367368 2.4559288725 1.2226711832 0.4616562126 0.6099374526 0.5335150257 -0.360848392774 +1403636910001666560.0000000000 1.0970915171 2.4800706137 1.2088555072 0.4672435013 0.6060631219 0.5342993821 -0.359019739103 +1403636910051666432.0000000000 1.0629607454 2.5021212274 1.1946109872 0.4697770806 0.6040842550 0.5343352909 -0.358995131396 +1403636910101666560.0000000000 1.0299808478 2.5222125654 1.1810115132 0.4675179755 0.6056484060 0.5332688564 -0.360889564217 +1403636910151666432.0000000000 0.9978375216 2.5407095186 1.1686624694 0.4632648828 0.6083403173 0.5326455207 -0.362762258165 +1403636910201666560.0000000000 0.9656519653 2.5580974446 1.1574470485 0.4569100262 0.6126921700 0.5323032905 -0.363998268878 +1403636910251666432.0000000000 0.9332845104 2.5747208464 1.1491958114 0.4532482022 0.6149535076 0.5325304964 -0.364430406473 +1403636910301666560.0000000000 0.9016769651 2.5905985845 1.1429711973 0.4491907682 0.6175591514 0.5324996273 -0.365092447528 +1403636910351666432.0000000000 0.8711796977 2.6060804338 1.1384520862 0.4458777788 0.6196239287 0.5329371645 -0.365016673669 +1403636910401666560.0000000000 0.8406290248 2.6213119469 1.1358100376 0.4443699059 0.6201455565 0.5335639276 -0.365053983087 +1403636910451666432.0000000000 0.8102415514 2.6363511279 1.1347688938 0.4436576971 0.6201300803 0.5346610478 -0.364340630891 +1403636910501666560.0000000000 0.7797280441 2.6511059849 1.1355509843 0.4428224714 0.6199787857 0.5348989484 -0.365263848662 +1403636910551666432.0000000000 0.7491400418 2.6658736110 1.1357178765 0.4426896472 0.6196587468 0.5360291442 -0.364309854903 +1403636910601666560.0000000000 0.7184783494 2.6804341960 1.1352776875 0.4429296893 0.6191451756 0.5365539863 -0.364118609279 +1403636910651666432.0000000000 0.6879571828 2.6946716675 1.1331336719 0.4426536609 0.6191436688 0.5370312278 -0.363753095207 +1403636910701666560.0000000000 0.6575025004 2.7085072253 1.1295497831 0.4426288870 0.6188663560 0.5371279465 -0.364112168077 +1403636910751666432.0000000000 0.6270906520 2.7219722608 1.1243280789 0.4418910365 0.6192301100 0.5370141070 -0.364557583347 +1403636910801666560.0000000000 0.5966110012 2.7351640260 1.1177149521 0.4413412410 0.6196684996 0.5367712788 -0.364836201451 +1403636910851666432.0000000000 0.5662419839 2.7481239520 1.1102076866 0.4403258254 0.6201964966 0.5364572243 -0.365627022608 +1403636910901666560.0000000000 0.5358521261 2.7607468845 1.1018718756 0.4388041846 0.6212413110 0.5357948902 -0.366652364927 +1403636910951666432.0000000000 0.5049106180 2.7732815314 1.0935274064 0.4394023815 0.6207052419 0.5338685546 -0.36964160506 +1403636911001666560.0000000000 0.4737709943 2.7858555122 1.0870412659 0.4424740762 0.6183982229 0.5295570797 -0.375991527916 +1403636911051666432.0000000000 0.4431843363 2.7988623115 1.0810968216 0.4467908827 0.6153350021 0.5259052590 -0.381004463097 +1403636911101666560.0000000000 0.4128580206 2.8124575920 1.0764695151 0.4494702114 0.6132579584 0.5241093232 -0.383667333524 +1403636911151666432.0000000000 0.3839742538 2.8263070981 1.0721161373 0.4485420297 0.6138641425 0.5249817430 -0.382589900244 +1403636911201666560.0000000000 0.3562800910 2.8404932386 1.0690891721 0.4470483780 0.6150039710 0.5276857655 -0.378768525979 +1403636911251666432.0000000000 0.3295300918 2.8545807404 1.0675114442 0.4439344658 0.6171458428 0.5302719487 -0.375319676098 +1403636911301666560.0000000000 0.3033384802 2.8688921624 1.0677385209 0.4425396117 0.6182093837 0.5326399530 -0.371847455835 +1403636911351666432.0000000000 0.2779315948 2.8832318608 1.0697993148 0.4425081742 0.6184799824 0.5346531984 -0.368530846138 +1403636911401666560.0000000000 0.2531553954 2.8969135258 1.0749576451 0.4425104808 0.6184080987 0.5348740085 -0.368328240624 +1403636911451666432.0000000000 0.2291477059 2.9104402486 1.0815401755 0.4433024931 0.6181901968 0.5352467433 -0.367198453109 +1403636911501666560.0000000000 0.2034080310 2.9230785138 1.0894016913 0.4428780978 0.6186435555 0.5355465562 -0.366509246627 +1403636911551666432.0000000000 0.1784462259 2.9354760585 1.0966219314 0.4430538371 0.6185076177 0.5359713694 -0.365904790165 +1403636911601666560.0000000000 0.1537730474 2.9475536971 1.1026644861 0.4427150015 0.6188908923 0.5359628904 -0.365679191388 +1403636911651666432.0000000000 0.1279649413 2.9580847546 1.1079662973 0.4433360473 0.6186042255 0.5360339476 -0.365307498288 +1403636911701666560.0000000000 0.1033026639 2.9692010552 1.1117647605 0.4428607462 0.6189590787 0.5357887378 -0.365642512282 +1403636911751666432.0000000000 0.0781521033 2.9799729993 1.1144670241 0.4424499321 0.6195815316 0.5348860639 -0.366406443528 +1403636911801666560.0000000000 0.0530352072 2.9904526296 1.1160994286 0.4401627200 0.6214560341 0.5330349426 -0.368677267443 +1403636911851666432.0000000000 0.0281562325 3.0009956779 1.1159901642 0.4379705025 0.6230702306 0.5313556087 -0.370980516872 +1403636911901666560.0000000000 0.0033514088 3.0117742619 1.1139510333 0.4331888400 0.6267731352 0.5295996247 -0.372863384338 +1403636911951666432.0000000000 -0.0218156112 3.0233677189 1.1104181294 0.4296633282 0.6294873047 0.5280180466 -0.374609263272 +1403636912001666560.0000000000 -0.0469672406 3.0360178188 1.1051234898 0.4295434495 0.6299018044 0.5282582278 -0.373710297703 +1403636912051666432.0000000000 -0.0723195443 3.0494331476 1.0985567489 0.4312264473 0.6291008401 0.5291707509 -0.371825497421 +1403636912101666560.0000000000 -0.0975940943 3.0631064024 1.0910906171 0.4311448103 0.6295818601 0.5287380192 -0.37172159065 +1403636912151666432.0000000000 -0.1233632880 3.0775591605 1.0842428884 0.4327169244 0.6283601305 0.5289798604 -0.371617971852 +1403636912201666560.0000000000 -0.1493845432 3.0928054647 1.0797272276 0.4345527636 0.6273060795 0.5294251420 -0.370621096621 +1403636912251666432.0000000000 -0.1752987487 3.1085967481 1.0773532702 0.4365877382 0.6261187192 0.5295032279 -0.370125421857 +1403636912301666560.0000000000 -0.2012913954 3.1247840627 1.0767170279 0.4389907776 0.6245460957 0.5302360595 -0.368888862342 +1403636912351666432.0000000000 -0.2269528190 3.1407924203 1.0773344017 0.4396044405 0.6244223024 0.5301451565 -0.368498083041 +1403636912401666560.0000000000 -0.2526043105 3.1569251754 1.0787713711 0.4395806546 0.6247344697 0.5300283339 -0.368165256055 +1403636912451666432.0000000000 -0.2784227198 3.1730517299 1.0800493256 0.4383630406 0.6257406081 0.5285907503 -0.369970748462 +1403636912501666560.0000000000 -0.3041484245 3.1895145450 1.0801516241 0.4362239749 0.6274837336 0.5267046103 -0.372229850132 +1403636912551666432.0000000000 -0.3298344014 3.2067186762 1.0783412183 0.4364678519 0.6278052272 0.5260898684 -0.372271220021 +1403636912601666560.0000000000 -0.3554058153 3.2242133033 1.0751608936 0.4355183914 0.6288350654 0.5253554376 -0.372681976274 +1403636912651666432.0000000000 -0.3811066844 3.2420359420 1.0709385119 0.4346195143 0.6298128147 0.5233724540 -0.374863936239 +1403636912701666560.0000000000 -0.4067642586 3.2602952357 1.0652458456 0.4326101546 0.6315317014 0.5219139549 -0.376326969484 +1403636912751666432.0000000000 -0.4323861589 3.2793481145 1.0587251650 0.4309190654 0.6328989699 0.5198314715 -0.37884415561 +1403636912801666560.0000000000 -0.4578511752 3.2991611771 1.0508813659 0.4302850473 0.6334533383 0.5188040899 -0.380044684855 +1403636912851666432.0000000000 -0.4830226552 3.3201921928 1.0419093903 0.4310731596 0.6331091229 0.5188130117 -0.379712823597 +1403636912901666560.0000000000 -0.5080769648 3.3425785544 1.0317265040 0.4333373250 0.6318056720 0.5196820437 -0.378114968005 +1403636912951666432.0000000000 -0.5329659036 3.3657338334 1.0206855834 0.4370086031 0.6293359780 0.5199697028 -0.377612520801 +1403636913001666560.0000000000 -0.5572819009 3.3894169381 1.0084987883 0.4413348811 0.6264001624 0.5207612612 -0.376369589689 +1403636913051666432.0000000000 -0.5810983354 3.4134083517 0.9957779193 0.4445419088 0.6242518880 0.5209857964 -0.375853524106 +1403636913101666560.0000000000 -0.6040378210 3.4375025943 0.9830134302 0.4473679115 0.6222369713 0.5212492011 -0.375476195892 +1403636913151666432.0000000000 -0.6256337959 3.4616980581 0.9712909616 0.4497167207 0.6204388673 0.5217721579 -0.374919055686 +1403636913201666560.0000000000 -0.6464502147 3.4859125854 0.9610614343 0.4519394379 0.6188541804 0.5215344673 -0.37519601175 +1403636913251666432.0000000000 -0.6670446340 3.5100502683 0.9526490792 0.4519595813 0.6186675913 0.5221412909 -0.374635049809 +1403636913301666560.0000000000 -0.6871552414 3.5342591246 0.9466199537 0.4518810960 0.6186755662 0.5227881319 -0.373813573774 +1403636913351666432.0000000000 -0.7069461957 3.5581566717 0.9423179633 0.4484369979 0.6209070638 0.5230957620 -0.373830845104 +1403636913401666560.0000000000 -0.7261229460 3.5820343949 0.9399091000 0.4453435257 0.6229730293 0.5230282970 -0.374185982355 +1403636913451666432.0000000000 -0.7447277347 3.6058399050 0.9398838714 0.4412311515 0.6255782124 0.5223165407 -0.375702545087 +1403636913501666560.0000000000 -0.7627267808 3.6303530343 0.9396517173 0.4399040392 0.6269013127 0.5220566598 -0.37541447024 +1403636913551666432.0000000000 -0.7808234581 3.6553793636 0.9386889317 0.4406000068 0.6266024071 0.5227713595 -0.374100471958 +1403636913601666560.0000000000 -0.7983651832 3.6807202004 0.9360269219 0.4414329334 0.6262310962 0.5237084774 -0.372425845121 +1403636913651666432.0000000000 -0.8156321725 3.7061304973 0.9320004562 0.4419628381 0.6262091133 0.5242973382 -0.371003096072 +1403636913701666560.0000000000 -0.8326606695 3.7316631408 0.9266659822 0.4429171775 0.6258487138 0.5248410545 -0.369702081096 +1403636913751666432.0000000000 -0.8495229116 3.7571702995 0.9204919638 0.4441844333 0.6250564840 0.5252062548 -0.369002670728 +1403636913801666560.0000000000 -0.8662145285 3.7824964815 0.9147438876 0.4442570552 0.6250124391 0.5252007297 -0.368997714608 +1403636913851666432.0000000000 -0.8824890778 3.8079303988 0.9094568937 0.4453719821 0.6244008683 0.5255967737 -0.368124143152 +1403636913901666560.0000000000 -0.8989088722 3.8331804284 0.9060205211 0.4457560044 0.6240262370 0.5254925904 -0.368443180806 +1403636913951666432.0000000000 -0.9153278008 3.8584827554 0.9049691269 0.4465246338 0.6231919449 0.5258096237 -0.368472238892 +1403636914001666560.0000000000 -0.9309854800 3.8837179367 0.9064253650 0.4466335090 0.6230793693 0.5260256620 -0.368222230693 +1403636914051666432.0000000000 -0.9463645403 3.9087584060 0.9093314612 0.4459962685 0.6234611203 0.5258443766 -0.368607177913 +1403636914101666560.0000000000 -0.9621696776 3.9336171304 0.9133195340 0.4450074968 0.6241133453 0.5244558369 -0.370670925642 +1403636914151666432.0000000000 -0.9777830377 3.9584930906 0.9168514876 0.4438181959 0.6249353969 0.5235317608 -0.37201566372 +1403636914201666560.0000000000 -0.9930381769 3.9836619226 0.9190999363 0.4434292341 0.6253627855 0.5234183868 -0.371920815921 +1403636914251666432.0000000000 -1.0079804505 4.0091542235 0.9201560935 0.4439760677 0.6254370451 0.5229742299 -0.371768353658 +1403636914301666560.0000000000 -1.0222378630 4.0346952127 0.9193469494 0.4437263621 0.6255135442 0.5243799154 -0.369953275235 +1403636914351666432.0000000000 -1.0364313930 4.0604173878 0.9178733724 0.4453100232 0.6245086964 0.5245811647 -0.369462410823 +1403636914401666560.0000000000 -1.0501280643 4.0862530918 0.9155532856 0.4470179074 0.6235051069 0.5256044666 -0.367636120059 +1403636914451666432.0000000000 -1.0635232869 4.1117168918 0.9141016572 0.4478094027 0.6229730101 0.5261411535 -0.366806289725 +1403636914501666560.0000000000 -1.0768470379 4.1368357830 0.9145440600 0.4488311477 0.6224468135 0.5267893002 -0.365518259938 +1403636914551666432.0000000000 -1.0900498599 4.1616665984 0.9168318216 0.4491577275 0.6223512082 0.5269784702 -0.365006851221 +1403636914601666560.0000000000 -1.1037427958 4.1861934117 0.9211186129 0.4496123698 0.6221014389 0.5269901154 -0.364856046757 +1403636914651666432.0000000000 -1.1174816380 4.2106008746 0.9279201100 0.4510690759 0.6212468800 0.5265876277 -0.365095156338 +1403636914701666560.0000000000 -1.1302166349 4.2343401670 0.9361894536 0.4510802395 0.6213557935 0.5261326314 -0.365551705903 +1403636914751666432.0000000000 -1.1429642486 4.2578764495 0.9449815697 0.4523042662 0.6210375600 0.5258998016 -0.364914508534 +1403636914801666560.0000000000 -1.1554121241 4.2808578240 0.9533418142 0.4526730706 0.6209679051 0.5255897013 -0.365022489633 +1403636914851666432.0000000000 -1.1673899565 4.3033253100 0.9602766188 0.4527498851 0.6212064333 0.5256313033 -0.364461029137 +1403636914901666560.0000000000 -1.1789433543 4.3255357100 0.9654220449 0.4522076421 0.6220692884 0.5257830732 -0.363442167083 +1403636914951666432.0000000000 -1.1899889902 4.3474050940 0.9688340710 0.4514366879 0.6229707943 0.5262888819 -0.362121967023 +1403636915001666560.0000000000 -1.2009446887 4.3689249449 0.9707082340 0.4504075008 0.6241790877 0.5264782252 -0.361046019366 +1403636915051666432.0000000000 -1.2117932190 4.3900464890 0.9711034003 0.4494748980 0.6249935905 0.5270521623 -0.359960200773 +1403636915101666560.0000000000 -1.2228410939 4.4110974445 0.9704657825 0.4492158523 0.6255302505 0.5273839059 -0.358863817483 +1403636915151666432.0000000000 -1.2335916422 4.4317430962 0.9683987509 0.4483234106 0.6264752972 0.5277942913 -0.357726162969 +1403636915201666560.0000000000 -1.2447336898 4.4519030348 0.9647941128 0.4470998840 0.6275609866 0.5286768556 -0.356047306066 +1403636915251666432.0000000000 -1.2561523133 4.4715985241 0.9595428595 0.4443872241 0.6296561811 0.5298626265 -0.35397554398 +1403636915301666560.0000000000 -1.2679629807 4.4908169042 0.9531884881 0.4420594096 0.6314259504 0.5315873467 -0.351140485113 +1403636915351666432.0000000000 -1.2804229410 4.5098647674 0.9459504594 0.4393157518 0.6333268654 0.5332437675 -0.348639980815 +1403636915401666560.0000000000 -1.2936337181 4.5287331155 0.9383582949 0.4380479511 0.6340518159 0.5341818314 -0.347479579729 +1403636915451666432.0000000000 -1.3080477720 4.5473899646 0.9312249546 0.4377576764 0.6342645081 0.5339747616 -0.34777536496 +1403636915501666560.0000000000 -1.3237904470 4.5657508607 0.9261409072 0.4383321867 0.6339666477 0.5312147562 -0.351798332156 +1403636915551666432.0000000000 -1.3407888125 4.5839334943 0.9235187692 0.4393241466 0.6333302282 0.5269329189 -0.358090512661 +1403636915601666560.0000000000 -1.3584843565 4.6020842608 0.9221991353 0.4395767195 0.6331361182 0.5230337029 -0.363794872246 +1403636915651666432.0000000000 -1.3770952499 4.6207429538 0.9228837254 0.4391904970 0.6331448040 0.5194846003 -0.369290014138 +1403636915701666560.0000000000 -1.3952116568 4.6402023125 0.9249493561 0.4390376966 0.6331084468 0.5166912915 -0.373429651668 +1403636915751666432.0000000000 -1.4121804350 4.6604926916 0.9285004078 0.4402498716 0.6320525879 0.5158906694 -0.374895177271 +1403636915801666560.0000000000 -1.4283855875 4.6812629308 0.9331649998 0.4398731181 0.6320843803 0.5152775239 -0.376125045069 +1403636915851666432.0000000000 -1.4446496119 4.7025385161 0.9402989732 0.4403028300 0.6315416119 0.5150705081 -0.376816907874 +1403636915901666560.0000000000 -1.4600907422 4.7244748402 0.9498355385 0.4407430716 0.6309643239 0.5152373637 -0.377041146031 +1403636915951666432.0000000000 -1.4752774215 4.7468028752 0.9594951320 0.4419214693 0.6300046549 0.5164491554 -0.375605936673 +1403636916001666560.0000000000 -1.4901634884 4.7700671810 0.9681228188 0.4452274512 0.6275494417 0.5186501215 -0.372768381718 +1403636916051666432.0000000000 -1.5048416291 4.7937327027 0.9751571489 0.4476673035 0.6257456391 0.5209515154 -0.369656460926 +1403636916101666560.0000000000 -1.5191744076 4.8174177222 0.9805217035 0.4506890896 0.6233559786 0.5236066407 -0.366255039907 +1403636916151666432.0000000000 -1.5329918834 4.8407732367 0.9847463323 0.4520678906 0.6219491109 0.5256322962 -0.364039304144 +1403636916201666560.0000000000 -1.5465063295 4.8637025011 0.9882595183 0.4526468787 0.6213242937 0.5268161765 -0.362672912507 +1403636916251666432.0000000000 -1.5595815985 4.8859202966 0.9927794982 0.4521986310 0.6215387365 0.5264858802 -0.36334365979 +1403636916301666560.0000000000 -1.5723077707 4.9076278198 0.9985114119 0.4514111536 0.6218521819 0.5263863513 -0.363930272676 +1403636916351666432.0000000000 -1.5844243152 4.9290267859 1.0057012513 0.4508225970 0.6219263133 0.5264606592 -0.364425330018 +1403636916401666560.0000000000 -1.5969070002 4.9506241434 1.0134400414 0.4512024847 0.6221196308 0.5271644804 -0.362603217613 +1403636916451666432.0000000000 -1.6094587726 4.9724308186 1.0209382890 0.4544928480 0.6218073629 0.5266034261 -0.359834248156 +1403636916501666560.0000000000 -1.6220562615 4.9938351834 1.0273334397 0.4560354599 0.6244771668 0.5236183413 -0.35760838935 +1403636916551666432.0000000000 -1.6346225120 5.0152856159 1.0324158196 0.4596782027 0.6269709736 0.5203309685 -0.353353974517 +1403636916601666560.0000000000 -1.6472978463 5.0362008240 1.0362541542 0.4625208709 0.6305583863 0.5159548630 -0.349658611701 +1403636916651666432.0000000000 -1.6598924003 5.0565344819 1.0387537760 0.4653083248 0.6340500024 0.5118565760 -0.345646644613 +1403636916701666560.0000000000 -1.6723211896 5.0759798774 1.0402225049 0.4676791730 0.6370644392 0.5078531145 -0.342797761825 +1403636916751666432.0000000000 -1.6847308707 5.0945141312 1.0405218724 0.4699484836 0.6395445769 0.5041959378 -0.340466757835 +1403636916801666560.0000000000 -1.6968572659 5.1122723063 1.0393040595 0.4712464450 0.6423296290 0.5003966970 -0.339031829572 +1403636916851666432.0000000000 -1.7086280150 5.1292127826 1.0368595009 0.4724846068 0.6443911932 0.4978585482 -0.337127798296 +1403636916901666560.0000000000 -1.7203018112 5.1456075817 1.0333127953 0.4744370374 0.6457078265 0.4960213424 -0.334564983708 +1403636916951666432.0000000000 -1.7320174963 5.1610515322 1.0287551553 0.4760172083 0.6465156030 0.4943079205 -0.33329397272 +1403636917001666560.0000000000 -1.7435498131 5.1755773717 1.0227107455 0.4766311026 0.6477584762 0.4926962301 -0.332388587908 +1403636917051666432.0000000000 -1.7549130994 5.1892071808 1.0156751647 0.4763494051 0.6492776688 0.4909346515 -0.332434837153 +1403636917101666560.0000000000 -1.7661638087 5.2021022246 1.0076148287 0.4759535266 0.6506314636 0.4892417769 -0.332850451109 +1403636917151666432.0000000000 -1.7772519854 5.2142793114 0.9986338633 0.4749681298 0.6522276866 0.4874330573 -0.333786361613 +1403636917201666560.0000000000 -1.7882448086 5.2262969658 0.9885008038 0.4750186484 0.6540605417 0.4847084077 -0.334095571593 +1403636917251666432.0000000000 -1.7989127721 5.2384204234 0.9767722195 0.4761854634 0.6564983307 0.4814504529 -0.332359455498 +1403636917301666560.0000000000 -1.8093956099 5.2505930901 0.9638472161 0.4790449149 0.6590281276 0.4767928614 -0.329949183584 +1403636917351666432.0000000000 -1.8191101048 5.2628347580 0.9496784212 0.4824427729 0.6624783935 0.4715938290 -0.325531272738 +1403636917401666560.0000000000 -1.8291128465 5.2753588076 0.9343545612 0.4870354145 0.6664960787 0.4651257241 -0.319746060172 +1403636917451666432.0000000000 -1.8388564014 5.2872569308 0.9175512629 0.4907161648 0.6713655640 0.4571152518 -0.315454547723 +1403636917501666560.0000000000 -1.8484784959 5.2988552748 0.8999094660 0.4937887402 0.6758547262 0.4512161047 -0.309511059614 +1403636917551666432.0000000000 -1.8577440151 5.3095426232 0.8834598714 0.4963503897 0.6796795120 0.4449534438 -0.306085746861 +1403636917601666560.0000000000 -1.8672699594 5.3197945758 0.8688859928 0.4981267444 0.6833540697 0.4390260093 -0.303567331928 +1403636917651666432.0000000000 -1.8754596600 5.3290772349 0.8560842033 0.5007098655 0.6857639796 0.4341173317 -0.300931117074 +1403636917701666560.0000000000 -1.8835020631 5.3376795560 0.8448261081 0.5021593419 0.6882279937 0.4298584606 -0.298998207062 +1403636917751666432.0000000000 -1.8914444403 5.3460679086 0.8354022780 0.5041299249 0.6903198663 0.4258982707 -0.296516718094 +1403636917801666560.0000000000 -1.8989411670 5.3539433714 0.8279213294 0.5060015299 0.6920242684 0.4227658539 -0.293826303176 +1403636917851666432.0000000000 -1.9061089576 5.3613900861 0.8227378288 0.5080152615 0.6933421730 0.4200492501 -0.291128412983 +1403636917901666560.0000000000 -1.9129636486 5.3681340322 0.8200893062 0.5096614727 0.6944308892 0.4175301462 -0.289274092128 +1403636917951666432.0000000000 -1.9190476095 5.3740971631 0.8185181724 0.5108071993 0.6953212635 0.4159864845 -0.287331847202 +1403636918001666560.0000000000 -1.9247065079 5.3793963556 0.8165371755 0.5107391503 0.6968765747 0.4147613206 -0.285449832528 +1403636918051666432.0000000000 -1.9299871067 5.3840681633 0.8134599502 0.5108756563 0.6979327683 0.4139979687 -0.283728032912 +1403636918101666560.0000000000 -1.9350015063 5.3881879572 0.8089120148 0.5113336703 0.6982985387 0.4143202251 -0.281524030064 +1403636918151666432.0000000000 -1.9398443425 5.3917075657 0.8032164689 0.5113829053 0.6987584529 0.4147079646 -0.279716736709 +1403636918201666560.0000000000 -1.9447671096 5.3946540041 0.7973707592 0.5114328428 0.6989244423 0.4157868510 -0.277601091112 +1403636918251666432.0000000000 -1.9495994117 5.3969824148 0.7927414194 0.5114502774 0.6989352770 0.4167259556 -0.276129625855 +1403636918301666560.0000000000 -1.9544136570 5.3984406441 0.7900361587 0.5115603720 0.6987697398 0.4175336402 -0.275122692213 +1403636918351666432.0000000000 -1.9589556810 5.3989378344 0.7886973668 0.5095172482 0.6999790730 0.4195018723 -0.272836306846 +1403636918401666560.0000000000 -1.9635282219 5.3983788989 0.7887269934 0.5044830831 0.7032122839 0.4217620847 -0.270381298634 +1403636918451666432.0000000000 -1.9688844053 5.3973676631 0.7905524334 0.5003999981 0.7057361650 0.4241424127 -0.267655601499 +1403636918501666560.0000000000 -1.9753810231 5.3960280571 0.7947937877 0.4972682282 0.7074969249 0.4260674812 -0.265779818741 +1403636918551666432.0000000000 -1.9832648261 5.3944388312 0.8013967920 0.4955073049 0.7082575080 0.4270910119 -0.265399850661 +1403636918601666560.0000000000 -1.9924933465 5.3928077032 0.8099615749 0.4948728279 0.7080666542 0.4284990019 -0.264822776214 +1403636918651666432.0000000000 -2.0035445952 5.3911510279 0.8212232797 0.4950583682 0.7071781498 0.4290137208 -0.266014104789 +1403636918701666560.0000000000 -2.0158126508 5.3886655733 0.8343378209 0.4952533119 0.7063650395 0.4285678784 -0.268518456682 +1403636918751666432.0000000000 -2.0289566053 5.3857776527 0.8495523781 0.4943551443 0.7064490326 0.4260142119 -0.273961031675 +1403636918801666560.0000000000 -2.0433628782 5.3827585495 0.8666234671 0.4922948043 0.7074597280 0.4215407492 -0.281868685278 +1403636918851666432.0000000000 -2.0584775771 5.3802424361 0.8853605518 0.4915221839 0.7077382474 0.4157596982 -0.290957710393 +1403636918901666560.0000000000 -2.0728079736 5.3774325429 0.9037831887 0.4924069756 0.7074707165 0.4109036575 -0.296949052671 +1403636918951666432.0000000000 -2.0873051919 5.3767070380 0.9231163468 0.4935273830 0.7083700367 0.4040198045 -0.302341877379 +1403636919001666560.0000000000 -2.1010320611 5.3769444205 0.9425126321 0.4945434604 0.7097605930 0.3985306644 -0.304696530986 +1403636919051666432.0000000000 -2.1144147193 5.3786181063 0.9626818717 0.4955330490 0.7110380040 0.3931978742 -0.307029943153 +1403636919101666560.0000000000 -2.1269695729 5.3818264102 0.9834604166 0.4965207443 0.7121378659 0.3896638610 -0.307390445355 +1403636919151666432.0000000000 -2.1378258757 5.3862848288 1.0044915473 0.4978720944 0.7129918741 0.3866523373 -0.307027580406 +1403636919201666560.0000000000 -2.1471378939 5.3918665159 1.0256960980 0.4994827987 0.7134789335 0.3843691025 -0.306145616196 +1403636919251666432.0000000000 -2.1548700294 5.3985471485 1.0469019147 0.5003684646 0.7143240633 0.3830434756 -0.304384999589 +1403636919301666560.0000000000 -2.1613587482 5.4063401076 1.0677595195 0.5021401013 0.7145654031 0.3814951544 -0.302841626234 +1403636919351666432.0000000000 -2.1664716033 5.4152595294 1.0870933520 0.5040234027 0.7151128828 0.3795213635 -0.300894514818 +1403636919401666560.0000000000 -2.1703117181 5.4251698362 1.1046404772 0.5062181867 0.7153332431 0.3789962104 -0.297327044327 +1403636919451666432.0000000000 -2.1730401746 5.4360066207 1.1203179579 0.5090956478 0.7149566172 0.3793725143 -0.292805656339 +1403636919501666560.0000000000 -2.1746936219 5.4473876630 1.1344924523 0.5128187292 0.7135956625 0.3811192065 -0.287308774346 +1403636919551666432.0000000000 -2.1753847336 5.4591285703 1.1471618202 0.5163024439 0.7122713608 0.3831227415 -0.281634976435 +1403636919601666560.0000000000 -2.1754884905 5.4710382292 1.1586663748 0.5191320284 0.7112131294 0.3844707204 -0.277236517902 +1403636919651666432.0000000000 -2.1750509513 5.4825542030 1.1689105907 0.5220522119 0.7098997804 0.3848437259 -0.274588959282 +1403636919701666560.0000000000 -2.1739828277 5.4934500462 1.1773262221 0.5235029257 0.7092761389 0.3855537235 -0.272434160581 +1403636919751666432.0000000000 -2.1723458939 5.5038191928 1.1843602412 0.5236026790 0.7095314514 0.3850851123 -0.27224035391 +1403636919801666560.0000000000 -2.1702263113 5.5137177254 1.1901463632 0.5243675177 0.7092545543 0.3839711483 -0.273061972617 +1403636919851666432.0000000000 -2.1677123511 5.5231751143 1.1942065027 0.5241726363 0.7095012497 0.3831981967 -0.27387983885 +1403636919901666560.0000000000 -2.1647187482 5.5321215641 1.1964837073 0.5240726194 0.7096620287 0.3822994385 -0.274908773778 +1403636919951666432.0000000000 -2.1612132141 5.5406111569 1.1974460218 0.5236714712 0.7099500280 0.3807180316 -0.277115370211 +1403636920001666560.0000000000 -2.1567461816 5.5487177541 1.1967590115 0.5231281762 0.7101319681 0.3792574219 -0.279666421012 +1403636920051666432.0000000000 -2.1513562042 5.5566216856 1.1945946070 0.5224161665 0.7103926329 0.3774355874 -0.282782661043 +1403636920101666560.0000000000 -2.1449126445 5.5643141863 1.1910794105 0.5215051357 0.7107702949 0.3758190843 -0.285653631465 +1403636920151666432.0000000000 -2.1372280234 5.5719730774 1.1862698144 0.5203134866 0.7113243124 0.3742792732 -0.288455583974 +1403636920201666560.0000000000 -2.1283081871 5.5797450981 1.1801356643 0.5195395154 0.7115116436 0.3732791274 -0.290676049894 +1403636920251666432.0000000000 -2.1179643488 5.5878239614 1.1723518414 0.5198372987 0.7110649985 0.3742711216 -0.289960132469 +1403636920301666560.0000000000 -2.1063540229 5.5962442226 1.1634232877 0.5222713974 0.7091806850 0.3774607994 -0.286039662298 +1403636920351666432.0000000000 -2.0936965785 5.6045289087 1.1536062922 0.5249284420 0.7071627093 0.3805950555 -0.281990136497 +1403636920401666560.0000000000 -2.0801018091 5.6123970447 1.1437574917 0.5266724513 0.7058046931 0.3832623827 -0.278506391909 +1403636920451666432.0000000000 -2.0654055829 5.6195547776 1.1348920975 0.5270446826 0.7053057026 0.3863968526 -0.274709374966 +1403636920501666560.0000000000 -2.0503095123 5.6259620831 1.1277791645 0.5265133235 0.7055470892 0.3883983261 -0.272275164721 +1403636920551666432.0000000000 -2.0344101065 5.6314479392 1.1227268525 0.5250426954 0.7065605770 0.3901648312 -0.269951335485 +1403636920601666560.0000000000 -2.0178354915 5.6358272705 1.1198202237 0.5228461079 0.7080386495 0.3915614236 -0.268314870614 +1403636920651666432.0000000000 -2.0015160719 5.6398727261 1.1186808883 0.5201826689 0.7100160577 0.3925894101 -0.266759711726 +1403636920701666560.0000000000 -1.9849019065 5.6432826701 1.1199537503 0.5176572333 0.7119346840 0.3938165336 -0.264742388702 +1403636920751666432.0000000000 -1.9687939019 5.6463792376 1.1228281456 0.5154337270 0.7135984643 0.3946500379 -0.263356511832 +1403636920801666560.0000000000 -1.9523605797 5.6487886284 1.1274833505 0.5128524885 0.7157014786 0.3952053783 -0.261851919018 +1403636920851666432.0000000000 -1.9367696706 5.6510861689 1.1343278174 0.5110199609 0.7170832108 0.3954959866 -0.261214840507 +1403636920901666560.0000000000 -1.9214208910 5.6529261750 1.1431961072 0.5098845918 0.7179944975 0.3954563599 -0.260990176212 +1403636920951666432.0000000000 -1.9067375606 5.6547556512 1.1530203198 0.5096739008 0.7184565725 0.3953671078 -0.260264324136 +1403636921001666560.0000000000 -1.8928624358 5.6564205377 1.1625911285 0.5095769737 0.7186682087 0.3951522429 -0.260196115911 +1403636921051666432.0000000000 -1.8795922195 5.6579947979 1.1709062387 0.5094669512 0.7189393430 0.3949388567 -0.259986434528 +1403636921101666560.0000000000 -1.8670012007 5.6594884169 1.1780706592 0.5099921556 0.7188365809 0.3941301795 -0.260467604179 +1403636921151666432.0000000000 -1.8550097634 5.6609558514 1.1835805464 0.5104448377 0.7187204788 0.3939549572 -0.260166163633 +1403636921201666560.0000000000 -1.8435764770 5.6623698941 1.1878701205 0.5121983057 0.7176669205 0.3931657743 -0.260821319525 +1403636921251666432.0000000000 -1.8326676701 5.6636268770 1.1910295382 0.5156651123 0.7152628725 0.3916253444 -0.262903223298 +1403636921301666560.0000000000 -1.8218566710 5.6646404514 1.1927790245 0.5194913859 0.7127222615 0.3898948405 -0.264835215506 +1403636921351666432.0000000000 -1.8110864912 5.6649604307 1.1931609716 0.5215677389 0.7113831474 0.3873879614 -0.268014325448 +1403636921401666560.0000000000 -1.8000802108 5.6645425681 1.1921883070 0.5222235427 0.7110211299 0.3845871242 -0.271706216777 +1403636921451666432.0000000000 -1.7887616286 5.6638051809 1.1900518952 0.5226373497 0.7108404269 0.3821000521 -0.274873859029 +1403636921501666560.0000000000 -1.7766005464 5.6624307429 1.1864984555 0.5202457529 0.7125965596 0.3796750792 -0.278203763676 +1403636921551666432.0000000000 -1.7636954530 5.6608578153 1.1813588227 0.5177111548 0.7145215335 0.3783124423 -0.279846090433 +1403636921601666560.0000000000 -1.7498022970 5.6592380690 1.1746760364 0.5134738783 0.7177209769 0.3774272333 -0.280659685825 +1403636921651666432.0000000000 -1.7350024387 5.6580921087 1.1662402745 0.5084274815 0.7214513343 0.3781166284 -0.279351541282 +1403636921701666560.0000000000 -1.7196657319 5.6575093286 1.1558520844 0.5018233518 0.7263280739 0.3811315874 -0.274516968011 +1403636921751666432.0000000000 -1.7044166592 5.6574934981 1.1451569513 0.4952894755 0.7310501810 0.3835009260 -0.270519884622 +1403636921801666560.0000000000 -1.6896119067 5.6588129143 1.1342592583 0.4923862801 0.7332516517 0.3868889130 -0.264980632318 +1403636921851666432.0000000000 -1.6758908422 5.6612842970 1.1240488123 0.4922728899 0.7336229493 0.3881040412 -0.262373823435 +1403636921901666560.0000000000 -1.6631404718 5.6647528653 1.1138634796 0.4940077047 0.7328060272 0.3885161769 -0.26078131561 +1403636921951666432.0000000000 -1.6515438522 5.6692750349 1.1040168763 0.4988349362 0.7301258216 0.3873159873 -0.260895222281 +1403636922001666560.0000000000 -1.6407170996 5.6746184166 1.0938343902 0.5045854071 0.7269788128 0.3860706542 -0.260470387315 +1403636922051666432.0000000000 -1.6301089659 5.6805062935 1.0832262018 0.5108469230 0.7239747863 0.3842325864 -0.259347738737 +1403636922101666560.0000000000 -1.6197282862 5.6862530383 1.0729094116 0.5153202213 0.7222748166 0.3815711490 -0.259167160372 +1403636922151666432.0000000000 -1.6091999183 5.6913625886 1.0637120093 0.5193600602 0.7208896592 0.3794563830 -0.258062163897 +1403636922201666560.0000000000 -1.5987618032 5.6961540759 1.0562304455 0.5212278694 0.7211859987 0.3776264621 -0.256145502633 +1403636922251666432.0000000000 -1.5883494724 5.7006703578 1.0500039664 0.5198411673 0.7236404252 0.3774986918 -0.252199194223 +1403636922301666560.0000000000 -1.5779211863 5.7046707136 1.0458378350 0.5186809161 0.7258659717 0.3774710162 -0.248202196413 +1403636922351666432.0000000000 -1.5682325781 5.7084376589 1.0435981029 0.5168869644 0.7283708403 0.3766318970 -0.245870289533 +1403636922401666560.0000000000 -1.5589195827 5.7118853250 1.0411084231 0.5151879926 0.7308209167 0.3762212439 -0.242774989837 +1403636922451666432.0000000000 -1.5502495937 5.7152249883 1.0375963940 0.5131746815 0.7337191784 0.3753301889 -0.239656343257 +1403636922501666560.0000000000 -1.5424350504 5.7188889941 1.0329188143 0.5124491655 0.7365869946 0.3729996455 -0.236022703643 +1403636922551666432.0000000000 -1.5355648974 5.7228026501 1.0268919840 0.5117448789 0.7398934347 0.3697837256 -0.232238843644 +1403636922601666560.0000000000 -1.5299903474 5.7270678568 1.0201466179 0.5130403048 0.7419523525 0.3658573401 -0.229008207207 +1403636922651666432.0000000000 -1.5258962451 5.7315547925 1.0131807522 0.5162478681 0.7426667471 0.3605415727 -0.227912298493 +1403636922701666560.0000000000 -1.5226805688 5.7363502115 1.0054890147 0.5224486485 0.7408341109 0.3566651001 -0.225836747028 +1403636922751666432.0000000000 -1.5205476605 5.7407783755 0.9980920842 0.5294021288 0.7381650566 0.3507650990 -0.227617179954 +1403636922801666560.0000000000 -1.5188103193 5.7444788351 0.9910707794 0.5337179049 0.7371547653 0.3443101811 -0.230648106697 +1403636922851666432.0000000000 -1.5168481467 5.7471178436 0.9851598700 0.5361773821 0.7369399616 0.3379901602 -0.234938203502 +1403636922901666560.0000000000 -1.5144319917 5.7492293696 0.9808228381 0.5385902918 0.7364700231 0.3325972498 -0.23856125459 +1403636922951666432.0000000000 -1.5111785814 5.7505490995 0.9783097106 0.5394628562 0.7368018009 0.3276432901 -0.242389784105 +1403636923001666560.0000000000 -1.5071522645 5.7515887683 0.9771348374 0.5396872295 0.7374532898 0.3230774604 -0.246010760605 +1403636923051666432.0000000000 -1.5020344083 5.7531071535 0.9763164929 0.5390925714 0.7390037149 0.3203992971 -0.246164577589 +1403636923101666560.0000000000 -1.4957530446 5.7549412381 0.9751136947 0.5402524372 0.7396356344 0.3182163057 -0.244550230253 +1403636923151666432.0000000000 -1.4883236673 5.7568326361 0.9722343697 0.5401320440 0.7420575430 0.3150117350 -0.241610398633 +1403636923201666560.0000000000 -1.4798994348 5.7590233634 0.9677284300 0.5401749613 0.7447281725 0.3123458963 -0.236708684543 +1403636923251666432.0000000000 -1.4701019498 5.7611193952 0.9615931736 0.5392463828 0.7483436517 0.3103839066 -0.229906389784 +1403636923301666560.0000000000 -1.4594795842 5.7632072801 0.9539729293 0.5386099375 0.7515751755 0.3093862842 -0.222068048209 +1403636923351666432.0000000000 -1.4485648338 5.7651213572 0.9451883807 0.5370404371 0.7550616321 0.3089016873 -0.214590885557 +1403636923401666560.0000000000 -1.4374361435 5.7665475212 0.9353717721 0.5342739388 0.7589829108 0.3083266893 -0.20840094083 +1403636923451666432.0000000000 -1.4266211889 5.7679577327 0.9246767102 0.5313381384 0.7628089922 0.3075202754 -0.20306034662 +1403636923501666560.0000000000 -1.4163327170 5.7693755180 0.9129814522 0.5274780148 0.7668514171 0.3073658932 -0.198070835063 +1403636923551666432.0000000000 -1.4069718953 5.7709944311 0.9019190436 0.5227798288 0.7711539561 0.3070196408 -0.194323870648 +1403636923601666560.0000000000 -1.3985772540 5.7734043947 0.8930039724 0.5193190326 0.7743144233 0.3070629249 -0.190937886107 +1403636923651666432.0000000000 -1.3916999461 5.7768222548 0.8867748982 0.5172804806 0.7763951637 0.3063743459 -0.189119576767 +1403636923701666560.0000000000 -1.3862970811 5.7816521829 0.8826254531 0.5159398490 0.7777510012 0.3070130048 -0.186151731786 +1403636923751666432.0000000000 -1.3828002149 5.7875393964 0.8819361301 0.5162777501 0.7779119506 0.3062751400 -0.185757423829 +1403636923801666560.0000000000 -1.3807445893 5.7945719198 0.8831718627 0.5172347927 0.7775438570 0.3062431893 -0.184685756282 +1403636923851666432.0000000000 -1.3801453143 5.8023240868 0.8852440766 0.5185947600 0.7766756551 0.3069898650 -0.183280180164 +1403636923901666560.0000000000 -1.3809458232 5.8103091424 0.8867132897 0.5174006342 0.7775107517 0.3065890243 -0.183784615655 +1403636923951666432.0000000000 -1.3830475578 5.8195517552 0.8871943070 0.5179021038 0.7771846637 0.3073216282 -0.182523495047 +1403636924001666560.0000000000 -1.3866277329 5.8291670055 0.8864595597 0.5180522377 0.7767917508 0.3080436691 -0.182552876952 +1403636924051666432.0000000000 -1.3916662779 5.8397935281 0.8843622113 0.5185016140 0.7764611029 0.3083458581 -0.182173169804 +1403636924101666560.0000000000 -1.3982223653 5.8512487635 0.8811987997 0.5193664272 0.7757602522 0.3086478082 -0.182184181154 +1403636924151666432.0000000000 -1.4061900522 5.8633986806 0.8769621371 0.5206333597 0.7746040703 0.3091508880 -0.182633971211 +1403636924201666560.0000000000 -1.4153297767 5.8762626998 0.8715615518 0.5215952158 0.7737570774 0.3096819381 -0.182580155843 +1403636924251666432.0000000000 -1.4256779278 5.8894961833 0.8654628419 0.5217424838 0.7733639943 0.3105984631 -0.182267681156 +1403636924301666560.0000000000 -1.4376952961 5.9031020837 0.8609146442 0.5231313670 0.7722909281 0.3096500787 -0.184437317171 +1403636924351666432.0000000000 -1.4509601016 5.9166976753 0.8578363378 0.5223621554 0.7727000579 0.3084772705 -0.186853345571 +1403636924401666560.0000000000 -1.4656321428 5.9308470034 0.8567380621 0.5223933225 0.7725940881 0.3054843296 -0.192049254155 +1403636924451666432.0000000000 -1.4811525041 5.9457964441 0.8578054015 0.5236678670 0.7716437818 0.3023089983 -0.197350218116 +1403636924501666560.0000000000 -1.4974195479 5.9618708498 0.8610809599 0.5258480736 0.7699854209 0.2993010380 -0.202546645896 +1403636924551666432.0000000000 -1.5142144235 5.9789279088 0.8664808296 0.5279613848 0.7683472826 0.2960840951 -0.207926520785 +1403636924601666560.0000000000 -1.5312888404 5.9968589297 0.8725076594 0.5293481260 0.7669927553 0.2925641020 -0.214287006114 +1403636924651666432.0000000000 -1.5477603523 6.0155690665 0.8776084668 0.5304986904 0.7659677060 0.2896767174 -0.218979478955 +1403636924701666560.0000000000 -1.5633901523 6.0349302125 0.8814822701 0.5320563071 0.7644866857 0.2878518741 -0.222749841844 +1403636924751666432.0000000000 -1.5781660716 6.0547253825 0.8840145129 0.5335438489 0.7628459365 0.2857951841 -0.227416251072 +1403636924801666560.0000000000 -1.5917794362 6.0751614856 0.8847584638 0.5350666825 0.7611587512 0.2839110241 -0.231809256041 +1403636924851666432.0000000000 -1.6039367244 6.0964124067 0.8837823633 0.5371636551 0.7592596776 0.2824645178 -0.234933492217 +1403636924901666560.0000000000 -1.6143855224 6.1185549734 0.8806190439 0.5391157442 0.7581885126 0.2809618549 -0.235721933175 +1403636924951666432.0000000000 -1.6231645793 6.1416614221 0.8753789022 0.5404085711 0.7585226966 0.2782355888 -0.234918820435 +1403636925001666560.0000000000 -1.6299937755 6.1655955795 0.8677394472 0.5411845742 0.7600209982 0.2754678524 -0.231527107055 +1403636925051666432.0000000000 -1.6346607988 6.1897948400 0.8578904858 0.5421988503 0.7613474585 0.2748302689 -0.225474560666 +1403636925101666560.0000000000 -1.6378488913 6.2143690265 0.8465890777 0.5441984860 0.7617903027 0.2748671390 -0.219024195899 +1403636925151666432.0000000000 -1.6396960374 6.2390321052 0.8331528469 0.5450168237 0.7628794874 0.2771428664 -0.210150853394 +1403636925201666560.0000000000 -1.6408965587 6.2638079617 0.8188944097 0.5462927602 0.7634078461 0.2796306228 -0.201443281143 +1403636925251666432.0000000000 -1.6417715476 6.2883766546 0.8036090858 0.5451503356 0.7653949313 0.2819217260 -0.193653946986 +1403636925301666560.0000000000 -1.6425596347 6.3125942775 0.7874240835 0.5422796327 0.7683532514 0.2840519656 -0.186763384665 +1403636925351666432.0000000000 -1.6437260543 6.3369062229 0.7702209516 0.5384063916 0.7719160193 0.2857935848 -0.180516601666 +1403636925401666560.0000000000 -1.6453152762 6.3610032110 0.7524055072 0.5334995497 0.7759630894 0.2872919223 -0.175279393218 +1403636925451666432.0000000000 -1.6480272413 6.3853593270 0.7350712655 0.5296570983 0.7792019384 0.2877557943 -0.171768158356 +1403636925501666560.0000000000 -1.6518183156 6.4100136080 0.7188581254 0.5261583193 0.7820698748 0.2882508942 -0.168628455294 +1403636925551666432.0000000000 -1.6571063853 6.4349992727 0.7045104210 0.5225954258 0.7848791765 0.2886142483 -0.166013598513 +1403636925601666560.0000000000 -1.6639798882 6.4601820336 0.6922415960 0.5189494621 0.7876100093 0.2890593913 -0.163727204303 +1403636925651666432.0000000000 -1.6725847051 6.4855842507 0.6826251250 0.5157283087 0.7900964879 0.2884752664 -0.162953589182 +1403636925701666560.0000000000 -1.6833774570 6.5123672999 0.6750567457 0.5142076189 0.7912754603 0.2890095992 -0.161081104148 +1403636925751666432.0000000000 -1.6962386610 6.5402185396 0.6702271703 0.5136121140 0.7918347415 0.2895149185 -0.159315568688 +1403636925801666560.0000000000 -1.7111420256 6.5688894835 0.6684089520 0.5141517611 0.7915792793 0.2895338569 -0.158809183502 +1403636925851666432.0000000000 -1.7287250092 6.5991507371 0.6687673434 0.5173664333 0.7895403036 0.2891234954 -0.15926608883 +1403636925901666560.0000000000 -1.7484347067 6.6302366254 0.6716204649 0.5233411471 0.7857419559 0.2871852159 -0.162013191686 +1403636925951666432.0000000000 -1.7698226657 6.6619713023 0.6756927650 0.5307982334 0.7807312599 0.2859445648 -0.164157366975 +1403636926001666560.0000000000 -1.7925066691 6.6941503055 0.6802284541 0.5393170855 0.7749602986 0.2841071709 -0.166903362017 +1403636926051666432.0000000000 -1.8162921078 6.7260668944 0.6840288780 0.5471491293 0.7695455771 0.2805523831 -0.172388501385 +1403636926101666560.0000000000 -1.8404386294 6.7570812172 0.6860045897 0.5528344331 0.7655172424 0.2770085167 -0.177830601664 +1403636926151666432.0000000000 -1.8647011999 6.7875598242 0.6859223663 0.5571428620 0.7623067137 0.2733704388 -0.183708760647 +1403636926201666560.0000000000 -1.8887244347 6.8172220831 0.6838565037 0.5593714883 0.7604352718 0.2697370370 -0.189957011926 +1403636926251666432.0000000000 -1.9120334219 6.8466094560 0.6796224085 0.5607348811 0.7592231213 0.2670452198 -0.19453404773 +1403636926301666560.0000000000 -1.9344092746 6.8753614278 0.6733165409 0.5611762320 0.7585641881 0.2648049131 -0.198846592 +1403636926351666432.0000000000 -1.9555144509 6.9031379178 0.6655199878 0.5611541841 0.7581877343 0.2624110442 -0.203464456643 +1403636926401666560.0000000000 -1.9755549759 6.9304970943 0.6559298053 0.5606760358 0.7580706625 0.2610329998 -0.206961413162 +1403636926451666432.0000000000 -1.9938065220 6.9571440075 0.6450384709 0.5602837851 0.7579721352 0.2607686587 -0.2087103953 +1403636926501666560.0000000000 -2.0102190865 6.9830033111 0.6332117620 0.5587916185 0.7586846450 0.2606471899 -0.210267874397 +1403636926551666432.0000000000 -2.0246583541 7.0084601048 0.6214349493 0.5577597100 0.7591348405 0.2629806096 -0.208469659214 +1403636926601666560.0000000000 -2.0379039687 7.0337121588 0.6110948078 0.5566097279 0.7596862745 0.2656816867 -0.206096134065 +1403636926651666432.0000000000 -2.0496358275 7.0582974587 0.6031727505 0.5566049659 0.7595071421 0.2683696556 -0.203267166651 +1403636926701666560.0000000000 -2.0602694629 7.0821504733 0.5971629028 0.5551323778 0.7603617901 0.2703313438 -0.201491825698 +1403636926751666432.0000000000 -2.0690639960 7.1047393777 0.5934204907 0.5524166980 0.7626920342 0.2710090579 -0.199225358078 +1403636926801666560.0000000000 -2.0770138148 7.1270642373 0.5919108252 0.5498535774 0.7656137513 0.2684917183 -0.198516559658 +1403636926851666432.0000000000 -2.0844123460 7.1497868806 0.5921733247 0.5470208153 0.7692362648 0.2653754119 -0.196518923382 +1403636926901666560.0000000000 -2.0907096929 7.1728136099 0.5940564941 0.5454651476 0.7725335145 0.2597802766 -0.195381548739 +1403636926951666432.0000000000 -2.0963153088 7.1965523056 0.5954216933 0.5444727222 0.7759217613 0.2533618759 -0.193138900562 +1403636927001666560.0000000000 -2.1009211560 7.2208626403 0.5962493431 0.5455497849 0.7783453823 0.2460639175 -0.189753646877 +1403636927051666432.0000000000 -2.1048402831 7.2459686412 0.5957603080 0.5468980512 0.7808604062 0.2383696157 -0.185309130965 +1403636927101666560.0000000000 -2.1075653869 7.2713687907 0.5935624836 0.5487342286 0.7832324247 0.2308775915 -0.179257504687 +1403636927151666432.0000000000 -2.1093132009 7.2972222228 0.5902151951 0.5504696020 0.7859069463 0.2217046826 -0.173725423443 +1403636927201666560.0000000000 -2.1099598158 7.3236275116 0.5853449826 0.5526973233 0.7883441091 0.2126800750 -0.166752571746 +1403636927251666432.0000000000 -2.1094689939 7.3504508737 0.5787911903 0.5550191616 0.7907795744 0.2031778106 -0.159185967634 +1403636927301666560.0000000000 -2.1080241914 7.3771205026 0.5706337413 0.5569856499 0.7931357357 0.1949381805 -0.150671153123 +1403636927351666432.0000000000 -2.1061347565 7.4036027796 0.5611123219 0.5575659584 0.7957980424 0.1886026451 -0.142319077717 +1403636927401666560.0000000000 -2.1036649808 7.4298686266 0.5498874221 0.5554861809 0.7997432549 0.1852558441 -0.13238618255 +1403636927451666432.0000000000 -2.1012384075 7.4557361631 0.5379523840 0.5514780283 0.8044636136 0.1824182629 -0.124233071588 +1403636927501666560.0000000000 -2.0990344510 7.4816768332 0.5254364446 0.5469435975 0.8091117053 0.1802420467 -0.11706303481 +1403636927551666432.0000000000 -2.0972869304 7.5078603738 0.5127251100 0.5417923547 0.8138371634 0.1784698833 -0.110808919053 +1403636927601666560.0000000000 -2.0963866186 7.5349067902 0.5014054528 0.5377691387 0.8175844868 0.1764008700 -0.10603156885 +1403636927651666432.0000000000 -2.0965179698 7.5635003465 0.4921810823 0.5361380771 0.8194815312 0.1751920818 -0.101556470719 +1403636927701666560.0000000000 -2.0978484042 7.5931982802 0.4853651696 0.5342942290 0.8213593584 0.1738795354 -0.0983076213067 +1403636927751666432.0000000000 -2.1006093892 7.6242424071 0.4809770292 0.5335474106 0.8223680446 0.1722980378 -0.0967023577288 +1403636927801666560.0000000000 -2.1047009119 7.6567595187 0.4790362013 0.5335362584 0.8227961026 0.1703433733 -0.096585556059 +1403636927851666432.0000000000 -2.1099479358 7.6909769113 0.4784828626 0.5339229881 0.8227746091 0.1694288177 -0.0962396031574 +1403636927901666560.0000000000 -2.1163656311 7.7267946276 0.4780212275 0.5347899646 0.8223911626 0.1683142647 -0.0966580456216 +1403636927951666432.0000000000 -2.1236611055 7.7640516760 0.4766719065 0.5361226624 0.8216290981 0.1679269963 -0.0964294560387 +1403636928001666560.0000000000 -2.1318225616 7.8023432146 0.4744124476 0.5370603055 0.8210778319 0.1672184610 -0.0971360307181 +1403636928051666432.0000000000 -2.1406688309 7.8418035490 0.4713242769 0.5389908241 0.8197847722 0.1673451889 -0.0971463151543 +1403636928101666560.0000000000 -2.1504777597 7.8826146690 0.4677016734 0.5428606497 0.8171629784 0.1671552479 -0.0980107380439 +1403636928151666432.0000000000 -2.1611687367 7.9245760182 0.4633307845 0.5471662101 0.8141978925 0.1668659529 -0.099230459885 +1403636928201666560.0000000000 -2.1727845745 7.9674491099 0.4586249611 0.5528587812 0.8102776192 0.1654225292 -0.102140759442 +1403636928251666432.0000000000 -2.1848789996 8.0105498803 0.4530224406 0.5583381048 0.8063907405 0.1634066955 -0.106258111285 +1403636928301666560.0000000000 -2.1968839127 8.0535148946 0.4459926230 0.5626931187 0.8032088064 0.1618678501 -0.10968530733 +1403636928351666432.0000000000 -2.2088080475 8.0959743722 0.4379168229 0.5675925501 0.7995812973 0.1606556748 -0.112686290695 +1403636928401666560.0000000000 -2.2203152334 8.1378903613 0.4280217515 0.5704540419 0.7973479214 0.1606005886 -0.114131193059 +1403636928451666432.0000000000 -2.2312229937 8.1791153026 0.4175261101 0.5727498643 0.7955576525 0.1604679538 -0.11530676638 +1403636928501666560.0000000000 -2.2414506221 8.2196463347 0.4076717089 0.5747881889 0.7940018192 0.1616385531 -0.114248094446 +1403636928551666432.0000000000 -2.2511362361 8.2590001516 0.3988915663 0.5747673475 0.7939012178 0.1627774798 -0.11343211493 +1403636928601666560.0000000000 -2.2603964229 8.2974880721 0.3911861907 0.5730948849 0.7949612619 0.1644305221 -0.112077867486 +1403636928651666432.0000000000 -2.2692269252 8.3350648621 0.3850308844 0.5701719298 0.7969507125 0.1664030193 -0.109925280887 +1403636928701666560.0000000000 -2.2781179875 8.3721150192 0.3808353301 0.5661747946 0.7996595234 0.1682462857 -0.108092256399 +1403636928751666432.0000000000 -2.2871405747 8.4088253683 0.3783964333 0.5620838731 0.8024297295 0.1700576446 -0.106059635586 +1403636928801666560.0000000000 -2.2962978763 8.4451613452 0.3780039375 0.5595003548 0.8041324447 0.1716708892 -0.104208781707 +1403636928851666432.0000000000 -2.3060120521 8.4817095171 0.3796427630 0.5570875578 0.8057595182 0.1726217399 -0.102989254678 +1403636928901666560.0000000000 -2.3161876158 8.5184412023 0.3835323939 0.5568662120 0.8058909766 0.1730892140 -0.102371283629 +1403636928951666432.0000000000 -2.3271779524 8.5556453478 0.3902894242 0.5595408530 0.8040146020 0.1734552475 -0.101920707918 +1403636929001666560.0000000000 -2.3392667839 8.5928784512 0.4003037829 0.5647122172 0.8004834721 0.1704262184 -0.106213119565 +1403636929051666432.0000000000 -2.3515803562 8.6299753757 0.4124657753 0.5696894536 0.7970470605 0.1664674649 -0.111617619029 +1403636929101666560.0000000000 -2.3640931392 8.6689108817 0.4252821587 0.5731089802 0.7945690220 0.1629157936 -0.116895723731 +1403636929151666432.0000000000 -2.3755906800 8.7051645690 0.4394737422 0.5753439272 0.7929260971 0.1597866294 -0.121308709996 +1403636929201666560.0000000000 -2.3864544286 8.7410443764 0.4541324354 0.5756840203 0.7926061990 0.1574176248 -0.12483194063 +1403636929251666432.0000000000 -2.3963853831 8.7759395634 0.4682985029 0.5744088915 0.7934273116 0.1557489183 -0.127553130278 +1403636929301666560.0000000000 -2.4055477947 8.8103044590 0.4814701714 0.5729282720 0.7943533811 0.1540982506 -0.13042097302 +1403636929351666432.0000000000 -2.4135098696 8.8443606374 0.4930402495 0.5718824762 0.7949243910 0.1535218327 -0.1321994437 +1403636929401666560.0000000000 -2.4197638760 8.8783192541 0.5028564881 0.5719018440 0.7948311012 0.1547505400 -0.131240511223 +1403636929451666432.0000000000 -2.4247591944 8.9117906103 0.5112409924 0.5714120055 0.7950546759 0.1557004562 -0.130895951833 +1403636929501666560.0000000000 -2.4282597931 8.9449453999 0.5177413198 0.5712112800 0.7951435725 0.1589049415 -0.127332604721 +1403636929551666432.0000000000 -2.4307665020 8.9773683868 0.5226186957 0.5712610057 0.7950552436 0.1621764652 -0.123478002388 +1403636929601666560.0000000000 -2.4327399123 9.0096133743 0.5262870307 0.5719519780 0.7944460485 0.1652189965 -0.120121163837 +1403636929651666432.0000000000 -2.4340621935 9.0412618626 0.5284525070 0.5722813380 0.7941126015 0.1688355428 -0.115645171915 +1403636929701666560.0000000000 -2.4353430976 9.0721534693 0.5298440307 0.5731597128 0.7933522228 0.1707962988 -0.113616981533 +1403636929751666432.0000000000 -2.4363414462 9.1020521059 0.5297308935 0.5738067277 0.7927753294 0.1727370756 -0.111422704129 +1403636929801666560.0000000000 -2.4373995214 9.1310675805 0.5282257468 0.5733226874 0.7930471309 0.1739402237 -0.110100603598 +1403636929851666432.0000000000 -2.4384933272 9.1588523030 0.5258567669 0.5738373146 0.7926619994 0.1735922148 -0.110740390443 +1403636929901666560.0000000000 -2.4399187143 9.1859028659 0.5232003612 0.5740579229 0.7924244487 0.1730281834 -0.112170593238 +1403636929951666432.0000000000 -2.4412803118 9.2119192165 0.5216550336 0.5741431088 0.7922987492 0.1719278196 -0.114294389107 +1403636930001666560.0000000000 -2.4427151175 9.2371173106 0.5217704613 0.5740627066 0.7923893110 0.1699257444 -0.117031748166 +1403636930051666432.0000000000 -2.4440009766 9.2622119602 0.5237198281 0.5738232362 0.7925352940 0.1686572522 -0.119035426302 +1403636930101666560.0000000000 -2.4447440018 9.2868122180 0.5280327333 0.5725083187 0.7934630484 0.1685779818 -0.119298281293 +1403636930151666432.0000000000 -2.4450137247 9.3105256513 0.5344951822 0.5716220018 0.7941998557 0.1663795218 -0.121707563604 +1403636930201666560.0000000000 -2.4448849853 9.3342673905 0.5420628493 0.5709391869 0.7946678843 0.1661049890 -0.12223146527 +1403636930251666432.0000000000 -2.4440831319 9.3571334283 0.5508323502 0.5694398418 0.7956916662 0.1656485200 -0.123181194616 +1403636930301666560.0000000000 -2.4425209421 9.3795973359 0.5607604605 0.5678915311 0.7968598542 0.1649286772 -0.123742123617 +1403636930351666432.0000000000 -2.4403040572 9.4022039425 0.5729974209 0.5677828532 0.7969530639 0.1650967810 -0.123415956895 +1403636930401666560.0000000000 -2.4372422613 9.4247724249 0.5852409525 0.5691701448 0.7960442644 0.1660778796 -0.121560739564 +1403636930451666432.0000000000 -2.4334819885 9.4469148495 0.5958951555 0.5700426117 0.7954761334 0.1685925280 -0.117667759459 +1403636930501666560.0000000000 -2.4295384966 9.4684738987 0.6054553250 0.5712192928 0.7946790228 0.1695409591 -0.115972554212 +1403636930551666432.0000000000 -2.4253381089 9.4895477992 0.6132749071 0.5726675197 0.7936309084 0.1706618101 -0.114352261286 +1403636930601666560.0000000000 -2.4211581131 9.5098524151 0.6193428689 0.5726550209 0.7935884237 0.1710008725 -0.114203075456 +1403636930651666432.0000000000 -2.4169241899 9.5295727745 0.6240170226 0.5731820965 0.7932282317 0.1698539402 -0.115762237933 +1403636930701666560.0000000000 -2.4127351795 9.5482605508 0.6273448194 0.5722370273 0.7938663299 0.1678759855 -0.118906216656 +1403636930751666432.0000000000 -2.4082775854 9.5664181493 0.6295562881 0.5714144836 0.7944104433 0.1655833457 -0.122391548832 +1403636930801666560.0000000000 -2.4034709517 9.5844291286 0.6304991395 0.5701680823 0.7952294768 0.1624699040 -0.12697230978 +1403636930851666432.0000000000 -2.3977385059 9.6025368666 0.6299368923 0.5701749474 0.7952147139 0.1607736480 -0.129173999772 +1403636930901666560.0000000000 -2.3910639401 9.6205265509 0.6282042728 0.5697524162 0.7957400211 0.1573923160 -0.131938098681 +1403636930951666432.0000000000 -2.3830297865 9.6387160412 0.6252152155 0.5691008767 0.7968129595 0.1523344922 -0.134192034763 +1403636931001666560.0000000000 -2.3735972665 9.6570928277 0.6209495251 0.5686716502 0.7980347418 0.1460903073 -0.13568613513 +1403636931051666432.0000000000 -2.3621007482 9.6756731184 0.6151990433 0.5689480598 0.7990912305 0.1408309323 -0.133857980987 +1403636931101666560.0000000000 -2.3490725342 9.6949941496 0.6103295119 0.5718749132 0.7983579580 0.1375414559 -0.129096872143 +1403636931151666432.0000000000 -2.3342810618 9.7137925866 0.6066273146 0.5765189591 0.7962524375 0.1361418608 -0.12277352852 +1403636931201666560.0000000000 -2.3178670835 9.7317311300 0.6037972891 0.5802020184 0.7947037070 0.1361239300 -0.115247176008 +1403636931251666432.0000000000 -2.3005327723 9.7488314875 0.6036752059 0.5851406653 0.7920500362 0.1352557916 -0.109421263399 +1403636931301666560.0000000000 -2.2824943186 9.7650694928 0.6056497897 0.5892265276 0.7897492479 0.1340756583 -0.105508020667 +1403636931351666432.0000000000 -2.2635251658 9.7799276456 0.6085822154 0.5916325069 0.7885818000 0.1342738881 -0.10040042041 +1403636931401666560.0000000000 -2.2438776191 9.7930919423 0.6132061278 0.5932560083 0.7879112733 0.1341537552 -0.0961556235602 +1403636931451666432.0000000000 -2.2234089044 9.8043169442 0.6182643341 0.5936145061 0.7880359887 0.1360868599 -0.0900081396055 +1403636931501666560.0000000000 -2.2028948923 9.8141239648 0.6251424854 0.5943201018 0.7877958654 0.1384196816 -0.0836736685226 +1403636931551666432.0000000000 -2.1823272517 9.8220190965 0.6331875695 0.5948482948 0.7875831058 0.1411359417 -0.0771297842612 +1403636931601666560.0000000000 -2.1624917504 9.8283436200 0.6414795551 0.5949245387 0.7875995564 0.1436918476 -0.0714449782566 +1403636931651666432.0000000000 -2.1435558424 9.8332041763 0.6492322029 0.5961172177 0.7867061391 0.1459273999 -0.066655138227 +1403636931701666560.0000000000 -2.1259603219 9.8361243765 0.6559362233 0.5962142929 0.7867473757 0.1457977444 -0.0655751595446 +1403636931751666432.0000000000 -2.1096299727 9.8367251497 0.6608860622 0.5932933245 0.7891755340 0.1429344482 -0.069099574463 +1403636931801666560.0000000000 -2.0939196851 9.8356096939 0.6641773357 0.5893225026 0.7923765423 0.1395614034 -0.0732189716392 +1403636931851666432.0000000000 -2.0788557934 9.8334734750 0.6658912201 0.5856683876 0.7952197589 0.1367242075 -0.0769712015819 +1403636931901666560.0000000000 -2.0640399693 9.8304423703 0.6659658544 0.5820810195 0.7979621229 0.1346656790 -0.0793932748559 +1403636931951666432.0000000000 -2.0494025231 9.8268749803 0.6645952487 0.5794303464 0.7999591052 0.1333004485 -0.0809746511321 +1403636932001666560.0000000000 -2.0347524236 9.8227821228 0.6618787122 0.5785761057 0.8006685762 0.1314831504 -0.0830162765034 +1403636932051666432.0000000000 -2.0200051807 9.8185624123 0.6578081448 0.5800606532 0.7996758416 0.1307578539 -0.0833700819747 +1403636932101666560.0000000000 -2.0056352384 9.8137284997 0.6523823849 0.5813401241 0.7987888276 0.1294161915 -0.0850383341731 +1403636932151666432.0000000000 -1.9912142942 9.8083767093 0.6459238372 0.5829860551 0.7976923148 0.1281473326 -0.0859796001045 +1403636932201666560.0000000000 -1.9762948516 9.8023749357 0.6393542705 0.5856055489 0.7958687806 0.1283854152 -0.0847125151842 +1403636932251666432.0000000000 -1.9610089679 9.7959250277 0.6342169866 0.5890746097 0.7934517468 0.1297629738 -0.0811603372862 +1403636932301666560.0000000000 -1.9457510056 9.7883409747 0.6304122688 0.5922951761 0.7911724790 0.1318701771 -0.0764381400772 +1403636932351666432.0000000000 -1.9307533102 9.7794005488 0.6284626641 0.5945814668 0.7895761882 0.1338596250 -0.0715815839517 +1403636932401666560.0000000000 -1.9162796505 9.7687487949 0.6284338972 0.5963541779 0.7883629245 0.1352815021 -0.0674129735871 +1403636932451666432.0000000000 -1.9024151755 9.7562907550 0.6303676951 0.5977716710 0.7875822805 0.1348943739 -0.0647046257087 +1403636932501666560.0000000000 -1.8890064034 9.7418362223 0.6341464949 0.5979234527 0.7880697832 0.1323820827 -0.0625183623105 +1403636932551666432.0000000000 -1.8761168668 9.7255193407 0.6396048045 0.5967936284 0.7898408598 0.1278163262 -0.0604298606177 +1403636932601666560.0000000000 -1.8637278668 9.7071686855 0.6477426567 0.5960254326 0.7916283490 0.1212632418 -0.0580815543358 +1403636932651666432.0000000000 -1.8520320951 9.6878574269 0.6577188789 0.5946027458 0.7940583887 0.1126290927 -0.0568642017651 +1403636932701666560.0000000000 -1.8410390557 9.6678712534 0.6698303708 0.5946302556 0.7952588116 0.1042124617 -0.0558394538086 +1403636932751666432.0000000000 -1.8303920425 9.6468542368 0.6829305934 0.5946238516 0.7962995222 0.0975462181 -0.0530498013854 +1403636932801666560.0000000000 -1.8199818838 9.6241325284 0.6978054496 0.5948434342 0.7970107273 0.0912840436 -0.0510138484268 +1403636932851666432.0000000000 -1.8093349205 9.5995969528 0.7138859774 0.5943362638 0.7981943538 0.0858557618 -0.0477385308393 +1403636932901666560.0000000000 -1.7992576925 9.5741430092 0.7286320971 0.5926889194 0.8000574475 0.0812662354 -0.04498582518 +1403636932951666432.0000000000 -1.7894092046 9.5479704029 0.7411038068 0.5912061273 0.8016616660 0.0776481560 -0.0422451438731 +1403636933001666560.0000000000 -1.7799422673 9.5213752564 0.7498831333 0.5894888306 0.8034296172 0.0737518564 -0.0395529065242 +1403636933051666432.0000000000 -1.7704459474 9.4941026578 0.7548538708 0.5885395527 0.8047216051 0.0690806425 -0.035667886466 +1403636933101666560.0000000000 -1.7612888713 9.4660136392 0.7562245619 0.5878220259 0.8057829609 0.0641770006 -0.03256375817 +1403636933151666432.0000000000 -1.7524138316 9.4371995526 0.7550737192 0.5863081279 0.8073026897 0.0602811879 -0.0295182114766 +1403636933201666560.0000000000 -1.7438114780 9.4070366076 0.7514427186 0.5805052474 0.8118132550 0.0564810917 -0.0279782607104 +1403636933251666432.0000000000 -1.7352690997 9.3763804060 0.7457573431 0.5722928912 0.8178567406 0.0544979828 -0.0249232497314 +1403636933301666560.0000000000 -1.7271620667 9.3460060098 0.7388306522 0.5634581172 0.8241475572 0.0528468303 -0.0224269202469 +1403636933351666432.0000000000 -1.7200338927 9.3166551001 0.7317299155 0.5565826476 0.8289319061 0.0510439918 -0.0219581945552 +1403636933401666560.0000000000 -1.7134578682 9.2891856214 0.7244611154 0.5529701458 0.8314361816 0.0496559441 -0.0217297249431 +1403636933451666432.0000000000 -1.7073644677 9.2634955857 0.7172459290 0.5540513930 0.8307831555 0.0484061492 -0.0219828823413 +1403636933501666560.0000000000 -1.7016545283 9.2393036343 0.7094418494 0.5564988115 0.8291748593 0.0478639096 -0.0220719651338 +1403636933551666432.0000000000 -1.6963978521 9.2163533809 0.7017834249 0.5604603520 0.8265126751 0.0478033986 -0.0218134544269 +1403636933601666560.0000000000 -1.6915777785 9.1943527693 0.6956620188 0.5642986970 0.8238885953 0.0475247430 -0.0227147929589 +1403636933651666432.0000000000 -1.6868706533 9.1725267796 0.6909287221 0.5682451105 0.8211406858 0.0479926947 -0.0228510332996 +1403636933701666560.0000000000 -1.6824317089 9.1515863156 0.6876754653 0.5718007251 0.8186360105 0.0483262200 -0.0233150059906 +1403636933751666432.0000000000 -1.6783120891 9.1312809843 0.6865280247 0.5755105546 0.8159732668 0.0493960848 -0.0231356043785 +1403636933801666560.0000000000 -1.6745417310 9.1109802159 0.6872186004 0.5787083349 0.8136547067 0.0498272726 -0.0240816190329 +1403636933851666432.0000000000 -1.6711127474 9.0905402382 0.6898241899 0.5813695659 0.8117298355 0.0490548311 -0.0264144945093 +1403636933901666560.0000000000 -1.6675686105 9.0698194848 0.6938074739 0.5833292691 0.8103564250 0.0478956185 -0.0274852325087 +1403636933951666432.0000000000 -1.6637302742 9.0490975180 0.6988946819 0.5836742315 0.8102477230 0.0454391977 -0.0275372140963 +1403636934001666560.0000000000 -1.6595902715 9.0285411226 0.7047428208 0.5837744361 0.8104312415 0.0411141345 -0.0267999713464 +1403636934051666432.0000000000 -1.6547885548 9.0077515734 0.7091622408 0.5840037348 0.8106025611 0.0354748820 -0.0245898021318 +1403636934101666560.0000000000 -1.6491295673 8.9866900050 0.7101835701 0.5838924935 0.8110780035 0.0288695275 -0.0197123967653 +1403636934151666432.0000000000 -1.6427914846 8.9655877666 0.7073222338 0.5842079308 0.8112236272 0.0211054558 -0.0131103047893 +1403636934201666560.0000000000 -1.6360759137 8.9442017582 0.7009616387 0.5845724530 0.8112255972 0.0123216416 -0.00602120036884 +1403636934251666432.0000000000 -1.6291086201 8.9224422379 0.6921764871 0.5845964624 0.8113180184 0.0026785254 0.00169550883371 +1403636934301666560.0000000000 -1.6220627575 8.9002086046 0.6819953848 0.5848872489 0.8110245511 -0.0078836081 0.009161457206 +1403636934351666432.0000000000 -1.6150114657 8.8778591863 0.6714755628 0.5853782997 0.8103560330 -0.0203401201 0.015544308635 +1403636934401666560.0000000000 -1.6079066894 8.8547299741 0.6609395884 0.5848532279 0.8101630153 -0.0342394090 0.0202547118353 +1403636934451666432.0000000000 -1.6004239779 8.8313994692 0.6513343521 0.5831223974 0.8105531142 -0.0485666562 0.0247628454371 +1403636934501666560.0000000000 -1.5920880781 8.8078074720 0.6435637584 0.5829142929 0.8095769996 -0.0619752112 0.0309044021461 +1403636934551666432.0000000000 -1.5829102096 8.7837234931 0.6373712433 0.5816215582 0.8091267177 -0.0748218369 0.0378419126166 +1403636934601666560.0000000000 -1.5728159891 8.7593183085 0.6332673377 0.5808166979 0.8081156472 -0.0862257054 0.0465423665561 +1403636934651666432.0000000000 -1.5621854177 8.7346896204 0.6318115320 0.5798248762 0.8070767207 -0.0978110995 0.0535095197343 +1403636934701666560.0000000000 -1.5510475750 8.7087365428 0.6323469567 0.5762685403 0.8080038243 -0.1062192124 0.0613340705868 +1403636934751666432.0000000000 -1.5393384842 8.6828084619 0.6345131624 0.5726333563 0.8091091655 -0.1122951583 0.0694492253742 +1403636934801666560.0000000000 -1.5274727675 8.6561872894 0.6386768453 0.5685960601 0.8107258157 -0.1162496574 0.0768647466725 +1403636934851666432.0000000000 -1.5153572966 8.6294761619 0.6444437364 0.5645564537 0.8124626093 -0.1190395012 0.0837264367835 +1403636934901666560.0000000000 -1.5035039728 8.6031614726 0.6526173907 0.5611441871 0.8139562085 -0.1215617787 0.088403765719 +1403636934951666432.0000000000 -1.4919896923 8.5773523186 0.6627740218 0.5588788500 0.8148536717 -0.1236475013 0.0915380806381 +1403636935001666560.0000000000 -1.4806867480 8.5521879916 0.6750778693 0.5573502742 0.8154611957 -0.1243841372 0.094404960807 +1403636935051666432.0000000000 -1.4695885739 8.5280667001 0.6897881333 0.5584859762 0.8144214372 -0.1242603292 0.0968013821054 +1403636935101666560.0000000000 -1.4580132971 8.5046630127 0.7061386824 0.5617753653 0.8121299486 -0.1243186007 0.0969446805323 +1403636935151666432.0000000000 -1.4473248409 8.4822204610 0.7242341028 0.5658217668 0.8094168346 -0.1243113345 0.0961083151835 +1403636935201666560.0000000000 -1.4370122803 8.4601166322 0.7422661428 0.5696029259 0.8069630793 -0.1252086880 0.0931980687975 +1403636935251666432.0000000000 -1.4266673756 8.4379732668 0.7585933414 0.5716138334 0.8057909729 -0.1250201317 0.0912606163814 +1403636935301666560.0000000000 -1.4163746053 8.4157664288 0.7734122627 0.5733798804 0.8048136145 -0.1252479915 0.0884505476165 +1403636935351666432.0000000000 -1.4059632337 8.3932256125 0.7864172539 0.5746565452 0.8042174841 -0.1249527720 0.0859703324679 +1403636935401666560.0000000000 -1.3953034488 8.3703753270 0.7974573382 0.5746043482 0.8045518791 -0.1245792025 0.0837026830288 +1403636935451666432.0000000000 -1.3843398535 8.3474221715 0.8067387344 0.5749145626 0.8046347909 -0.1237330886 0.0820135462551 +1403636935501666560.0000000000 -1.3730639006 8.3244005578 0.8146858064 0.5754554944 0.8045218039 -0.1226355287 0.0809701682788 +1403636935551666432.0000000000 -1.3613741301 8.3011095289 0.8204582196 0.5755123092 0.8047515362 -0.1215141779 0.0799678151649 +1403636935601666560.0000000000 -1.3495566956 8.2775505302 0.8244763512 0.5758645209 0.8047094638 -0.1208686023 0.0788258420972 +1403636935651666432.0000000000 -1.3375113675 8.2534091999 0.8265028699 0.5760392190 0.8048054252 -0.1200532498 0.0778091447649 +1403636935701666560.0000000000 -1.3250096557 8.2290388944 0.8269800162 0.5763692985 0.8047631856 -0.1187431561 0.077812015894 +1403636935751666432.0000000000 -1.3120480132 8.2047067085 0.8253994918 0.5734659838 0.8069814606 -0.1178493207 0.0776480866724 +1403636935801666560.0000000000 -1.2985793325 8.1802538503 0.8217939496 0.5696096809 0.8098969659 -0.1160870984 0.0783294427795 +1403636935851666432.0000000000 -1.2846500223 8.1560967174 0.8165525922 0.5656813120 0.8127462152 -0.1151058052 0.0787330712547 +1403636935901666560.0000000000 -1.2702842525 8.1322653910 0.8098748462 0.5612459397 0.8159221677 -0.1143538367 0.0787223692569 +1403636935951666432.0000000000 -1.2557966792 8.1087760651 0.8013178534 0.5547856048 0.8204275329 -0.1150253074 0.0766862085765 +1403636936001666560.0000000000 -1.2407196999 8.0861950190 0.7916656835 0.5485201449 0.8246642790 -0.1152979082 0.0759003948502 +1403636936051666432.0000000000 -1.2251625126 8.0649521279 0.7815301537 0.5439507362 0.8277203609 -0.1155322175 0.0751592142816 +1403636936101666560.0000000000 -1.2089916583 8.0456149727 0.7710084310 0.5413788589 0.8294489222 -0.1152865555 0.0750494949762 +1403636936151666432.0000000000 -1.1918906000 8.0287966439 0.7602019667 0.5410556688 0.8296574383 -0.1145367070 0.0762144418878 +1403636936201666560.0000000000 -1.1740776785 8.0138289292 0.7497450773 0.5421187440 0.8289113941 -0.1137116138 0.0779925449651 +1403636936251666432.0000000000 -1.1554856615 8.0007890396 0.7402071419 0.5443856517 0.8273801336 -0.1128017938 0.0797629744861 +1403636936301666560.0000000000 -1.1364945320 7.9890298888 0.7329973235 0.5489005744 0.8243031539 -0.1124338710 0.0811855558678 +1403636936351666432.0000000000 -1.1173304619 7.9778787884 0.7270855317 0.5533533225 0.8212001532 -0.1129411471 0.0816988749338 +1403636936401666560.0000000000 -1.0978417387 7.9680454598 0.7225822492 0.5571303377 0.8185157061 -0.1127358968 0.083237270717 +1403636936451666432.0000000000 -1.0786948805 7.9588433887 0.7203419827 0.5617696416 0.8152396937 -0.1141004034 0.0823420279885 +1403636936501666560.0000000000 -1.0592426429 7.9501032451 0.7196622646 0.5655425275 0.8124836524 -0.1134450978 0.0846296275615 +1403636936551666432.0000000000 -1.0397191606 7.9423273830 0.7206729368 0.5680177656 0.8105911499 -0.1144786868 0.0848082302044 +1403636936601666560.0000000000 -1.0198140736 7.9353286953 0.7216531937 0.5695889932 0.8092685669 -0.1152564389 0.0858412416101 +1403636936651666432.0000000000 -1.0001064265 7.9285502781 0.7211607443 0.5698523268 0.8088453027 -0.1166859193 0.0861510199983 +1403636936701666560.0000000000 -0.9805742215 7.9218168318 0.7190231125 0.5700679701 0.8085169306 -0.1174267795 0.0867976604134 +1403636936751666432.0000000000 -0.9610119196 7.9150818864 0.7153588761 0.5702068677 0.8082510446 -0.1175579647 0.0881731359776 +1403636936801666560.0000000000 -0.9413943932 7.9083470467 0.7104117186 0.5702345911 0.8080515951 -0.1179181194 0.0893333524373 +1403636936851666432.0000000000 -0.9217776458 7.9016506228 0.7048454827 0.5691042908 0.8086783901 -0.1173911088 0.0915363052184 +1403636936901666560.0000000000 -0.9023785882 7.8954527564 0.7004598487 0.5692912626 0.8083884059 -0.1171823558 0.0931876548742 +1403636936951666432.0000000000 -0.8833301585 7.8895575170 0.6975751217 0.5687140963 0.8086660515 -0.1170359464 0.0944779396151 +1403636937001666560.0000000000 -0.8646365609 7.8836852772 0.6969612189 0.5684870278 0.8087331980 -0.1163149975 0.0961453847473 +1403636937051666432.0000000000 -0.8463779229 7.8775114168 0.6982501277 0.5681121218 0.8088713675 -0.1159979544 0.0975715250614 +1403636937101666560.0000000000 -0.8289012063 7.8710259093 0.7014873906 0.5676913182 0.8090750626 -0.1169577663 0.0971853444321 +1403636937151666432.0000000000 -0.8119987999 7.8649525250 0.7063311391 0.5679474066 0.8088341399 -0.1184314051 0.095901406168 +1403636937201666560.0000000000 -0.7956291767 7.8596098307 0.7125306591 0.5681737577 0.8085774446 -0.1207549920 0.0938047391332 +1403636937251666432.0000000000 -0.7791885063 7.8541233796 0.7177642175 0.5678214552 0.8087210902 -0.1220152284 0.0930659835287 +1403636937301666560.0000000000 -0.7626415225 7.8488517081 0.7216121106 0.5678276260 0.8086362629 -0.1223039304 0.0933859206739 +1403636937351666432.0000000000 -0.7463097123 7.8437464225 0.7240874990 0.5685472200 0.8080532056 -0.1229841869 0.0931609647466 +1403636937401666560.0000000000 -0.7299610669 7.8385417916 0.7246680733 0.5683464751 0.8080733009 -0.1233430568 0.0937353451168 +1403636937451666432.0000000000 -0.7138336226 7.8333906498 0.7238258269 0.5682424575 0.8080643745 -0.1239494372 0.0936430092069 +1403636937501666560.0000000000 -0.6978316691 7.8283051982 0.7214173983 0.5684609321 0.8078202837 -0.1241531545 0.0941517510232 +1403636937551666432.0000000000 -0.6818989512 7.8233859704 0.7176693098 0.5688811651 0.8074009527 -0.1243028785 0.0950090307839 +1403636937601666560.0000000000 -0.6661438690 7.8183380507 0.7124727384 0.5687164092 0.8074011835 -0.1244164857 0.0958410814586 +1403636937651666432.0000000000 -0.6502140131 7.8130477901 0.7057827104 0.5682104897 0.8076059447 -0.1229760109 0.0989261248173 +1403636937701666560.0000000000 -0.6345151883 7.8080074707 0.6976294284 0.5676650525 0.8078042734 -0.1209058989 0.102909705972 +1403636937751666432.0000000000 -0.6193158126 7.8032840599 0.6880470996 0.5675584937 0.8076870793 -0.1180099960 0.107668839386 +1403636937801666560.0000000000 -0.6050804871 7.7990164927 0.6774714156 0.5675410965 0.8075052692 -0.1168708727 0.110333780237 +1403636937851666432.0000000000 -0.5918220659 7.7953113929 0.6663235903 0.5701655955 0.8054868387 -0.1166687086 0.111761168919 +1403636937901666560.0000000000 -0.5792428076 7.7918805588 0.6542182703 0.5741492250 0.8024020696 -0.1153109735 0.114921562407 +1403636937951666432.0000000000 -0.5677083096 7.7883701077 0.6411760021 0.5776145039 0.7996339820 -0.1142686459 0.117854386058 +1403636938001666560.0000000000 -0.5576085372 7.7844823673 0.6274262567 0.5813154236 0.7966677047 -0.1133299822 0.120620320273 +1403636938051666432.0000000000 -0.5492233214 7.7798844008 0.6126755625 0.5848775755 0.7937917779 -0.1134290167 0.12225666939 +1403636938101666560.0000000000 -0.5423697296 7.7744721671 0.5970702724 0.5881347484 0.7909679150 -0.1154309036 0.123056823032 +1403636938151666432.0000000000 -0.5371609464 7.7679961442 0.5808217922 0.5909563754 0.7882932396 -0.1195731490 0.122746050047 +1403636938201666560.0000000000 -0.5339054568 7.7604626472 0.5651316251 0.5926288757 0.7866338926 -0.1250405257 0.119845741113 +1403636938251666432.0000000000 -0.5316583471 7.7520928363 0.5507666030 0.5939046793 0.7852040625 -0.1302959108 0.117280807347 +1403636938301666560.0000000000 -0.5306720107 7.7422742982 0.5383172110 0.5949427152 0.7840055946 -0.1368107085 0.112522101226 +1403636938351666432.0000000000 -0.5309102500 7.7304258623 0.5276123559 0.5944231574 0.7839982205 -0.1457844543 0.103705318768 +1403636938401666560.0000000000 -0.5313728915 7.7159067706 0.5184661237 0.5928956398 0.7846167108 -0.1545656895 0.0946616347995 +1403636938451666432.0000000000 -0.5312936662 7.6992656153 0.5103298270 0.5896530452 0.7863314536 -0.1631446495 0.0858833781726 +1403636938501666560.0000000000 -0.5295503765 7.6815009951 0.5043016687 0.5865424475 0.7879716572 -0.1690449214 0.0805756746415 +1403636938551666432.0000000000 -0.5260510915 7.6618861952 0.4996942491 0.5820262363 0.7907908460 -0.1725710279 0.0781955137471 +1403636938601666560.0000000000 -0.5204656431 7.6411384910 0.4966548675 0.5790447868 0.7925262935 -0.1750062566 0.077343513167 +1403636938651666432.0000000000 -0.5130961705 7.6192096473 0.4951908408 0.5768814254 0.7937795168 -0.1769783454 0.0761614397979 +1403636938701666560.0000000000 -0.5034508273 7.5963828832 0.4955654904 0.5758994331 0.7943219863 -0.1770632168 0.0777241422682 +1403636938751666432.0000000000 -0.4916261696 7.5726011584 0.4969496172 0.5747355371 0.7950721118 -0.1762657789 0.0804349090246 +1403636938801666560.0000000000 -0.4780272567 7.5477907274 0.4990253815 0.5734766659 0.7959931298 -0.1743928450 0.0843005729285 +1403636938851666432.0000000000 -0.4626020982 7.5222739670 0.5017043839 0.5723524509 0.7968927364 -0.1713464895 0.0895266396479 +1403636938901666560.0000000000 -0.4459670594 7.4956866663 0.5042011054 0.5694948798 0.7990999745 -0.1672402444 0.0956321767416 +1403636938951666432.0000000000 -0.4285203083 7.4687594293 0.5067122109 0.5664180769 0.8013322574 -0.1643571712 0.100119407205 +1403636939001666560.0000000000 -0.4104378930 7.4419700198 0.5084702959 0.5645384413 0.8026819995 -0.1610505517 0.105169747458 +1403636939051666432.0000000000 -0.3920576262 7.4154065749 0.5089468320 0.5626632364 0.8040588322 -0.1591627039 0.107548642605 +1403636939101666560.0000000000 -0.3732880423 7.3894618281 0.5086485709 0.5630760448 0.8038249820 -0.1578694423 0.109032129534 +1403636939151666432.0000000000 -0.3545116083 7.3638161333 0.5071906685 0.5645543797 0.8029563312 -0.1567796837 0.109360017445 +1403636939201666560.0000000000 -0.3353330396 7.3385512075 0.5044072734 0.5660367667 0.8020319855 -0.1560855874 0.109473112337 +1403636939251666432.0000000000 -0.3162837815 7.3136287884 0.5002062128 0.5670358281 0.8014917460 -0.1554589525 0.109150652189 +1403636939301666560.0000000000 -0.2971705455 7.2888519622 0.4950190022 0.5686908867 0.8005278563 -0.1546550197 0.108755007276 +1403636939351666432.0000000000 -0.2779214381 7.2639814974 0.4889014802 0.5695403337 0.8001932210 -0.1534626286 0.108461232569 +1403636939401666560.0000000000 -0.2585240217 7.2390217359 0.4830772792 0.5700567995 0.8001485316 -0.1521623876 0.107908204507 +1403636939451666432.0000000000 -0.2390868386 7.2137185691 0.4786443964 0.5712455999 0.7996316444 -0.1505441027 0.107722657755 +1403636939501666560.0000000000 -0.2195656511 7.1882712370 0.4762971925 0.5738101067 0.7981131838 -0.1489523100 0.107566336066 +1403636939551666432.0000000000 -0.2001340257 7.1625123878 0.4757594025 0.5770411439 0.7960575666 -0.1471015386 0.108060197741 +1403636939601666560.0000000000 -0.1807969174 7.1359736307 0.4775086527 0.5807319094 0.7936323478 -0.1452603741 0.108616617975 +1403636939651666432.0000000000 -0.1618551518 7.1089677890 0.4815360402 0.5843620157 0.7911797492 -0.1448259120 0.107615492633 +1403636939701666560.0000000000 -0.1433533431 7.0805877283 0.4860191516 0.5863942690 0.7897755198 -0.1452974852 0.106231023764 +1403636939751666432.0000000000 -0.1249327384 7.0510661149 0.4903293611 0.5874265793 0.7890646973 -0.1447298518 0.10658417955 +1403636939801666560.0000000000 -0.1067302069 7.0207137834 0.4934921761 0.5877783280 0.7888239006 -0.1443032097 0.107005021908 +1403636939851666432.0000000000 -0.0887839645 6.9893184290 0.4947282610 0.5866643795 0.7896326971 -0.1442810735 0.107182467073 +1403636939901666560.0000000000 -0.0714236354 6.9571541642 0.4945684991 0.5858731601 0.7901902899 -0.1458702499 0.105232201727 +1403636939951666432.0000000000 -0.0538442914 6.9240486088 0.4928139733 0.5851619953 0.7903270041 -0.1489014659 0.103908706582 +1403636940001666560.0000000000 -0.0357389270 6.8902091862 0.4892902905 0.5841569901 0.7902640203 -0.1525944577 0.104681997658 +1403636940051666432.0000000000 -0.0174624806 6.8553589618 0.4843645351 0.5821134854 0.7907896146 -0.1564447236 0.106398891108 +1403636940101666560.0000000000 0.0009107363 6.8196799928 0.4779967585 0.5802576113 0.7911204441 -0.1603885935 0.108189863384 +1403636940151666432.0000000000 0.0191444193 6.7831136011 0.4703310892 0.5777727213 0.7919515633 -0.1648547986 0.108693603034 +1403636940201666560.0000000000 0.0374023925 6.7458921840 0.4617703835 0.5758252078 0.7925498916 -0.1685330706 0.109025701531 +1403636940251666432.0000000000 0.0560712708 6.7083047206 0.4523644536 0.5745681053 0.7926897642 -0.1716868529 0.109718069028 +1403636940301666560.0000000000 0.0751169381 6.6701686721 0.4421646714 0.5740579196 0.7923425615 -0.1740230059 0.111205951499 +1403636940351666432.0000000000 0.0946270627 6.6315945957 0.4310347132 0.5739686677 0.7917338296 -0.1758159118 0.113164820982 +1403636940401666560.0000000000 0.1143021750 6.5924164422 0.4190433912 0.5738909670 0.7911317515 -0.1784406449 0.11366022167 +1403636940451666432.0000000000 0.1341305014 6.5526019503 0.4067284289 0.5738509028 0.7905718918 -0.1803168056 0.114791440703 +1403636940501666560.0000000000 0.1540976719 6.5123373146 0.3951691616 0.5731407012 0.7905559843 -0.1820484787 0.115712245296 +1403636940551666432.0000000000 0.1744974572 6.4719181326 0.3851608494 0.5710424807 0.7915268274 -0.1842569493 0.115953194882 +1403636940601666560.0000000000 0.1951746556 6.4314902762 0.3760659265 0.5667417306 0.7942482127 -0.1854629551 0.116520726208 +1403636940651666432.0000000000 0.2165953175 6.3908933830 0.3689794958 0.5628938530 0.7966124272 -0.1857465181 0.118563831391 +1403636940701666560.0000000000 0.2386430946 6.3515822554 0.3638727473 0.5590258626 0.7990755220 -0.1852876115 0.12098304082 +1403636940751666432.0000000000 0.2609990690 6.3121770027 0.3609376648 0.5554757309 0.8013698877 -0.1851308986 0.122391036833 +1403636940801666560.0000000000 0.2837518311 6.2730859200 0.3599594608 0.5527141552 0.8031486491 -0.1847575348 0.123789997628 +1403636940851666432.0000000000 0.3068036803 6.2342682011 0.3611363234 0.5508350133 0.8042851407 -0.1844498041 0.125237655513 +1403636940901666560.0000000000 0.3298638561 6.1956786509 0.3639514868 0.5489913595 0.8055376578 -0.1831028462 0.127243533377 +1403636940951666432.0000000000 0.3532713974 6.1577977946 0.3685309501 0.5480292187 0.8061451644 -0.1821557823 0.128892281873 +1403636941001666560.0000000000 0.3770237609 6.1216906969 0.3758326738 0.5502258261 0.8047006207 -0.1818998245 0.128922089758 +1403636941051666432.0000000000 0.4010028072 6.0864374908 0.3845140205 0.5513122936 0.8040023779 -0.1811494353 0.129691222864 +1403636941101666560.0000000000 0.4250581643 6.0515586049 0.3946018558 0.5534776456 0.8024808610 -0.1806339406 0.130607591762 +1403636941151666432.0000000000 0.4490739913 6.0171556620 0.4054565623 0.5552725026 0.8013341046 -0.1802256818 0.130594043714 +1403636941201666560.0000000000 0.4728690738 5.9830872429 0.4166729401 0.5566350395 0.8005141071 -0.1794467950 0.130894785495 +1403636941251666432.0000000000 0.4963783683 5.9494218359 0.4281484495 0.5589723271 0.7990549631 -0.1791680323 0.130230256271 +1403636941301666560.0000000000 0.5198550396 5.9160148601 0.4386867498 0.5614897321 0.7975204591 -0.1778829512 0.130568195717 +1403636941351666432.0000000000 0.5432186704 5.8828298031 0.4477635137 0.5631972862 0.7966724427 -0.1762664668 0.13058318616 +1403636941401666560.0000000000 0.5661330261 5.8497905078 0.4554970174 0.5644675993 0.7961406440 -0.1747703451 0.13035233341 +1403636941451666432.0000000000 0.5886883555 5.8168168811 0.4619986525 0.5659387392 0.7954714866 -0.1731056927 0.130279993363 +1403636941501666560.0000000000 0.6110031304 5.7839110881 0.4668888721 0.5668144671 0.7953024693 -0.1716468872 0.129432176875 +1403636941551666432.0000000000 0.6331266025 5.7507985085 0.4702283414 0.5669223050 0.7956003674 -0.1698552693 0.12949263661 +1403636941601666560.0000000000 0.6548824701 5.7180607820 0.4722701596 0.5664715520 0.7963046092 -0.1687441750 0.128585977582 +1403636941651666432.0000000000 0.6762831721 5.6854922900 0.4733453151 0.5665323050 0.7965552785 -0.1676704561 0.128169628823 +1403636941701666560.0000000000 0.6972554286 5.6529348473 0.4729480844 0.5658643917 0.7973327186 -0.1665225727 0.127782075633 +1403636941751666432.0000000000 0.7180856538 5.6206296910 0.4722410433 0.5657853185 0.7976487946 -0.1655183797 0.127463876943 +1403636941801666560.0000000000 0.7385452289 5.5884934436 0.4724910073 0.5652960322 0.7982764576 -0.1652365773 0.126063344147 +1403636941851666432.0000000000 0.7584150487 5.5558652195 0.4749251497 0.5651602835 0.7986188751 -0.1646970542 0.125206336046 +1403636941901666560.0000000000 0.7780974923 5.5232434818 0.4782637077 0.5638202558 0.7997325995 -0.1647955326 0.124003713128 +1403636941951666432.0000000000 0.7977343866 5.4914874659 0.4839319911 0.5631389429 0.8003908711 -0.1644686110 0.123284469982 +1403636942001666560.0000000000 0.8170444391 5.4597210539 0.4911568128 0.5630027215 0.8005880423 -0.1655897182 0.12110642983 +1403636942051666432.0000000000 0.8363664642 5.4282045216 0.4992429210 0.5636239175 0.8002634016 -0.1667427475 0.118757836633 +1403636942101666560.0000000000 0.8559959115 5.3963796163 0.5081004915 0.5638837461 0.8000560413 -0.1671898892 0.118291980331 +1403636942151666432.0000000000 0.8755200544 5.3647116837 0.5170166489 0.5646087851 0.7995416120 -0.1680525823 0.117083133466 +1403636942201666560.0000000000 0.8951423704 5.3327535202 0.5248172089 0.5654787207 0.7988610427 -0.1687686952 0.116498834601 +1403636942251666432.0000000000 0.9150010310 5.3007848568 0.5310996573 0.5656463424 0.7986272915 -0.1700229489 0.115459350128 +1403636942301666560.0000000000 0.9350810730 5.2687322984 0.5358342311 0.5663639406 0.7979600513 -0.1713563030 0.114580368322 +1403636942351666432.0000000000 0.9552530860 5.2367345932 0.5392414597 0.5672664893 0.7971160449 -0.1731185978 0.113334426666 +1403636942401666560.0000000000 0.9756418915 5.2046843300 0.5408823373 0.5675736593 0.7966606521 -0.1753910895 0.111489517111 +1403636942451666432.0000000000 0.9966790306 5.1724394510 0.5407344838 0.5673495085 0.7965705942 -0.1772602506 0.110311500707 +1403636942501666560.0000000000 1.0180787885 5.1401283171 0.5392103611 0.5665418693 0.7968139962 -0.1793268986 0.109360090106 +1403636942551666432.0000000000 1.0400409101 5.1073483591 0.5361394032 0.5645048805 0.7980478402 -0.1808592658 0.108368863768 +1403636942601666560.0000000000 1.0628332384 5.0744487561 0.5318797772 0.5628725874 0.7989196245 -0.1818144602 0.108836510225 +1403636942651666432.0000000000 1.0862533919 5.0413077531 0.5264125127 0.5604347972 0.8004367053 -0.1823867830 0.109311391304 +1403636942701666560.0000000000 1.1105595244 5.0083420606 0.5197598809 0.5578238620 0.8021001414 -0.1815273225 0.111873738086 +1403636942751666432.0000000000 1.1354488865 4.9756453635 0.5123880773 0.5562048181 0.8030689779 -0.1812103892 0.113486615493 +1403636942801666560.0000000000 1.1609986887 4.9435362780 0.5055687713 0.5553685224 0.8034822949 -0.1807649720 0.115351770846 +1403636942851666432.0000000000 1.1872127294 4.9122997692 0.5006346923 0.5563824121 0.8026077042 -0.1797834462 0.118056754128 +1403636942901666560.0000000000 1.2138069353 4.8815058171 0.4979939471 0.5584920506 0.8009308718 -0.1788041099 0.120935761095 +1403636942951666432.0000000000 1.2406450267 4.8508047456 0.4970036422 0.5594273491 0.8000860153 -0.1776675241 0.123845306971 +1403636943001666560.0000000000 1.2673834311 4.8206467953 0.4986970433 0.5608768629 0.7989127052 -0.1776293017 0.124913831391 +1403636943051666432.0000000000 1.2941321011 4.7903465915 0.5024664203 0.5626707265 0.7975295389 -0.1766385175 0.127071327232 +1403636943101666560.0000000000 1.3209958457 4.7604694699 0.5079481220 0.5639987927 0.7963257251 -0.1768316856 0.128457216011 +1403636943151666432.0000000000 1.3475080942 4.7309765426 0.5141047545 0.5655088757 0.7950109817 -0.1780492066 0.128279891293 +1403636943201666560.0000000000 1.3737608828 4.7012328687 0.5193049959 0.5664499899 0.7941657228 -0.1783848133 0.128895586008 +1403636943251666432.0000000000 1.3997166212 4.6713752236 0.5231793601 0.5663737560 0.7940114255 -0.1788880446 0.129482401225 +1403636943301666560.0000000000 1.4254963972 4.6413067866 0.5255139991 0.5667019857 0.7934827248 -0.1789521996 0.131187404769 +1403636943351666432.0000000000 1.4509452318 4.6108686057 0.5263125138 0.5667923082 0.7930898820 -0.1791780003 0.132853914992 +1403636943401666560.0000000000 1.4758565507 4.5804832913 0.5260002848 0.5675949603 0.7921995332 -0.1800293633 0.133586260455 +1403636943451666432.0000000000 1.5002431785 4.5499960183 0.5240056385 0.5674827995 0.7919975628 -0.1806657248 0.134398767323 +1403636943501666560.0000000000 1.5243087679 4.5197140500 0.5208050099 0.5678263644 0.7915204815 -0.1807589315 0.135627268295 +1403636943551666432.0000000000 1.5477223077 4.4889780599 0.5158683256 0.5677993920 0.7913045598 -0.1810311895 0.136633277117 +1403636943601666560.0000000000 1.5707783253 4.4580466116 0.5097771787 0.5682439332 0.7907839940 -0.1806967391 0.138232397263 +1403636943651666432.0000000000 1.5933593203 4.4267193260 0.5023381866 0.5682744835 0.7905967557 -0.1801223900 0.139917139716 +1403636943701666560.0000000000 1.6153737269 4.3952722630 0.4940273863 0.5693138155 0.7897034498 -0.1807330114 0.139949345819 +1403636943751666432.0000000000 1.6366954239 4.3633321043 0.4838951342 0.5690526787 0.7896918446 -0.1809613982 0.140779301706 +1403636943801666560.0000000000 1.6571944425 4.3312347781 0.4722906734 0.5686915524 0.7898551680 -0.1805545100 0.141840758311 +1403636943851666432.0000000000 1.6763359394 4.2988646796 0.4595303387 0.5679581982 0.7908408180 -0.1801571342 0.139777297088 +1403636943901666560.0000000000 1.6943305854 4.2661776462 0.4448927977 0.5651259165 0.7938207440 -0.1782322201 0.136801317997 +1403636943951666432.0000000000 1.7113777318 4.2330982193 0.4286419370 0.5599729372 0.7988406176 -0.1756365049 0.132044671876 +1403636944001666560.0000000000 1.7282100283 4.2001964231 0.4113896280 0.5536256966 0.8045628785 -0.1728212472 0.127710528835 +1403636944051666432.0000000000 1.7450183707 4.1678433405 0.3942707480 0.5472493419 0.8101253887 -0.1700451591 0.123691779296 +1403636944101666560.0000000000 1.7619057060 4.1364065088 0.3782805455 0.5400679872 0.8159665250 -0.1673689394 0.120469238685 +1403636944151666432.0000000000 1.7790690396 4.1067345254 0.3645277332 0.5355071240 0.8199166811 -0.1648052420 0.117507396713 +1403636944201666560.0000000000 1.7967681771 4.0793799663 0.3528802455 0.5325527778 0.8225826134 -0.1619074085 0.116324434498 +1403636944251666432.0000000000 1.8145305542 4.0542169081 0.3435416933 0.5316567147 0.8238371105 -0.1604705320 0.113502253164 +1403636944301666560.0000000000 1.8330959195 4.0312517550 0.3372280251 0.5328584122 0.8235771721 -0.1582092707 0.11292643972 +1403636944351666432.0000000000 1.8522155628 4.0109487654 0.3327051815 0.5365489738 0.8216591577 -0.1564911822 0.111812061629 +1403636944401666560.0000000000 1.8719380346 3.9928339687 0.3302045306 0.5410629361 0.8190673304 -0.1548968967 0.111294918453 +1403636944451666432.0000000000 1.8921516016 3.9759470111 0.3290273574 0.5463913839 0.8158302475 -0.1513767138 0.113853210181 +1403636944501666560.0000000000 1.9124055379 3.9604947716 0.3297832489 0.5525136377 0.8119544017 -0.1480354102 0.116379753961 +1403636944551666432.0000000000 1.9324403888 3.9454602207 0.3317514540 0.5582714258 0.8081346188 -0.1431953728 0.121435324939 +1403636944601666560.0000000000 1.9515668605 3.9308942102 0.3349662830 0.5624749840 0.8052675779 -0.1383855389 0.126552214127 +1403636944651666432.0000000000 1.9692751078 3.9165408829 0.3389181478 0.5648944671 0.8036982253 -0.1334382867 0.130987126853 +1403636944701666560.0000000000 1.9851411456 3.9027990016 0.3443566158 0.5671324222 0.8026149426 -0.1285367649 0.132847166503 +1403636944751666432.0000000000 1.9988785701 3.8892557132 0.3512291317 0.5687011039 0.8022935750 -0.1273487944 0.1291756882 +1403636944801666560.0000000000 2.0110943422 3.8758495541 0.3596456141 0.5702178997 0.8019829827 -0.1269892605 0.124693905304 +1403636944851666432.0000000000 2.0221250290 3.8625851889 0.3697844983 0.5718740535 0.8014774905 -0.1266119724 0.120678530085 +1403636944901666560.0000000000 2.0319782720 3.8492877828 0.3809858476 0.5724043323 0.8016714123 -0.1268738185 0.116530086986 +1403636944951666432.0000000000 2.0408180030 3.8360700350 0.3921537891 0.5736289970 0.8012697207 -0.1271140024 0.112954144895 +1403636945001666560.0000000000 2.0489548025 3.8226925760 0.4010736973 0.5742020974 0.8012129403 -0.1263741451 0.111262532166 +1403636945051666432.0000000000 2.0565644481 3.8101761954 0.4070680504 0.5746881085 0.8011597948 -0.1255607036 0.110050311112 +1403636945101666560.0000000000 2.0632489844 3.7969973641 0.4094588714 0.5753187905 0.8009704221 -0.1245966691 0.109226106345 +1403636945151666432.0000000000 2.0690380015 3.7828029174 0.4085871224 0.5752781601 0.8012076618 -0.1240373536 0.108333079747 +1403636945201666560.0000000000 2.0741250363 3.7681616191 0.4061232152 0.5753951728 0.8013029831 -0.1231435604 0.10802586725 +1403636945251666432.0000000000 2.0785761506 3.7531873638 0.4030228381 0.5757903329 0.8011650267 -0.1226045669 0.107555626051 +1403636945301666560.0000000000 2.0824634119 3.7382886151 0.4007244265 0.5757807307 0.8012545707 -0.1225653657 0.106983149415 +1403636945351666432.0000000000 2.0856026563 3.7229982629 0.4000585067 0.5758712459 0.8012231172 -0.1222950579 0.10704084905 +1403636945401666560.0000000000 2.0880022505 3.7072384288 0.4011553358 0.5751715099 0.8016937863 -0.1220325603 0.10757723505 +1403636945451666432.0000000000 2.0894662628 3.6912721740 0.4042265800 0.5754581043 0.8014299396 -0.1222726973 0.107737689013 +1403636945501666560.0000000000 2.0901166016 3.6748919878 0.4079586470 0.5752881462 0.8014545536 -0.1228429670 0.107813509198 +1403636945551666432.0000000000 2.0899436015 3.6578878924 0.4106592996 0.5738508758 0.8023777327 -0.1242654415 0.106973110764 +1403636945601666560.0000000000 2.0891706764 3.6403935026 0.4116419790 0.5704105949 0.8046726698 -0.1257425316 0.106407064472 +1403636945651666432.0000000000 2.0877964859 3.6225954015 0.4105631242 0.5647041237 0.8085125423 -0.1266367212 0.106676438074 +1403636945701666560.0000000000 2.0858142845 3.6047812745 0.4078847293 0.5576594747 0.8132183782 -0.1280451573 0.10628366427 +1403636945751666432.0000000000 2.0836984182 3.5877345999 0.4037311786 0.5509840072 0.8175827913 -0.1285984844 0.106945935187 +1403636945801666560.0000000000 2.0812447140 3.5718418473 0.3979773810 0.5443274764 0.8218929619 -0.1295154089 0.106889272263 +1403636945851666432.0000000000 2.0787494948 3.5576274809 0.3916584251 0.5409083866 0.8239621513 -0.1303158356 0.107341853525 +1403636945901666560.0000000000 2.0759424826 3.5452613704 0.3849952278 0.5404275071 0.8241053020 -0.1320902344 0.106492867186 +1403636945951666432.0000000000 2.0733285505 3.5347616544 0.3777748917 0.5437363067 0.8217394826 -0.1318082474 0.108266511035 +1403636946001666560.0000000000 2.0703843889 3.5258096124 0.3696718128 0.5500103099 0.8174059542 -0.1315879372 0.109639316918 +1403636946051666432.0000000000 2.0670455854 3.5177158453 0.3604128134 0.5558994497 0.8131955690 -0.1314424333 0.111407607674 +1403636946101666560.0000000000 2.0631028578 3.5102554569 0.3488277105 0.5583469678 0.8113317090 -0.1318426516 0.112281060929 +1403636946151666432.0000000000 2.0587421577 3.5031334084 0.3356212856 0.5602643286 0.8097970964 -0.1325470686 0.112977074521 +1403636946201666560.0000000000 2.0540040024 3.4965572946 0.3209406950 0.5613812423 0.8088084283 -0.1338637043 0.112962541925 +1403636946251666432.0000000000 2.0490276797 3.4904563313 0.3047743863 0.5634105275 0.8071604043 -0.1337550349 0.114761708805 +1403636946301666560.0000000000 2.0434972750 3.4843616334 0.2872862311 0.5659900998 0.8051617578 -0.1341571092 0.115635724451 +1403636946351666432.0000000000 2.0378097366 3.4785655998 0.2676982735 0.5676008678 0.8036935697 -0.1343211314 0.117744360829 +1403636946401666560.0000000000 2.0310549072 3.4729341875 0.2469607893 0.5695117536 0.8022032170 -0.1356955043 0.117102908738 +1403636946451666432.0000000000 2.0238547896 3.4670247963 0.2242739935 0.5695700989 0.8018806698 -0.1370614079 0.117437065034 +1403636946501666560.0000000000 2.0160041700 3.4610807445 0.2005408255 0.5701064491 0.8012857282 -0.1379232424 0.117885527732 +1403636946551666432.0000000000 2.0075556953 3.4552258935 0.1767248353 0.5707050122 0.8006120130 -0.1386763080 0.118680560355 +1403636946601666560.0000000000 1.9983442507 3.4486351513 0.1537666351 0.5706217045 0.8004398392 -0.1393780471 0.119418148213 +1403636946651666432.0000000000 1.9883157102 3.4416690045 0.1316903431 0.5693182763 0.8011763213 -0.1406219165 0.119242102619 +1403636946701666560.0000000000 1.9770895008 3.4348705791 0.1119346797 0.5688270881 0.8014966085 -0.1456493907 0.113248335377 +1403636946751666432.0000000000 1.9654541221 3.4277263306 0.0945483122 0.5685598470 0.8015629562 -0.1524330763 0.104884149867 +1403636946801666560.0000000000 1.9540138336 3.4206001588 0.0794355135 0.5691042850 0.8009116514 -0.1595190121 0.0959923130563 +1403636946851666432.0000000000 1.9436098902 3.4127064376 0.0651264770 0.5687707058 0.8008621250 -0.1647487594 0.0893173397608 +1403636946901666560.0000000000 1.9346109745 3.4045188052 0.0506525913 0.5681519326 0.8010158957 -0.1682994417 0.0851599329562 +1403636946951666432.0000000000 1.9266622188 3.3959349518 0.0356097741 0.5673425204 0.8011634749 -0.1739981282 0.0773576267964 +1403636947001666560.0000000000 1.9207360379 3.3865178855 0.0193921979 0.5676218336 0.8005102755 -0.1785535738 0.0714658954937 +1403636947051666432.0000000000 1.9174169749 3.3765459505 0.0018480713 0.5668255058 0.8007774054 -0.1810256362 0.0685135897989 +1403636947101666560.0000000000 1.9167546775 3.3660966019 -0.0166580263 0.5653509998 0.8019329073 -0.1799287814 0.070053499664 +1403636947151666432.0000000000 1.9191756120 3.3550617473 -0.0351995602 0.5627841147 0.8041136292 -0.1753388148 0.0770169565408 +1403636947201666560.0000000000 1.9236615434 3.3431179948 -0.0528211532 0.5563272841 0.8089494760 -0.1699686579 0.0849196891192 +1403636947251666432.0000000000 1.9298242630 3.3307112697 -0.0690767184 0.5484823877 0.8145534774 -0.1638322531 0.093961139696 +1403636947301666560.0000000000 1.9370616731 3.3191019278 -0.0828441504 0.5404099214 0.8200356465 -0.1592720486 0.10065321588 +1403636947351666432.0000000000 1.9450773075 3.3094680905 -0.0936340446 0.5333199325 0.8247230711 -0.1559218158 0.105309510527 +1403636947401666560.0000000000 1.9534330204 3.3015391077 -0.1020970140 0.5277465580 0.8283018227 -0.1542394052 0.107749091945 +1403636947451666432.0000000000 1.9625968231 3.2964018577 -0.1081025275 0.5249609295 0.8300141561 -0.1529521738 0.109991616103 +1403636947501666560.0000000000 1.9720921034 3.2942231786 -0.1106156499 0.5268065341 0.8287461808 -0.1546471698 0.108346187675 +1403636947551666432.0000000000 1.9823624715 3.2943603650 -0.1111192084 0.5308956642 0.8259991635 -0.1569734884 0.105992921831 +1403636947601666560.0000000000 1.9938658622 3.2964633461 -0.1094587376 0.5370292741 0.8218942211 -0.1573902364 0.106384968931 +1403636947651666432.0000000000 2.0060879040 3.2996464549 -0.1068260646 0.5412331064 0.8191341575 -0.1559167166 0.108516975863 +1403636947701666560.0000000000 2.0187494001 3.3042114467 -0.1042526931 0.5434108431 0.8176497056 -0.1548822504 0.110295526265 +1403636947751666432.0000000000 2.0319234131 3.3096363122 -0.1027725881 0.5444240981 0.8169698308 -0.1523411044 0.113819527877 +1403636947801666560.0000000000 2.0447987482 3.3157961841 -0.1018550052 0.5446859359 0.8168387955 -0.1491254400 0.117699687701 +1403636947851666432.0000000000 2.0580031661 3.3231517142 -0.1030034651 0.5447140193 0.8167851631 -0.1445870501 0.123463433897 +1403636947901666560.0000000000 2.0707162746 3.3318682315 -0.1050504793 0.5451961116 0.8163847009 -0.1401495640 0.1289779816 +1403636947951666432.0000000000 2.0825050378 3.3418655994 -0.1081820896 0.5459196675 0.8159124840 -0.1372507343 0.131987768458 +1403636948001666560.0000000000 2.0927967322 3.3529997830 -0.1124327282 0.5447023499 0.8168855065 -0.1384450591 0.129731973169 +1403636948051666432.0000000000 2.1019793667 3.3650484552 -0.1179857213 0.5426570208 0.8184685757 -0.1402839544 0.12630502967 +1403636948101666560.0000000000 2.1103690018 3.3783810287 -0.1247605711 0.5406720121 0.8200179391 -0.1415166025 0.123358850921 +1403636948151666432.0000000000 2.1185971325 3.3926578679 -0.1326079692 0.5397792178 0.8207597423 -0.1405015426 0.123495578376 +1403636948201666560.0000000000 2.1264029458 3.4081941868 -0.1411420583 0.5405678968 0.8204021169 -0.1388763733 0.124258072372 +1403636948251666432.0000000000 2.1334988233 3.4249819876 -0.1505248458 0.5409748053 0.8203344007 -0.1374162639 0.124557221652 +1403636948301666560.0000000000 2.1399727504 3.4431057834 -0.1605483203 0.5419255149 0.8198366374 -0.1356032641 0.125683646778 +1403636948351666432.0000000000 2.1457724276 3.4624337229 -0.1714474507 0.5427526180 0.8194948445 -0.1336610415 0.126421997848 +1403636948401666560.0000000000 2.1509328581 3.4828870267 -0.1830054363 0.5429620986 0.8195034036 -0.1312350163 0.127998834025 +1403636948451666432.0000000000 2.1550456761 3.5044658932 -0.1951747179 0.5433346452 0.8194705811 -0.1285655981 0.129330263224 +1403636948501666560.0000000000 2.1586147367 3.5272041416 -0.2080767355 0.5441528801 0.8188926087 -0.1231105551 0.134745425958 +1403636948551666432.0000000000 2.1607720951 3.5509864290 -0.2214405144 0.5455335322 0.8177669535 -0.1166442923 0.141578544053 +1403636948601666560.0000000000 2.1609204161 3.5761132616 -0.2349010223 0.5471336817 0.8164050440 -0.1107882400 0.147829307996 +1403636948651666432.0000000000 2.1584395350 3.6023294638 -0.2473560970 0.5488811762 0.8149942754 -0.1058491247 0.152675303177 +1403636948701666560.0000000000 2.1526057326 3.6302556994 -0.2575203689 0.5521707757 0.8129816594 -0.1046244911 0.152387570811 +1403636948751666432.0000000000 2.1433495948 3.6592209566 -0.2656654166 0.5550056316 0.8116636499 -0.1071595486 0.14726744207 +1403636948801666560.0000000000 2.1310534481 3.6888825404 -0.2714504900 0.5585807605 0.8101157824 -0.1127397730 0.137803108409 +1403636948851666432.0000000000 2.1168034354 3.7194016968 -0.2749340682 0.5622664731 0.8082437993 -0.1176399998 0.129457346396 +1403636948901666560.0000000000 2.1008211082 3.7500102029 -0.2765934518 0.5661417779 0.8061522444 -0.1224897034 0.120823502335 +1403636948951666432.0000000000 2.0834972391 3.7806472162 -0.2768012518 0.5703347635 0.8036792671 -0.1280803813 0.111415030815 +1403636949001666560.0000000000 2.0658804516 3.8107885372 -0.2775388260 0.5746783863 0.8009351375 -0.1322752513 0.103686622846 +1403636949051666432.0000000000 2.0486786831 3.8402012733 -0.2800551811 0.5766879200 0.7997002543 -0.1344955795 0.0991034073421 +1403636949101666560.0000000000 2.0320484284 3.8688710752 -0.2841160679 0.5780654531 0.7988915565 -0.1336920784 0.098686580272 +1403636949151666432.0000000000 2.0156051815 3.8964347270 -0.2895051980 0.5781044017 0.7990105071 -0.1322254512 0.0994682884801 +1403636949201666560.0000000000 1.9992420607 3.9230645547 -0.2959124587 0.5779743346 0.7992531262 -0.1309899735 0.0999086367951 +1403636949251666432.0000000000 1.9829119951 3.9488061117 -0.3038781617 0.5769826488 0.8000707605 -0.1290539642 0.101601552523 +1403636949301666560.0000000000 1.9658269196 3.9734596697 -0.3124812491 0.5770056574 0.8001570518 -0.1290610151 0.100779056187 +1403636949351666432.0000000000 1.9484525507 3.9976119042 -0.3219005889 0.5780595424 0.7995574268 -0.1300749586 0.0981610504538 +1403636949401666560.0000000000 1.9311250160 4.0207802058 -0.3326903456 0.5784173529 0.7993934355 -0.1310403155 0.096082969087 +1403636949451666432.0000000000 1.9140460848 4.0430871378 -0.3447883383 0.5790635343 0.7990113761 -0.1315784217 0.094622212801 +1403636949501666560.0000000000 1.8969581572 4.0643264751 -0.3571585520 0.5799890522 0.7983809250 -0.1332004894 0.0919686221983 +1403636949551666432.0000000000 1.8799828573 4.0845514430 -0.3692398909 0.5800503909 0.7983989805 -0.1346854146 0.089221359338 +1403636949601666560.0000000000 1.8636886048 4.1040802157 -0.3795362128 0.5806804393 0.7979921520 -0.1356927443 0.0872137136082 +1403636949651666432.0000000000 1.8481944870 4.1226326302 -0.3886778979 0.5784316799 0.7996164275 -0.1365884754 0.085871700852 +1403636949701666560.0000000000 1.8333181442 4.1396861354 -0.3965303703 0.5753276183 0.8018624603 -0.1361316144 0.0865038150435 +1403636949751666432.0000000000 1.8193632084 4.1563179099 -0.4022235798 0.5713121082 0.8047527804 -0.1352087099 0.0877156891498 +1403636949801666560.0000000000 1.8058039420 4.1721414788 -0.4058854146 0.5677394001 0.8073492308 -0.1339505150 0.0889744491211 +1403636949851666432.0000000000 1.7924213736 4.1867597237 -0.4085650105 0.5629617663 0.8106858587 -0.1351004074 0.087237423959 +1403636949901666560.0000000000 1.7799526647 4.2010336052 -0.4103601231 0.5593108937 0.8132038034 -0.1345633055 0.0881113788652 +1403636949951666432.0000000000 1.7680264098 4.2153721916 -0.4108408425 0.5559231132 0.8155237383 -0.1350845651 0.0873079885353 +1403636950001666560.0000000000 1.7572115063 4.2308960415 -0.4098763982 0.5537165759 0.8169748867 -0.1358834903 0.0865197383602 +1403636950051666432.0000000000 1.7473771427 4.2473681854 -0.4076459268 0.5510317540 0.8187041252 -0.1366430563 0.0861175744405 +1403636950101666560.0000000000 1.7382815321 4.2646615832 -0.4050017429 0.5488571360 0.8201193814 -0.1375825026 0.0850358719851 +1403636950151666432.0000000000 1.7304192284 4.2826591226 -0.4031824841 0.5477479901 0.8208098827 -0.1370534051 0.0863692071337 +1403636950201666560.0000000000 1.7235848065 4.3013630715 -0.4029776833 0.5466298201 0.8214893205 -0.1357345350 0.0890352294784 +1403636950251666432.0000000000 1.7174372903 4.3208413604 -0.4040476265 0.5469625046 0.8212552086 -0.1343835028 0.0911755178881 +1403636950301666560.0000000000 1.7121135333 4.3411205517 -0.4063343562 0.5477303829 0.8206560182 -0.1330630093 0.0938582072655 +1403636950351666432.0000000000 1.7071275070 4.3624177377 -0.4092851681 0.5498852371 0.8191356391 -0.1317449676 0.0963654208049 +1403636950401666560.0000000000 1.7023823394 4.3845800328 -0.4132525729 0.5521521511 0.8175663982 -0.1299999392 0.0990616092637 +1403636950451666432.0000000000 1.6979123745 4.4075583269 -0.4180600318 0.5556708504 0.8151133085 -0.1287040981 0.101269222503 +1403636950501666560.0000000000 1.6937476757 4.4310162291 -0.4245522133 0.5579148056 0.8134592951 -0.1252125480 0.10647470457 +1403636950551666432.0000000000 1.6892124562 4.4548582640 -0.4318513557 0.5604485637 0.8115942611 -0.1218295420 0.111219267707 +1403636950601666560.0000000000 1.6840613750 4.4790694751 -0.4390885457 0.5622865830 0.8102075710 -0.1190056157 0.115044139044 +1403636950651666432.0000000000 1.6776061409 4.5033078748 -0.4450109153 0.5631567115 0.8095485413 -0.1177788333 0.116678292367 +1403636950701666560.0000000000 1.6698410091 4.5276023204 -0.4496281327 0.5650377810 0.8083699339 -0.1185003668 0.115013125266 +1403636950751666432.0000000000 1.6612765367 4.5522119963 -0.4523521257 0.5669273017 0.8071744759 -0.1196608104 0.112889727093 +1403636950801666560.0000000000 1.6516499906 4.5770716587 -0.4532174385 0.5693686004 0.8056590810 -0.1217108798 0.109175564471 +1403636950851666432.0000000000 1.6411016953 4.6010978087 -0.4529734434 0.5703115574 0.8051982339 -0.1233802600 0.105725318706 +1403636950901666560.0000000000 1.6303163212 4.6251396885 -0.4511110611 0.5713597856 0.8045573796 -0.1239282063 0.10429390239 +1403636950951666432.0000000000 1.6191924724 4.6486924780 -0.4480075081 0.5715972260 0.8044827483 -0.1241240139 0.103331253817 +1403636951001666560.0000000000 1.6078621437 4.6724951369 -0.4426859389 0.5725967363 0.8038830080 -0.1246534714 0.101816497076 +1403636951051666432.0000000000 1.5961105855 4.6956494221 -0.4347058096 0.5737468508 0.8031432142 -0.1264516604 0.0989217179471 +1403636951101666560.0000000000 1.5839086156 4.7172949910 -0.4263040277 0.5733651903 0.8035040282 -0.1293292719 0.0943799482073 +1403636951151666432.0000000000 1.5717890788 4.7383653753 -0.4187770949 0.5710803637 0.8051683726 -0.1325891135 0.089393718614 +1403636951201666560.0000000000 1.5604334554 4.7589441646 -0.4132783846 0.5673864031 0.8077468614 -0.1335416149 0.0882287631836 +1403636951251666432.0000000000 1.5497763413 4.7792392470 -0.4098204803 0.5636413847 0.8103442563 -0.1334379534 0.0885713743352 +1403636951301666560.0000000000 1.5397326410 4.7997946436 -0.4086408707 0.5584584545 0.8138972422 -0.1329559008 0.0895441919118 +1403636951351666432.0000000000 1.5301924217 4.8205751433 -0.4091743767 0.5538400506 0.8170414004 -0.1326038572 0.0901152899689 +1403636951401666560.0000000000 1.5211860825 4.8420702784 -0.4108430213 0.5495483567 0.8199398637 -0.1317957089 0.0912420664873 +1403636951451666432.0000000000 1.5129374568 4.8643318196 -0.4133836734 0.5471216392 0.8215207509 -0.1307298198 0.0931197188044 +1403636951501666560.0000000000 1.5050387150 4.8871875546 -0.4166854668 0.5456223230 0.8224915033 -0.1305660552 0.0935762413045 +1403636951551666432.0000000000 1.4976053897 4.9109291031 -0.4206867497 0.5452344424 0.8226977804 -0.1300863301 0.0946853297887 +1403636951601666560.0000000000 1.4905076716 4.9354120923 -0.4254791409 0.5447759765 0.8229800939 -0.1287717559 0.0966474795145 +1403636951651666432.0000000000 1.4836623333 4.9610557086 -0.4305976768 0.5458148768 0.8222297366 -0.1278658397 0.098360091629 +1403636951701666560.0000000000 1.4769526867 4.9875607117 -0.4354373384 0.5479100631 0.8207764939 -0.1268244339 0.100180201982 +1403636951751666432.0000000000 1.4704284085 5.0156595343 -0.4387990771 0.5507619101 0.8188449149 -0.1261615378 0.10118097705 +1403636951801666560.0000000000 1.4642501970 5.0454510945 -0.4392860923 0.5537297586 0.8167898276 -0.1256982071 0.102165027001 +1403636951851666432.0000000000 1.4582831971 5.0760048282 -0.4377996481 0.5561706544 0.8150986724 -0.1232445766 0.105352417191 +1403636951901666560.0000000000 1.4518259585 5.1064530699 -0.4352111983 0.5581447543 0.8136770127 -0.1219109267 0.107433133604 +1403636951951666432.0000000000 1.4451517653 5.1371135251 -0.4321627954 0.5591698838 0.8128259362 -0.1194902862 0.111198515971 +1403636952001666560.0000000000 1.4377145127 5.1686642085 -0.4294011203 0.5599090158 0.8122690763 -0.1180391982 0.113082223649 +1403636952051666432.0000000000 1.4292691275 5.2005575766 -0.4274225393 0.5607585561 0.8115764738 -0.1175918008 0.114305018948 +1403636952101666560.0000000000 1.4198920338 5.2327877070 -0.4264383054 0.5626682499 0.8102576265 -0.1179445841 0.113912661183 +1403636952151666432.0000000000 1.4096303060 5.2650914441 -0.4271084474 0.5640371863 0.8093717703 -0.1192871682 0.112026610063 +1403636952201666560.0000000000 1.3987466477 5.2974664243 -0.4291802489 0.5667914187 0.8074959107 -0.1206464592 0.110191985586 +1403636952251666432.0000000000 1.3873073166 5.3297121407 -0.4328532978 0.5693684941 0.8057723890 -0.1226074726 0.10732093274 +1403636952301666560.0000000000 1.3752318859 5.3617429122 -0.4378125100 0.5719230615 0.8040878986 -0.1256406179 0.10276720439 +1403636952351666432.0000000000 1.3630577038 5.3933044556 -0.4441166561 0.5745377618 0.8022877130 -0.1281489460 0.0990890182286 +1403636952401666560.0000000000 1.3511373506 5.4240416290 -0.4522408854 0.5762669204 0.8010578361 -0.1298603319 0.096742306673 +1403636952451666432.0000000000 1.3393994671 5.4540204501 -0.4620931816 0.5778437906 0.8000087714 -0.1290340985 0.0971221949825 +1403636952501666560.0000000000 1.3278266347 5.4833672263 -0.4736509801 0.5782326793 0.7997266244 -0.1279642154 0.0985365639956 +1403636952551666432.0000000000 1.3161540854 5.5119215843 -0.4863790962 0.5777982652 0.8000608771 -0.1263613113 0.100421992612 +1403636952601666560.0000000000 1.3043300054 5.5395910943 -0.4986533447 0.5782190340 0.7997847466 -0.1245118627 0.102488554617 +1403636952651666432.0000000000 1.2921241588 5.5657769017 -0.5093083395 0.5787962022 0.7993579430 -0.1237567701 0.103470271796 +1403636952701666560.0000000000 1.2794964220 5.5910044908 -0.5183245048 0.5783877687 0.7997107762 -0.1229097484 0.104035845771 +1403636952751666432.0000000000 1.2663730967 5.6154581469 -0.5264539777 0.5766501317 0.8009769919 -0.1228206032 0.104046064206 +1403636952801666560.0000000000 1.2527617695 5.6382985276 -0.5341987606 0.5726270119 0.8038763240 -0.1227634625 0.103972559884 +1403636952851666432.0000000000 1.2386932217 5.6609580382 -0.5405495245 0.5694679754 0.8061354519 -0.1233398543 0.10314619998 +1403636952901666560.0000000000 1.2243384185 5.6834620589 -0.5466968054 0.5663593305 0.8083345632 -0.1247055813 0.10139457862 +1403636952951666432.0000000000 1.2097961679 5.7061286747 -0.5539818676 0.5625604760 0.8109929530 -0.1270840301 0.0983147509833 +1403636953001666560.0000000000 1.1952992930 5.7290437442 -0.5621465709 0.5601758518 0.8125775393 -0.1307111669 0.0939965350427 +1403636953051666432.0000000000 1.1810726184 5.7521294288 -0.5716636770 0.5584881630 0.8136751652 -0.1338237369 0.0900827660722 +1403636953101666560.0000000000 1.1674139480 5.7755273689 -0.5822433183 0.5580209954 0.8139203865 -0.1368243887 0.0861699477927 +1403636953151666432.0000000000 1.1547399678 5.7990596161 -0.5945800253 0.5570756052 0.8145276731 -0.1382705013 0.0842182191727 +1403636953201666560.0000000000 1.1431284320 5.8229636610 -0.6084088777 0.5567126358 0.8147213620 -0.1389366839 0.0836465259961 +1403636953251666432.0000000000 1.1326443798 5.8467963922 -0.6232828943 0.5561493900 0.8151290094 -0.1385471714 0.0840668499884 +1403636953301666560.0000000000 1.1232454069 5.8713467456 -0.6370811886 0.5562443824 0.8151101800 -0.1380329545 0.0844658808166 +1403636953351666432.0000000000 1.1149389342 5.8964303390 -0.6496284765 0.5559943004 0.8153743188 -0.1369234711 0.0853640510048 +1403636953401666560.0000000000 1.1076620008 5.9222214562 -0.6599690976 0.5575560396 0.8143882406 -0.1345427688 0.0883249669142 +1403636953451666432.0000000000 1.1010693478 5.9476656259 -0.6690241424 0.5589787686 0.8134747440 -0.1320972006 0.0913887670488 +1403636953501666560.0000000000 1.0949493649 5.9728833275 -0.6762559158 0.5602346531 0.8127142682 -0.1287476247 0.0951667007729 +1403636953551666432.0000000000 1.0888482141 5.9981348335 -0.6818943013 0.5618074717 0.8117072920 -0.1268714087 0.0969911465031 +1403636953601666560.0000000000 1.0829894915 6.0239651222 -0.6871978676 0.5609782270 0.8123198962 -0.1244676636 0.0997377346677 +1403636953651666432.0000000000 1.0771299403 6.0502849638 -0.6908690138 0.5591768269 0.8136611995 -0.1218003489 0.102183187005 +1403636953701666560.0000000000 1.0707776943 6.0764884198 -0.6927070985 0.5563733772 0.8156680432 -0.1193780501 0.104322526678 +1403636953751666432.0000000000 1.0640757968 6.1038328411 -0.6923782185 0.5545016054 0.8170080874 -0.1169167524 0.106565603104 +1403636953801666560.0000000000 1.0568616501 6.1319781980 -0.6895575613 0.5532658796 0.8178327630 -0.1133744094 0.11042047565 +1403636953851666432.0000000000 1.0489050636 6.1611680339 -0.6847374170 0.5536205893 0.8176718740 -0.1111160672 0.112116765813 +1403636953901666560.0000000000 1.0395775977 6.1912082421 -0.6778307666 0.5542131522 0.8174691982 -0.1115348893 0.110235477516 +1403636953951666432.0000000000 1.0293868817 6.2224263144 -0.6694453295 0.5547804739 0.8172284154 -0.1123333248 0.10834005266 +1403636954001666560.0000000000 1.0183092929 6.2540574927 -0.6612538167 0.5552751771 0.8170479650 -0.1136664815 0.105745125144 +1403636954051666432.0000000000 1.0067794768 6.2860716934 -0.6540069912 0.5560702563 0.8166024034 -0.1145837082 0.10400460876 +1403636954101666560.0000000000 0.9949032968 6.3182871447 -0.6484236142 0.5565112075 0.8163092734 -0.1149560182 0.10353530731 +1403636954151666432.0000000000 0.9824101337 6.3505272728 -0.6438121300 0.5573617066 0.8157781862 -0.1156039678 0.102418755991 +1403636954201666560.0000000000 0.9696031318 6.3833241425 -0.6403713801 0.5574816495 0.8157091261 -0.1159301084 0.101946270491 +1403636954251666432.0000000000 0.9565315053 6.4170335383 -0.6377167637 0.5559182103 0.8167640939 -0.1161945716 0.101735834362 +1403636954301666560.0000000000 0.9430547157 6.4513863454 -0.6342573302 0.5553928514 0.8170864300 -0.1164088753 0.101771902725 +1403636954351666432.0000000000 0.9289758087 6.4861560662 -0.6294225842 0.5546993891 0.8174809246 -0.1176991829 0.100898106482 +1403636954401666560.0000000000 0.9146131837 6.5212479427 -0.6235461154 0.5522677106 0.8190264131 -0.1181608157 0.101163887503 +1403636954451666432.0000000000 0.8996754728 6.5567826344 -0.6156221237 0.5517367397 0.8192737812 -0.1193723466 0.1006344093 +1403636954501666560.0000000000 0.8845172572 6.5926886574 -0.6067862097 0.5504616337 0.8199480408 -0.1206216879 0.100636020677 +1403636954551666432.0000000000 0.8695593179 6.6297640602 -0.5972149117 0.5502811791 0.8198389399 -0.1210262153 0.102016624614 +1403636954601666560.0000000000 0.8546071038 6.6678023936 -0.5889629222 0.5498211131 0.8198602033 -0.1211898814 0.104110534127 +1403636954651666432.0000000000 0.8394987787 6.7067694525 -0.5836532153 0.5509676266 0.8187853391 -0.1216971398 0.105901128907 +1403636954701666560.0000000000 0.8242382232 6.7465525904 -0.5825632202 0.5528195283 0.8171822757 -0.1230538143 0.107058190861 +1403636954751666432.0000000000 0.8087568032 6.7868120821 -0.5853956804 0.5560320446 0.8146503582 -0.1245534539 0.107979611052 +1403636954801666560.0000000000 0.7928198704 6.8274682718 -0.5907839354 0.5590156602 0.8122342107 -0.1264198125 0.10860529302 +1403636954851666432.0000000000 0.7767425030 6.8685172572 -0.5980007701 0.5618439626 0.8098523099 -0.1277052926 0.11028125866 +1403636954901666560.0000000000 0.7600081065 6.9095587479 -0.6069082961 0.5643721641 0.8077364946 -0.1301182770 0.110068386502 +1403636954951666432.0000000000 0.7429265586 6.9501827682 -0.6175118646 0.5665573038 0.8057876484 -0.1323425320 0.110474166265 +1403636955001666560.0000000000 0.7255045185 6.9901708610 -0.6296083779 0.5676472445 0.8045587372 -0.1333204583 0.11263880168 +1403636955051666432.0000000000 0.7077383225 7.0295567679 -0.6422117670 0.5672217758 0.8044029444 -0.1346351737 0.114318546967 +1403636955101666560.0000000000 0.6896007857 7.0681506788 -0.6539722999 0.5660515331 0.8047182100 -0.1354599639 0.116896803252 +1403636955151666432.0000000000 0.6711174399 7.1068284736 -0.6639930540 0.5654538188 0.8046520224 -0.1359437424 0.119651161916 +1403636955201666560.0000000000 0.6521679298 7.1456973090 -0.6722362711 0.5646679717 0.8046858423 -0.1375056362 0.121338275104 +1403636955251666432.0000000000 0.6326487279 7.1849075636 -0.6775710029 0.5649707079 0.8039677865 -0.1400890266 0.121733159584 +1403636955301666560.0000000000 0.6126814086 7.2239834314 -0.6818027130 0.5651361014 0.8033055423 -0.1418121030 0.123331748135 +1403636955351666432.0000000000 0.5922234883 7.2627559501 -0.6840553931 0.5650463475 0.8027975580 -0.1428578367 0.1258186969 +1403636955401666560.0000000000 0.5709728095 7.3013047171 -0.6851041835 0.5652013461 0.8022196536 -0.1449697760 0.126391573195 +1403636955451666432.0000000000 0.5492907650 7.3396453642 -0.6865569161 0.5647482989 0.8020675510 -0.1457593984 0.128456997821 +1403636955501666560.0000000000 0.5270520036 7.3780610392 -0.6892962930 0.5642557990 0.8020546224 -0.1470351710 0.129245636201 +1403636955551666432.0000000000 0.5045662263 7.4168521083 -0.6937777176 0.5638568826 0.8019848717 -0.1479653397 0.130353134791 +1403636955601666560.0000000000 0.4812853133 7.4552847071 -0.6994893177 0.5639020414 0.8016396041 -0.1492660488 0.130797857258 +1403636955651666432.0000000000 0.4574954965 7.4931826446 -0.7064709517 0.5633640784 0.8016971941 -0.1499288308 0.131999507257 +1403636955701666560.0000000000 0.4331442200 7.5307671885 -0.7134237132 0.5633791374 0.8014662187 -0.1507226411 0.132433127765 +1403636955751666432.0000000000 0.4081765061 7.5680232199 -0.7195584587 0.5629607290 0.8015931964 -0.1516300883 0.132408011285 +1403636955801666560.0000000000 0.3829214403 7.6054920221 -0.7240239143 0.5629404646 0.8014158828 -0.1514999098 0.133710110055 +1403636955851666432.0000000000 0.3570068854 7.6428698346 -0.7265406782 0.5624783560 0.8016077094 -0.1532187642 0.132541275041 +1403636955901666560.0000000000 0.3305272208 7.6800898140 -0.7266251200 0.5630577554 0.8011648333 -0.1556682374 0.129877918727 +1403636955951666432.0000000000 0.3035472720 7.7167738835 -0.7247881159 0.5630728057 0.8010463419 -0.1596637820 0.125623446559 +1403636956001666560.0000000000 0.2765628168 7.7522738013 -0.7202000458 0.5645249424 0.7999009208 -0.1644566821 0.120100399667 +1403636956051666432.0000000000 0.2500781779 7.7875376780 -0.7136021502 0.5659432783 0.7986474941 -0.1695692321 0.114527993978 +1403636956101666560.0000000000 0.2242113422 7.8217886598 -0.7053093810 0.5672791071 0.7974607338 -0.1741403385 0.10920593011 +1403636956151666432.0000000000 0.1995839087 7.8547700813 -0.6970812252 0.5669420628 0.7974500856 -0.1768441445 0.106659303374 +1403636956201666560.0000000000 0.1759804632 7.8869711390 -0.6897089442 0.5676206065 0.7966678625 -0.1795448180 0.104359102866 +1403636956251666432.0000000000 0.1537197283 7.9185809084 -0.6845454281 0.5674969643 0.7964833140 -0.1809669243 0.103983163541 +1403636956301666560.0000000000 0.1328326875 7.9493520264 -0.6818730988 0.5663406191 0.7971817122 -0.1795036370 0.107415385826 +1403636956351666432.0000000000 0.1133669406 7.9793165932 -0.6814246196 0.5654650672 0.7976551173 -0.1755449999 0.114802110297 +1403636956401666560.0000000000 0.0944542256 8.0086216009 -0.6827326158 0.5636134528 0.7989028395 -0.1717960011 0.120748759009 +1403636956451666432.0000000000 0.0758853502 8.0378163463 -0.6849249091 0.5634591234 0.7989297180 -0.1678475181 0.126697800386 +1403636956501666560.0000000000 0.0571008550 8.0669846587 -0.6885753916 0.5637021024 0.7989357232 -0.1641799216 0.13033266386 +1403636956551666432.0000000000 0.0373765565 8.0963504583 -0.6923950132 0.5674728275 0.7970626146 -0.1605510093 0.129958269724 +1403636956601666560.0000000000 0.0166903759 8.1250614219 -0.6974174943 0.5714229208 0.7955213925 -0.1575900868 0.125646027703 +1403636956651666432.0000000000 -0.0048540902 8.1529149963 -0.7035161461 0.5756092361 0.7941818180 -0.1548945427 0.118139442935 +1403636956701666560.0000000000 -0.0271784477 8.1797310503 -0.7108520029 0.5789885065 0.7937774135 -0.1523304365 0.107168863657 +1403636956751666432.0000000000 -0.0494325723 8.2048719328 -0.7185728703 0.5801604325 0.7951915806 -0.1478662453 0.0960197699418 +1403636956801666560.0000000000 -0.0711240677 8.2286684633 -0.7249666104 0.5810279493 0.7969722085 -0.1417853778 0.0844909907855 +1403636956851666432.0000000000 -0.0921100476 8.2507751419 -0.7296874271 0.5807781431 0.7997044366 -0.1333142367 0.0734634385454 +1403636956901666560.0000000000 -0.1117934195 8.2712985622 -0.7329409112 0.5798296956 0.8029545221 -0.1217934366 0.0650224451952 +1403636956951666432.0000000000 -0.1300761118 8.2911280853 -0.7340019089 0.5804399410 0.8049393539 -0.1082117280 0.0587565601779 +1403636957001666560.0000000000 -0.1473978894 8.3096283897 -0.7335954934 0.5805888013 0.8071036610 -0.0931761074 0.0530898977649 +1403636957051666432.0000000000 -0.1637500676 8.3268353065 -0.7312730630 0.5813050642 0.8085846236 -0.0769196924 0.0485663441733 +1403636957101666560.0000000000 -0.1796564231 8.3435576380 -0.7265997851 0.5816863476 0.8099704093 -0.0609227396 0.0433283843967 +1403636957151666432.0000000000 -0.1952314863 8.3592640750 -0.7208650234 0.5810488099 0.8117109705 -0.0452305266 0.0382332368465 +1403636957201666560.0000000000 -0.2104987928 8.3742613230 -0.7135538645 0.5808085401 0.8127722924 -0.0313616008 0.0328495136827 +1403636957251666432.0000000000 -0.2255692253 8.3889157125 -0.7047973539 0.5809826363 0.8132304450 -0.0202934659 0.0265253648202 +1403636957301666560.0000000000 -0.2402942432 8.4031808400 -0.6968443670 0.5800549565 0.8142278471 -0.0111995931 0.021067260524 +1403636957351666432.0000000000 -0.2547686072 8.4172180886 -0.6900030147 0.5798802542 0.8145322787 -0.0032352809 0.0162969537273 +1403636957401666560.0000000000 -0.2692854435 8.4309078645 -0.6849906506 0.5796379452 0.8147962063 0.0024974637 0.0109889630233 +1403636957451666432.0000000000 -0.2836123491 8.4444058919 -0.6820012316 0.5794540915 0.8149406471 0.0073424100 0.00712646973656 +1403636957501666560.0000000000 -0.2981133407 8.4579840288 -0.6809361544 0.5795723269 0.8148489596 0.0103028668 0.00330786282423 +1403636957551666432.0000000000 -0.3126737575 8.4711922279 -0.6817727259 0.5792738487 0.8150284027 0.0130471793 -0.000531128747991 +1403636957601666560.0000000000 -0.3272221370 8.4841214759 -0.6843297647 0.5797056091 0.8146481550 0.0163699310 -0.00467073350419 +1403636957651666432.0000000000 -0.3418195687 8.4965913614 -0.6889535296 0.5796094890 0.8145844440 0.0205385567 -0.00912093398717 +1403636957701666560.0000000000 -0.3563928616 8.5084656440 -0.6953059587 0.5797068451 0.8142989691 0.0254607897 -0.0144537495722 +1403636957751666432.0000000000 -0.3711242525 8.5197129989 -0.7031783285 0.5789202513 0.8145035452 0.0314938037 -0.0210584372392 +1403636957801666560.0000000000 -0.3859645609 8.5303131210 -0.7122232161 0.5776831580 0.8147678988 0.0396412980 -0.0293940049756 +1403636957851666432.0000000000 -0.4006011630 8.5400939034 -0.7221304343 0.5765514515 0.8146300856 0.0494830113 -0.0389573986409 +1403636957901666560.0000000000 -0.4150287540 8.5491977278 -0.7329240907 0.5753859021 0.8141193347 0.0612873278 -0.0488327353202 +1403636957951666432.0000000000 -0.4287815700 8.5572736471 -0.7431877598 0.5742092307 0.8131945115 0.0746582816 -0.0585199698338 +1403636958001666560.0000000000 -0.4419593706 8.5646841733 -0.7519526592 0.5730249452 0.8117981157 0.0883837988 -0.069386854823 +1403636958051666432.0000000000 -0.4544137836 8.5724860109 -0.7587121790 0.5710077109 0.8106589758 0.1018648261 -0.0800360934329 +1403636958101666560.0000000000 -0.4659612898 8.5807058237 -0.7637787867 0.5695827475 0.8088506582 0.1163003224 -0.0883761366657 +1403636958151666432.0000000000 -0.4765706330 8.5895045871 -0.7669398010 0.5677510875 0.8073711279 0.1289178316 -0.0958684367491 +1403636958201666560.0000000000 -0.4867341681 8.5991648001 -0.7677163607 0.5656285776 0.8061141401 0.1395364183 -0.10379736693 +1403636958251666432.0000000000 -0.4959135170 8.6085928955 -0.7649300246 0.5644953617 0.8041473467 0.1498549028 -0.110614372923 +1403636958301666560.0000000000 -0.5042344733 8.6176425183 -0.7605420533 0.5640132759 0.8016440767 0.1600442164 -0.116797464125 +1403636958351666432.0000000000 -0.5118695650 8.6268113458 -0.7546836647 0.5620246893 0.8002203206 0.1702205530 -0.121657924117 +1403636958401666560.0000000000 -0.5185035327 8.6364794784 -0.7471000708 0.5609767733 0.7985017148 0.1794653839 -0.124467856122 +1403636958451666432.0000000000 -0.5247034015 8.6462168906 -0.7375512049 0.5599665589 0.7971668156 0.1862436616 -0.127576719972 +1403636958501666560.0000000000 -0.5303284652 8.6559572913 -0.7290439648 0.5584148784 0.7965418993 0.1922674278 -0.129333145094 +1403636958551666432.0000000000 -0.5358593634 8.6662800155 -0.7216796877 0.5577806127 0.7957028623 0.1967129610 -0.130544069417 +1403636958601666560.0000000000 -0.5414933855 8.6769693375 -0.7154176898 0.5576659663 0.7948445053 0.1993191229 -0.132298033535 +1403636958651666432.0000000000 -0.5470406964 8.6881970796 -0.7100422829 0.5574412506 0.7943172134 0.2016124126 -0.132935517145 +1403636958701666560.0000000000 -0.5526245918 8.6999441474 -0.7053368059 0.5580511123 0.7935277146 0.2030639917 -0.132882419912 +1403636958751666432.0000000000 -0.5578627034 8.7114785422 -0.7017531696 0.5582293513 0.7932504709 0.2039301614 -0.132461960756 +1403636958801666560.0000000000 -0.5633867736 8.7232938654 -0.6989356662 0.5582124194 0.7932209176 0.2039085365 -0.132743283927 +1403636958851666432.0000000000 -0.5692647786 8.7353927324 -0.6971275672 0.5580108777 0.7934742729 0.2035511908 -0.132624851861 +1403636958901666560.0000000000 -0.5749484503 8.7477258149 -0.6969993594 0.5576033989 0.7940581680 0.2037189642 -0.130570513386 +1403636958951666432.0000000000 -0.5808351509 8.7605466828 -0.6978629846 0.5582478686 0.7939924571 0.2034360560 -0.12864317476 +1403636959001666560.0000000000 -0.5869687339 8.7732102465 -0.7001925555 0.5582722946 0.7943749766 0.2024468097 -0.127733045501 +1403636959051666432.0000000000 -0.5933122072 8.7859599904 -0.7041054259 0.5581996945 0.7948405181 0.2014695130 -0.126695253062 +1403636959101666560.0000000000 -0.5997534686 8.7984093628 -0.7095629220 0.5572074702 0.7959531978 0.2001814094 -0.126117982062 +1403636959151666432.0000000000 -0.6066539598 8.8111353703 -0.7162752480 0.5569476704 0.7965289319 0.1986495298 -0.12605283562 +1403636959201666560.0000000000 -0.6138151643 8.8240767180 -0.7244255842 0.5572816418 0.7966605311 0.1978748454 -0.124958854987 +1403636959251666432.0000000000 -0.6211064225 8.8369872960 -0.7338955841 0.5580919810 0.7964162547 0.1975998644 -0.123323896878 +1403636959301666560.0000000000 -0.6286047721 8.8501020981 -0.7448686714 0.5593000865 0.7959059972 0.1984877686 -0.119664792349 +1403636959351666432.0000000000 -0.6364145723 8.8628995092 -0.7572719032 0.5603377586 0.7953498424 0.2001586311 -0.115657887608 +1403636959401666560.0000000000 -0.6450234920 8.8754695037 -0.7708690819 0.5612073162 0.7950158327 0.2002431084 -0.113573198607 +1403636959451666432.0000000000 -0.6544678860 8.8877643491 -0.7858112931 0.5628194749 0.7940276206 0.2006236422 -0.111823658152 +1403636959501666560.0000000000 -0.6646595032 8.8995689139 -0.8017148742 0.5648574583 0.7927935644 0.2002930494 -0.110892336834 +1403636959551666432.0000000000 -0.6759958831 8.9105713367 -0.8167305041 0.5670979441 0.7914846415 0.1972177368 -0.114267880035 +1403636959601666560.0000000000 -0.6877594009 8.9210697252 -0.8307791658 0.5693301130 0.7901643969 0.1938988377 -0.11792662537 +1403636959651666432.0000000000 -0.6993998368 8.9309730065 -0.8438745486 0.5695549830 0.7901715414 0.1924755626 -0.119118488368 +1403636959701666560.0000000000 -0.7108404445 8.9402415006 -0.8552379614 0.5680256574 0.7915804406 0.1909378192 -0.119540820709 +1403636959751666432.0000000000 -0.7232860448 8.9506007019 -0.8638385468 0.5667363140 0.7927854782 0.1894923571 -0.119974091101 +1403636959801666560.0000000000 -0.7357453147 8.9606707462 -0.8700815022 0.5652359170 0.7940123100 0.1891626852 -0.119458311554 +1403636959851666432.0000000000 -0.7479225160 8.9694635189 -0.8742559467 0.5644035955 0.7947924363 0.1882147360 -0.119702872847 +1403636959901666560.0000000000 -0.7597940029 8.9778219131 -0.8772153975 0.5631800770 0.7959092363 0.1877555581 -0.118762531261 +1403636959951666432.0000000000 -0.7715228556 8.9854199089 -0.8780930683 0.5624855202 0.7964937422 0.1875807624 -0.118411214629 +1403636960001666560.0000000000 -0.7833899862 8.9929871178 -0.8768191020 0.5622891678 0.7967505097 0.1868242327 -0.118811713301 +1403636960051666432.0000000000 -0.7952004607 9.0007206071 -0.8745664205 0.5623495369 0.7967599544 0.1869000995 -0.118342411088 +1403636960101666560.0000000000 -0.8074463651 9.0087918077 -0.8708016691 0.5626466305 0.7965790859 0.1865846175 -0.118645310527 +1403636960151666432.0000000000 -0.8195455713 9.0170326506 -0.8665276728 0.5629969650 0.7963947509 0.1874493378 -0.116844186425 +1403636960201666560.0000000000 -0.8318998419 9.0251088252 -0.8630625852 0.5631398406 0.7962414564 0.1884309570 -0.115615040404 +1403636960251666432.0000000000 -0.8439941429 9.0329872529 -0.8610123222 0.5644942895 0.7951537982 0.1922351474 -0.110101237633 +1403636960301666560.0000000000 -0.8568443187 9.0407783455 -0.8604741945 0.5648714502 0.7947986629 0.1945534146 -0.106603466237 +1403636960351666432.0000000000 -0.8704452710 9.0483519783 -0.8608641956 0.5659575294 0.7938954022 0.1966230981 -0.1037377591 +1403636960401666560.0000000000 -0.8849683529 9.0558832710 -0.8618664956 0.5682476894 0.7921725997 0.1973806742 -0.10294661344 +1403636960451666432.0000000000 -0.9006323142 9.0626419299 -0.8638543679 0.5706917129 0.7899788215 0.1988998744 -0.103359906822 +1403636960501666560.0000000000 -0.9171575328 9.0684890057 -0.8667515302 0.5729422520 0.7875602508 0.2015532522 -0.104222424018 +1403636960551666432.0000000000 -0.9346397777 9.0732216799 -0.8708511103 0.5747092519 0.7853183127 0.2047921756 -0.105093236242 +1403636960601666560.0000000000 -0.9530310651 9.0768027033 -0.8759692067 0.5762546801 0.7831795029 0.2081866131 -0.105918572808 +1403636960651666432.0000000000 -0.9724074338 9.0792808975 -0.8819408547 0.5771107671 0.7816937328 0.2099971929 -0.108624351067 +1403636960701666560.0000000000 -0.9927718321 9.0804591509 -0.8886565289 0.5758715300 0.7819446843 0.2093887644 -0.114415195783 +1403636960751666432.0000000000 -1.0136680843 9.0802055616 -0.8964792353 0.5729344050 0.7834697106 0.2081028873 -0.120890729674 +1403636960801666560.0000000000 -1.0348144728 9.0787836456 -0.9054501147 0.5694995096 0.7848494612 0.2087004636 -0.126987197026 +1403636960851666432.0000000000 -1.0563087637 9.0764814846 -0.9152436475 0.5664520342 0.7852156217 0.2114752584 -0.133591674148 +1403636960901666560.0000000000 -1.0779176856 9.0734300015 -0.9256039300 0.5633707502 0.7848105789 0.2170118446 -0.139970040817 +1403636960951666432.0000000000 -1.0995170364 9.0695438914 -0.9354152484 0.5606313961 0.7834604030 0.2245804849 -0.146443984093 +1403636961001666560.0000000000 -1.1213006336 9.0652539055 -0.9437962437 0.5591990951 0.7803060615 0.2344257146 -0.153177696717 +1403636961051666432.0000000000 -1.1430710410 9.0605699934 -0.9506762054 0.5573745215 0.7769437682 0.2446741502 -0.160706515141 +1403636961101666560.0000000000 -1.1646948628 9.0551428977 -0.9560409201 0.5549124934 0.7736679577 0.2547442872 -0.169160763743 +1403636961151666432.0000000000 -1.1859248216 9.0491451363 -0.9596144141 0.5526355786 0.7697871669 0.2652017707 -0.178015886106 +1403636961201666560.0000000000 -1.2064211258 9.0427181855 -0.9622890080 0.5493791568 0.7662269177 0.2765900346 -0.185948394747 +1403636961251666432.0000000000 -1.2267981449 9.0362223782 -0.9631243394 0.5461589684 0.7625290190 0.2869494850 -0.194730248178 +1403636961301666560.0000000000 -1.2470734133 9.0304570492 -0.9621690575 0.5438380117 0.7583521095 0.2980982174 -0.200698150969 +1403636961351666432.0000000000 -1.2671109849 9.0249388355 -0.9591564650 0.5424548162 0.7540569898 0.3074539768 -0.206428875637 +1403636961401666560.0000000000 -1.2867542698 9.0192745345 -0.9536621982 0.5404860286 0.7506451688 0.3154758686 -0.211852920239 +1403636961451666432.0000000000 -1.3050841851 9.0128399385 -0.9463801380 0.5388356523 0.7477136176 0.3220160190 -0.216532143774 +1403636961501666560.0000000000 -1.3232420751 9.0064747963 -0.9373913910 0.5365517010 0.7456894735 0.3274200716 -0.221032979273 +1403636961551666432.0000000000 -1.3415762529 9.0002371830 -0.9264778142 0.5348526491 0.7429952746 0.3331907940 -0.225553896813 +1403636961601666560.0000000000 -1.3594398161 8.9935163132 -0.9137429118 0.5326522389 0.7402828185 0.3392060737 -0.230655978789 +1403636961651666432.0000000000 -1.3768772386 8.9864174463 -0.8995685712 0.5303377923 0.7373297065 0.3452495184 -0.236409602134 +1403636961701666560.0000000000 -1.3945178935 8.9796174420 -0.8832608655 0.5287998666 0.7336606808 0.3518848798 -0.241432677636 +1403636961751666432.0000000000 -1.4114532108 8.9723868921 -0.8659281889 0.5267999890 0.7300077198 0.3589009574 -0.246496660112 +1403636961801666560.0000000000 -1.4280194934 8.9650501540 -0.8491366300 0.5249330260 0.7260878804 0.3661417828 -0.25136010625 +1403636961851666432.0000000000 -1.4441414369 8.9573103364 -0.8341077013 0.5216977209 0.7228267623 0.3745084561 -0.255139914657 +1403636961901666560.0000000000 -1.4600710596 8.9493243193 -0.8202507889 0.5199859922 0.7181780911 0.3824317637 -0.259962965587 +1403636961951666432.0000000000 -1.4760703778 8.9408315510 -0.8077574678 0.5174050633 0.7135815021 0.3898772337 -0.266625547976 +1403636962001666560.0000000000 -1.4917305544 8.9321043200 -0.7972503403 0.5138999771 0.7094860814 0.3982500842 -0.271906572802 +1403636962051666432.0000000000 -1.5070641572 8.9229519316 -0.7880021880 0.5098943669 0.7054572043 0.4066526964 -0.277437293887 +1403636962101666560.0000000000 -1.5220215009 8.9134549188 -0.7795489735 0.5063100779 0.7008173974 0.4153119732 -0.282879913449 +1403636962151666432.0000000000 -1.5367199297 8.9035693093 -0.7705967459 0.5027703076 0.6958189485 0.4238644415 -0.288785290245 +1403636962201666560.0000000000 -1.5511141752 8.8935329337 -0.7602642397 0.4993271824 0.6905984417 0.4320870990 -0.295037109763 +1403636962251666432.0000000000 -1.5654017531 8.8832863413 -0.7484534554 0.4972294412 0.6839555446 0.4406261172 -0.301357463218 +1403636962301666560.0000000000 -1.5791831123 8.8725004430 -0.7352817274 0.4938270972 0.6779513806 0.4499010279 -0.306766668178 +1403636962351666432.0000000000 -1.5924478096 8.8609380457 -0.7208314719 0.4896298643 0.6723152456 0.4582098246 -0.313526016701 +1403636962401666560.0000000000 -1.6057682247 8.8492072181 -0.7045380943 0.4862991762 0.6656280897 0.4672686985 -0.3195501852 +1403636962451666432.0000000000 -1.6188443996 8.8371450796 -0.6866924753 0.4824397005 0.6592759312 0.4762886095 -0.325202002431 +1403636962501666560.0000000000 -1.6316304099 8.8249475237 -0.6673946387 0.4798067188 0.6518045352 0.4862908329 -0.329328994037 +1403636962551666432.0000000000 -1.6440533192 8.8121919408 -0.6474939997 0.4769973359 0.6439742492 0.4968007502 -0.33310617308 +1403636962601666560.0000000000 -1.6562005812 8.7988355554 -0.6273977428 0.4741007125 0.6360483959 0.5073028238 -0.336622633544 +1403636962651666432.0000000000 -1.6680899557 8.7850888386 -0.6084956658 0.4720055682 0.6281285451 0.5171264397 -0.339478305289 +1403636962701666560.0000000000 -1.6797553841 8.7706704950 -0.5909303783 0.4707153896 0.6204044185 0.5262978897 -0.341373564981 +1403636962751666432.0000000000 -1.6914853223 8.7551536319 -0.5748111507 0.4697086930 0.6136959255 0.5336236112 -0.343506763233 +1403636962801666560.0000000000 -1.7030760052 8.7386442413 -0.5604619453 0.4676144497 0.6093548619 0.5390847773 -0.345558940901 +1403636962851666432.0000000000 -1.7148422113 8.7209393081 -0.5475437821 0.4667514679 0.6052304271 0.5430151532 -0.347812795583 +1403636962901666560.0000000000 -1.7264437996 8.7016833669 -0.5361914000 0.4641939917 0.6036788468 0.5445085472 -0.351576776878 +1403636962951666432.0000000000 -1.7378225638 8.6810358229 -0.5261139657 0.4617071160 0.6030844721 0.5441075706 -0.356458426933 +1403636963001666560.0000000000 -1.7491987335 8.6595896897 -0.5167373885 0.4615806755 0.6014942488 0.5417931208 -0.362778393726 +1403636963051666432.0000000000 -1.7601897850 8.6374867162 -0.5086065675 0.4627425091 0.5997065652 0.5389169526 -0.36849684411 +1403636963101666560.0000000000 -1.7702209658 8.6146547578 -0.5021628911 0.4636736079 0.5986993995 0.5362987324 -0.372759284349 +1403636963151666432.0000000000 -1.7792593576 8.5913029639 -0.4973689839 0.4638179461 0.5987241570 0.5346397978 -0.374916768514 +1403636963201666560.0000000000 -1.7873140055 8.5673772361 -0.4941014128 0.4632746851 0.6000113680 0.5337525545 -0.374794790467 +1403636963251666432.0000000000 -1.7943731180 8.5427673620 -0.4922741976 0.4599834275 0.6034802963 0.5328531368 -0.374558824549 +1403636963301666560.0000000000 -1.8004943360 8.5178116421 -0.4913533431 0.4565781719 0.6070212230 0.5314579350 -0.374985427823 +1403636963351666432.0000000000 -1.8061093407 8.4926175410 -0.4912223108 0.4535003113 0.6107917269 0.5295064802 -0.375358257417 +1403636963401666560.0000000000 -1.8113503337 8.4675533869 -0.4919820692 0.4520743789 0.6133449237 0.5280773937 -0.374928028753 +1403636963451666432.0000000000 -1.8157674664 8.4427613129 -0.4936893051 0.4519191577 0.6149268300 0.5275522899 -0.373259494357 +1403636963501666560.0000000000 -1.8190904465 8.4181972755 -0.4953331370 0.4532737915 0.6155894993 0.5272908549 -0.370886495452 +1403636963551666432.0000000000 -1.8215083906 8.3935554967 -0.4958740995 0.4543416212 0.6162881217 0.5264467627 -0.369616623313 +1403636963601666560.0000000000 -1.8224806168 8.3689375783 -0.4955240113 0.4556795490 0.6169037679 0.5260498245 -0.367501662422 +1403636963651666432.0000000000 -1.8233031951 8.3442286377 -0.4938731410 0.4567726791 0.6177594302 0.5253923057 -0.365643174557 +1403636963701666560.0000000000 -1.8249160362 8.3194078988 -0.4898888638 0.4580097103 0.6185516816 0.5246148718 -0.363868326126 +1403636963751666432.0000000000 -1.8262151738 8.2940523189 -0.4833982006 0.4588235278 0.6193872889 0.5236327007 -0.362834881871 +1403636963801666560.0000000000 -1.8261985471 8.2681265130 -0.4757972247 0.4593911318 0.6203266380 0.5229091046 -0.361553202981 +1403636963851666432.0000000000 -1.8260589760 8.2418980332 -0.4664480959 0.4603581001 0.6206503000 0.5219898262 -0.361095896144 +1403636963901666560.0000000000 -1.8256378564 8.2155306449 -0.4548950671 0.4616682394 0.6208267053 0.5211862374 -0.360279814341 +1403636963951666432.0000000000 -1.8242398237 8.1886360610 -0.4420648876 0.4620528331 0.6213126636 0.5201538928 -0.3604409538 +1403636964001666560.0000000000 -1.8228338617 8.1613864482 -0.4275537972 0.4626575141 0.6213321765 0.5199422978 -0.359936602837 +1403636964051666432.0000000000 -1.8209374338 8.1337420508 -0.4114687592 0.4630467039 0.6215260618 0.5193711320 -0.359926008758 +1403636964101666560.0000000000 -1.8182487447 8.1057472328 -0.3944560880 0.4636152804 0.6210163056 0.5196915175 -0.359611382738 +1403636964151666432.0000000000 -1.8150892153 8.0775746133 -0.3775036528 0.4644309559 0.6203449805 0.5197445515 -0.359640923093 +1403636964201666560.0000000000 -1.8114894079 8.0491985695 -0.3616428114 0.4655137129 0.6193840576 0.5194059151 -0.360385720607 +1403636964251666432.0000000000 -1.8070529996 8.0203914152 -0.3477810620 0.4654278445 0.6190903619 0.5197234208 -0.360543494427 +1403636964301666560.0000000000 -1.8021936022 7.9914375816 -0.3357932104 0.4659352471 0.6184046811 0.5210680798 -0.359121222027 +1403636964351666432.0000000000 -1.7971544101 7.9618390862 -0.3251209967 0.4662599482 0.6176551594 0.5213426077 -0.359590948442 +1403636964401666560.0000000000 -1.7918195789 7.9318645979 -0.3159917048 0.4666054342 0.6169874775 0.5220919500 -0.359201638522 +1403636964451666432.0000000000 -1.7860023101 7.9013866003 -0.3083851537 0.4667347777 0.6160884884 0.5231148557 -0.359088386641 +1403636964501666560.0000000000 -1.7798282419 7.8705985525 -0.3020706732 0.4676013381 0.6145582066 0.5246032011 -0.358411328896 +1403636964551666432.0000000000 -1.7729688766 7.8388475737 -0.2970625426 0.4674040223 0.6128402475 0.5273281743 -0.357610552883 +1403636964601666560.0000000000 -1.7657398946 7.8063938112 -0.2931344006 0.4695819751 0.6080470092 0.5313910694 -0.356924550137 +1403636964651666432.0000000000 -1.7580352799 7.7724056296 -0.2902815780 0.4687117903 0.6044498470 0.5355471251 -0.35796496607 +1403636964701666560.0000000000 -1.7497356626 7.7374171847 -0.2889324057 0.4675395461 0.5999114016 0.5410344053 -0.358880001447 +1403636964751666432.0000000000 -1.7410506846 7.7013907751 -0.2888285085 0.4665047027 0.5943600649 0.5471534368 -0.360184108723 +1403636964801666560.0000000000 -1.7318074448 7.6638528839 -0.2896466676 0.4650742786 0.5881442610 0.5533500795 -0.36276153753 +1403636964851666432.0000000000 -1.7218706671 7.6243454548 -0.2901436535 0.4608720011 0.5826428466 0.5586422899 -0.368840214536 +1403636964901666560.0000000000 -1.7109246255 7.5829734796 -0.2891236578 0.4561387590 0.5764368478 0.5632746871 -0.377332240795 +1403636964951666432.0000000000 -1.6986944543 7.5404210791 -0.2868282069 0.4528850480 0.5684448690 0.5693891073 -0.384137486821 +1403636965001666560.0000000000 -1.6855476785 7.4960113761 -0.2828065592 0.4476973513 0.5609371323 0.5758972631 -0.391483023336 +1403636965051666432.0000000000 -1.6713178528 7.4502079903 -0.2770679362 0.4409284333 0.5548911559 0.5813665052 -0.399613448807 +1403636965101666560.0000000000 -1.6561900598 7.4038465070 -0.2698875178 0.4352949924 0.5490697316 0.5887558117 -0.402997882891 +1403636965151666432.0000000000 -1.6403501236 7.3568420650 -0.2608555394 0.4288296666 0.5448489124 0.5944230149 -0.407315674927 +1403636965201666560.0000000000 -1.6236902171 7.3095023775 -0.2504915232 0.4218995546 0.5422674835 0.6012046599 -0.408043746532 +1403636965251666432.0000000000 -1.6065757403 7.2615644709 -0.2384347069 0.4149251558 0.5406400833 0.6079691554 -0.407331463835 +1403636965301666560.0000000000 -1.5893747415 7.2132292001 -0.2259702217 0.4062335513 0.5418433991 0.6152361318 -0.403564783818 +1403636965351666432.0000000000 -1.5722436530 7.1643019211 -0.2120022317 0.3978215082 0.5435557341 0.6225051449 -0.398462741311 +1403636965401666560.0000000000 -1.5560480305 7.1147601894 -0.1963744852 0.3895485793 0.5462013125 0.6289352749 -0.392882234954 +1403636965451666432.0000000000 -1.5410741440 7.0645943661 -0.1781340501 0.3820208655 0.5492758095 0.6331959626 -0.389125964762 +1403636965501666560.0000000000 -1.5286945909 7.0137148449 -0.1571269694 0.3757373510 0.5524182035 0.6342155218 -0.389135250846 +1403636965551666432.0000000000 -1.5195098220 6.9628138232 -0.1332005033 0.3737879558 0.5534063804 0.6320895080 -0.393048083746 +1403636965601666560.0000000000 -1.5137051174 6.9113699698 -0.1052075608 0.3749268701 0.5531151862 0.6257576163 -0.402393884833 +1403636965651666432.0000000000 -1.5101069189 6.8597625048 -0.0747742056 0.3780984858 0.5514388572 0.6183661560 -0.413013339885 +1403636965701666560.0000000000 -1.5074497374 6.8081353242 -0.0444365051 0.3798927306 0.5510254493 0.6107619391 -0.423110294352 +1403636965751666432.0000000000 -1.5052161072 6.7572607776 -0.0159030263 0.3816795498 0.5506976744 0.6047399224 -0.430514133277 +1403636965801666560.0000000000 -1.5028823529 6.7076343081 0.0097878556 0.3857524405 0.5487951992 0.6015075989 -0.433828874551 +1403636965851666432.0000000000 -1.5001996219 6.6593953669 0.0325668382 0.3916108691 0.5457704878 0.6010031721 -0.433094318805 +1403636965901666560.0000000000 -1.4967953630 6.6123394927 0.0530198197 0.3968894858 0.5432273945 0.6016214213 -0.43062094632 +1403636965951666432.0000000000 -1.4927927543 6.5659210619 0.0714910854 0.4007213774 0.5413987662 0.6026185701 -0.427972677354 +1403636966001666560.0000000000 -1.4884239458 6.5197948639 0.0885166783 0.4049427545 0.5394070157 0.6033553220 -0.425468908876 +1403636966051666432.0000000000 -1.4835842074 6.4732760098 0.1041000441 0.4081044855 0.5379232964 0.6039243500 -0.423514622617 +1403636966101666560.0000000000 -1.4781636069 6.4264099592 0.1182994186 0.4097670261 0.5376051417 0.6035154362 -0.4228957486 +1403636966151666432.0000000000 -1.4723535606 6.3794530928 0.1308804003 0.4120902207 0.5369924533 0.6033730550 -0.421617968838 +1403636966201666560.0000000000 -1.4657498721 6.3322880401 0.1415793445 0.4123796870 0.5374756509 0.6030009175 -0.42125148297 +1403636966251666432.0000000000 -1.4586262869 6.2850989684 0.1508287908 0.4134439914 0.5374156351 0.6017022564 -0.422140848177 +1403636966301666560.0000000000 -1.4511790093 6.2381653161 0.1579283837 0.4142273147 0.5376594140 0.6013978856 -0.421495752576 +1403636966351666432.0000000000 -1.4431802114 6.1905932482 0.1640614463 0.4132345203 0.5391900028 0.5991180615 -0.423755732067 +1403636966401666560.0000000000 -1.4343505387 6.1433583742 0.1687219672 0.4083321904 0.5433643668 0.5949046904 -0.429078543514 +1403636966451666432.0000000000 -1.4246780573 6.0964062775 0.1722055190 0.4026709981 0.5481475644 0.5899716564 -0.435113501892 +1403636966501666560.0000000000 -1.4146618184 6.0517359759 0.1737460096 0.3976816752 0.5523703608 0.5853725377 -0.440539739263 +1403636966551666432.0000000000 -1.4040255128 6.0088359523 0.1734734131 0.3948383734 0.5551563601 0.5823869852 -0.443541964386 +1403636966601666560.0000000000 -1.3928491934 5.9682155285 0.1710801342 0.3956155485 0.5556254020 0.5814967656 -0.44343010951 +1403636966651666432.0000000000 -1.3808007016 5.9297276290 0.1665767188 0.3993200722 0.5543062675 0.5829146984 -0.439884639563 +1403636966701666560.0000000000 -1.3677451786 5.8925541374 0.1607418519 0.4032353934 0.5527885141 0.5853346585 -0.434982084341 +1403636966751666432.0000000000 -1.3538851470 5.8562178238 0.1557375716 0.4077679448 0.5506707789 0.5870521161 -0.431111133518 +1403636966801666560.0000000000 -1.3391064418 5.8201777279 0.1527140944 0.4100187754 0.5498897577 0.5871936840 -0.429778356392 +1403636966851666432.0000000000 -1.3230795992 5.7841412662 0.1514663141 0.4101061964 0.5505085234 0.5867081914 -0.429565794169 +1403636966901666560.0000000000 -1.3064769995 5.7484296083 0.1525469578 0.4096057107 0.5515647666 0.5855465104 -0.430272883433 +1403636966951666432.0000000000 -1.2889931430 5.7131697934 0.1555184220 0.4078070078 0.5532723280 0.5839745330 -0.431922354423 +1403636967001666560.0000000000 -1.2708386796 5.6789558991 0.1589284243 0.4081321046 0.5535759772 0.5834961616 -0.431872726728 +1403636967051666432.0000000000 -1.2519109331 5.6459311512 0.1611925149 0.4097953802 0.5531095974 0.5837873941 -0.430499475174 +1403636967101666560.0000000000 -1.2320423911 5.6134828045 0.1620681053 0.4119046131 0.5519340005 0.5851019072 -0.428204632123 +1403636967151666432.0000000000 -1.2115352916 5.5815155408 0.1612640030 0.4139276291 0.5510563482 0.5860765033 -0.42604594963 +1403636967201666560.0000000000 -1.1902223796 5.5497281460 0.1589699753 0.4150658336 0.5505148152 0.5866494616 -0.424848445111 +1403636967251666432.0000000000 -1.1681376112 5.5180987889 0.1554774358 0.4153332115 0.5507224399 0.5863488598 -0.424733012925 +1403636967301666560.0000000000 -1.1454540081 5.4868666944 0.1506175337 0.4163752545 0.5503971901 0.5869259213 -0.423335025103 +1403636967351666432.0000000000 -1.1220315169 5.4559405613 0.1460384458 0.4180871011 0.5494786085 0.5870666190 -0.422645501046 +1403636967401666560.0000000000 -1.0978208090 5.4250807299 0.1426638794 0.4191738436 0.5490605324 0.5871429368 -0.422005915071 +1403636967451666432.0000000000 -1.0732832564 5.3941796546 0.1413780516 0.4198176622 0.5490356963 0.5870959836 -0.421463214075 +1403636967501666560.0000000000 -1.0477599224 5.3631320621 0.1423936420 0.4194974928 0.5494597272 0.5861950818 -0.422482174555 +1403636967551666432.0000000000 -1.0213887793 5.3326037159 0.1453267410 0.4207758655 0.5490870088 0.5862735433 -0.421585649909 +1403636967601666560.0000000000 -0.9934245760 5.3019530437 0.1497608000 0.4215290902 0.5489864622 0.5860685446 -0.421249037311 +1403636967651666432.0000000000 -0.9646853247 5.2712393299 0.1537462704 0.4221239225 0.5490348224 0.5861147855 -0.420525404802 +1403636967701666560.0000000000 -0.9351872156 5.2405235412 0.1548196595 0.4228382741 0.5490463711 0.5864210220 -0.419364115383 +1403636967751666432.0000000000 -0.9057128310 5.2095700074 0.1524199541 0.4231504210 0.5491217102 0.5859809017 -0.419565789084 +1403636967801666560.0000000000 -0.8753754981 5.1784443830 0.1454080844 0.4231291762 0.5492857563 0.5857335736 -0.419717808589 +1403636967851666432.0000000000 -0.8442732900 5.1472145371 0.1340608659 0.4232156959 0.5491911409 0.5855655438 -0.419988761041 +1403636967901666560.0000000000 -0.8122726933 5.1156815947 0.1202319198 0.4240180253 0.5487421467 0.5853055316 -0.420128796064 +1403636967951666432.0000000000 -0.7797788754 5.0838280998 0.1042589808 0.4245844358 0.5481721361 0.5852863096 -0.42032761265 +1403636968001666560.0000000000 -0.7465887353 5.0517583925 0.0864640289 0.4241776020 0.5485172988 0.5850453271 -0.420623465986 +1403636968051666432.0000000000 -0.7125895914 5.0195624182 0.0674029363 0.4240313055 0.5482730081 0.5853046974 -0.420728620131 +1403636968101666560.0000000000 -0.6781721120 4.9871314484 0.0477145607 0.4234382107 0.5483426685 0.5840661904 -0.422950451981 +1403636968151666432.0000000000 -0.6425505689 4.9549083784 0.0277820602 0.4217752636 0.5494780618 0.5834006363 -0.424055638043 +1403636968201666560.0000000000 -0.6059842937 4.9228519853 0.0085081398 0.4208302704 0.5500833149 0.5832722863 -0.424386227682 +1403636968251666432.0000000000 -0.5683679769 4.8912493586 -0.0085149060 0.4210768915 0.5499544000 0.5840144661 -0.423286561024 +1403636968301666560.0000000000 -0.5293599764 4.8594274911 -0.0236065428 0.4200828648 0.5505197768 0.5840169881 -0.423535736011 +1403636968351666432.0000000000 -0.4896892561 4.8279782022 -0.0364647076 0.4197666525 0.5507650130 0.5847316615 -0.422543183494 +1403636968401666560.0000000000 -0.4488901305 4.7967086132 -0.0472975084 0.4192291216 0.5511467897 0.5848039998 -0.422478924334 +1403636968451666432.0000000000 -0.4079473363 4.7657120835 -0.0561363804 0.4184507826 0.5518445244 0.5848003005 -0.422344849605 +1403636968501666560.0000000000 -0.3659175387 4.7350114013 -0.0627858210 0.4179498683 0.5523464138 0.5847203375 -0.42229548141 +1403636968551666432.0000000000 -0.3230611366 4.7044214613 -0.0674380249 0.4178798434 0.5523974470 0.5844611110 -0.422656724557 +1403636968601666560.0000000000 -0.2802529733 4.6740183786 -0.0708890041 0.4194746885 0.5513427071 0.5853655792 -0.421199885709 +1403636968651666432.0000000000 -0.2370099702 4.6439340613 -0.0726817639 0.4221228081 0.5496775177 0.5872116498 -0.418150020609 +1403636968701666560.0000000000 -0.1925889771 4.6135892607 -0.0736672770 0.4236017400 0.5486235062 0.5881418383 -0.416728919455 +1403636968751666432.0000000000 -0.1475934577 4.5831080221 -0.0756132167 0.4254765185 0.5471787525 0.5897746780 -0.414404360718 +1403636968801666560.0000000000 -0.1023794487 4.5520307473 -0.0783555557 0.4263960690 0.5466966760 0.5901354310 -0.413581080118 +1403636968851666432.0000000000 -0.0564917776 4.5203406515 -0.0808795207 0.4268485665 0.5464758738 0.5901894238 -0.413329002967 +1403636968901666560.0000000000 -0.0096989166 4.4876605700 -0.0817471376 0.4245120187 0.5484999053 0.5885391608 -0.415402282062 +1403636968951666432.0000000000 0.0371307301 4.4545429831 -0.0808427540 0.4237256943 0.5491406349 0.5880397306 -0.416065348628 +1403636969001666560.0000000000 0.0840347068 4.4209011298 -0.0778740445 0.4225907744 0.5499993249 0.5875814446 -0.416732319346 +1403636969051666432.0000000000 0.1319398869 4.3869053663 -0.0728143146 0.4217660594 0.5506259641 0.5863261815 -0.418504537133 +1403636969101666560.0000000000 0.1807125354 4.3525321865 -0.0663351655 0.4188298557 0.5527154141 0.5854979061 -0.419856433698 +1403636969151666432.0000000000 0.2299696759 4.3185392512 -0.0594937058 0.4161750506 0.5546561696 0.5864119162 -0.418659677138 +1403636969201666560.0000000000 0.2796809697 4.2848399080 -0.0511100271 0.4132371160 0.5568981926 0.5881024266 -0.416215118587 +1403636969251666432.0000000000 0.3298216456 4.2512597343 -0.0412295740 0.4089424113 0.5600007929 0.5898367907 -0.413833029873 +1403636969301666560.0000000000 0.3799567528 4.2181378918 -0.0292854572 0.4058581802 0.5624165953 0.5919673779 -0.410537859914 +1403636969351666432.0000000000 0.4296844428 4.1850359262 -0.0162540539 0.4038445454 0.5639699643 0.5939068641 -0.407580788755 +1403636969401666560.0000000000 0.4783920412 4.1519856556 -0.0013791799 0.4027764479 0.5650686867 0.5955659388 -0.404684722798 +1403636969451666432.0000000000 0.5261833644 4.1190636333 0.0135881378 0.4018328640 0.5660469977 0.5965373563 -0.402820466646 +1403636969501666560.0000000000 0.5729023292 4.0863755796 0.0274456959 0.4013232939 0.5668322994 0.5975015426 -0.400790050721 +1403636969551666432.0000000000 0.6184935078 4.0537502114 0.0399459701 0.4009246222 0.5675197353 0.5979763905 -0.399505987112 +1403636969601666560.0000000000 0.6632144546 4.0211715975 0.0508416848 0.4003661148 0.5684228486 0.5981661807 -0.398496749656 +1403636969651666432.0000000000 0.7068481938 3.9885612792 0.0602271815 0.4007342516 0.5685997304 0.5977677450 -0.398472243984 +1403636969701666560.0000000000 0.7494339813 3.9559112455 0.0681067681 0.4009121042 0.5688539070 0.5974650884 -0.398384469148 +1403636969751666432.0000000000 0.7908198870 3.9232282528 0.0748328860 0.4012898065 0.5689856752 0.5967973639 -0.398816623314 +1403636969801666560.0000000000 0.8313761000 3.8904866080 0.0800392952 0.4014718759 0.5689605749 0.5974959641 -0.397621390112 +1403636969851666432.0000000000 0.8708162499 3.8578179799 0.0839783104 0.4009450264 0.5696227964 0.5975268054 -0.397158246165 +1403636969901666560.0000000000 0.9089278403 3.8252435862 0.0867561902 0.4009495088 0.5697282900 0.5970205761 -0.397763244355 +1403636969951666432.0000000000 0.9458385293 3.7927350422 0.0879453461 0.4019823026 0.5689475289 0.5965805166 -0.39849796091 +1403636970001666560.0000000000 0.9814611927 3.7598844556 0.0882273068 0.4026803034 0.5684068744 0.5945514389 -0.401585339562 +1403636970051666432.0000000000 1.0159324277 3.7271512284 0.0875737681 0.4061916781 0.5657825492 0.5922534190 -0.405134934808 +1403636970101666560.0000000000 1.0499572214 3.6943969096 0.0854367538 0.4091876479 0.5633392819 0.5908716924 -0.407535232032 +1403636970151666432.0000000000 1.0836236261 3.6615532954 0.0826360714 0.4125128567 0.5608214566 0.5891875286 -0.410085958087 +1403636970201666560.0000000000 1.1173795051 3.6287211826 0.0793475595 0.4138859672 0.5596947405 0.5878656469 -0.412133697768 +1403636970251666432.0000000000 1.1511236488 3.5959275627 0.0764095401 0.4160758846 0.5577378768 0.5865881006 -0.414395607276 +1403636970301666560.0000000000 1.1854587156 3.5632661518 0.0726908391 0.4150858309 0.5582788256 0.5873075750 -0.413640324589 +1403636970351666432.0000000000 1.2201406248 3.5306057488 0.0691486110 0.4131826888 0.5594152206 0.5880897932 -0.41289837942 +1403636970401666560.0000000000 1.2549438744 3.4980642226 0.0652069618 0.4103924673 0.5613528467 0.5907052664 -0.409302202005 +1403636970451666432.0000000000 1.2891750121 3.4651599626 0.0617312133 0.4070306546 0.5632910601 0.5931832840 -0.40640228763 +1403636970501666560.0000000000 1.3228464237 3.4322807298 0.0591143612 0.4036763607 0.5655185148 0.5947608658 -0.404343564066 +1403636970551666432.0000000000 1.3557709850 3.3994840351 0.0567295055 0.4011330930 0.5669895381 0.5969109494 -0.40163717946 +1403636970601666560.0000000000 1.3877481208 3.3665761204 0.0557150101 0.3986628065 0.5681715427 0.5988840243 -0.399483404216 +1403636970651666432.0000000000 1.4188083747 3.3336427624 0.0567139192 0.3968592166 0.5689022144 0.6008264613 -0.39731674519 +1403636970701666560.0000000000 1.4485220244 3.3005800265 0.0595744476 0.3946871320 0.5697952957 0.6029576634 -0.394965118806 +1403636970751666432.0000000000 1.4764864780 3.2673079936 0.0650657739 0.3917660422 0.5713275114 0.6044125753 -0.39343319848 +1403636970801666560.0000000000 1.5027885705 3.2341783340 0.0716143953 0.3900592802 0.5719095697 0.6064136047 -0.391197829849 +1403636970851666432.0000000000 1.5274999511 3.2008487848 0.0774705466 0.3872166268 0.5732749374 0.6090584651 -0.387900652419 +1403636970901666560.0000000000 1.5500417729 3.1672061645 0.0824963041 0.3841689456 0.5749262026 0.6107681960 -0.385793071007 +1403636970951666432.0000000000 1.5703294705 3.1337647017 0.0865875771 0.3812530457 0.5766094054 0.6115118459 -0.384994767537 +1403636971001666560.0000000000 1.5879490846 3.0999882274 0.0898283402 0.3791094730 0.5778913153 0.6102925110 -0.387118439497 +1403636971051666432.0000000000 1.6030281766 3.0662636456 0.0919576569 0.3773154977 0.5791621724 0.6075297220 -0.391295067866 +1403636971101666560.0000000000 1.6158060742 3.0328656253 0.0930745104 0.3764359648 0.5800089552 0.6032536591 -0.397455153607 +1403636971151666432.0000000000 1.6266704508 3.0001926076 0.0927455862 0.3764851734 0.5799694776 0.5988912790 -0.404009350384 +1403636971201666560.0000000000 1.6359201198 2.9682520703 0.0910649616 0.3749282218 0.5811410212 0.5935284485 -0.411616232357 +1403636971251666432.0000000000 1.6439643973 2.9379123800 0.0878900245 0.3743617782 0.5816966129 0.5884512094 -0.418577930317 +1403636971301666560.0000000000 1.6512050994 2.9094526954 0.0834580744 0.3733422478 0.5823941467 0.5835868049 -0.425275281419 +1403636971351666432.0000000000 1.6577143693 2.8830966437 0.0775755883 0.3714717213 0.5834653419 0.5800123661 -0.430305252426 +1403636971401666560.0000000000 1.6636986523 2.8590549174 0.0702690140 0.3708081683 0.5836536353 0.5779545920 -0.433380001691 +1403636971451666432.0000000000 1.6688321544 2.8373248654 0.0614899079 0.3721286212 0.5827328325 0.5776358716 -0.433911897883 +1403636971501666560.0000000000 1.6734640894 2.8177725357 0.0510446600 0.3736731225 0.5814322306 0.5793957326 -0.431978638122 +1403636971551666432.0000000000 1.6775099252 2.8002653214 0.0396651097 0.3766578888 0.5791186413 0.5807228902 -0.430710295844 +1403636971601666560.0000000000 1.6807145105 2.7846369201 0.0274345142 0.3821857239 0.5752253366 0.5821606421 -0.429114053911 +1403636971651666432.0000000000 1.6836286040 2.7706269026 0.0140485788 0.3887000227 0.5705723068 0.5834299803 -0.427748749979 +1403636971701666560.0000000000 1.6863505580 2.7578356261 -0.0005049548 0.3949762993 0.5658402898 0.5851180683 -0.425975745344 +1403636971751666432.0000000000 1.6891380712 2.7457172866 -0.0156383208 0.3994256210 0.5622553126 0.5853302787 -0.426282302716 +1403636971801666560.0000000000 1.6920892532 2.7342533165 -0.0312831596 0.4016651864 0.5604137480 0.5842386299 -0.428096639085 +1403636971851666432.0000000000 1.6952826895 2.7233624533 -0.0470810316 0.4031244442 0.5588687518 0.5836385422 -0.42956076735 +1403636971901666560.0000000000 1.6992664504 2.7131413183 -0.0618637140 0.4037206545 0.5580685997 0.5835271303 -0.430192002905 +1403636971951666432.0000000000 1.7040451727 2.7036085307 -0.0753308002 0.4034890511 0.5579603858 0.5836899785 -0.430328714517 +1403636972001666560.0000000000 1.7088940482 2.6948434984 -0.0870318602 0.4034209023 0.5575404952 0.5843620457 -0.430024617201 +1403636972051666432.0000000000 1.7138489689 2.6868994449 -0.0957641681 0.4039846737 0.5570356936 0.5843849991 -0.430118346806 +1403636972101666560.0000000000 1.7207277327 2.6797622091 -0.1038418613 0.4044357434 0.5567646095 0.5851227547 -0.429041094779 +1403636972151666432.0000000000 1.7282959934 2.6730410761 -0.1110104344 0.4036682120 0.5575614041 0.5857508642 -0.427870518224 +1403636972201666560.0000000000 1.7369510493 2.6666354534 -0.1158304600 0.3995525027 0.5603674081 0.5861674626 -0.427497217937 +1403636972251666432.0000000000 1.7462446790 2.6609191078 -0.1193167117 0.3954459406 0.5632805357 0.5869833520 -0.426366146163 +1403636972301666560.0000000000 1.7554271364 2.6561203537 -0.1212853640 0.3919616377 0.5658450198 0.5882411033 -0.424450106033 +1403636972351666432.0000000000 1.7638455665 2.6525556949 -0.1210918383 0.3914720621 0.5663073182 0.5899988872 -0.421837597842 +1403636972401666560.0000000000 1.7709145495 2.6496553725 -0.1186602482 0.3912293469 0.5667137994 0.5907656571 -0.420441441949 +1403636972451666432.0000000000 1.7776858068 2.6475314143 -0.1139222712 0.3924977395 0.5660102323 0.5917999480 -0.418749045437 +1403636972501666560.0000000000 1.7845457932 2.6460138553 -0.1073911718 0.3945605593 0.5647116966 0.5916865463 -0.418723889654 +1403636972551666432.0000000000 1.7897740829 2.6447866753 -0.0990891569 0.3961190064 0.5639069722 0.5913253028 -0.418847282135 +1403636972601666560.0000000000 1.7952096561 2.6441370510 -0.0890006351 0.3982934807 0.5627302863 0.5913822582 -0.418286926572 +1403636972651666432.0000000000 1.8008401797 2.6440571537 -0.0783106037 0.4018869660 0.5604871404 0.5914637438 -0.417745941768 +1403636972701666560.0000000000 1.8066453086 2.6438997810 -0.0684660718 0.4028397420 0.5601679442 0.5912401796 -0.417572827916 +1403636972751666432.0000000000 1.8125517783 2.6438682349 -0.0600341377 0.4036019467 0.5599225497 0.5914492586 -0.416869261835 +1403636972801666560.0000000000 1.8184154109 2.6437219721 -0.0530952258 0.4034262558 0.5602101569 0.5911442338 -0.417085520108 +1403636972851666432.0000000000 1.8243075093 2.6437076810 -0.0480140596 0.4032519226 0.5605229934 0.5912153147 -0.416732902998 +1403636972901666560.0000000000 1.8301613454 2.6439275151 -0.0445036617 0.4039853022 0.5608377499 0.5910441684 -0.415840937068 +1403636972951666432.0000000000 1.8360057930 2.6445033971 -0.0429184205 0.4040052858 0.5631594787 0.5901223158 -0.413988868282 +1403636973001666560.0000000000 1.8414790537 2.6456999218 -0.0432065015 0.4053785655 0.5666150645 0.5884181719 -0.41034088544 +1403636973051666432.0000000000 1.8465694010 2.6468303365 -0.0447621988 0.4062944703 0.5711664805 0.5857516478 -0.40692586805 +1403636973101666560.0000000000 1.8514549945 2.6481457384 -0.0475785380 0.4075207196 0.5756852955 0.5826165481 -0.403820828541 +1403636973151666432.0000000000 1.8560975596 2.6495323328 -0.0516406427 0.4095241213 0.5790409359 0.5798648140 -0.400946861936 +1403636973201666560.0000000000 1.8606613713 2.6507755072 -0.0571149590 0.4105033559 0.5825299107 0.5771562552 -0.398793875431 +1403636973251666432.0000000000 1.8648883701 2.6522279071 -0.0638664021 0.4134916310 0.5840789567 0.5746825829 -0.397009284963 +1403636973301666560.0000000000 1.8690335535 2.6536000983 -0.0718357629 0.4154385951 0.5860166111 0.5724433043 -0.395352967085 +1403636973351666432.0000000000 1.8728721424 2.6549051610 -0.0810204367 0.4167858369 0.5878492759 0.5702840404 -0.394333498761 +1403636973401666560.0000000000 1.8761744126 2.6561659635 -0.0914963312 0.4187828779 0.5888110541 0.5691407056 -0.392429995039 +1403636973451666432.0000000000 1.8790985367 2.6568908898 -0.1027334606 0.4187777806 0.5908144501 0.5674884470 -0.391816690061 +1403636973501666560.0000000000 1.8816320871 2.6577467900 -0.1149304407 0.4203604222 0.5913668861 0.5665444046 -0.390652990682 +1403636973551666432.0000000000 1.8838859448 2.6584764487 -0.1279093945 0.4226910445 0.5911442352 0.5658180269 -0.389526295049 +1403636973601666560.0000000000 1.8858167480 2.6587697468 -0.1414929428 0.4244138063 0.5911298930 0.5639476744 -0.390386207773 +1403636973651666432.0000000000 1.8877425733 2.6589195402 -0.1556741235 0.4264171894 0.5906211654 0.5626733289 -0.390811648423 +1403636973701666560.0000000000 1.8897527132 2.6588168135 -0.1694462964 0.4275024978 0.5903366668 0.5620717275 -0.390921484905 +1403636973751666432.0000000000 1.8916448840 2.6587615524 -0.1811617455 0.4303816423 0.5887887486 0.5610609208 -0.391548329898 +1403636973801666560.0000000000 1.8936080997 2.6584266161 -0.1912633843 0.4319100832 0.5876630705 0.5606056006 -0.392208052101 +1403636973851666432.0000000000 1.8961875424 2.6577359384 -0.1996771423 0.4331784231 0.5867177817 0.5606983595 -0.392091887341 +1403636973901666560.0000000000 1.8991773520 2.6565336167 -0.2058726358 0.4331689732 0.5865513588 0.5602539717 -0.392985535861 +1403636973951666432.0000000000 1.9022585431 2.6548962550 -0.2095480259 0.4322979363 0.5871046742 0.5594159984 -0.394309949915 +1403636974001666560.0000000000 1.9063125142 2.6530706548 -0.2121941843 0.4302571066 0.5893035328 0.5592456443 -0.393502830763 +1403636974051666432.0000000000 1.9105760060 2.6515477354 -0.2139322609 0.4286287666 0.5926759048 0.5575483680 -0.392622553677 +1403636974101666560.0000000000 1.9144756501 2.6505587333 -0.2147351281 0.4276505640 0.5972187815 0.5550291330 -0.390368266778 +1403636974151666432.0000000000 1.9181865192 2.6501427423 -0.2161742530 0.4276051269 0.6030446688 0.5515479467 -0.386375265018 +1403636974201666560.0000000000 1.9215367737 2.6506910627 -0.2186802048 0.4304560314 0.6088966849 0.5465284263 -0.381128733249 +1403636974251666432.0000000000 1.9240204059 2.6519882342 -0.2227078958 0.4355871462 0.6144974607 0.5404615059 -0.374910748623 +1403636974301666560.0000000000 1.9259248803 2.6536485029 -0.2281241758 0.4406898956 0.6210384193 0.5337061357 -0.367779089231 +1403636974351666432.0000000000 1.9278071798 2.6556679463 -0.2344139908 0.4474035623 0.6272178800 0.5254248310 -0.361049207904 +1403636974401666560.0000000000 1.9295878226 2.6575022041 -0.2422709871 0.4528976348 0.6344299384 0.5164771829 -0.354448452179 +1403636974451666432.0000000000 1.9309872201 2.6596882177 -0.2513027194 0.4604372374 0.6408794389 0.5062307760 -0.34785269379 +1403636974501666560.0000000000 1.9324726795 2.6616004812 -0.2615932894 0.4665943700 0.6481104093 0.4954091049 -0.341778305318 +1403636974551666432.0000000000 1.9339787035 2.6636327990 -0.2729813430 0.4733946285 0.6548694497 0.4849676399 -0.334439707249 +1403636974601666560.0000000000 1.9349819491 2.6657320107 -0.2852323502 0.4801920273 0.6617426934 0.4734774083 -0.327614664638 +1403636974651666432.0000000000 1.9360729068 2.6675058920 -0.2981081151 0.4851410788 0.6694097125 0.4631915455 -0.319346775023 +1403636974701666560.0000000000 1.9378849028 2.6686942832 -0.3099452217 0.4883582051 0.6774752071 0.4529077063 -0.312102894699 +1403636974751666432.0000000000 1.9406394240 2.6693281361 -0.3203910637 0.4904948670 0.6858219634 0.4429065827 -0.304789729093 +1403636974801666560.0000000000 1.9430913782 2.6697598394 -0.3286830432 0.4916009406 0.6941639762 0.4332910420 -0.297865342454 +1403636974851666432.0000000000 1.9456269058 2.6697505567 -0.3343982981 0.4911608272 0.7029044041 0.4228612500 -0.293044030451 +1403636974901666560.0000000000 1.9477523803 2.6698861065 -0.3385790935 0.4898440485 0.7118624241 0.4130724442 -0.287534090429 +1403636974951666432.0000000000 1.9495623388 2.6706524755 -0.3403568379 0.4895825861 0.7196219033 0.4029642665 -0.282971743435 +1403636975001666560.0000000000 1.9513725360 2.6721247153 -0.3406544289 0.4895574330 0.7265396635 0.3943990268 -0.27735003999 +1403636975051666432.0000000000 1.9522331761 2.6749495844 -0.3391033628 0.4913935844 0.7318257626 0.3855934482 -0.272545576145 +1403636975101666560.0000000000 1.9525919440 2.6792209920 -0.3365979230 0.4962850732 0.7344506296 0.3784040191 -0.26663420102 +1403636975151666432.0000000000 1.9526594672 2.6840863040 -0.3342747983 0.5017470676 0.7355364053 0.3722202252 -0.262084300417 +1403636975201666560.0000000000 1.9522087381 2.6896818793 -0.3326830585 0.5081757037 0.7351852203 0.3672227620 -0.25769669963 +1403636975251666432.0000000000 1.9514304311 2.6955319890 -0.3321513508 0.5145477631 0.7339098335 0.3635279931 -0.253898314277 +1403636975301666560.0000000000 1.9507065402 2.7011487264 -0.3329167686 0.5196145037 0.7327373381 0.3603717659 -0.251453676252 +1403636975351666432.0000000000 1.9498325362 2.7064655631 -0.3351678444 0.5240120113 0.7313234057 0.3575219049 -0.250510630063 +1403636975401666560.0000000000 1.9493644877 2.7114028081 -0.3398073100 0.5260420842 0.7311001091 0.3569353846 -0.247728656497 +1403636975451666432.0000000000 1.9490165800 2.7157250673 -0.3455277284 0.5266307853 0.7314576269 0.3561960774 -0.246483489226 +1403636975501666560.0000000000 1.9489670722 2.7194819386 -0.3526152911 0.5257767111 0.7323802061 0.3567342002 -0.24478315734 +1403636975551666432.0000000000 1.9489025767 2.7229174763 -0.3594365363 0.5236687694 0.7339250258 0.3579943193 -0.2428273951 +1403636975601666560.0000000000 1.9486303508 2.7261615874 -0.3647973433 0.5215261661 0.7352545160 0.3596663303 -0.240938551301 +1403636975651666432.0000000000 1.9481079122 2.7290256652 -0.3678223854 0.5194760617 0.7360992108 0.3613368060 -0.240287922939 +1403636975701666560.0000000000 1.9472762170 2.7317506269 -0.3687670623 0.5176718075 0.7366998236 0.3631856113 -0.239552669371 +1403636975751666432.0000000000 1.9458173019 2.7343562440 -0.3675495457 0.5157637869 0.7371346211 0.3652040474 -0.23926192801 +1403636975801666560.0000000000 1.9437216074 2.7371390263 -0.3642353720 0.5145588831 0.7375103114 0.3661502237 -0.239252398313 +1403636975851666432.0000000000 1.9401514472 2.7410832493 -0.3595416842 0.5140786311 0.7384709504 0.3659128646 -0.237679599412 +1403636975901666560.0000000000 1.9355747979 2.7456873639 -0.3546638544 0.5140977457 0.7404644991 0.3636544551 -0.234885654623 +1403636975951666432.0000000000 1.9300524568 2.7506984704 -0.3504149744 0.5149284203 0.7428148698 0.3587466089 -0.233185895498 +1403636976001666560.0000000000 1.9240378558 2.7560920650 -0.3470976422 0.5168977951 0.7452555781 0.3517015754 -0.231768838669 +1403636976051666432.0000000000 1.9175913417 2.7619798504 -0.3445186026 0.5202593978 0.7475046123 0.3419854006 -0.231544810737 +1403636976101666560.0000000000 1.9109253216 2.7682156040 -0.3429015384 0.5238704969 0.7499315611 0.3301756975 -0.232693714869 +1403636976151666432.0000000000 1.9043333164 2.7747389147 -0.3419930102 0.5269836380 0.7529504402 0.3169331320 -0.234323002972 +1403636976201666560.0000000000 1.8984214565 2.7819388091 -0.3428816651 0.5297059007 0.7565132431 0.3035141006 -0.234475078686 +1403636976251666432.0000000000 1.8935417259 2.7897062708 -0.3455320969 0.5321625111 0.7604058274 0.2898482228 -0.233610888374 +1403636976301666560.0000000000 1.8899565357 2.7987507437 -0.3495330681 0.5348838854 0.7644103053 0.2774603252 -0.229329200717 +1403636976351666432.0000000000 1.8876627986 2.8084867236 -0.3546429111 0.5378975439 0.7682578912 0.2648380238 -0.224291921675 +1403636976401666560.0000000000 1.8873095971 2.8189835200 -0.3614836398 0.5407186909 0.7721921887 0.2531671972 -0.217368100913 +1403636976451666432.0000000000 1.8883243165 2.8307184946 -0.3694137958 0.5440552343 0.7755820866 0.2422403075 -0.209274849067 +1403636976501666560.0000000000 1.8910972956 2.8430775091 -0.3789968011 0.5472508572 0.7787470316 0.2345614069 -0.19761200977 +1403636976551666432.0000000000 1.8950843039 2.8557774382 -0.3898418949 0.5507164177 0.7808556044 0.2292952041 -0.185471457776 +1403636976601666560.0000000000 1.8999225505 2.8683208440 -0.4020392535 0.5537761377 0.7823303639 0.2253598318 -0.174654336548 +1403636976651666432.0000000000 1.9054648038 2.8804162432 -0.4156228727 0.5563068485 0.7834605467 0.2222555799 -0.165271652726 +1403636976701666560.0000000000 1.9112370446 2.8922684130 -0.4304870158 0.5583624829 0.7843363806 0.2192229269 -0.158079372713 +1403636976751666432.0000000000 1.9168812946 2.9039114915 -0.4466272407 0.5592896879 0.7856128095 0.2156893982 -0.153250259815 +1403636976801666560.0000000000 1.9224632526 2.9150890045 -0.4642181410 0.5586481341 0.7875671598 0.2126169024 -0.14981416433 +1403636976851666432.0000000000 1.9281664908 2.9255429516 -0.4831012182 0.5551104203 0.7911405190 0.2100953796 -0.147678813241 +1403636976901666560.0000000000 1.9339438138 2.9360945337 -0.5009206148 0.5525361055 0.7936901840 0.2078942283 -0.146764211746 +1403636976951666432.0000000000 1.9396750096 2.9469948683 -0.5168048650 0.5495596588 0.7963136082 0.2056996879 -0.146821174246 +1403636977001666560.0000000000 1.9454081421 2.9583855586 -0.5299500276 0.5487218288 0.7971592358 0.2042908264 -0.147332161179 +1403636977051666432.0000000000 1.9510435461 2.9704998704 -0.5411010276 0.5468592430 0.7985024175 0.2039198460 -0.147497640485 +1403636977101666560.0000000000 1.9563831640 2.9839774161 -0.5491558818 0.5458019677 0.7992474656 0.2032983770 -0.148234512527 +1403636977151666432.0000000000 1.9621422806 2.9978981414 -0.5551135983 0.5446505769 0.7998490237 0.2034130251 -0.149065185465 +1403636977201666560.0000000000 1.9679284377 3.0125433206 -0.5590994321 0.5432369950 0.8004853168 0.2038352004 -0.150226615058 +1403636977251666432.0000000000 1.9737806310 3.0281049961 -0.5613778125 0.5427222353 0.8004500217 0.2045047991 -0.151360910346 +1403636977301666560.0000000000 1.9797101493 3.0445824699 -0.5631956580 0.5427173855 0.7999753082 0.2059407741 -0.15193993322 +1403636977351666432.0000000000 1.9855729793 3.0617272626 -0.5652572951 0.5449714358 0.7978709426 0.2068983418 -0.153626720562 +1403636977401666560.0000000000 1.9916108534 3.0793822756 -0.5686883802 0.5473255953 0.7957056615 0.2087101637 -0.154036555834 +1403636977451666432.0000000000 1.9976461120 3.0977067378 -0.5730128525 0.5512378726 0.7924317767 0.2104530878 -0.154590377752 +1403636977501666560.0000000000 2.0038158314 3.1161093814 -0.5787327738 0.5540944861 0.7898830596 0.2120701290 -0.155210544193 +1403636977551666432.0000000000 2.0101035179 3.1347331318 -0.5853309488 0.5575208109 0.7870594438 0.2130797140 -0.155900650625 +1403636977601666560.0000000000 2.0166629712 3.1530198185 -0.5934945975 0.5589830671 0.7856054543 0.2133353542 -0.15763891505 +1403636977651666432.0000000000 2.0236816454 3.1715309401 -0.6030532950 0.5607786115 0.7840259390 0.2145928731 -0.15741846962 +1403636977701666560.0000000000 2.0310827060 3.1901431132 -0.6139529144 0.5605286900 0.7844324114 0.2133860390 -0.157923329815 +1403636977751666432.0000000000 2.0387848837 3.2088119613 -0.6262800055 0.5586946007 0.7863052067 0.2108915567 -0.158458879228 +1403636977801666560.0000000000 2.0469699430 3.2273303758 -0.6396136331 0.5563645767 0.7885942681 0.2073388178 -0.159962973245 +1403636977851666432.0000000000 2.0558765926 3.2456033429 -0.6538690918 0.5536258462 0.7911221387 0.2044021618 -0.160760506271 +1403636977901666560.0000000000 2.0652423493 3.2646052899 -0.6682282096 0.5534575364 0.7917850028 0.2022855338 -0.160753934683 +1403636977951666432.0000000000 2.0752051378 3.2843913104 -0.6815125584 0.5550141906 0.7913028940 0.2011122267 -0.159225784627 +1403636978001666560.0000000000 2.0862780897 3.3037899565 -0.6931711915 0.5568977648 0.7904261487 0.2007334956 -0.157472050546 +1403636978051666432.0000000000 2.0983277044 3.3231825897 -0.7025903874 0.5589477369 0.7894867069 0.2014097206 -0.15402042529 +1403636978101666560.0000000000 2.1104632187 3.3432412025 -0.7104877404 0.5598673535 0.7892433491 0.2021681433 -0.150902366725 +1403636978151666432.0000000000 2.1225061688 3.3635614757 -0.7160225146 0.5595838807 0.7897188619 0.2022811919 -0.149306125504 +1403636978201666560.0000000000 2.1351340451 3.3838101417 -0.7199779249 0.5593024916 0.7902136781 0.2032885570 -0.146344895489 +1403636978251666432.0000000000 2.1483677281 3.4034920320 -0.7225173179 0.5576617878 0.7916148096 0.2039846356 -0.1440471872 +1403636978301666560.0000000000 2.1619060154 3.4226767501 -0.7236019262 0.5571568355 0.7921220958 0.2047944197 -0.142049609758 +1403636978351666432.0000000000 2.1750092319 3.4421307821 -0.7227090841 0.5553575575 0.7936252909 0.2049767691 -0.140432920052 +1403636978401666560.0000000000 2.1878163883 3.4614380293 -0.7195428391 0.5533251392 0.7951395451 0.2058318625 -0.138627697113 +1403636978451666432.0000000000 2.2003676991 3.4806912751 -0.7150587994 0.5503107130 0.7973450060 0.2073398081 -0.135680745134 +1403636978501666560.0000000000 2.2122617692 3.5001179705 -0.7104527021 0.5461622251 0.8003606907 0.2077853849 -0.133995605763 +1403636978551666432.0000000000 2.2235018777 3.5198879886 -0.7064243063 0.5424821966 0.8029768647 0.2087849652 -0.131719624582 +1403636978601666560.0000000000 2.2337756199 3.5401985393 -0.7037769880 0.5383406582 0.8059719916 0.2087389157 -0.130485821131 +1403636978651666432.0000000000 2.2432882367 3.5613861201 -0.7023766374 0.5355533982 0.8079735986 0.2091540141 -0.12890236635 +1403636978701666560.0000000000 2.2516597499 3.5835462341 -0.7023924114 0.5336005652 0.8093514131 0.2095010019 -0.127789111926 +1403636978751666432.0000000000 2.2590061024 3.6066083203 -0.7038070132 0.5316655920 0.8107108097 0.2097613755 -0.126806335787 +1403636978801666560.0000000000 2.2651073847 3.6310138155 -0.7063196347 0.5306234550 0.8114847050 0.2099166808 -0.125961540097 +1403636978851666432.0000000000 2.2696247925 3.6567623972 -0.7093517895 0.5320349075 0.8105445292 0.2097130069 -0.126399676232 +1403636978901666560.0000000000 2.2730372447 3.6840334075 -0.7130739126 0.5354247632 0.8083952566 0.2086722866 -0.127566880369 +1403636978951666432.0000000000 2.2753233604 3.7126511385 -0.7177120431 0.5402679079 0.8051673360 0.2082010830 -0.128329488827 +1403636979001666560.0000000000 2.2766343537 3.7420410030 -0.7232026757 0.5478094883 0.8001251552 0.2069939306 -0.129838411922 +1403636979051666432.0000000000 2.2774378201 3.7714716732 -0.7305918303 0.5543935333 0.7956403860 0.2057802451 -0.131372284425 +1403636979101666560.0000000000 2.2779481957 3.8005697261 -0.7402195024 0.5595068234 0.7920294600 0.2050081651 -0.132714360024 +1403636979151666432.0000000000 2.2780007931 3.8291338047 -0.7513430237 0.5632123146 0.7893847710 0.2044145946 -0.133709556653 +1403636979201666560.0000000000 2.2777751835 3.8569423506 -0.7642260441 0.5637468557 0.7889866842 0.2042967581 -0.133986303435 +1403636979251666432.0000000000 2.2773118480 3.8837873970 -0.7782801786 0.5604527680 0.7912176804 0.2050609480 -0.13348140159 +1403636979301666560.0000000000 2.2765709768 3.9102989301 -0.7911536132 0.5564396733 0.7940121201 0.2062714083 -0.131801931865 +1403636979351666432.0000000000 2.2751533968 3.9368810601 -0.8026427503 0.5520323838 0.7970285310 0.2073141392 -0.130486074584 +1403636979401666560.0000000000 2.2726545975 3.9641262885 -0.8125910698 0.5480985660 0.7996346207 0.2088745136 -0.128622987728 +1403636979451666432.0000000000 2.2693823435 3.9916646220 -0.8202245093 0.5443462101 0.8022063650 0.2092638146 -0.12790937147 +1403636979501666560.0000000000 2.2655062551 4.0191926181 -0.8255593826 0.5414218727 0.8041238433 0.2094051596 -0.128049519776 +1403636979551666432.0000000000 2.2609912842 4.0471858144 -0.8294038307 0.5391395822 0.8057032005 0.2100110878 -0.126752541153 +1403636979601666560.0000000000 2.2551335272 4.0762545026 -0.8307840212 0.5383373141 0.8063063858 0.2096544932 -0.126917067528 +1403636979651666432.0000000000 2.2482066973 4.1064215413 -0.8306170469 0.5372871596 0.8071761763 0.2091120611 -0.126733083397 +1403636979701666560.0000000000 2.2407397380 4.1374031406 -0.8297350176 0.5374043935 0.8072836265 0.2101416919 -0.123814916322 +1403636979751666432.0000000000 2.2318780616 4.1690393735 -0.8273490528 0.5367731207 0.8079280544 0.2096126852 -0.12324527594 +1403636979801666560.0000000000 2.2215772848 4.2021856842 -0.8229712197 0.5392286173 0.8065422647 0.2087754877 -0.123023856859 +1403636979851666432.0000000000 2.2100579684 4.2365791550 -0.8170380842 0.5436466625 0.8039181895 0.2076623516 -0.122638487637 +1403636979901666560.0000000000 2.1972196928 4.2713788049 -0.8108499054 0.5469604960 0.8020176425 0.2056459156 -0.12374035091 +1403636979951666432.0000000000 2.1835759375 4.3066533627 -0.8056729179 0.5509580397 0.7996276990 0.2045866528 -0.123227768598 +1403636980001666560.0000000000 2.1691831456 4.3418876407 -0.8024305138 0.5530510260 0.7984913000 0.2037584482 -0.122591603361 +1403636980051666432.0000000000 2.1544687602 4.3767994051 -0.8007488091 0.5546624909 0.7976614061 0.2031257547 -0.121760954975 +1403636980101666560.0000000000 2.1392304388 4.4116176187 -0.8006276783 0.5559158788 0.7970380231 0.2022233442 -0.121629127306 +1403636980151666432.0000000000 2.1233791372 4.4462231666 -0.8017388524 0.5569936408 0.7965526932 0.2010434567 -0.121833573144 +1403636980201666560.0000000000 2.1068016959 4.4806625620 -0.8043659767 0.5573452379 0.7965570926 0.2000652851 -0.12180708355 +1403636980251666432.0000000000 2.0895960572 4.5147584779 -0.8082031778 0.5576684390 0.7965141162 0.1988974623 -0.12251928103 +1403636980301666560.0000000000 2.0718609402 4.5487585127 -0.8130485983 0.5597415396 0.7953211287 0.1968780465 -0.124067505347 +1403636980351666432.0000000000 2.0540706741 4.5822686522 -0.8192671710 0.5623417938 0.7935981514 0.1959284758 -0.124842754588 +1403636980401666560.0000000000 2.0358028060 4.6152318547 -0.8267006491 0.5647842283 0.7919536293 0.1936470193 -0.12778519644 +1403636980451666432.0000000000 2.0175822890 4.6478353788 -0.8357832808 0.5670503160 0.7903683404 0.1927921036 -0.128852747256 +1403636980501666560.0000000000 1.9992570300 4.6796529359 -0.8458782650 0.5684642711 0.7893703616 0.1907558297 -0.131738446148 +1403636980551666432.0000000000 1.9812409770 4.7104529306 -0.8569658479 0.5690238010 0.7888219232 0.1896315352 -0.13420792939 +1403636980601666560.0000000000 1.9637111758 4.7399241580 -0.8684172420 0.5695678293 0.7883055363 0.1879060232 -0.137325146146 +1403636980651666432.0000000000 1.9469466680 4.7684761990 -0.8793696089 0.5697837810 0.7879845703 0.1868210907 -0.13973059779 +1403636980701666560.0000000000 1.9306666936 4.7971702845 -0.8887290122 0.5704770582 0.7872888883 0.1880101684 -0.139227544055 +1403636980751666432.0000000000 1.9149952359 4.8253257021 -0.8965235066 0.5693075293 0.7879704503 0.1891588029 -0.13860178139 +1403636980801666560.0000000000 1.8999680182 4.8531349419 -0.9027407379 0.5681120744 0.7886496481 0.1926280197 -0.134814129333 +1403636980851666432.0000000000 1.8853132909 4.8797964551 -0.9072372079 0.5654371992 0.7902471335 0.1956124320 -0.132385868676 +1403636980901666560.0000000000 1.8701677715 4.9070346032 -0.9092527846 0.5627268152 0.7919669515 0.1981963054 -0.129788689018 +1403636980951666432.0000000000 1.8551042894 4.9338043125 -0.9099668689 0.5613222290 0.7927025654 0.2010647351 -0.126936875443 +1403636981001666560.0000000000 1.8398488677 4.9595491106 -0.9100944435 0.5601993301 0.7933060031 0.2024054425 -0.125993384129 +1403636981051666432.0000000000 1.8237594122 4.9853959522 -0.9110269289 0.5600529300 0.7933142933 0.2030184300 -0.125605194032 +1403636981101666560.0000000000 1.8071068940 5.0104885166 -0.9125779010 0.5609283360 0.7927092942 0.2019194450 -0.127278885219 +1403636981151666432.0000000000 1.7900410778 5.0350643136 -0.9155526895 0.5609510641 0.7927547211 0.1998714622 -0.130097095953 +1403636981201666560.0000000000 1.7727622611 5.0592126767 -0.9194639471 0.5610221454 0.7928844171 0.1966265847 -0.13388965484 +1403636981251666432.0000000000 1.7553316609 5.0831918030 -0.9239086314 0.5610480474 0.7930950568 0.1916199561 -0.139667862297 +1403636981301666560.0000000000 1.7382785173 5.1071418616 -0.9291255138 0.5615272524 0.7928865894 0.1865051230 -0.145718358957 +1403636981351666432.0000000000 1.7221001363 5.1310852574 -0.9354007809 0.5617048978 0.7928560492 0.1818310003 -0.151011192839 +1403636981401666560.0000000000 1.7071181279 5.1550355764 -0.9434723050 0.5616380411 0.7930754526 0.1796196061 -0.152744343264 +1403636981451666432.0000000000 1.6936629177 5.1789956512 -0.9534340487 0.5617818885 0.7933125720 0.1805325651 -0.149880838616 +1403636981501666560.0000000000 1.6814030342 5.2029566172 -0.9640978135 0.5618291668 0.7937153795 0.1829057998 -0.144600664005 +1403636981551666432.0000000000 1.6702662919 5.2268888595 -0.9745290373 0.5619153288 0.7940766329 0.1866031853 -0.13737800278 +1403636981601666560.0000000000 1.6596428461 5.2506089248 -0.9835691347 0.5608557460 0.7951293581 0.1906089751 -0.129916722335 +1403636981651666432.0000000000 1.6487429362 5.2746470679 -0.9903558472 0.5599862684 0.7960317630 0.1935159456 -0.123694746767 +1403636981701666560.0000000000 1.6376453280 5.2980183423 -0.9947810911 0.5590533546 0.7969482867 0.1950968914 -0.119457013037 +1403636981751666432.0000000000 1.6261622369 5.3211291781 -0.9971370986 0.5584647508 0.7976861583 0.1959197636 -0.115885121014 +1403636981801666560.0000000000 1.6139821421 5.3441721501 -0.9974810013 0.5559266853 0.7997265181 0.1963710769 -0.113231695779 +1403636981851666432.0000000000 1.6010105615 5.3672610694 -0.9957148238 0.5531331965 0.8019416895 0.1966718378 -0.110694994372 +1403636981901666560.0000000000 1.5870776441 5.3904669925 -0.9915469313 0.5499969233 0.8043579617 0.1968044681 -0.108534119891 +1403636981951666432.0000000000 1.5719497008 5.4138208436 -0.9864146489 0.5453527360 0.8078351542 0.1960910843 -0.107429249885 +1403636982001666560.0000000000 1.5558147418 5.4377212952 -0.9815753430 0.5409517255 0.8110002121 0.1956603397 -0.106615749364 +1403636982051666432.0000000000 1.5385878334 5.4623592357 -0.9776358580 0.5362724092 0.8143487169 0.1946257031 -0.106625073166 +1403636982101666560.0000000000 1.5201578982 5.4879808736 -0.9748305046 0.5321904291 0.8171911135 0.1939731834 -0.106519647718 +1403636982151666432.0000000000 1.5004558352 5.5147688532 -0.9727613093 0.5292337054 0.8192702104 0.1927197520 -0.10755047497 +1403636982201666560.0000000000 1.4795986739 5.5428995789 -0.9715962316 0.5276006454 0.8204930855 0.1911111442 -0.109110889135 +1403636982251666432.0000000000 1.4574270117 5.5725208105 -0.9712620376 0.5272921139 0.8207997549 0.1887065774 -0.112430497152 +1403636982301666560.0000000000 1.4343202624 5.6037795510 -0.9719213292 0.5280238256 0.8204281001 0.1859138215 -0.116295412688 +1403636982351666432.0000000000 1.4107482565 5.6367013380 -0.9736105864 0.5310088457 0.8184937262 0.1838608190 -0.119552604189 +1403636982401666560.0000000000 1.3867463927 5.6714499637 -0.9755263489 0.5357189282 0.8153972559 0.1815970299 -0.123105905185 +1403636982451666432.0000000000 1.3629152413 5.7074184020 -0.9765399505 0.5419932590 0.8111374903 0.1799145347 -0.126214259293 +1403636982501666560.0000000000 1.3393651384 5.7445524272 -0.9759746650 0.5478452051 0.8069741350 0.1783492112 -0.129807301488 +1403636982551666432.0000000000 1.3161572798 5.7830272545 -0.9736627449 0.5531447698 0.8031578617 0.1784889671 -0.130805204605 +1403636982601666560.0000000000 1.2934827564 5.8220160465 -0.9707480532 0.5552748436 0.8014727529 0.1791483770 -0.131214074599 +1403636982651666432.0000000000 1.2710880298 5.8615209202 -0.9665647637 0.5546049709 0.8016642020 0.1794514843 -0.132457533949 +1403636982701666560.0000000000 1.2492866992 5.9013326462 -0.9614805486 0.5538700746 0.8019022561 0.1798659123 -0.133525150192 +1403636982751666432.0000000000 1.2284494910 5.9411701281 -0.9568451422 0.5516674766 0.8031626635 0.1821258152 -0.131995904129 +1403636982801666560.0000000000 1.2081551812 5.9812336962 -0.9522070056 0.5497975711 0.8041084619 0.1841178797 -0.131273831412 +1403636982851666432.0000000000 1.1885350372 6.0216841716 -0.9486039551 0.5480700365 0.8051690965 0.1856594618 -0.129817276824 +1403636982901666560.0000000000 1.1693169982 6.0625517406 -0.9463953755 0.5468353513 0.8058804970 0.1878147156 -0.127488649414 +1403636982951666432.0000000000 1.1498614115 6.1039181505 -0.9452019608 0.5477356707 0.8051365221 0.1890297761 -0.126524936253 +1403636983001666560.0000000000 1.1301169063 6.1458515636 -0.9454639567 0.5489200527 0.8042679415 0.1898052173 -0.125753065235 +1403636983051666432.0000000000 1.1101493842 6.1882446084 -0.9471661523 0.5522520549 0.8018973417 0.1899516764 -0.126082044372 +1403636983101666560.0000000000 1.0901762583 6.2305017162 -0.9502274212 0.5550883403 0.7999265352 0.1898499973 -0.12629905502 +1403636983151666432.0000000000 1.0703406970 6.2731342437 -0.9549828227 0.5576945020 0.7980927165 0.1903492422 -0.125666321322 +1403636983201666560.0000000000 1.0507948608 6.3158208423 -0.9611353144 0.5596016564 0.7967488588 0.1915878304 -0.123819810087 +1403636983251666432.0000000000 1.0311974935 6.3585914197 -0.9684579211 0.5614285839 0.7954326296 0.1922654466 -0.122958834151 +1403636983301666560.0000000000 1.0115821726 6.4011298609 -0.9771014169 0.5629138989 0.7944847053 0.1929051919 -0.121283067298 +1403636983351666432.0000000000 0.9919369396 6.4434817312 -0.9867197327 0.5636296445 0.7940512440 0.1926715625 -0.121168951351 +1403636983401666560.0000000000 0.9725031083 6.4854449023 -0.9972692635 0.5649075230 0.7932273898 0.1932949712 -0.119611256203 +1403636983451666432.0000000000 0.9526882860 6.5270127307 -1.0077765254 0.5653133702 0.7930784069 0.1925583011 -0.11986965683 +1403636983501666560.0000000000 0.9329213486 6.5679298630 -1.0177188859 0.5645663488 0.7937499191 0.1922470320 -0.119444473756 +1403636983551666432.0000000000 0.9132342618 6.6082338195 -1.0261764236 0.5634123438 0.7947146725 0.1922695839 -0.11843786271 +1403636983601666560.0000000000 0.8933136872 6.6475692097 -1.0332059807 0.5619113501 0.7959622451 0.1926193455 -0.116608433221 +1403636983651666432.0000000000 0.8730480568 6.6862397296 -1.0388510519 0.5587544134 0.7983446908 0.1928256316 -0.11514137422 +1403636983701666560.0000000000 0.8520994890 6.7251512688 -1.0420139914 0.5566307319 0.8000449037 0.1928019519 -0.113656445578 +1403636983751666432.0000000000 0.8303657079 6.7637976506 -1.0423218348 0.5542855709 0.8018599475 0.1930133230 -0.111955293351 +1403636983801666560.0000000000 0.8078247464 6.8027603498 -1.0407846380 0.5529987291 0.8028972399 0.1935344435 -0.109967481654 +1403636983851666432.0000000000 0.7848009294 6.8411449097 -1.0375918710 0.5508360923 0.8046055721 0.1934429936 -0.108486316799 +1403636983901666560.0000000000 0.7611349110 6.8791765710 -1.0328963452 0.5494561588 0.8056696267 0.1933880528 -0.107682139594 +1403636983951666432.0000000000 0.7364941289 6.9175249387 -1.0268645920 0.5481427277 0.8068524651 0.1924744326 -0.107155225911 +1403636984001666560.0000000000 0.7108731538 6.9560961093 -1.0188597133 0.5469929405 0.8078462517 0.1918853141 -0.106598231604 +1403636984051666432.0000000000 0.6843996923 6.9949867867 -1.0100732953 0.5454507975 0.8091043194 0.1912123653 -0.106167128947 +1403636984101666560.0000000000 0.6570325865 7.0344811300 -1.0013824795 0.5451644732 0.8095436329 0.1905822814 -0.10541915199 +1403636984151666432.0000000000 0.6290584411 7.0746964471 -0.9938876528 0.5466287450 0.8087367796 0.1899241506 -0.105217172436 +1403636984201666560.0000000000 0.6004123438 7.1154571580 -0.9879127492 0.5490032363 0.8073767694 0.1890134304 -0.104938657954 +1403636984251666432.0000000000 0.5708095440 7.1564863409 -0.9835542157 0.5522474710 0.8054351557 0.1873018646 -0.10590067169 +1403636984301666560.0000000000 0.5407140578 7.1978412234 -0.9816252982 0.5551192584 0.8036287749 0.1869477905 -0.105232717128 +1403636984351666432.0000000000 0.5100477449 7.2395409489 -0.9815230178 0.5574045163 0.8022831336 0.1854131437 -0.106131733732 +1403636984401666560.0000000000 0.4788427296 7.2810929730 -0.9836757055 0.5588511905 0.8014514929 0.1848124638 -0.105854638836 +1403636984451666432.0000000000 0.4471200104 7.3225710696 -0.9874334293 0.5608579127 0.8001798895 0.1844888960 -0.105424823536 +1403636984501666560.0000000000 0.4148891313 7.3637605437 -0.9925336869 0.5625466094 0.7991692480 0.1836992013 -0.105472407532 +1403636984551666432.0000000000 0.3821871139 7.4044192424 -0.9987959450 0.5632362649 0.7987435929 0.1835794826 -0.105224314023 +1403636984601666560.0000000000 0.3489012511 7.4445592598 -1.0045989421 0.5639633528 0.7982468933 0.1834565852 -0.105313414633 +1403636984651666432.0000000000 0.3150965088 7.4842773600 -1.0090085758 0.5641363806 0.7981081414 0.1835190007 -0.105329554174 +1403636984701666560.0000000000 0.2809125197 7.5232983427 -1.0116462817 0.5647682727 0.7975768720 0.1839591368 -0.105199654517 +1403636984751666432.0000000000 0.2461453554 7.5618361412 -1.0125243741 0.5650883620 0.7972669657 0.1833056636 -0.106955889288 +1403636984801666560.0000000000 0.2110013852 7.6001267993 -1.0121778765 0.5651730263 0.7972006425 0.1822204327 -0.108840708062 +1403636984851666432.0000000000 0.1757020708 7.6376670310 -1.0107685964 0.5644165481 0.7977077276 0.1808060475 -0.111380046788 +1403636984901666560.0000000000 0.1405715394 7.6745126960 -1.0080330356 0.5637447195 0.7982109035 0.1789879083 -0.114081432956 +1403636984951666432.0000000000 0.1058233351 7.7106449192 -1.0040508546 0.5641152400 0.7979650943 0.1780906455 -0.115366486591 +1403636985001666560.0000000000 0.0715715963 7.7457212721 -0.9990280346 0.5638270776 0.7981589401 0.1778218250 -0.115847880948 +1403636985051666432.0000000000 0.0376573256 7.7806349127 -0.9935460996 0.5635924143 0.7983569052 0.1777402677 -0.115750765605 +1403636985101666560.0000000000 0.0037427125 7.8157809964 -0.9884589326 0.5637417642 0.7982851914 0.1785704129 -0.114230399414 +1403636985151666432.0000000000 -0.0298545751 7.8500499882 -0.9859273577 0.5628495816 0.7989341859 0.1797687609 -0.112194953881 +1403636985201666560.0000000000 -0.0638162288 7.8846993628 -0.9859338464 0.5635481937 0.7984795868 0.1803784185 -0.110938762121 +1403636985251666432.0000000000 -0.0976941671 7.9184845603 -0.9898112782 0.5642053443 0.7980826202 0.1808901043 -0.10961400895 +1403636985301666560.0000000000 -0.1319485036 7.9521766269 -0.9968568660 0.5647086682 0.7977927843 0.1810844855 -0.108808099477 +1403636985351666432.0000000000 -0.1665638172 7.9854911109 -1.0051900648 0.5646615762 0.7975713757 0.1823073572 -0.108633477581 +1403636985401666560.0000000000 -0.2015780981 8.0178926459 -1.0130196817 0.5644769841 0.7970293608 0.1848977269 -0.109191404988 +1403636985451666432.0000000000 -0.2371892094 8.0498180490 -1.0199134204 0.5635431559 0.7964990585 0.1897420882 -0.109573268527 +1403636985501666560.0000000000 -0.2734004380 8.0811559083 -1.0244177726 0.5632096339 0.7952471286 0.1949565536 -0.111215353961 +1403636985551666432.0000000000 -0.3100917971 8.1118124137 -1.0270123431 0.5632530476 0.7937650394 0.1995449915 -0.113423379238 +1403636985601666560.0000000000 -0.3471419612 8.1417057443 -1.0280054300 0.5637738462 0.7921043543 0.2039137530 -0.114668756086 +1403636985651666432.0000000000 -0.3847951310 8.1706866486 -1.0272006234 0.5643650084 0.7904390827 0.2085052265 -0.114994627418 +1403636985701666560.0000000000 -0.4229791798 8.1987067019 -1.0245829589 0.5657046628 0.7884746106 0.2119365086 -0.115624129146 +1403636985751666432.0000000000 -0.4618527624 8.2256137912 -1.0201346820 0.5673437656 0.7863828881 0.2147031896 -0.116728511045 +1403636985801666560.0000000000 -0.5013780959 8.2515125480 -1.0144050362 0.5693415857 0.7841014434 0.2168438069 -0.118380102276 +1403636985851666432.0000000000 -0.5416914755 8.2766392099 -1.0074693872 0.5751297851 0.7792401128 0.2173644494 -0.121504210103 +1403636985901666560.0000000000 -0.5826249862 8.3007613350 -1.0011200191 0.5832025630 0.7726549709 0.2171742102 -0.125357205167 +1403636985951666432.0000000000 -0.6238984353 8.3233129188 -0.9960520907 0.5923583872 0.7652228106 0.2160867468 -0.129815673157 +1403636986001666560.0000000000 -0.6645925431 8.3434549813 -0.9937810553 0.5982347340 0.7602754306 0.2160883985 -0.131917689175 +1403636986051666432.0000000000 -0.7044691897 8.3610797419 -0.9942696782 0.6009172259 0.7579215448 0.2171777335 -0.131480992971 +1403636986101666560.0000000000 -0.7439555701 8.3758164088 -0.9969712801 0.5995889228 0.7586912154 0.2176210399 -0.132370111507 +1403636986151666432.0000000000 -0.7830313832 8.3879844507 -1.0021026575 0.5944865139 0.7625004447 0.2188244228 -0.13150942434 +1403636986201666560.0000000000 -0.8218448499 8.3977562537 -1.0084407815 0.5883270129 0.7671437190 0.2196821831 -0.130773004541 +1403636986251666432.0000000000 -0.8601371145 8.4054058442 -1.0164210595 0.5808315364 0.7727195650 0.2217373096 -0.12795220113 +1403636986301666560.0000000000 -0.8987383905 8.4115634301 -1.0245218409 0.5754397908 0.7766620600 0.2224722264 -0.127166033866 +1403636986351666432.0000000000 -0.9376450556 8.4167236137 -1.0331537093 0.5714391388 0.7795108397 0.2238218487 -0.125395141284 +1403636986401666560.0000000000 -0.9772839208 8.4203758270 -1.0420361369 0.5677620147 0.7821919192 0.2228181951 -0.127177624322 +1403636986451666432.0000000000 -1.0175030054 8.4232582860 -1.0507934057 0.5651975498 0.7841018257 0.2208914520 -0.13016536764 +1403636986501666560.0000000000 -1.0580803455 8.4253510259 -1.0588189453 0.5627661591 0.7858584175 0.2192132461 -0.132914824504 +1403636986551666432.0000000000 -1.0990898781 8.4270144470 -1.0642530192 0.5615190766 0.7867774690 0.2166724982 -0.136859670128 +1403636986601666560.0000000000 -1.1395202648 8.4275136552 -1.0678784592 0.5604095467 0.7875012081 0.2151721789 -0.139584815023 +1403636986651666432.0000000000 -1.1793367347 8.4275171441 -1.0694081558 0.5595460324 0.7880932295 0.2141717838 -0.141236490632 +1403636986701666560.0000000000 -1.2189691760 8.4273577227 -1.0683558481 0.5585542136 0.7887829081 0.2121461153 -0.144335512611 +1403636986751666432.0000000000 -1.2583491018 8.4277238395 -1.0649391407 0.5581445917 0.7889876134 0.2107315672 -0.146851514304 +1403636986801666560.0000000000 -1.2972879107 8.4283775463 -1.0593051745 0.5569520382 0.7898384189 0.2085868755 -0.149837293622 +1403636986851666432.0000000000 -1.3351290991 8.4291273870 -1.0514889347 0.5578917644 0.7891594927 0.2078739677 -0.150905559284 +1403636986901666560.0000000000 -1.3720745410 8.4300457028 -1.0413245108 0.5577308914 0.7893901051 0.2069676927 -0.151538407501 +1403636986951666432.0000000000 -1.4082588515 8.4314718753 -1.0289642971 0.5588392330 0.7886242924 0.2074349102 -0.150801840944 +1403636987001666560.0000000000 -1.4435266441 8.4331369151 -1.0145118778 0.5596517594 0.7882157214 0.2076891534 -0.149569717393 +1403636987051666432.0000000000 -1.4775203399 8.4344550486 -0.9986223771 0.5612819971 0.7873093537 0.2088915338 -0.14652927475 +1403636987101666560.0000000000 -1.5109494161 8.4353643704 -0.9824460256 0.5625199913 0.7866151661 0.2094375304 -0.144719593334 +1403636987151666432.0000000000 -1.5438306230 8.4360270108 -0.9669851317 0.5634091883 0.7861933141 0.2093543278 -0.143669498705 +1403636987201666560.0000000000 -1.5760112234 8.4364835228 -0.9526822070 0.5646704760 0.7855483380 0.2090538346 -0.142679908888 +1403636987251666432.0000000000 -1.6077436854 8.4365836381 -0.9398176891 0.5653265907 0.7853302150 0.2074300966 -0.143649065935 +1403636987301666560.0000000000 -1.6387369727 8.4365213967 -0.9290581177 0.5667210872 0.7845833934 0.2073384537 -0.14236177065 +1403636987351666432.0000000000 -1.6693875429 8.4358945956 -0.9199831258 0.5671282037 0.7843189316 0.2070620233 -0.142599903673 +1403636987401666560.0000000000 -1.6997650290 8.4346923828 -0.9121207298 0.5683764586 0.7831492887 0.2072313222 -0.143807413347 +1403636987451666432.0000000000 -1.7296943045 8.4328402057 -0.9060111742 0.5695841808 0.7816312419 0.2094860316 -0.14402105801 +1403636987501666560.0000000000 -1.7592317617 8.4305121420 -0.9004045481 0.5728708641 0.7786360984 0.2108037287 -0.145281063172 +1403636987551666432.0000000000 -1.7881395643 8.4272526738 -0.8962377818 0.5757417561 0.7760000613 0.2130669194 -0.144733627914 +1403636987601666560.0000000000 -1.8164208338 8.4227713500 -0.8930147536 0.5781951042 0.7736176757 0.2145337595 -0.145538239899 +1403636987651666432.0000000000 -1.8439641744 8.4169458065 -0.8910069546 0.5794443043 0.7722299422 0.2155640638 -0.146414989188 +1403636987701666560.0000000000 -1.8708336651 8.4098400468 -0.8894333042 0.5802633154 0.7711450274 0.2169392425 -0.146857742815 +1403636987751666432.0000000000 -1.8970312355 8.4011631815 -0.8871306104 0.5803474860 0.7705805150 0.2179572286 -0.147976727566 +1403636987801666560.0000000000 -1.9225442762 8.3910438427 -0.8834038209 0.5798498701 0.7704532384 0.2184802305 -0.149807624924 +1403636987851666432.0000000000 -1.9473681216 8.3798795529 -0.8774411237 0.5791688681 0.7705565102 0.2190480676 -0.151076242255 +1403636987901666560.0000000000 -1.9711777560 8.3669836587 -0.8695961395 0.5771592414 0.7716931356 0.2181880859 -0.154178058392 +1403636987951666432.0000000000 -1.9940595803 8.3529838503 -0.8606322050 0.5744027628 0.7733654486 0.2174180982 -0.157151899917 +1403636988001666560.0000000000 -2.0163388474 8.3382936716 -0.8508454694 0.5704750347 0.7759794276 0.2158543395 -0.160689348904 +1403636988051666432.0000000000 -2.0373731814 8.3229765370 -0.8416849726 0.5663197546 0.7789049507 0.2141700517 -0.163463152401 +1403636988101666560.0000000000 -2.0574275520 8.3073599687 -0.8337893448 0.5627051503 0.7813805861 0.2124276124 -0.166378493084 +1403636988151666432.0000000000 -2.0761913843 8.2917209541 -0.8274619775 0.5598170896 0.7834524743 0.2111148521 -0.168040370025 +1403636988201666560.0000000000 -2.0938049086 8.2762998432 -0.8221845934 0.5581782238 0.7846228747 0.2091782923 -0.170436079189 +1403636988251666432.0000000000 -2.1100109158 8.2613573951 -0.8179597869 0.5582028199 0.7846402236 0.2074394604 -0.172389679618 +1403636988301666560.0000000000 -2.1250013298 8.2468716094 -0.8139540054 0.5604427012 0.7830940653 0.2047260283 -0.17537079861 +1403636988351666432.0000000000 -2.1382224142 8.2328755979 -0.8097641637 0.5644230241 0.7803235214 0.2028857367 -0.177085373923 +1403636988401666560.0000000000 -2.1497020558 8.2193002202 -0.8041956735 0.5681671987 0.7776131323 0.2010979480 -0.17906274374 +1403636988451666432.0000000000 -2.1587682537 8.2055339187 -0.7971350098 0.5716791513 0.7750409005 0.2008994675 -0.179259461432 +1403636988501666560.0000000000 -2.1651988540 8.1907570274 -0.7879824987 0.5747822732 0.7727762029 0.2006840685 -0.179354908983 +1403636988551666432.0000000000 -2.1692410640 8.1751463535 -0.7772776260 0.5764032515 0.7715010021 0.2002397361 -0.180137568304 +1403636988601666560.0000000000 -2.1707787674 8.1587209261 -0.7655495494 0.5777025312 0.7704739753 0.1999888165 -0.180649140843 +1403636988651666432.0000000000 -2.1701862511 8.1417020017 -0.7538770315 0.5781748220 0.7700813104 0.1997483659 -0.181077996937 +1403636988701666560.0000000000 -2.1676819188 8.1242106728 -0.7431674611 0.5787015362 0.7696465506 0.1993085475 -0.18172732875 +1403636988751666432.0000000000 -2.1630589620 8.1060738354 -0.7338323242 0.5800983056 0.7686329469 0.1999340172 -0.180874922153 +1403636988801666560.0000000000 -2.1565982312 8.0871374373 -0.7255788026 0.5813557798 0.7676150922 0.1992553298 -0.181906132758 +1403636988851666432.0000000000 -2.1479085958 8.0673549621 -0.7188048500 0.5825031387 0.7666553635 0.1986097653 -0.18298581426 +1403636988901666560.0000000000 -2.1369789629 8.0469565520 -0.7132201369 0.5838954106 0.7655519131 0.1976751698 -0.184176396848 +1403636988951666432.0000000000 -2.1238741453 8.0257020452 -0.7088198496 0.5850745437 0.7645739620 0.1963516019 -0.185904500751 +1403636989001666560.0000000000 -2.1081560547 8.0035946960 -0.7057373664 0.5861847480 0.7637630305 0.1955804372 -0.186552317151 +1403636989051666432.0000000000 -2.0898561733 7.9802012553 -0.7036213325 0.5871511665 0.7629957356 0.1939363117 -0.18836061725 +1403636989101666560.0000000000 -2.0686147387 7.9558666744 -0.7027681761 0.5875952890 0.7627680836 0.1937726575 -0.188065903728 +1403636989151666432.0000000000 -2.0449203945 7.9305511148 -0.7025856858 0.5875652294 0.7628513654 0.1930301677 -0.188584861155 +1403636989201666560.0000000000 -2.0186451228 7.9042617294 -0.7027441085 0.5873122936 0.7632249794 0.1930588533 -0.18783018865 +1403636989251666432.0000000000 -1.9894044704 7.8769468552 -0.7026582099 0.5859403438 0.7645930178 0.1949217266 -0.184599434041 +1403636989301666560.0000000000 -1.9576468878 7.8491839083 -0.7020068086 0.5832613060 0.7672218423 0.1983924753 -0.178374099395 +1403636989351666432.0000000000 -1.9242133062 7.8212713746 -0.6992187972 0.5801056380 0.7700519918 0.2025924625 -0.171620723877 +1403636989401666560.0000000000 -1.8886366466 7.7915753893 -0.6945482781 0.5753330506 0.7740016590 0.2061280554 -0.165603555153 +1403636989451666432.0000000000 -1.8521436980 7.7615420501 -0.6873296825 0.5703049253 0.7779382569 0.2088108518 -0.161128485387 +1403636989501666560.0000000000 -1.8145345621 7.7305047049 -0.6780276263 0.5670390267 0.7804870964 0.2103748035 -0.158269000902 +1403636989551666432.0000000000 -1.7765932646 7.6997361787 -0.6671354291 0.5644690854 0.7825599127 0.2117986853 -0.155293115053 +1403636989601666560.0000000000 -1.7380457878 7.6685079864 -0.6552922335 0.5638223120 0.7830828860 0.2133889279 -0.152809553198 +1403636989651666432.0000000000 -1.6991548708 7.6373950384 -0.6444969975 0.5625986234 0.7839947014 0.2154571639 -0.149710746701 +1403636989701666560.0000000000 -1.6604824347 7.6063438203 -0.6347395002 0.5624399427 0.7841343395 0.2174648327 -0.146641382402 +1403636989751666432.0000000000 -1.6219683219 7.5751205017 -0.6264054113 0.5621577456 0.7843297798 0.2189535407 -0.144446573843 +1403636989801666560.0000000000 -1.5839134548 7.5436928100 -0.6193627160 0.5615825615 0.7847506943 0.2192182676 -0.143995574848 +1403636989851666432.0000000000 -1.5463290533 7.5124024232 -0.6137677928 0.5618516076 0.7845174320 0.2190920369 -0.144408619238 +1403636989901666560.0000000000 -1.5091495834 7.4813176710 -0.6092499599 0.5632139863 0.7835360643 0.2182775646 -0.145657633839 +1403636989951666432.0000000000 -1.4722201168 7.4501769618 -0.6056489744 0.5662648581 0.7813816445 0.2168563715 -0.147513220483 +1403636990001666560.0000000000 -1.4353436663 7.4187183425 -0.6030727449 0.5687216373 0.7795475075 0.2157779292 -0.149336091284 +1403636990051666432.0000000000 -1.3983075676 7.3869453358 -0.5999756379 0.5719040917 0.7772668034 0.2150117139 -0.150173196812 +1403636990101666560.0000000000 -1.3612494371 7.3546286914 -0.5956471670 0.5740058009 0.7756540836 0.2143939119 -0.151371508817 +1403636990151666432.0000000000 -1.3238140486 7.3214180502 -0.5897686446 0.5751176842 0.7747543891 0.2145926230 -0.151477034695 +1403636990201666560.0000000000 -1.2859526756 7.2874545754 -0.5826815843 0.5750853067 0.7747422107 0.2154054918 -0.15050538585 +1403636990251666432.0000000000 -1.2481855150 7.2532289408 -0.5740593710 0.5735334932 0.7757073879 0.2168045072 -0.149442919434 +1403636990301666560.0000000000 -1.2099267790 7.2180160962 -0.5638741795 0.5716297590 0.7769434451 0.2184231129 -0.147951497261 +1403636990351666432.0000000000 -1.1716506467 7.1821584450 -0.5518850810 0.5704211523 0.7776022473 0.2196265297 -0.147372458043 +1403636990401666560.0000000000 -1.1334745859 7.1456175512 -0.5395900533 0.5681484510 0.7789983138 0.2216225574 -0.145782052484 +1403636990451666432.0000000000 -1.0960030755 7.1084555378 -0.5276193303 0.5664925301 0.7798891497 0.2222565294 -0.146496288778 +1403636990501666560.0000000000 -1.0587498756 7.0705519016 -0.5171716001 0.5637404183 0.7815768303 0.2230547328 -0.146904681097 +1403636990551666432.0000000000 -1.0219567171 7.0327129702 -0.5077817798 0.5630891285 0.7817806709 0.2236967603 -0.147341017362 +1403636990601666560.0000000000 -0.9852357333 6.9944072074 -0.4999801709 0.5615196419 0.7826308392 0.2247115349 -0.147273172284 +1403636990651666432.0000000000 -0.9487170623 6.9563973070 -0.4936420165 0.5596896246 0.7836831094 0.2252998838 -0.147743935342 +1403636990701666560.0000000000 -0.9123804958 6.9187925256 -0.4890905174 0.5590568166 0.7838275431 0.2270480389 -0.146693716372 +1403636990751666432.0000000000 -0.8765262670 6.8809111938 -0.4861907822 0.5581222939 0.7842558935 0.2279844510 -0.146510370241 +1403636990801666560.0000000000 -0.8414134511 6.8429446292 -0.4851042984 0.5579820176 0.7841377057 0.2290491958 -0.146015727008 +1403636990851666432.0000000000 -0.8070840031 6.8048194544 -0.4855338008 0.5579901156 0.7839018967 0.2298315323 -0.14602162172 +1403636990901666560.0000000000 -0.7734075995 6.7669030364 -0.4874967090 0.5574591112 0.7841981363 0.2296411204 -0.14675686743 +1403636990951666432.0000000000 -0.7401929869 6.7294755734 -0.4907423714 0.5573696354 0.7842205346 0.2302237440 -0.146062556102 +1403636991001666560.0000000000 -0.7075780864 6.6927424484 -0.4949599993 0.5577945071 0.7838439374 0.2303318314 -0.146291548233 +1403636991051666432.0000000000 -0.6755093614 6.6565126480 -0.5000278173 0.5591373439 0.7828887424 0.2302406135 -0.1464237259 +1403636991101666560.0000000000 -0.6440475510 6.6203062206 -0.5065207917 0.5587051845 0.7832740589 0.2303633911 -0.145818289375 +1403636991151666432.0000000000 -0.6135501156 6.5850418471 -0.5136682605 0.5589554464 0.7832383498 0.2297733220 -0.145981906061 +1403636991201666560.0000000000 -0.5834705043 6.5500678195 -0.5199554001 0.5589306772 0.7833599796 0.2303189858 -0.144557273616 +1403636991251666432.0000000000 -0.5538064296 6.5144574670 -0.5246378386 0.5582703210 0.7839532632 0.2298424291 -0.144651262191 +1403636991301666560.0000000000 -0.5238768544 6.4778521976 -0.5285176909 0.5581873937 0.7840845201 0.2298373100 -0.144267493962 +1403636991351666432.0000000000 -0.4945546043 6.4412486622 -0.5306007936 0.5577618479 0.7846531182 0.2286887891 -0.144646613553 +1403636991401666560.0000000000 -0.4657754261 6.4049615518 -0.5308155694 0.5572109757 0.7851545258 0.2289908587 -0.143567008181 +1403636991451666432.0000000000 -0.4373955271 6.3684397372 -0.5282546832 0.5572092264 0.7853489619 0.2287987598 -0.14281461259 +1403636991501666560.0000000000 -0.4097329134 6.3324230272 -0.5231827363 0.5569891887 0.7858071498 0.2282974722 -0.141952214408 +1403636991551666432.0000000000 -0.3837776709 6.2975123615 -0.5157233820 0.5569386815 0.7860911731 0.2265562602 -0.143360502086 +1403636991601666560.0000000000 -0.3581950199 6.2628537834 -0.5071964385 0.5563093569 0.7869136482 0.2249820984 -0.143770181748 +1403636991651666432.0000000000 -0.3337047950 6.2289616136 -0.4960682954 0.5555251478 0.7878692969 0.2219663782 -0.146235112062 +1403636991701666560.0000000000 -0.3091136132 6.1946687528 -0.4839892254 0.5539267689 0.7894472282 0.2182594234 -0.149335302763 +1403636991751666432.0000000000 -0.2847858447 6.1612725247 -0.4708097034 0.5526478139 0.7907800842 0.2150634791 -0.151640865784 +1403636991801666560.0000000000 -0.2603050660 6.1287495460 -0.4566015121 0.5520677699 0.7916214205 0.2119728405 -0.15370172084 +1403636991851666432.0000000000 -0.2356463177 6.0971192095 -0.4428419412 0.5509870488 0.7928086619 0.2091048575 -0.155379716478 +1403636991901666560.0000000000 -0.2106507248 6.0664888520 -0.4302401299 0.5503555932 0.7936435939 0.2073492565 -0.155707587454 +1403636991951666432.0000000000 -0.1851231345 6.0368985888 -0.4190977944 0.5505742191 0.7938811941 0.2063600834 -0.155036108221 +1403636992001666560.0000000000 -0.1591513216 6.0080510125 -0.4102556550 0.5510737946 0.7939477977 0.2063164770 -0.152964305262 +1403636992051666432.0000000000 -0.1325246206 5.9799540789 -0.4030556025 0.5539243947 0.7923791121 0.2074827139 -0.149177850798 +1403636992101666560.0000000000 -0.1057557524 5.9524233003 -0.3972300647 0.5570643594 0.7905060228 0.2087350909 -0.145633750543 +1403636992151666432.0000000000 -0.0790848133 5.9250893885 -0.3925329948 0.5602787805 0.7884971182 0.2090063680 -0.143792631287 +1403636992201666560.0000000000 -0.0523342613 5.8977746281 -0.3890346933 0.5635527129 0.7864458413 0.2093475824 -0.141721092823 +1403636992251666432.0000000000 -0.0256613061 5.8702067293 -0.3866528885 0.5652227793 0.7854867621 0.2093152247 -0.140431096985 +1403636992301666560.0000000000 0.0009702349 5.8424577877 -0.3853733312 0.5660568327 0.7851452197 0.2092111474 -0.139130665174 +1403636992351666432.0000000000 0.0276093778 5.8144040254 -0.3852861206 0.5655739865 0.7857796074 0.2091174904 -0.137645739607 +1403636992401666560.0000000000 0.0539501251 5.7862725641 -0.3861716804 0.5637212913 0.7873817232 0.2094209906 -0.135614071647 +1403636992451666432.0000000000 0.0799615371 5.7581220963 -0.3864859828 0.5611936633 0.7894643259 0.2094604315 -0.133918176813 +1403636992501666560.0000000000 0.1055246552 5.7301985791 -0.3851786764 0.5596453456 0.7908693809 0.2092966752 -0.132354113005 +1403636992551666432.0000000000 0.1306375504 5.7026544223 -0.3823164980 0.5586985245 0.7918227622 0.2096840931 -0.130020202788 +1403636992601666560.0000000000 0.1550926214 5.6753697105 -0.3770751185 0.5577713635 0.7927595507 0.2092950538 -0.128914628154 +1403636992651666432.0000000000 0.1788765116 5.6485710832 -0.3699086947 0.5573703155 0.7933457613 0.2085669044 -0.128221218447 +1403636992701666560.0000000000 0.2022483136 5.6217859032 -0.3616934173 0.5570834401 0.7937892648 0.2085244224 -0.126784104343 +1403636992751666432.0000000000 0.2248168857 5.5952411261 -0.3535183060 0.5562311620 0.7946015313 0.2081873323 -0.125989426337 +1403636992801666560.0000000000 0.2466503695 5.5691187828 -0.3463100074 0.5564200687 0.7947546836 0.2081548203 -0.124230715998 +1403636992851666432.0000000000 0.2674995996 5.5431836619 -0.3404464793 0.5568275915 0.7946917916 0.2078935454 -0.123240673572 +1403636992901666560.0000000000 0.2875987675 5.5176850246 -0.3362358143 0.5575085814 0.7944737691 0.2080412259 -0.121303174903 +1403636992951666432.0000000000 0.3066717084 5.4924218882 -0.3335411281 0.5583356196 0.7940473901 0.2080578554 -0.120258084965 +1403636993001666560.0000000000 0.3247014948 5.4673813753 -0.3318579332 0.5599992361 0.7931718973 0.2066526886 -0.120722256383 +1403636993051666432.0000000000 0.3419480472 5.4423259225 -0.3309789638 0.5617816041 0.7922353779 0.2044499621 -0.122330488532 +1403636993101666560.0000000000 0.3581074242 5.4169301951 -0.3307629913 0.5632475630 0.7910407529 0.2028690644 -0.125900169818 +1403636993151666432.0000000000 0.3733549383 5.3908732998 -0.3299891641 0.5643724916 0.7896141241 0.2023141209 -0.130622441324 +1403636993201666560.0000000000 0.3883596198 5.3641268978 -0.3284241638 0.5646047499 0.7882464595 0.2039311559 -0.135281480966 +1403636993251666432.0000000000 0.4029868156 5.3371382069 -0.3250183071 0.5644844116 0.7866585605 0.2072737722 -0.139868658798 +1403636993301666560.0000000000 0.4171152980 5.3101535781 -0.3196877838 0.5639953240 0.7848956706 0.2117739724 -0.144913233706 +1403636993351666432.0000000000 0.4312120075 5.2829264270 -0.3120683455 0.5633568807 0.7827297098 0.2176430734 -0.150315398301 +1403636993401666560.0000000000 0.4454484153 5.2552823148 -0.3024650042 0.5624945564 0.7803841368 0.2243036244 -0.155847223502 +1403636993451666432.0000000000 0.4599904829 5.2267692995 -0.2910248551 0.5612316235 0.7778766302 0.2315945888 -0.162144871687 +1403636993501666560.0000000000 0.4749412007 5.1977643900 -0.2783150641 0.5594192820 0.7754729194 0.2398253060 -0.167856011767 +1403636993551666432.0000000000 0.4902793628 5.1685130239 -0.2641079231 0.5583423438 0.7723184373 0.2484168215 -0.173398792753 +1403636993601666560.0000000000 0.5059563537 5.1387515310 -0.2494021428 0.5555770129 0.7703287345 0.2567303350 -0.178933950317 +1403636993651666432.0000000000 0.5218257849 5.1097559640 -0.2348831444 0.5526339868 0.7688443778 0.2640942307 -0.183652488851 +1403636993701666560.0000000000 0.5379613489 5.0811302005 -0.2212151047 0.5501898252 0.7674084552 0.2705363090 -0.187578049556 +1403636993751666432.0000000000 0.5542861345 5.0530386796 -0.2092291846 0.5481717256 0.7661336049 0.2762346851 -0.190371892387 +1403636993801666560.0000000000 0.5705499752 5.0254327471 -0.1988832639 0.5463437515 0.7651943053 0.2806754347 -0.192892407211 +1403636993851666432.0000000000 0.5869841898 4.9984537034 -0.1901585285 0.5460318943 0.7634767695 0.2852456027 -0.193874544644 +1403636993901666560.0000000000 0.6032412858 4.9713308270 -0.1828381802 0.5450765841 0.7624031431 0.2890139565 -0.195202197282 +1403636993951666432.0000000000 0.6192006704 4.9442862787 -0.1766066509 0.5457219287 0.7605995480 0.2905831682 -0.198084139963 +1403636994001666560.0000000000 0.6349745272 4.9172937806 -0.1718905787 0.5479436923 0.7579651213 0.2922878765 -0.199535415941 +1403636994051666432.0000000000 0.6507382412 4.8901305985 -0.1683974533 0.5510445114 0.7549622544 0.2936436809 -0.200387947473 +1403636994101666560.0000000000 0.6665532515 4.8624176096 -0.1657499501 0.5553345137 0.7513248757 0.2938718898 -0.201875757553 +1403636994151666432.0000000000 0.6825345831 4.8340556323 -0.1644066829 0.5585370494 0.7485476546 0.2938985781 -0.20331354875 +1403636994201666560.0000000000 0.6986240909 4.8048830602 -0.1638928381 0.5622042229 0.7454758903 0.2937058199 -0.204765720078 +1403636994251666432.0000000000 0.7150108014 4.7746550723 -0.1645228892 0.5652480485 0.7430542609 0.2928979665 -0.206339017774 +1403636994301666560.0000000000 0.7320019448 4.7432514417 -0.1662085055 0.5678489080 0.7410321924 0.2921308252 -0.207553579627 +1403636994351666432.0000000000 0.7497382294 4.7106205581 -0.1690669238 0.5695189679 0.7397270931 0.2919688227 -0.207860961912 +1403636994401666560.0000000000 0.7682636190 4.6766817660 -0.1725712440 0.5713867068 0.7384132154 0.2912826079 -0.208368896385 +1403636994451666432.0000000000 0.7878853139 4.6411978863 -0.1764839841 0.5716256444 0.7383879168 0.2911267396 -0.208020740568 +1403636994501666560.0000000000 0.8084915138 4.6043507113 -0.1795096370 0.5706174637 0.7392766657 0.2910455005 -0.207745609406 +1403636994551666432.0000000000 0.8298945522 4.5658819995 -0.1808690166 0.5675637964 0.7416220731 0.2896052689 -0.209754203612 +1403636994601666560.0000000000 0.8522472049 4.5264234989 -0.1807554882 0.5647596871 0.7438911013 0.2897702982 -0.209059081145 +1403636994651666432.0000000000 0.8752203175 4.4856391388 -0.1791440142 0.5603313957 0.7474002122 0.2894648080 -0.208882202685 +1403636994701666560.0000000000 0.8985010643 4.4440336586 -0.1754826853 0.5547017966 0.7516792460 0.2878087363 -0.210832538394 +1403636994751666432.0000000000 0.9224325527 4.4019367454 -0.1701414427 0.5485006104 0.7563229962 0.2861720023 -0.212669205433 +1403636994801666560.0000000000 0.9468244017 4.3598382429 -0.1634966462 0.5429035272 0.7605341338 0.2841604160 -0.214700837088 +1403636994851666432.0000000000 0.9717138021 4.3183109195 -0.1562767225 0.5392611134 0.7632184842 0.2816030560 -0.217703274658 +1403636994901666560.0000000000 0.9972696726 4.2775113193 -0.1501980065 0.5363055146 0.7654548910 0.2801771482 -0.218988516653 +1403636994951666432.0000000000 1.0234383792 4.2376662999 -0.1451490652 0.5362174664 0.7656577494 0.2789443473 -0.22006610498 +1403636995001666560.0000000000 1.0503914195 4.1986884130 -0.1417031569 0.5380376776 0.7644997233 0.2785919344 -0.220095807985 +1403636995051666432.0000000000 1.0779918986 4.1604603480 -0.1400930473 0.5413534691 0.7622097807 0.2799508942 -0.21817462835 +1403636995101666560.0000000000 1.1058245124 4.1227154485 -0.1392533748 0.5457423592 0.7590334893 0.2813067436 -0.216563975493 +1403636995151666432.0000000000 1.1341963300 4.0852217724 -0.1384045007 0.5498772192 0.7559904999 0.2827086397 -0.214916804673 +1403636995201666560.0000000000 1.1630952231 4.0477332273 -0.1367358368 0.5524435241 0.7539490393 0.2841927379 -0.213545045635 +1403636995251666432.0000000000 1.1925771794 4.0102124074 -0.1331091842 0.5548760722 0.7519550294 0.2851821833 -0.212949056306 +1403636995301666560.0000000000 1.2227402326 3.9722875136 -0.1272941293 0.5562397007 0.7507218972 0.2865300467 -0.211930556617 +1403636995351666432.0000000000 1.2540669727 3.9334367094 -0.1197139468 0.5563854443 0.7503286716 0.2882292691 -0.210632405806 +1403636995401666560.0000000000 1.2854339312 3.8941469288 -0.1108026204 0.5549297238 0.7510046605 0.2905159708 -0.208914987933 +1403636995451666432.0000000000 1.3171856761 3.8541690580 -0.0999429613 0.5523281515 0.7526652213 0.2922308605 -0.207436259606 +1403636995501666560.0000000000 1.3495367472 3.8133226785 -0.0875676259 0.5493193209 0.7545959655 0.2936140984 -0.206455742757 +1403636995551666432.0000000000 1.3819667060 3.7721675373 -0.0729099188 0.5481723642 0.7552225308 0.2937498101 -0.207019412535 +1403636995601666560.0000000000 1.4143060881 3.7314225475 -0.0576095576 0.5469843504 0.7559775595 0.2947553542 -0.205974102868 +1403636995651666432.0000000000 1.4463003364 3.6904538406 -0.0422009109 0.5456718484 0.7569188591 0.2936728296 -0.207538776786 +1403636995701666560.0000000000 1.4785026280 3.6494668478 -0.0279363419 0.5457038260 0.7569261184 0.2933632546 -0.207865789519 +1403636995751666432.0000000000 1.5104338380 3.6083150349 -0.0152391790 0.5448825643 0.7574920580 0.2926561910 -0.208952451761 +1403636995801666560.0000000000 1.5424979726 3.5671624747 -0.0040476682 0.5430154997 0.7589945625 0.2902814340 -0.211655640642 +1403636995851666432.0000000000 1.5748398070 3.5261287744 0.0055031394 0.5400253824 0.7611648141 0.2879881335 -0.214624199419 +1403636995901666560.0000000000 1.6074667903 3.4859149540 0.0136817958 0.5374472598 0.7630610835 0.2861679371 -0.216785925723 +1403636995951666432.0000000000 1.6404181329 3.4465831600 0.0204170919 0.5351768881 0.7647905830 0.2845859276 -0.218384780497 +1403636996001666560.0000000000 1.6739543926 3.4080408098 0.0256409130 0.5339446948 0.7657569899 0.2840214431 -0.218748977573 +1403636996051666432.0000000000 1.7081506256 3.3707472798 0.0289627285 0.5342794407 0.7656154088 0.2861603447 -0.215617212129 +1403636996101666560.0000000000 1.7428462322 3.3343530752 0.0311950815 0.5345397298 0.7655701022 0.2877051740 -0.213062030233 +1403636996151666432.0000000000 1.7778474790 3.2986657316 0.0335258689 0.5355914302 0.7649213623 0.2895934410 -0.210173186478 +1403636996201666560.0000000000 1.8130790734 3.2632961134 0.0369637826 0.5361240408 0.7645688776 0.2913291674 -0.207684280946 +1403636996251666432.0000000000 1.8480241657 3.2288224557 0.0413577859 0.5369211018 0.7640668510 0.2928901337 -0.205263117032 +1403636996301666560.0000000000 1.8819322503 3.1953762054 0.0486545783 0.5376046102 0.7632098948 0.2946853796 -0.20408935914 +1403636996351666432.0000000000 1.9156579162 3.1617266858 0.0578797139 0.5369078755 0.7628098412 0.2966684572 -0.204545608581 +1403636996401666560.0000000000 1.9488693654 3.1283082372 0.0699397508 0.5365302518 0.7616958853 0.2991165656 -0.206116344382 +1403636996451666432.0000000000 1.9819122043 3.0945665325 0.0837608000 0.5351969286 0.7606379745 0.3030127007 -0.207791777094 +1403636996501666560.0000000000 2.0142423562 3.0610995192 0.0989302345 0.5348760205 0.7582365615 0.3079061498 -0.210187445846 +1403636996551666432.0000000000 2.0463414763 3.0276616518 0.1157009483 0.5340186934 0.7557067835 0.3139628223 -0.212505620253 +1403636996601666560.0000000000 2.0779644155 2.9939170559 0.1337161216 0.5316646089 0.7536369404 0.3202506500 -0.21634145908 +1403636996651666432.0000000000 2.1088316742 2.9604561201 0.1513652900 0.5295149246 0.7507255354 0.3272515033 -0.221204811599 +1403636996701666560.0000000000 2.1394921304 2.9270654577 0.1657142740 0.5267980877 0.7477562040 0.3356396430 -0.22514542919 +1403636996751666432.0000000000 2.1699606798 2.8934568209 0.1758645370 0.5235057509 0.7447577840 0.3434656824 -0.230887195248 +1403636996801666560.0000000000 2.2000514365 2.8599374158 0.1821924855 0.5205392087 0.7409814764 0.3524844331 -0.23609343145 +1403636996851666432.0000000000 2.2296218602 2.8265116882 0.1856845840 0.5166827316 0.7375453792 0.3606537869 -0.242888069849 +1403636996901666560.0000000000 2.2587475290 2.7931726712 0.1871725265 0.5128698538 0.7336281982 0.3693669298 -0.249644249049 +1403636996951666432.0000000000 2.2874058824 2.7600557486 0.1871013927 0.5086041742 0.7297665350 0.3777508279 -0.25703484273 +1403636997001666560.0000000000 2.3152859713 2.7278819330 0.1856002948 0.5052552805 0.7250722743 0.3871324160 -0.262898822957 +1403636997051666432.0000000000 2.3426064478 2.6961769823 0.1829012815 0.5019152007 0.7206429192 0.3953902445 -0.269112372199 +1403636997101666560.0000000000 2.3694792601 2.6651342914 0.1786296848 0.4979538759 0.7170268896 0.4033721391 -0.274235837494 +1403636997151666432.0000000000 2.3959608542 2.6351390390 0.1733756340 0.4947361306 0.7139132647 0.4097840361 -0.278641445738 +1403636997201666560.0000000000 2.4217079640 2.6060867795 0.1668251560 0.4919999412 0.7112337117 0.4150881479 -0.282461492344 +1403636997251666432.0000000000 2.4464676687 2.5781855492 0.1594313886 0.4901276558 0.7085837380 0.4199785950 -0.285134962739 +1403636997301666560.0000000000 2.4705978427 2.5512163705 0.1521215808 0.4885214731 0.7065512189 0.4238287122 -0.287230513823 +1403636997351666432.0000000000 2.4945051378 2.5250508297 0.1457246775 0.4871025038 0.7051431461 0.4267681980 -0.288744176421 +1403636997401666560.0000000000 2.5176594794 2.4999163550 0.1414605442 0.4863276804 0.7038088536 0.4294593947 -0.289314903145 +1403636997451666432.0000000000 2.5403560099 2.4753703020 0.1398296664 0.4860623232 0.7027493258 0.4304074475 -0.290923069141 +1403636997501666560.0000000000 2.5620647617 2.4518673780 0.1394128916 0.4862320940 0.7019084290 0.4317824825 -0.290631718627 +1403636997551666432.0000000000 2.5829944759 2.4289243350 0.1408662725 0.4859171731 0.7017714098 0.4323926884 -0.290582092169 +1403636997601666560.0000000000 2.6030255313 2.4067564403 0.1446335830 0.4851886450 0.7023380973 0.4324582052 -0.290332699942 +1403636997651666432.0000000000 2.6220261744 2.3855281828 0.1504870164 0.4852301846 0.7025744295 0.4323805873 -0.289806602153 +1403636997701666560.0000000000 2.6399671602 2.3649978190 0.1581232257 0.4855576823 0.7027694144 0.4325075415 -0.288593336537 +1403636997751666432.0000000000 2.6563801537 2.3453055846 0.1675128517 0.4859804299 0.7031805052 0.4325289458 -0.286843005566 +1403636997801666560.0000000000 2.6716530837 2.3260739123 0.1784675337 0.4857320703 0.7040649196 0.4324302113 -0.285238597218 +1403636997851666432.0000000000 2.6867463351 2.3071510712 0.1926342877 0.4861270787 0.7043733770 0.4318961702 -0.28461255664 +1403636997901666560.0000000000 2.7001831746 2.2889549068 0.2073169720 0.4865009768 0.7050694808 0.4312367279 -0.283246732 +1403636997951666432.0000000000 2.7126550448 2.2710045017 0.2242082416 0.4866471301 0.7056227466 0.4301170644 -0.283320350652 +1403636998001666560.0000000000 2.7244433535 2.2538804343 0.2431800411 0.4870204563 0.7062002174 0.4293900029 -0.282341200518 +1403636998051666432.0000000000 2.7353518716 2.2370174696 0.2634129676 0.4871740616 0.7069017632 0.4285846086 -0.281543183649 +1403636998101666560.0000000000 2.7455637450 2.2204213594 0.2840885606 0.4870957697 0.7075568487 0.4276921777 -0.281390152903 +1403636998151666432.0000000000 2.7544771196 2.2045985347 0.3049655628 0.4880592169 0.7075585731 0.4264125779 -0.281658267637 +1403636998201666560.0000000000 2.7623724675 2.1890911030 0.3248414972 0.4880911407 0.7081788887 0.4243503783 -0.283154474492 +1403636998251666432.0000000000 2.7696926357 2.1740734429 0.3426960118 0.4877210568 0.7087789896 0.4236965662 -0.283269720363 +1403636998301666560.0000000000 2.7764232185 2.1598585340 0.3589126513 0.4879590295 0.7093531638 0.4234277229 -0.281820932401 +1403636998351666432.0000000000 2.7821385030 2.1461629076 0.3737339184 0.4882944380 0.7095099777 0.4226498174 -0.282012881365 +1403636998401666560.0000000000 2.7867570299 2.1329929878 0.3870801076 0.4882166691 0.7099143540 0.4218931345 -0.282262780271 +1403636998451666432.0000000000 2.7905593372 2.1204121022 0.3994880408 0.4880195718 0.7104626907 0.4210682964 -0.282455576034 +1403636998501666560.0000000000 2.7935918214 2.1085927559 0.4126941458 0.4881597294 0.7107584831 0.4201033141 -0.282905748965 +1403636998551666432.0000000000 2.7961472144 2.0974949736 0.4275539121 0.4907321902 0.7093310735 0.4197063503 -0.282626830242 +1403636998601666560.0000000000 2.7983046078 2.0868043044 0.4436546432 0.4929554442 0.7079414797 0.4184707480 -0.284070456829 +1403636998651666432.0000000000 2.7996847096 2.0772459748 0.4619813594 0.4997191912 0.7035319815 0.4173533536 -0.284850240007 +1403636998701666560.0000000000 2.8010306973 2.0674199831 0.4819940880 0.5045817556 0.7002504369 0.4151552064 -0.287563440163 +1403636998751666432.0000000000 2.8027344140 2.0576590921 0.5029098741 0.5088049740 0.6973973738 0.4136327513 -0.289244444437 +1403636998801666560.0000000000 2.8050443707 2.0480733186 0.5239766856 0.5123049949 0.6953459022 0.4130660609 -0.288814988939 +1403636998851666432.0000000000 2.8079093319 2.0380513627 0.5440866344 0.5150982318 0.6933368583 0.4146124649 -0.286451246329 +1403636998901666560.0000000000 2.8109087381 2.0273953005 0.5630759384 0.5171256195 0.6921056993 0.4149510102 -0.285283111606 +1403636998951666432.0000000000 2.8144057214 2.0160466712 0.5802350338 0.5183220448 0.6915214881 0.4158044881 -0.283278867817 +1403636999001666560.0000000000 2.8181367918 2.0040078679 0.5958857980 0.5187115848 0.6913716193 0.4165719072 -0.281800323062 +1403636999051666432.0000000000 2.8222993475 1.9911226054 0.6100300236 0.5202282373 0.6903753935 0.4174236263 -0.2801819293 +1403636999101666560.0000000000 2.8267912382 1.9771164418 0.6223732811 0.5199649019 0.6906596229 0.4179450980 -0.279191119662 +1403636999151666432.0000000000 2.8312806392 1.9624243672 0.6331776085 0.5199506421 0.6908858770 0.4185745457 -0.27771097286 +1403636999201666560.0000000000 2.8358269483 1.9467211378 0.6423429786 0.5188403577 0.6918209752 0.4191494847 -0.276590185815 +1403636999251666432.0000000000 2.8404109062 1.9302249250 0.6501416144 0.5181301709 0.6924176463 0.4194748793 -0.275934330548 +1403636999301666560.0000000000 2.8448882096 1.9127693034 0.6565581689 0.5163259917 0.6938689215 0.4189900974 -0.276406744246 +1403636999351666432.0000000000 2.8495187609 1.8945520854 0.6616544107 0.5142150347 0.6956078803 0.4178695522 -0.277664567905 +1403636999401666560.0000000000 2.8536753015 1.8757093443 0.6660243933 0.5132147416 0.6963934212 0.4162199886 -0.280013844452 +1403636999451666432.0000000000 2.8577732539 1.8566284838 0.6691565469 0.5120663352 0.6973762240 0.4148715326 -0.281666614812 +1403636999501666560.0000000000 2.8619224420 1.8372542180 0.6711921952 0.5121201258 0.6973602871 0.4141210255 -0.282710776257 +1403636999551666432.0000000000 2.8661534368 1.8176001319 0.6724920812 0.5132550119 0.6967902155 0.4127530826 -0.284055595283 +1403636999601666560.0000000000 2.8705354563 1.7974677966 0.6728760089 0.5138628152 0.6963721178 0.4115620742 -0.285705337327 +1403636999651666432.0000000000 2.8753549820 1.7770100066 0.6724394529 0.5149663243 0.6957079795 0.4105459017 -0.286796364601 +1403636999701666560.0000000000 2.8806866248 1.7561668584 0.6710086044 0.5157805633 0.6953311554 0.4096592311 -0.28751401572 +1403636999751666432.0000000000 2.8865788218 1.7348610063 0.6687954231 0.5158025510 0.6954242875 0.4092806591 -0.287788343999 +1403636999801666560.0000000000 2.8928674031 1.7134887324 0.6661616430 0.5162355459 0.6954601202 0.4086941985 -0.287758812998 +1403636999851666432.0000000000 2.8998382713 1.6915974039 0.6627001439 0.5162920818 0.6955031093 0.4089800404 -0.287146718257 +1403636999901666560.0000000000 2.9073125286 1.6694544040 0.6584912339 0.5169357188 0.6951813650 0.4093395055 -0.286254260293 +1403636999951666432.0000000000 2.9153437367 1.6468963908 0.6540097792 0.5178314938 0.6946711433 0.4099505324 -0.284996680002 +1403637000001666560.0000000000 2.9239648219 1.6239409547 0.6505309368 0.5191997537 0.6937023134 0.4113937167 -0.282778934879 +1403637000051666432.0000000000 2.9330433214 1.5999876836 0.6486809887 0.5197232246 0.6931415654 0.4128346763 -0.281087299961 +1403637000101666560.0000000000 2.9429123126 1.5750797849 0.6485313264 0.5192036113 0.6935480403 0.4134204108 -0.280182600738 +1403637000151666432.0000000000 2.9532377447 1.5490998419 0.6506500946 0.5183761196 0.6940788153 0.4135635606 -0.280189182556 +1403637000201666560.0000000000 2.9637372561 1.5223219416 0.6543530507 0.5168045690 0.6950130675 0.4142373325 -0.27978081739 +1403637000251666432.0000000000 2.9737676376 1.4952398911 0.6589824405 0.5154347772 0.6960249717 0.4141953081 -0.279854383351 +1403637000301666560.0000000000 2.9837921736 1.4678754698 0.6635786851 0.5144290655 0.6966985369 0.4143348570 -0.279822285661 +1403637000351666432.0000000000 2.9936325705 1.4402649364 0.6677354634 0.5141667353 0.6968796754 0.4139715305 -0.280390545833 +1403637000401666560.0000000000 3.0039071144 1.4122338328 0.6709638732 0.5139533007 0.6969890807 0.4128356439 -0.282178945302 +1403637000451666432.0000000000 3.0146786063 1.3842411900 0.6724506593 0.5146683280 0.6965258045 0.4136416590 -0.28083606217 +1403637000501666560.0000000000 3.0255239858 1.3557067152 0.6731182384 0.5150402971 0.6962223545 0.4139056024 -0.28051751785 +1403637000551666432.0000000000 3.0367741844 1.3265790857 0.6736813117 0.5154505347 0.6960267702 0.4142268381 -0.279774208983 +1403637000601666560.0000000000 3.0481577304 1.2967718993 0.6748588590 0.5151898476 0.6961145776 0.4143445714 -0.27986155844 +1403637000651666432.0000000000 3.0596360050 1.2661239417 0.6775524685 0.5152525694 0.6961208822 0.4131866442 -0.281437922188 +1403637000701666560.0000000000 3.0711639769 1.2352481745 0.6817937378 0.5150947394 0.6962728942 0.4124936510 -0.282365816305 +1403637000751666432.0000000000 3.0827318899 1.2042814716 0.6882770110 0.5154115590 0.6960005615 0.4126302517 -0.282259488132 +1403637000801666560.0000000000 3.0942802442 1.1730661458 0.6971735757 0.5157264688 0.6961003963 0.4116252950 -0.282904690887 +1403637000851666432.0000000000 3.1060688285 1.1412463436 0.7062988455 0.5157186656 0.6962286528 0.4107739056 -0.283839249199 +1403637000901666560.0000000000 3.1181824195 1.1091927847 0.7141205665 0.5153218756 0.6966835591 0.4108326572 -0.28335827267 +1403637000951666432.0000000000 3.1304677323 1.0770076108 0.7206018030 0.5153121875 0.6969695279 0.4106562889 -0.282927974836 +1403637001001666560.0000000000 3.1432710743 1.0444392882 0.7255542638 0.5157400836 0.6968883996 0.4099340068 -0.283395191943 +1403637001051666432.0000000000 3.1565817218 1.0114642218 0.7284809675 0.5158820676 0.6968161663 0.4097639000 -0.28356034441 +1403637001101666560.0000000000 3.1701078862 0.9781716477 0.7301961831 0.5157420705 0.6971507162 0.4091862556 -0.283826714484 +1403637001151666432.0000000000 3.1839725536 0.9447193589 0.7308797812 0.5159307982 0.6970890765 0.4090209423 -0.283873386716 +1403637001201666560.0000000000 3.1981320520 0.9111293734 0.7318070249 0.5159918099 0.6972304013 0.4078168402 -0.285144953302 +1403637001251666432.0000000000 3.2131992652 0.8770325743 0.7336683415 0.5153901653 0.6978013505 0.4074302824 -0.285388888757 +1403637001301666560.0000000000 3.2291495995 0.8425669848 0.7375077858 0.5153561447 0.6978289521 0.4071712064 -0.285752351412 +1403637001351666432.0000000000 3.2457434940 0.8079273689 0.7435841510 0.5142345985 0.6987923723 0.4065063790 -0.286364386804 +1403637001401666560.0000000000 3.2623956113 0.7733900186 0.7518491661 0.5125317786 0.7000390471 0.4062237954 -0.286772970453 +1403637001451666432.0000000000 3.2793994323 0.7388944226 0.7612627171 0.5106055573 0.7015485848 0.4070271129 -0.285377780063 +1403637001501666560.0000000000 3.2964712296 0.7045849894 0.7717492169 0.5089481392 0.7031571006 0.4070040658 -0.284410924406 +1403637001551666432.0000000000 3.3139049837 0.6705117624 0.7819005390 0.5079579902 0.7042177170 0.4069633957 -0.283613966047 +1403637001601666560.0000000000 3.3316010776 0.6365323368 0.7911654013 0.5073155093 0.7049527881 0.4069845081 -0.282906611391 +1403637001651666432.0000000000 3.3494728762 0.6026411265 0.7994080002 0.5064250586 0.7057787254 0.4060601587 -0.283769622024 +1403637001701666560.0000000000 3.3674584310 0.5693301410 0.8061305993 0.5073412725 0.7053921414 0.4065065838 -0.282452044281 +1403637001751666432.0000000000 3.3856441896 0.5360889579 0.8116938369 0.5077196114 0.7054535370 0.4060676153 -0.282250235085 +1403637001801666560.0000000000 3.4038384335 0.5028335614 0.8161006821 0.5080397387 0.7053865235 0.4048488984 -0.283589220362 +1403637001851666432.0000000000 3.4225178809 0.4697380783 0.8181233794 0.5072562491 0.7061496034 0.4055373685 -0.282105083293 +1403637001901666560.0000000000 3.4410509912 0.4368847190 0.8190766153 0.5067425717 0.7066054992 0.4057747591 -0.281544808888 +1403637001951666432.0000000000 3.4595102360 0.4043920297 0.8189835323 0.5068010183 0.7067168068 0.4058473280 -0.281055206816 +1403637002001666560.0000000000 3.4779282982 0.3718837682 0.8176495816 0.5059842223 0.7072867563 0.4062973424 -0.280442294937 +1403637002051666432.0000000000 3.4960569004 0.3397380252 0.8155794862 0.5061669773 0.7072739697 0.4067700851 -0.279457726082 +1403637002101666560.0000000000 3.5141533251 0.3077663621 0.8126311380 0.5054777120 0.7079003018 0.4064758298 -0.279547572164 +1403637002151666432.0000000000 3.5322033234 0.2758559506 0.8087011376 0.5056154828 0.7077800739 0.4063545537 -0.279779068466 +1403637002201666560.0000000000 3.5503396063 0.2440809054 0.8036534704 0.5051577454 0.7080953476 0.4064706909 -0.279639425836 +1403637002251666432.0000000000 3.5683921412 0.2126761452 0.7976143928 0.5050255000 0.7082430154 0.4066437028 -0.279252528279 +1403637002301666560.0000000000 3.5864380475 0.1816057416 0.7913566045 0.5059116579 0.7076429338 0.4071514611 -0.278428734603 +1403637002351666432.0000000000 3.6050516974 0.1505695535 0.7856914145 0.5062105942 0.7073469547 0.4076959539 -0.277840114582 +1403637002401666560.0000000000 3.6226499170 0.1200203508 0.7815189365 0.5064230767 0.7070943508 0.4088421614 -0.276407911253 +1403637002451666432.0000000000 3.6400006152 0.0895035324 0.7795206668 0.5073883458 0.7063962539 0.4090798491 -0.276070780877 +1403637002501666560.0000000000 3.6565379970 0.0592982036 0.7794340225 0.5079309409 0.7059600684 0.4095693673 -0.275462292163 +1403637002551666432.0000000000 3.6728039806 0.0292251506 0.7809756477 0.5093741441 0.7048427383 0.4112412760 -0.27315802846 +1403637002601666560.0000000000 3.6885972735 -0.0011059010 0.7859872457 0.5097976498 0.7045607311 0.4110103039 -0.273442978476 +1403637002651666432.0000000000 3.7047395617 -0.0317732713 0.7929003486 0.5098871821 0.7045989224 0.4111638412 -0.272946360431 +1403637002701666560.0000000000 3.7209971621 -0.0626614910 0.8004132312 0.5100700124 0.7047787818 0.4112178687 -0.272057559425 +1403637002751666432.0000000000 3.7365553176 -0.0936749635 0.8077535942 0.5097969602 0.7052457534 0.4108360496 -0.271936071573 +1403637002801666560.0000000000 3.7516968188 -0.1248169448 0.8143692284 0.5104113455 0.7050981603 0.4102927483 -0.271986587022 +1403637002851666432.0000000000 3.7664213867 -0.1562270338 0.8195612975 0.5098252406 0.7058133664 0.4090213132 -0.273143334566 +1403637002901666560.0000000000 3.7809098201 -0.1879269765 0.8231577826 0.5093663470 0.7065517431 0.4071317554 -0.2749077894 +1403637002951666432.0000000000 3.7952897930 -0.2195013104 0.8245022158 0.5092803265 0.7070187004 0.4064176384 -0.274923279236 +1403637003001666560.0000000000 3.8094564540 -0.2511328378 0.8242900593 0.5088394267 0.7076421306 0.4059235101 -0.27486570675 +1403637003051666432.0000000000 3.8232607512 -0.2826758837 0.8227080878 0.5085880069 0.7082334661 0.4050830023 -0.275047919457 +1403637003101666560.0000000000 3.8370154158 -0.3141024832 0.8195869352 0.5083065102 0.7088933130 0.4046016017 -0.274576594802 +1403637003151666432.0000000000 3.8504088536 -0.3453557587 0.8153651460 0.5089539184 0.7087644390 0.4042903236 -0.274168220608 +1403637003201666560.0000000000 3.8637433746 -0.3764448608 0.8099489232 0.5091643845 0.7091357327 0.4033839412 -0.274152399469 +1403637003251666432.0000000000 3.8771329955 -0.4073080879 0.8036961565 0.5098516351 0.7090856558 0.4029380929 -0.273659891415 +1403637003301666560.0000000000 3.8902542206 -0.4383670763 0.7983875838 0.5103647640 0.7090551088 0.4014556089 -0.274958277519 +1403637003351666432.0000000000 3.9035161563 -0.4696199490 0.7941710435 0.5104931731 0.7092281814 0.4003173302 -0.275931408376 +1403637003401666560.0000000000 3.9166691097 -0.5005545595 0.7912764291 0.5117899881 0.7085525956 0.3997983795 -0.276017178781 +1403637003451666432.0000000000 3.9292273750 -0.5311404218 0.7905161484 0.5127342606 0.7080926365 0.3988953855 -0.276750551338 +1403637003501666560.0000000000 3.9420326060 -0.5616315602 0.7918766855 0.5128960274 0.7084002775 0.3977395367 -0.277326473538 +1403637003551666432.0000000000 3.9553482823 -0.5923634977 0.7949678467 0.5123855173 0.7089411156 0.3973633302 -0.277427395939 +1403637003601666560.0000000000 3.9689512872 -0.6229987877 0.7996407216 0.5122412906 0.7093031792 0.3967925061 -0.277585243363 +1403637003651666432.0000000000 3.9826713543 -0.6535559052 0.8060619802 0.5121333974 0.7095944181 0.3963105904 -0.277728394421 +1403637003701666560.0000000000 3.9966995692 -0.6840047467 0.8125711825 0.5118808117 0.7099102230 0.3962444188 -0.277481297554 +1403637003751666432.0000000000 4.0108301266 -0.7141754810 0.8181709223 0.5116329335 0.7100478184 0.3964259755 -0.277327032467 +1403637003801666560.0000000000 4.0251469670 -0.7443461323 0.8227861382 0.5105027190 0.7105616726 0.3961594573 -0.278472202716 +1403637003851666432.0000000000 4.0398945409 -0.7740021909 0.8259112105 0.5094458556 0.7110819568 0.3974016901 -0.277307171906 +1403637003901666560.0000000000 4.0546424266 -0.8032910729 0.8275970935 0.5091681768 0.7108770952 0.3990201443 -0.276015303457 +1403637003951666432.0000000000 4.0694185564 -0.8326286983 0.8273089068 0.5075092484 0.7114796771 0.4009057078 -0.274782905753 +1403637004001666560.0000000000 4.0842299333 -0.8618196441 0.8253984864 0.5065053992 0.7115954989 0.4027672566 -0.27361042308 +1403637004051666432.0000000000 4.0990248776 -0.8907309131 0.8215770871 0.5054513638 0.7118618519 0.4050752742 -0.271450999117 +1403637004101666560.0000000000 4.1132025393 -0.9194230624 0.8167125302 0.5045066482 0.7120467143 0.4058879312 -0.271509679353 +1403637004151666432.0000000000 4.1267971365 -0.9476946582 0.8107443518 0.5045222041 0.7115876275 0.4073681237 -0.270465535301 +1403637004201666560.0000000000 4.1398242468 -0.9759787294 0.8047461290 0.5033417276 0.7120254232 0.4081043757 -0.270402885443 +1403637004251666432.0000000000 4.1519144394 -1.0039801201 0.8005965049 0.5030982102 0.7116460349 0.4091459220 -0.270280828925 +1403637004301666560.0000000000 4.1629954112 -1.0320622682 0.7989875090 0.5021068130 0.7119466758 0.4085203315 -0.272271588418 +1403637004351666432.0000000000 4.1735066616 -1.0595143821 0.7989883694 0.5015405361 0.7123126156 0.4081501581 -0.272912580764 +1403637004401666560.0000000000 4.1828972132 -1.0860782881 0.8012651528 0.5022028503 0.7119746417 0.4064589440 -0.275091863961 +1403637004451666432.0000000000 4.1918195891 -1.1122408007 0.8063601796 0.5036452159 0.7112149530 0.4049535586 -0.276635866446 +1403637004501666560.0000000000 4.2001476445 -1.1379233143 0.8150924084 0.5072620402 0.7091921590 0.4028093976 -0.278345636638 +1403637004551666432.0000000000 4.2089511418 -1.1636359107 0.8265176904 0.5097805806 0.7079878650 0.4012685189 -0.279034976975 +1403637004601666560.0000000000 4.2185424001 -1.1898978949 0.8403613383 0.5097264308 0.7087855947 0.3989978404 -0.280361676916 +1403637004651666432.0000000000 4.2287009536 -1.2166096678 0.8557423643 0.5080795821 0.7107634896 0.3951544129 -0.28376643585 +1403637004701666560.0000000000 4.2390316389 -1.2428527438 0.8707762119 0.5055150612 0.7133656891 0.3910815483 -0.287435451998 +1403637004751666432.0000000000 4.2499222938 -1.2681100771 0.8836285246 0.5041172666 0.7151832933 0.3875110443 -0.290196190614 +1403637004801666560.0000000000 4.2608175889 -1.2926055139 0.8933929422 0.5019627176 0.7173483586 0.3842102588 -0.29296286381 +1403637004851666432.0000000000 4.2729066022 -1.3164401604 0.8986945711 0.5001741837 0.7193315843 0.3827676360 -0.293047427105 +1403637004901666560.0000000000 4.2856162043 -1.3392137904 0.8994652076 0.4975951750 0.7217193532 0.3825353713 -0.291867961289 +1403637004951666432.0000000000 4.2986338119 -1.3605373817 0.8964887533 0.4951866692 0.7240590586 0.3831129780 -0.289401258368 +1403637005001666560.0000000000 4.3119898835 -1.3806245073 0.8901218862 0.4943607240 0.7251275855 0.3850128332 -0.285591627232 +1403637005051666432.0000000000 4.3252887968 -1.3991690010 0.8823539602 0.4958693991 0.7245366412 0.3870744245 -0.281662181443 +1403637005101666560.0000000000 4.3383767113 -1.4164231498 0.8740597308 0.4990709390 0.7227996964 0.3882616491 -0.278821965603 +1403637005151666432.0000000000 4.3512032004 -1.4326477966 0.8647299968 0.5027448785 0.7206404427 0.3904059463 -0.274787438898 +1403637005201666560.0000000000 4.3635991354 -1.4484289294 0.8551274294 0.5044075559 0.7196703430 0.3908100419 -0.27370627701 +1403637005251666432.0000000000 4.3760479494 -1.4636503851 0.8442860115 0.5049485336 0.7194014034 0.3924008455 -0.271127600366 +1403637005301666560.0000000000 4.3883652203 -1.4786408017 0.8325922901 0.5040379441 0.7199551912 0.3938823931 -0.269196831326 +1403637005351666432.0000000000 4.4004763586 -1.4933685844 0.8204537657 0.5030013586 0.7205548033 0.3950095335 -0.267876608067 +1403637005401666560.0000000000 4.4121348776 -1.5076811019 0.8082684418 0.5034605860 0.7197797236 0.3959735104 -0.267674367315 +1403637005451666432.0000000000 4.4231643264 -1.5218899724 0.7963301746 0.5056003911 0.7176178921 0.3966032941 -0.268511885315 +1403637005501666560.0000000000 4.4338916576 -1.5359189399 0.7847220125 0.5081882679 0.7151409986 0.3975511949 -0.268832817588 +1403637005551666432.0000000000 4.4440226541 -1.5501325639 0.7748801826 0.5092080714 0.7138149878 0.3980262392 -0.269722850341 +1403637005601666560.0000000000 4.4541666008 -1.5646887727 0.7674711335 0.5083266087 0.7138065590 0.3980936288 -0.271303737529 +1403637005651666432.0000000000 4.4643349754 -1.5794997399 0.7621594792 0.5045694710 0.7157874005 0.3989210991 -0.271882332925 +1403637005701666560.0000000000 4.4739394288 -1.5941816439 0.7601172306 0.4999151764 0.7185508512 0.3985999904 -0.273655875854 +1403637005751666432.0000000000 4.4832126797 -1.6083325163 0.7612541774 0.4966382622 0.7204757797 0.3983988510 -0.274851674209 +1403637005801666560.0000000000 4.4919089349 -1.6214435720 0.7650844026 0.4962462971 0.7204073861 0.3988663056 -0.275060867674 +1403637005851666432.0000000000 4.5000517639 -1.6335889560 0.7703438350 0.4982081711 0.7187621108 0.3999560477 -0.274234947264 +1403637005901666560.0000000000 4.5075120851 -1.6451409005 0.7757309673 0.5001615412 0.7171768685 0.4007405685 -0.273683701972 +1403637005951666432.0000000000 4.5143811326 -1.6562232994 0.7807303943 0.5024514607 0.7154442940 0.4011712248 -0.27339283138 +1403637006001666560.0000000000 4.5207495527 -1.6669642353 0.7848695993 0.5045333872 0.7140209267 0.4010144963 -0.273509691182 +1403637006051666432.0000000000 4.5266303623 -1.6776106969 0.7882780592 0.5055498823 0.7133390684 0.4000114081 -0.27487736072 +1403637006101666560.0000000000 4.5322322525 -1.6882247465 0.7909930205 0.5058716680 0.7130748594 0.3988874061 -0.276598874974 +1403637006151666432.0000000000 4.5379521099 -1.6987110913 0.7932242181 0.5061907054 0.7128036245 0.3986266890 -0.277089742646 +1403637006201666560.0000000000 4.5435072540 -1.7092487161 0.7952186907 0.5053373994 0.7132778500 0.3986077120 -0.277453984145 +1403637006251666432.0000000000 4.5492181778 -1.7196600193 0.7965758291 0.5027949795 0.7150417524 0.3989458268 -0.277046436911 +1403637006301666560.0000000000 4.5549543873 -1.7298670959 0.7973677805 0.4987460789 0.7178182681 0.3994256785 -0.27649305634 +1403637006351666432.0000000000 4.5605049978 -1.7396597563 0.7973735760 0.4935839394 0.7212727205 0.4008657156 -0.274676601661 +1403637006401666560.0000000000 4.5654017891 -1.7488500386 0.7972711505 0.4894730441 0.7239890676 0.4018829342 -0.273397286524 +1403637006451666432.0000000000 4.5695131918 -1.7573229067 0.7968386207 0.4856764562 0.7264999133 0.4016624519 -0.273831208072 +1403637006501666560.0000000000 4.5727055769 -1.7647855794 0.7960771734 0.4827191272 0.7284222575 0.4000056839 -0.276366987544 +1403637006551666432.0000000000 4.5749497253 -1.7709405587 0.7955970359 0.4834944554 0.7270879539 0.3985836581 -0.280548189148 +1403637006601666560.0000000000 4.5766034495 -1.7756040440 0.7948758212 0.4865867165 0.7235351308 0.3993525148 -0.283280515839 +1403637006651666432.0000000000 4.5778777858 -1.7794427496 0.7935273679 0.4897014895 0.7189445303 0.4017078508 -0.286255159188 +1403637006701666560.0000000000 4.5789027134 -1.7826799715 0.7913527020 0.4923646086 0.7138595113 0.4054067858 -0.289183381835 +1403637006751666432.0000000000 4.5799799885 -1.7855119814 0.7886170125 0.4944734088 0.7082014297 0.4100192072 -0.292969337403 +1403637006801666560.0000000000 4.5814664067 -1.7882678276 0.7849567858 0.4950276617 0.7028886710 0.4149730597 -0.297812844069 +1403637006851666432.0000000000 4.5829844782 -1.7908262622 0.7805209812 0.4923509607 0.6989422389 0.4211725524 -0.302793591896 +1403637006901666560.0000000000 4.5844723628 -1.7932036076 0.7758848311 0.4891936748 0.6943885740 0.4285442629 -0.307999791501 +1403637006951666432.0000000000 4.5862817236 -1.7954826619 0.7706475029 0.4852967830 0.6893680928 0.4382274309 -0.311793816349 +1403637007001666560.0000000000 4.5884818400 -1.7973372933 0.7657540686 0.4824545345 0.6835127871 0.4478811949 -0.315357459437 +1403637007051666432.0000000000 4.5905198262 -1.7987768260 0.7611972682 0.4805397856 0.6775856819 0.4558761724 -0.31958734907 +1403637007101666560.0000000000 4.5924625452 -1.7996672281 0.7562287943 0.4792641328 0.6720648960 0.4631402177 -0.322700798307 +1403637007151666432.0000000000 4.5944750106 -1.8003069278 0.7513719026 0.4781413490 0.6670109577 0.4691881667 -0.32609768021 +1403637007201666560.0000000000 4.5963275793 -1.8007547128 0.7466932404 0.4775003705 0.6624545082 0.4739778676 -0.32938184788 +1403637007251666432.0000000000 4.5978168120 -1.8007553568 0.7420696902 0.4791123594 0.6572229605 0.4778760570 -0.331879197054 +1403637007301666560.0000000000 4.5997941217 -1.8006941219 0.7373829241 0.4821120368 0.6517004088 0.4809411986 -0.333991204341 +1403637007351666432.0000000000 4.6020322373 -1.8011586946 0.7328527824 0.4842926703 0.6475191197 0.4826985214 -0.336424934424 +1403637007401666560.0000000000 4.6048228500 -1.8022414416 0.7276947779 0.4850081152 0.6451432223 0.4847593424 -0.336995149594 +1403637007451666432.0000000000 4.6084652329 -1.8041983091 0.7218862773 0.4832675421 0.6449321730 0.4863622646 -0.337589577013 +1403637007501666560.0000000000 4.6125741152 -1.8065789341 0.7159573075 0.4820981332 0.6448106582 0.4878324398 -0.337372369394 +1403637007551666432.0000000000 4.6171734962 -1.8095859533 0.7097564338 0.4804350534 0.6454350323 0.4891974867 -0.336573316708 +1403637007601666560.0000000000 4.6222358943 -1.8132456715 0.7027236715 0.4760120774 0.6483361925 0.4908440147 -0.334880332178 +1403637007651666432.0000000000 4.6274462289 -1.8174451059 0.6951960451 0.4710134969 0.6519436785 0.4932593734 -0.331377302048 +1403637007701666560.0000000000 4.6325529391 -1.8220921592 0.6879647425 0.4664542811 0.6554768582 0.4949987315 -0.328247997478 +1403637007751666432.0000000000 4.6370823244 -1.8269137328 0.6810748222 0.4632247832 0.6581010740 0.4967604687 -0.324892002678 +1403637007801666560.0000000000 4.6403851750 -1.8316848302 0.6754127016 0.4633146593 0.6586293317 0.4967679752 -0.323679639106 +1403637007851666432.0000000000 4.6423245640 -1.8367942184 0.6704999908 0.4650451396 0.6580640288 0.4952074873 -0.324737273336 +1403637007901666560.0000000000 4.6431775048 -1.8422540990 0.6667795226 0.4675467925 0.6572020851 0.4902071845 -0.330427499539 +1403637007951666432.0000000000 4.6435787696 -1.8478695790 0.6634769951 0.4697686745 0.6565362860 0.4846227387 -0.336776333398 +1403637008001666560.0000000000 4.6443390190 -1.8531732261 0.6599031874 0.4721787574 0.6557111462 0.4808272140 -0.340433993722 +1403637008051666432.0000000000 4.6459553834 -1.8582519500 0.6559524743 0.4740790890 0.6552941587 0.4795975509 -0.340330386739 +1403637008101666560.0000000000 4.6486002254 -1.8632538248 0.6512677010 0.4722275873 0.6576584064 0.4810321653 -0.336295379436 +1403637008151666432.0000000000 4.6517768758 -1.8682854321 0.6464961979 0.4682657528 0.6614407338 0.4837289916 -0.330499021222 +1403637008201666560.0000000000 4.6546248765 -1.8733891281 0.6424744701 0.4639659930 0.6652832290 0.4860688468 -0.325378024355 +1403637008251666432.0000000000 4.6567875559 -1.8783062541 0.6394466222 0.4607861384 0.6682609253 0.4881131136 -0.320700886539 +1403637008301666560.0000000000 4.6580847676 -1.8828857753 0.6374030097 0.4593277542 0.6699766589 0.4900840451 -0.316175456901 +1403637008351666432.0000000000 4.6579226849 -1.8872883360 0.6366728425 0.4590881540 0.6708287400 0.4907215325 -0.313718418326 +1403637008401666560.0000000000 4.6562375899 -1.8916352383 0.6374751095 0.4607380793 0.6704855042 0.4895608487 -0.313846756188 +1403637008451666432.0000000000 4.6528232998 -1.8959263556 0.6400147007 0.4646005275 0.6685551595 0.4856934083 -0.318248741833 +1403637008501666560.0000000000 4.6483731516 -1.9000107118 0.6431242074 0.4683405224 0.6667718031 0.4817366790 -0.322493860159 +1403637008551666432.0000000000 4.6435192916 -1.9040169419 0.6464616578 0.4718203569 0.6650552911 0.4779571492 -0.326563889826 +1403637008601666560.0000000000 4.6386536728 -1.9078544835 0.6487614258 0.4743427023 0.6640978914 0.4746497760 -0.329667380256 +1403637008651666432.0000000000 4.6341830011 -1.9118481430 0.6498053552 0.4758410108 0.6636769174 0.4721600451 -0.331923445417 +1403637008701666560.0000000000 4.6299859816 -1.9160450971 0.6499981904 0.4743138275 0.6653420572 0.4689631906 -0.335290718324 +1403637008751666432.0000000000 4.6261217599 -1.9202933079 0.6494406426 0.4697096015 0.6691042221 0.4656434932 -0.338893150469 +1403637008801666560.0000000000 4.6226133854 -1.9241795236 0.6483600667 0.4631361914 0.6740489189 0.4625431461 -0.342369334333 +1403637008851666432.0000000000 4.6192148074 -1.9269373234 0.6464088153 0.4574045991 0.6781499238 0.4603552772 -0.344915543764 +1403637008901666560.0000000000 4.6159438295 -1.9279564353 0.6426986843 0.4534590308 0.6811033788 0.4595999745 -0.345312841109 +1403637008951666432.0000000000 4.6129251444 -1.9268580187 0.6376971338 0.4525580871 0.6821337568 0.4593233922 -0.344828561727 +1403637009001666560.0000000000 4.6101597221 -1.9236833569 0.6315793110 0.4550955376 0.6808788752 0.4605590122 -0.34231185375 +1403637009051666432.0000000000 4.6074057165 -1.9186704218 0.6241227071 0.4594275593 0.6784626829 0.4629522046 -0.338067984239 +1403637009101666560.0000000000 4.6051362265 -1.9125806328 0.6156220594 0.4638548618 0.6758090257 0.4656761284 -0.333566442279 +1403637009151666432.0000000000 4.6032590527 -1.9057985255 0.6070067916 0.4676886030 0.6734780866 0.4681103941 -0.329495518028 +1403637009201666560.0000000000 4.6013082355 -1.8982076014 0.5979292302 0.4718745652 0.6707750412 0.4711392809 -0.324689107937 +1403637009251666432.0000000000 4.5993501945 -1.8901539949 0.5880608633 0.4762920978 0.6678502535 0.4751085954 -0.318423772768 +1403637009301666560.0000000000 4.5963971217 -1.8819459600 0.5778567796 0.4807000894 0.6646862567 0.4798955593 -0.311158892409 +1403637009351666432.0000000000 4.5915360404 -1.8739406790 0.5676613226 0.4857622496 0.6610301244 0.4834641088 -0.305510502186 +1403637009401666560.0000000000 4.5895305849 -1.8701116859 0.5659240102 0.4775922275 0.6608084534 0.4788104901 -0.325543187245 +1403637009451666432.0000000000 4.5899450099 -1.8645972528 0.5619746351 0.4786989502 0.6539403445 0.4859081047 -0.327265419398 diff --git a/data/euroc_groundtruth/MH_03_medium.txt b/data/euroc_groundtruth/MH_03_medium.txt new file mode 100755 index 00000000..134b3f1b --- /dev/null +++ b/data/euroc_groundtruth/MH_03_medium.txt @@ -0,0 +1,2632 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403637132888318976.0000000000 4.6053979055 -1.8480601270 0.5587802567 0.4895050236 0.6601100115 0.4362728530 -0.366477287495 +1403637132938319104.0000000000 4.6053662210 -1.8476316042 0.5586384325 0.4899099547 0.6599110595 0.4365313624 -0.365986337832 +1403637132988318976.0000000000 4.6051003710 -1.8478513267 0.5587431947 0.4890700274 0.6607357371 0.4356430823 -0.366679558852 +1403637133038319104.0000000000 4.6047968101 -1.8477829055 0.5587033690 0.4887768113 0.6611309512 0.4354998430 -0.366528281059 +1403637133088318976.0000000000 4.6051499000 -1.8477694265 0.5588528485 0.4893955558 0.6604729490 0.4357749920 -0.366561904665 +1403637133138319104.0000000000 4.6063243719 -1.8484318468 0.5599004518 0.4889010200 0.6598586575 0.4351928657 -0.369011536929 +1403637133188318976.0000000000 4.6072515488 -1.8482409130 0.5608780200 0.4896561599 0.6595321061 0.4354831222 -0.368250860698 +1403637133238319104.0000000000 4.6076354927 -1.8473726342 0.5614334922 0.4918185750 0.6590826392 0.4363449739 -0.365140559032 +1403637133288318976.0000000000 4.6085067746 -1.8469514190 0.5629914620 0.4929506310 0.6589672768 0.4373750921 -0.362580794201 +1403637133338319104.0000000000 4.6094818850 -1.8465863086 0.5660221937 0.4932197507 0.6595985531 0.4377852569 -0.360566353317 +1403637133388318976.0000000000 4.6103791226 -1.8457527567 0.5707320418 0.4936418435 0.6617783776 0.4366845184 -0.357314624104 +1403637133438319104.0000000000 4.6112912648 -1.8453105006 0.5752269165 0.4926208826 0.6644323523 0.4360973768 -0.354504433258 +1403637133488318976.0000000000 4.6125496520 -1.8458491253 0.5784793980 0.4890660400 0.6669293193 0.4371506124 -0.353438868322 +1403637133538319104.0000000000 4.6130156676 -1.8447260206 0.5805040542 0.4860848641 0.6707209787 0.4369211288 -0.350649113425 +1403637133588318976.0000000000 4.6136365544 -1.8432872877 0.5820662562 0.4832157821 0.6744515058 0.4364201782 -0.348073415023 +1403637133638319104.0000000000 4.6147375699 -1.8413447347 0.5848205072 0.4819642479 0.6771852270 0.4357908061 -0.345278156596 +1403637133688318976.0000000000 4.6164855791 -1.8391579616 0.5894588164 0.4824367058 0.6784087606 0.4359172563 -0.342041699373 +1403637133738319104.0000000000 4.6187189234 -1.8372736579 0.5974728885 0.4832160464 0.6792628233 0.4352790747 -0.340053519936 +1403637133788318976.0000000000 4.6210041406 -1.8357564995 0.6089892343 0.4845211685 0.6802265137 0.4338092129 -0.338143008394 +1403637133838319104.0000000000 4.6221786721 -1.8337028937 0.6243506347 0.4856411473 0.6828295277 0.4314216799 -0.334322966965 +1403637133888318976.0000000000 4.6227641147 -1.8317654725 0.6446973436 0.4854280246 0.6865090394 0.4290718915 -0.330094355643 +1403637133938319104.0000000000 4.6230760421 -1.8305003814 0.6704093499 0.4843362192 0.6897953047 0.4270701975 -0.327432299508 +1403637133988318976.0000000000 4.6233684911 -1.8295591808 0.6998090187 0.4851504172 0.6917059409 0.4256647530 -0.324008459964 +1403637134038319104.0000000000 4.6235429832 -1.8289398578 0.7316844567 0.4869462490 0.6922509104 0.4245044428 -0.321664430057 +1403637134088318976.0000000000 4.6237437222 -1.8282600191 0.7639807038 0.4904573962 0.6918702737 0.4244109890 -0.3172418308 +1403637134138319104.0000000000 4.6237559283 -1.8276892218 0.7964924743 0.4948822888 0.6913999002 0.4238562026 -0.31209552665 +1403637134188318976.0000000000 4.6232054527 -1.8268086752 0.8285776267 0.5004732719 0.6901900938 0.4229472026 -0.30705016258 +1403637134238319104.0000000000 4.6220715746 -1.8262175517 0.8606190965 0.5082183526 0.6876112336 0.4203230587 -0.303699561766 +1403637134288318976.0000000000 4.6212494586 -1.8263979984 0.8905536845 0.5146517118 0.6839715406 0.4173743037 -0.305147895026 +1403637134338319104.0000000000 4.6205884892 -1.8264386079 0.9169776572 0.5210143350 0.6797198203 0.4143225720 -0.307996485136 +1403637134388318976.0000000000 4.6198968317 -1.8262070120 0.9385654264 0.5271649990 0.6756454435 0.4107126479 -0.311312414329 +1403637134438319104.0000000000 4.6189239630 -1.8258017156 0.9532961278 0.5315685162 0.6740078251 0.4055990886 -0.314066463555 +1403637134488318976.0000000000 4.6177309045 -1.8255076214 0.9604144285 0.5326170910 0.6742179989 0.4006189167 -0.318203720737 +1403637134538319104.0000000000 4.6164459594 -1.8244190347 0.9583489602 0.5319367195 0.6758966730 0.3978156915 -0.319295614427 +1403637134588318976.0000000000 4.6153603098 -1.8223670648 0.9471828543 0.5300553983 0.6782338792 0.3977482769 -0.317547458073 +1403637134638319104.0000000000 4.6145104263 -1.8195331785 0.9275437445 0.5273122423 0.6808786497 0.4001811839 -0.313370521264 +1403637134688318976.0000000000 4.6137911415 -1.8165618205 0.9002152264 0.5230933148 0.6839713280 0.4040065681 -0.308764148632 +1403637134738319104.0000000000 4.6130571133 -1.8141540698 0.8669701838 0.5157957128 0.6879888506 0.4090013535 -0.305522530989 +1403637134788318976.0000000000 4.6129908850 -1.8127021451 0.8301368911 0.5065954135 0.6928371580 0.4150389879 -0.301795291562 +1403637134838319104.0000000000 4.6135331999 -1.8125058230 0.7921086124 0.4956165849 0.6993887736 0.4194301128 -0.29882758341 +1403637134888318976.0000000000 4.6146628546 -1.8132512700 0.7550472256 0.4844118979 0.7057365430 0.4236236731 -0.296351191212 +1403637134938319104.0000000000 4.6160672506 -1.8145332193 0.7207002793 0.4751887394 0.7119405437 0.4250167674 -0.294443664507 +1403637134988318976.0000000000 4.6174655878 -1.8164284537 0.6906905574 0.4682039676 0.7158826446 0.4253570422 -0.295581580143 +1403637135038319104.0000000000 4.6188442595 -1.8180498738 0.6654506847 0.4644191283 0.7180702580 0.4253944184 -0.296191773306 +1403637135088318976.0000000000 4.6200466407 -1.8193672981 0.6454853200 0.4619246122 0.7194469680 0.4254383610 -0.296688243485 +1403637135138319104.0000000000 4.6249946604 -1.8163290638 0.6269595431 0.4599997961 0.7201592613 0.4273625674 -0.295181405261 +1403637135188318976.0000000000 4.6271995119 -1.8167547670 0.6182082945 0.4573869567 0.7214685380 0.4301184587 -0.292024711328 +1403637135238319104.0000000000 4.6292041237 -1.8170044863 0.6177347123 0.4527443317 0.7241221315 0.4336630458 -0.287412719908 +1403637135288318976.0000000000 4.6302008957 -1.8164306631 0.6277002027 0.4485160010 0.7270689682 0.4358455519 -0.283271543121 +1403637135338319104.0000000000 4.6299590134 -1.8150397916 0.6484724211 0.4481198015 0.7281251881 0.4359483603 -0.281018471069 +1403637135388318976.0000000000 4.6286500444 -1.8132499867 0.6779538491 0.4525043412 0.7262723546 0.4346268663 -0.280834070618 +1403637135438319104.0000000000 4.6267009335 -1.8108556034 0.7139740376 0.4612194000 0.7215661771 0.4325618197 -0.281973738657 +1403637135488318976.0000000000 4.6243198079 -1.8081818049 0.7546617264 0.4724881845 0.7152913733 0.4301792294 -0.282946986842 +1403637135538319104.0000000000 4.6217619008 -1.8060288152 0.7978074687 0.4831526617 0.7089110654 0.4272300092 -0.285452493664 +1403637135588318976.0000000000 4.6189396991 -1.8037596306 0.8415216744 0.4937508337 0.7033151814 0.4240583698 -0.285888735086 +1403637135638319104.0000000000 4.6157555522 -1.8019727545 0.8844143127 0.5033193201 0.6989459626 0.4192136368 -0.287061195839 +1403637135688318976.0000000000 4.6126968227 -1.8007930745 0.9251317837 0.5118534095 0.6946368321 0.4138894359 -0.290140127407 +1403637135738319104.0000000000 4.6101162084 -1.8006166397 0.9617183164 0.5176792418 0.6913230699 0.4084177584 -0.295424356251 +1403637135788318976.0000000000 4.6081675805 -1.8009212854 0.9920325556 0.5215693680 0.6888372016 0.4032787837 -0.301388331886 +1403637135838319104.0000000000 4.6068213359 -1.8007203630 1.0134570351 0.5242283872 0.6871845592 0.3997701461 -0.305197985008 +1403637135888318976.0000000000 4.6052347528 -1.8001544790 1.0255101079 0.5251571342 0.6868132851 0.3968979817 -0.308171199107 +1403637135938319104.0000000000 4.6098215872 -1.7973442173 1.0300847548 0.5250537672 0.6875873124 0.3956559988 -0.308218364042 +1403637135988318976.0000000000 4.6085748342 -1.7964953384 1.0214660383 0.5230331382 0.6887454043 0.3964574816 -0.30803826012 +1403637136038319104.0000000000 4.6071030637 -1.7962448610 1.0026871473 0.5203071498 0.6900395680 0.3988957183 -0.306607355475 +1403637136088318976.0000000000 4.6051426459 -1.7958806286 0.9750953499 0.5176779980 0.6917390665 0.4019593495 -0.303208238034 +1403637136138319104.0000000000 4.6027425314 -1.7956971852 0.9406012269 0.5137985845 0.6947851473 0.4038580872 -0.300305276435 +1403637136188318976.0000000000 4.6007093846 -1.7955920264 0.9004561802 0.5097945155 0.6978370205 0.4081164445 -0.294234621424 +1403637136238319104.0000000000 4.5992937950 -1.7965662559 0.8585880502 0.5027019946 0.7030101668 0.4108627951 -0.290274307459 +1403637136288318976.0000000000 4.5992336111 -1.7981935956 0.8160344356 0.4940072506 0.7086046818 0.4155222724 -0.284916623619 +1403637136338319104.0000000000 4.6000228140 -1.8000150884 0.7753196021 0.4847270553 0.7151563864 0.4190119236 -0.279320662971 +1403637136388318976.0000000000 4.6021651991 -1.8026941752 0.7375472343 0.4742191298 0.7215049940 0.4222942428 -0.276069435173 +1403637136438319104.0000000000 4.6052952845 -1.8057972380 0.7035188680 0.4639667078 0.7271623332 0.4257866532 -0.27326829515 +1403637136488318976.0000000000 4.6082912359 -1.8051908317 0.6735577727 0.4539873322 0.7324775860 0.4274936546 -0.273168928327 +1403637136538319104.0000000000 4.6112359484 -1.8075169831 0.6543679640 0.4463616467 0.7365994214 0.4281766322 -0.273582426783 +1403637136588318976.0000000000 4.6135593249 -1.8089437468 0.6436059765 0.4421077042 0.7388419894 0.4291019944 -0.272992254191 +1403637136638319104.0000000000 4.6151566969 -1.8094723406 0.6425552224 0.4401834362 0.7396095714 0.4307014743 -0.271500394952 +1403637136688318976.0000000000 4.6161029319 -1.8092715073 0.6524296359 0.4400221324 0.7392584230 0.4328318028 -0.269321624552 +1403637136738319104.0000000000 4.6162547857 -1.8090889168 0.6741899576 0.4401293949 0.7390587944 0.4326306467 -0.270016550939 +1403637136788318976.0000000000 4.6159667275 -1.8086055296 0.7058802929 0.4425035857 0.7374545474 0.4322038959 -0.271203170244 +1403637136838319104.0000000000 4.6154679273 -1.8078540060 0.7454689270 0.4480457786 0.7335649994 0.4310365390 -0.274490207407 +1403637136888318976.0000000000 4.6142489459 -1.8060146288 0.7906119363 0.4572112198 0.7284015922 0.4283753906 -0.277278822962 +1403637136938319104.0000000000 4.6135991836 -1.8031523232 0.8400393682 0.4673753062 0.7235332416 0.4235478636 -0.280476698902 +1403637136988318976.0000000000 4.6120860759 -1.7995734761 0.8891323641 0.4790448485 0.7190715623 0.4176372505 -0.281124969339 +1403637137038319104.0000000000 4.6110723244 -1.7967973249 0.9358381206 0.4896771372 0.7152581838 0.4101656375 -0.28352456972 +1403637137088318976.0000000000 4.6100781065 -1.7947655038 0.9778939160 0.4996758265 0.7115521958 0.4022564128 -0.286718188014 +1403637137138319104.0000000000 4.6091721783 -1.7944176333 1.0129530831 0.5066011189 0.7081465007 0.3942132322 -0.294074424987 +1403637137188318976.0000000000 4.6084851020 -1.7947621619 1.0383180838 0.5114227878 0.7046913088 0.3883448755 -0.30173688719 +1403637137238319104.0000000000 4.6089032287 -1.7935764262 1.0554304751 0.5155704399 0.7007016723 0.3864544960 -0.306361241758 +1403637137288318976.0000000000 4.6085893987 -1.7920748843 1.0592533319 0.5189415931 0.6979726448 0.3853303053 -0.308308880541 +1403637137338319104.0000000000 4.6079347125 -1.7905495697 1.0525208327 0.5217850242 0.6957804252 0.3848075148 -0.309116749788 +1403637137388318976.0000000000 4.6069629664 -1.7898238553 1.0354831076 0.5231158279 0.6940918863 0.3855435768 -0.309745757766 +1403637137438319104.0000000000 4.6053827211 -1.7895896647 1.0099203854 0.5220734496 0.6937871393 0.3866216771 -0.3108414345 +1403637137488318976.0000000000 4.6039024839 -1.7894612886 0.9763892198 0.5200201611 0.6947848987 0.3902321090 -0.307525409718 +1403637137538319104.0000000000 4.6029184280 -1.7902661489 0.9371487831 0.5156916618 0.6970313815 0.3957798397 -0.302601522997 +1403637137588318976.0000000000 4.6027098807 -1.7910245600 0.8938089569 0.5103543351 0.7009861968 0.4022445508 -0.293864128231 +1403637137638319104.0000000000 4.6027640895 -1.7922223506 0.8486589654 0.5028327994 0.7070407454 0.4083193594 -0.283774313357 +1403637137688318976.0000000000 4.6031338874 -1.7941592585 0.8040662059 0.4935538756 0.7142690154 0.4124803257 -0.275833874618 +1403637137738319104.0000000000 4.6040730478 -1.7973877896 0.7622827809 0.4831029631 0.7207737718 0.4162233048 -0.271762501916 +1403637137788318976.0000000000 4.6068480931 -1.8017673451 0.7246399401 0.4736832495 0.7256725620 0.4194325406 -0.270369850077 +1403637137838319104.0000000000 4.6091738784 -1.8019764597 0.6886763717 0.4657426078 0.7290862648 0.4225673255 -0.270099791044 +1403637137888318976.0000000000 4.6137086608 -1.8057517253 0.6621602600 0.4584016318 0.7316163194 0.4264322729 -0.269742510021 +1403637137938319104.0000000000 4.6180165210 -1.8079888722 0.6439120308 0.4522769490 0.7342942248 0.4303427737 -0.266575786474 +1403637137988318976.0000000000 4.6212853029 -1.8086685173 0.6360046146 0.4459154072 0.7373270869 0.4343458589 -0.262396439378 +1403637138038319104.0000000000 4.6232408141 -1.8080207223 0.6403322061 0.4401333985 0.7404689789 0.4369702173 -0.258931094994 +1403637138088318976.0000000000 4.6239510707 -1.8067299708 0.6577479656 0.4364211211 0.7424049532 0.4371662391 -0.259339873435 +1403637138138319104.0000000000 4.6236151691 -1.8050028385 0.6867321415 0.4366071896 0.7408399177 0.4374183400 -0.263050516389 +1403637138188318976.0000000000 4.6226555542 -1.8011972213 0.7240521445 0.4430323159 0.7348377925 0.4400876109 -0.264686003625 +1403637138238319104.0000000000 4.6215663712 -1.7959929853 0.7677582010 0.4563509755 0.7265105197 0.4413291704 -0.262973031318 +1403637138288318976.0000000000 4.6200622500 -1.7910077678 0.8164612948 0.4707861584 0.7185559472 0.4380097174 -0.264924953972 +1403637138338319104.0000000000 4.6179627220 -1.7881925360 0.8654003440 0.4854252036 0.7108564430 0.4319246066 -0.269233399333 +1403637138388318976.0000000000 4.6153082146 -1.7865596586 0.9129140776 0.4998996782 0.7041872097 0.4228167167 -0.274675644253 +1403637138438319104.0000000000 4.6134221377 -1.7854661621 0.9554996658 0.5139815854 0.6974434021 0.4148872455 -0.277964393986 +1403637138488318976.0000000000 4.6122681976 -1.7850822986 0.9911813063 0.5251452312 0.6926053770 0.4069226097 -0.280952429462 +1403637138538319104.0000000000 4.6116463418 -1.7851835169 1.0174078802 0.5331706923 0.6889473100 0.4004179373 -0.284158569263 +1403637138588318976.0000000000 4.6114382299 -1.7850806861 1.0329294054 0.5388064196 0.6859100107 0.3964870903 -0.286379270705 +1403637138638319104.0000000000 4.6117109586 -1.7834255389 1.0417558574 0.5410450450 0.6841337705 0.3943258862 -0.289375774535 +1403637138688318976.0000000000 4.6108372157 -1.7824917609 1.0359858077 0.5406291361 0.6840522799 0.3939362953 -0.290872499166 +1403637138738319104.0000000000 4.6090707865 -1.7816657800 1.0198557965 0.5375466746 0.6858015033 0.3936193727 -0.292888477308 +1403637138788318976.0000000000 4.6066711838 -1.7801544261 0.9944558596 0.5334336878 0.6890013894 0.3939586718 -0.292441705486 +1403637138838319104.0000000000 4.6033788542 -1.7781380217 0.9610849946 0.5284703868 0.6936710240 0.3945469426 -0.289607097228 +1403637138888318976.0000000000 4.6007269923 -1.7765392479 0.9216815247 0.5223512965 0.6984318094 0.3967958157 -0.286173393842 +1403637138938319104.0000000000 4.5990267154 -1.7761592726 0.8785729793 0.5158378189 0.7020789533 0.4007334882 -0.283565088478 +1403637138988318976.0000000000 4.5968594333 -1.7771387420 0.8351769811 0.5074509421 0.7056340907 0.4027091131 -0.287053029148 +1403637139038319104.0000000000 4.5948276362 -1.7789882425 0.7926572400 0.4992907728 0.7084442197 0.4048029895 -0.291461921178 +1403637139088318976.0000000000 4.5932000938 -1.7815889005 0.7528035084 0.4921382289 0.7109912394 0.4060980717 -0.295593939821 +1403637139138319104.0000000000 4.5921892479 -1.7848959040 0.7159766795 0.4865908131 0.7128337015 0.4077465175 -0.298060852917 +1403637139188318976.0000000000 4.5900784810 -1.7848274637 0.6803496891 0.4811438019 0.7145057923 0.4095721892 -0.300387643838 +1403637139238319104.0000000000 4.5891874619 -1.7873791551 0.6515688965 0.4778021957 0.7150272403 0.4122045494 -0.300879572123 +1403637139288318976.0000000000 4.5876205368 -1.7892378221 0.6284410122 0.4761209839 0.7145633737 0.4141871627 -0.301922155199 +1403637139338319104.0000000000 4.5855690468 -1.7901370557 0.6110684049 0.4752611878 0.7137539055 0.4165699017 -0.301913369528 +1403637139388318976.0000000000 4.5834416050 -1.7901543916 0.5984609215 0.4749343646 0.7122644369 0.4198430364 -0.301410925482 +1403637139438319104.0000000000 4.5821142169 -1.7904623653 0.5896852978 0.4740563531 0.7097417050 0.4236037512 -0.303475119709 +1403637139488318976.0000000000 4.5808150597 -1.7908791224 0.5835654871 0.4737142472 0.7069019191 0.4262093516 -0.306969179911 +1403637139538319104.0000000000 4.5792675415 -1.7916232520 0.5789094539 0.4737176254 0.7045936870 0.4272267646 -0.310832172116 +1403637139588318976.0000000000 4.5776538921 -1.7923494401 0.5748803661 0.4753317145 0.7023317423 0.4273457523 -0.313313729272 +1403637139638319104.0000000000 4.5763143843 -1.7929405642 0.5710843527 0.4778123027 0.6994522751 0.4284586428 -0.314460028622 +1403637139688318976.0000000000 4.5751523308 -1.7932548212 0.5672097076 0.4793390353 0.6970903925 0.4293763918 -0.316124956489 +1403637139738319104.0000000000 4.5743470288 -1.7934060763 0.5628305502 0.4799381507 0.6955593709 0.4300776022 -0.317631530487 +1403637139788318976.0000000000 4.5740178443 -1.7930188403 0.5587202042 0.4806082086 0.6948991978 0.4303988978 -0.317628153039 +1403637139838319104.0000000000 4.5742966709 -1.7924376547 0.5565023035 0.4819419151 0.6939591182 0.4284876411 -0.320235966436 +1403637139888318976.0000000000 4.5748699773 -1.7913556857 0.5562343734 0.4868666837 0.6911228074 0.4250878046 -0.323435396592 +1403637139938319104.0000000000 4.5754406806 -1.7902397278 0.5558406510 0.4905187058 0.6901770418 0.4208046141 -0.325531145942 +1403637139988318976.0000000000 4.5763234863 -1.7899050851 0.5552344531 0.4928500139 0.6905532118 0.4160805602 -0.327279838892 +1403637140038319104.0000000000 4.5776038748 -1.7896596184 0.5553856662 0.4955157306 0.6907681193 0.4103715328 -0.329998138108 +1403637140088318976.0000000000 4.5790815363 -1.7888514891 0.5558106535 0.5009223643 0.6888469890 0.4069101409 -0.330137468072 +1403637140138319104.0000000000 4.5805954790 -1.7885592634 0.5566177874 0.5062922358 0.6869618647 0.4028805398 -0.330815415321 +1403637140188318976.0000000000 4.5818357970 -1.7883488120 0.5570570049 0.5085407045 0.6865994823 0.4000592511 -0.331542000943 +1403637140238319104.0000000000 4.5828726037 -1.7872446938 0.5561167791 0.5087047647 0.6881437788 0.3993333127 -0.328953655474 +1403637140288318976.0000000000 4.5835559408 -1.7865413866 0.5556117956 0.5086633693 0.6887897293 0.3981593073 -0.329088820108 +1403637140338319104.0000000000 4.5840692255 -1.7861721429 0.5550176923 0.5081227799 0.6893785694 0.3965219950 -0.330664083281 +1403637140388318976.0000000000 4.5841823424 -1.7864648564 0.5552948805 0.5074671040 0.6898651187 0.3955523324 -0.331815624518 +1403637140438319104.0000000000 4.5844048516 -1.7863636578 0.5552229483 0.5077228178 0.6896040041 0.3961869604 -0.331209526285 +1403637140488318976.0000000000 4.5845039546 -1.7866239341 0.5553548482 0.5073550008 0.6899021751 0.3954468191 -0.332035698661 +1403637140538319104.0000000000 4.5846244421 -1.7866595895 0.5553387105 0.5072983751 0.6899530600 0.3953928437 -0.332080762482 +1403637140588318976.0000000000 4.5846874372 -1.7869921802 0.5554920626 0.5067482819 0.6902636271 0.3948104325 -0.332967004733 +1403637140638319104.0000000000 4.5847767321 -1.7869527512 0.5553979816 0.5067599402 0.6902220202 0.3949170248 -0.332909100646 +1403637140688318976.0000000000 4.5848035289 -1.7870685104 0.5553624631 0.5066412439 0.6902413911 0.3948913559 -0.33308000398 +1403637140738319104.0000000000 4.5848727547 -1.7870614672 0.5553100119 0.5066447136 0.6902211428 0.3949684301 -0.333025295456 +1403637140788318976.0000000000 4.5849395776 -1.7871077417 0.5552952409 0.5065537359 0.6902405531 0.3949923054 -0.333095136809 +1403637140838319104.0000000000 4.5850313453 -1.7871316586 0.5553365629 0.5065091325 0.6902795192 0.3949606711 -0.333119726739 +1403637140888318976.0000000000 4.5850487718 -1.7870985349 0.5553056686 0.5064850552 0.6903162270 0.3949213513 -0.333126885642 +1403637140938319104.0000000000 4.5850596757 -1.7871075915 0.5552811385 0.5065237497 0.6903037210 0.3949491420 -0.333061013841 +1403637140988318976.0000000000 4.5850935392 -1.7871617329 0.5552672601 0.5064320909 0.6903611091 0.3949365863 -0.333096336259 +1403637141038319104.0000000000 4.5850609613 -1.7871524118 0.5552246535 0.5064393168 0.6903515859 0.3949569814 -0.333080904787 +1403637141088318976.0000000000 4.5850559972 -1.7871703933 0.5552287028 0.5064039505 0.6903792960 0.3949265336 -0.3331133435 +1403637141138319104.0000000000 4.5850683876 -1.7871231527 0.5552238794 0.5064282609 0.6903710369 0.3949788277 -0.333031490453 +1403637141188318976.0000000000 4.5850422288 -1.7871457254 0.5552512354 0.5063541575 0.6904090791 0.3949459420 -0.333104298437 +1403637141238319104.0000000000 4.5850213163 -1.7871152640 0.5552459764 0.5063856311 0.6903763821 0.3949970528 -0.333063615633 +1403637141288318976.0000000000 4.5850016712 -1.7871477656 0.5552924619 0.5063408570 0.6904045838 0.3949904753 -0.333081028569 +1403637141338319104.0000000000 4.5849477172 -1.7871490903 0.5552756681 0.5063137203 0.6904007363 0.3950048967 -0.333113151311 +1403637141388318976.0000000000 4.5849076765 -1.7871253732 0.5552671036 0.5063214511 0.6904067585 0.3950113452 -0.333081271107 +1403637141438319104.0000000000 4.5849053116 -1.7871188531 0.5552803752 0.5062764546 0.6904292145 0.3950332898 -0.333077095064 +1403637141488318976.0000000000 4.5848125667 -1.7870660072 0.5552483182 0.5062958297 0.6904306834 0.3950061176 -0.333076824892 +1403637141538319104.0000000000 4.5847680831 -1.7870763443 0.5552889914 0.5062580062 0.6904560798 0.3950267897 -0.333057154872 +1403637141588318976.0000000000 4.5846899187 -1.7870605752 0.5552680280 0.5062620892 0.6904546029 0.3950457031 -0.333031576475 +1403637141638319104.0000000000 4.5846330963 -1.7870410627 0.5552906315 0.5062836995 0.6904637395 0.3950004194 -0.333033494971 +1403637141688318976.0000000000 4.5846033496 -1.7870608824 0.5553376731 0.5062064629 0.6905118452 0.3949696380 -0.333087666709 +1403637141738319104.0000000000 4.5845744633 -1.7870220801 0.5553173764 0.5062355803 0.6905015125 0.3949878530 -0.333043232049 +1403637141788318976.0000000000 4.5845762831 -1.7870535686 0.5553576988 0.5061672456 0.6905393664 0.3950158120 -0.333035450474 +1403637141838319104.0000000000 4.5846022295 -1.7870829674 0.5553637847 0.5061561324 0.6905299680 0.3950129459 -0.333075224917 +1403637141888318976.0000000000 4.5846145774 -1.7870850018 0.5553256254 0.5061600000 0.6905233174 0.3950653451 -0.333020983685 +1403637141938319104.0000000000 4.5845822351 -1.7871530226 0.5553451190 0.5060671100 0.6905697351 0.3950279619 -0.33311023768 +1403637141988318976.0000000000 4.5846068878 -1.7870978732 0.5553623707 0.5061012135 0.6905602637 0.3950315238 -0.333073834222 +1403637142038319104.0000000000 4.5846462210 -1.7870696506 0.5553918772 0.5060751110 0.6905878971 0.3950053628 -0.333087228538 +1403637142088318976.0000000000 4.5847160737 -1.7870494857 0.5553737035 0.5060515352 0.6905948913 0.3950589047 -0.333045044433 +1403637142138319104.0000000000 4.5847637861 -1.7870620909 0.5553419635 0.5059659763 0.6906373860 0.3950627580 -0.333082345719 +1403637142188318976.0000000000 4.5847835562 -1.7870283264 0.5553328616 0.5060323843 0.6906033843 0.3950823813 -0.333028682877 +1403637142238319104.0000000000 4.5847698725 -1.7870705746 0.5553422570 0.5060055408 0.6906191962 0.3950509844 -0.333073923166 +1403637142288318976.0000000000 4.5847799642 -1.7870996139 0.5553753961 0.5060021322 0.6906197109 0.3950645244 -0.333061974245 +1403637142338319104.0000000000 4.5848131264 -1.7870979559 0.5553805519 0.5059908293 0.6906197926 0.3950645457 -0.333078950591 +1403637142388318976.0000000000 4.5848392447 -1.7870770588 0.5553659397 0.5060445355 0.6905874290 0.3951047286 -0.333016792945 +1403637142438319104.0000000000 4.5848019180 -1.7871086671 0.5553513741 0.5059776687 0.6906271745 0.3950677674 -0.333079815976 +1403637142488318976.0000000000 4.5847797353 -1.7870963940 0.5553454756 0.5059810304 0.6906353327 0.3950678080 -0.333057744382 +1403637142538319104.0000000000 4.5847801147 -1.7871083577 0.5553350346 0.5059759267 0.6906265351 0.3950498293 -0.333105062982 +1403637142588318976.0000000000 4.5847819847 -1.7871223642 0.5553458351 0.5059622034 0.6906296306 0.3950629634 -0.333103913204 +1403637142638319104.0000000000 4.5847736962 -1.7871312225 0.5552754560 0.5059239992 0.6906567097 0.3950551074 -0.333115112926 +1403637142688318976.0000000000 4.5848178740 -1.7871205619 0.5552821160 0.5059058950 0.6906561247 0.3950934895 -0.333098299858 +1403637142738319104.0000000000 4.5848049726 -1.7871250885 0.5552461559 0.5058898338 0.6906576176 0.3951035911 -0.333107615649 +1403637142788318976.0000000000 4.5847737929 -1.7871540357 0.5553120497 0.5058534320 0.6906750309 0.3950838158 -0.33315024459 +1403637142838319104.0000000000 4.5847281513 -1.7871294681 0.5553058657 0.5058645144 0.6906806992 0.3950682032 -0.333140180064 +1403637142888318976.0000000000 4.5847706853 -1.7871158269 0.5553822220 0.5058586228 0.6906764468 0.3950594474 -0.333168324697 +1403637142938319104.0000000000 4.5847551482 -1.7871250421 0.5553477943 0.5058343410 0.6906812314 0.3950670153 -0.333186298489 +1403637142988318976.0000000000 4.5848219243 -1.7871638220 0.5553578754 0.5058028999 0.6907039631 0.3950475049 -0.333210040007 +1403637143038319104.0000000000 4.5848712731 -1.7871634144 0.5553719506 0.5058184647 0.6906847267 0.3950301107 -0.333246906506 +1403637143088318976.0000000000 4.5849415497 -1.7871963984 0.5553850390 0.5057657491 0.6907008985 0.3950555031 -0.333263297352 +1403637143138319104.0000000000 4.5849599110 -1.7872419164 0.5553684794 0.5057413446 0.6906933051 0.3951077749 -0.333254102645 +1403637143188318976.0000000000 4.5849917256 -1.7872789062 0.5554254281 0.5057239907 0.6907181228 0.3950833087 -0.333258006971 +1403637143238319104.0000000000 4.5850188248 -1.7873017348 0.5553878783 0.5057311020 0.6907086048 0.3950979600 -0.33324957273 +1403637143288318976.0000000000 4.5850530461 -1.7873405749 0.5553695247 0.5057152388 0.6907100819 0.3950933819 -0.333276010972 +1403637143338319104.0000000000 4.5850876123 -1.7873405077 0.5553387357 0.5056793312 0.6907143165 0.3951324933 -0.33327535124 +1403637143388318976.0000000000 4.5851244963 -1.7873353508 0.5553690050 0.5056659289 0.6907139962 0.3951233393 -0.333307201654 +1403637143438319104.0000000000 4.5851185264 -1.7873044737 0.5552970596 0.5057140047 0.6906918649 0.3951016002 -0.333305893589 +1403637143488318976.0000000000 4.5851230664 -1.7872897953 0.5553192202 0.5056682631 0.6907054469 0.3950879884 -0.333363277391 +1403637143538319104.0000000000 4.5851702620 -1.7873099148 0.5552675300 0.5056119622 0.6907342726 0.3951108007 -0.333361910733 +1403637143588318976.0000000000 4.5851479538 -1.7872789211 0.5552888268 0.5057023486 0.6906677778 0.3950801663 -0.333398886713 +1403637143638319104.0000000000 4.5851671035 -1.7873122888 0.5552871230 0.5055978505 0.6907190500 0.3951076722 -0.333418558129 +1403637143688318976.0000000000 4.5851183055 -1.7873295019 0.5552718056 0.5055763878 0.6907309356 0.3951111491 -0.333422360698 +1403637143738319104.0000000000 4.5850445019 -1.7873622584 0.5552809276 0.5056178847 0.6907058704 0.3951096677 -0.333413115732 +1403637143788318976.0000000000 4.5849802011 -1.7874177324 0.5553396387 0.5056087019 0.6907187898 0.3950767634 -0.333439267338 +1403637143838319104.0000000000 4.5849339446 -1.7874504099 0.5553460759 0.5055966125 0.6907348346 0.3950791973 -0.33342147737 +1403637143888318976.0000000000 4.5848998823 -1.7874493354 0.5554259701 0.5056159608 0.6907103032 0.3950521295 -0.333475024948 +1403637143938319104.0000000000 4.5849030197 -1.7874990067 0.5554936610 0.5055352035 0.6905944584 0.3952381560 -0.333616924171 +1403637143988318976.0000000000 4.5849656112 -1.7874859183 0.5554917507 0.5055095256 0.6906336115 0.3952374595 -0.333575605802 +1403637144038319104.0000000000 4.5849930993 -1.7873672630 0.5554684291 0.5055049723 0.6906848003 0.3951395805 -0.333592478176 +1403637144088318976.0000000000 4.5850573859 -1.7872340208 0.5554937409 0.5055192601 0.6907256161 0.3951047010 -0.333527624369 +1403637144138319104.0000000000 4.5850782979 -1.7870838916 0.5555184693 0.5055054127 0.6908414483 0.3949060244 -0.333544004544 +1403637144188318976.0000000000 4.5851638095 -1.7870516673 0.5555483714 0.5055370971 0.6908290800 0.3949833320 -0.333430042452 +1403637144238319104.0000000000 4.5851212184 -1.7871422864 0.5555607164 0.5054113135 0.6908980656 0.3949403909 -0.333528641669 +1403637144288318976.0000000000 4.5851734716 -1.7872556018 0.5555480046 0.5054048945 0.6909173593 0.3950015604 -0.333425947618 +1403637144338319104.0000000000 4.5851119647 -1.7873000967 0.5555057299 0.5054528941 0.6909440189 0.3948680755 -0.333456050374 +1403637144388318976.0000000000 4.5851567108 -1.7873155445 0.5554446040 0.5054656691 0.6908859621 0.3949210691 -0.333494218833 +1403637144438319104.0000000000 4.5851434678 -1.7873012778 0.5553535958 0.5054665773 0.6908278502 0.3949360497 -0.333595469512 +1403637144488318976.0000000000 4.5851690323 -1.7873009423 0.5553014997 0.5054650311 0.6907425218 0.3950494851 -0.33364018822 +1403637144538319104.0000000000 4.5851538987 -1.7873574337 0.5553461144 0.5054215844 0.6907176705 0.3950634176 -0.333740944062 +1403637144588318976.0000000000 4.5852075919 -1.7871952122 0.5552624735 0.5055077424 0.6910116616 0.3947869058 -0.33332882403 +1403637144638319104.0000000000 4.5852222296 -1.7872437031 0.5553120742 0.5055056555 0.6908642935 0.3948941514 -0.333510373839 +1403637144688318976.0000000000 4.5852293584 -1.7873011374 0.5553639198 0.5054019459 0.6909290463 0.3948951739 -0.333532198901 +1403637144738319104.0000000000 4.5851958002 -1.7873974234 0.5554181463 0.5054969572 0.6906944432 0.3950859286 -0.333648200049 +1403637144788318976.0000000000 4.5850936905 -1.7874682435 0.5554451231 0.5054759485 0.6907253304 0.3950155602 -0.333699401446 +1403637144838319104.0000000000 4.5850209466 -1.7874402738 0.5554080410 0.5054913815 0.6907106188 0.3950898790 -0.333618482351 +1403637144888318976.0000000000 4.5849393893 -1.7874247713 0.5553850972 0.5053848402 0.6907608772 0.3950828060 -0.333684207227 +1403637144938319104.0000000000 4.5849501742 -1.7873486939 0.5553527331 0.5054053928 0.6906561764 0.3952906191 -0.333623682411 +1403637144988318976.0000000000 4.5849532749 -1.7873302735 0.5553562653 0.5051956417 0.6906512929 0.3954599225 -0.333750812541 +1403637145038319104.0000000000 4.5849734991 -1.7872680266 0.5553707089 0.5052444286 0.6906765171 0.3954063137 -0.333688272452 +1403637145088318976.0000000000 4.5849175663 -1.7872999489 0.5554618583 0.5052483502 0.6907441865 0.3952939483 -0.333675392827 +1403637145138319104.0000000000 4.5849021974 -1.7873608989 0.5554501606 0.5052161691 0.6908292175 0.3952434423 -0.333607907744 +1403637145188318976.0000000000 4.5849092976 -1.7874141851 0.5554446614 0.5052282521 0.6909085051 0.3951494405 -0.333536760427 +1403637145238319104.0000000000 4.5849357237 -1.7874594148 0.5554052029 0.5052147482 0.6909459813 0.3950790110 -0.333563013845 +1403637145288318976.0000000000 4.5849748897 -1.7874529766 0.5554042515 0.5051679555 0.6910222381 0.3950306376 -0.333533204534 +1403637145338319104.0000000000 4.5850399116 -1.7874852536 0.5553733603 0.5051509482 0.6909818201 0.3950324054 -0.333640588855 +1403637145388318976.0000000000 4.5851140219 -1.7874726781 0.5553371091 0.5051765025 0.6909644996 0.3950490309 -0.333618082269 +1403637145438319104.0000000000 4.5851510573 -1.7875057588 0.5553179829 0.5051641699 0.6909366225 0.3950642799 -0.333676430073 +1403637145488318976.0000000000 4.5851932462 -1.7875399077 0.5553129059 0.5051566532 0.6909201079 0.3950422254 -0.333748109153 +1403637145538319104.0000000000 4.5851921997 -1.7875612210 0.5552852391 0.5051637386 0.6909293803 0.3950360781 -0.333725464313 +1403637145588318976.0000000000 4.5851839591 -1.7875686368 0.5552812833 0.5051577886 0.6909066653 0.3950669962 -0.333744898019 +1403637145638319104.0000000000 4.5851813375 -1.7876382138 0.5552135077 0.5050901872 0.6909250764 0.3950888917 -0.333783176946 +1403637145688318976.0000000000 4.5851968428 -1.7876476868 0.5551711343 0.5050801829 0.6909153945 0.3951654743 -0.333727694904 +1403637145738319104.0000000000 4.5852023306 -1.7876577535 0.5551943907 0.5050305009 0.6909159906 0.3951553544 -0.333813620189 +1403637145788318976.0000000000 4.5852298165 -1.7876604727 0.5552155389 0.5050303618 0.6908950918 0.3951779522 -0.333830333899 +1403637145838319104.0000000000 4.5852030821 -1.7876729110 0.5552557306 0.5050057453 0.6909329933 0.3951543380 -0.33381708331 +1403637145888318976.0000000000 4.5851783506 -1.7876511510 0.5552921447 0.5050157698 0.6909630701 0.3951269784 -0.333772046263 +1403637145938319104.0000000000 4.5851998215 -1.7876419620 0.5553196471 0.5049782035 0.6909781141 0.3951292576 -0.333795041258 +1403637145988318976.0000000000 4.5852467787 -1.7876032510 0.5553348262 0.5049618236 0.6909495783 0.3952032956 -0.333791240213 +1403637146038319104.0000000000 4.5852464074 -1.7875239278 0.5553567572 0.5048639368 0.6910021847 0.3952190135 -0.333811799432 +1403637146088318976.0000000000 4.5851778157 -1.7873769518 0.5553207702 0.5048712213 0.6910241881 0.3952092108 -0.333766836449 +1403637146138319104.0000000000 4.5850815533 -1.7872608442 0.5553228401 0.5048602237 0.6910159097 0.3952220073 -0.333785458123 +1403637146188318976.0000000000 4.5849804347 -1.7871526668 0.5553692841 0.5049160127 0.6909518035 0.3953256019 -0.333711093437 +1403637146238319104.0000000000 4.5849998291 -1.7869265371 0.5554101817 0.5051949331 0.6908524097 0.3954798100 -0.333311787279 +1403637146288318976.0000000000 4.5848341987 -1.7872195340 0.5556167347 0.5047512858 0.6910027704 0.3952052578 -0.333997178061 +1403637146338319104.0000000000 4.5848028173 -1.7872048302 0.5556257733 0.5050407930 0.6908038427 0.3955320130 -0.333583985053 +1403637146388318976.0000000000 4.5846499352 -1.7874902135 0.5557479668 0.5047206594 0.6909781056 0.3952742198 -0.334012881047 +1403637146438319104.0000000000 4.5847737600 -1.7875190930 0.5556294562 0.5048808846 0.6909271574 0.3955164582 -0.333589098837 +1403637146488318976.0000000000 4.5847693296 -1.7877244829 0.5555604420 0.5046510805 0.6910873479 0.3952476689 -0.333923411489 +1403637146538319104.0000000000 4.5848167572 -1.7876834860 0.5553812464 0.5048104293 0.6910007821 0.3954358493 -0.33363878474 +1403637146588318976.0000000000 4.5848570139 -1.7877758644 0.5553240569 0.5045461897 0.6911504522 0.3952191699 -0.33398503363 +1403637146638319104.0000000000 4.5849128067 -1.7877101491 0.5552129311 0.5046984414 0.6910254730 0.3954360125 -0.333756856065 +1403637146688318976.0000000000 4.5849160404 -1.7877334154 0.5552613563 0.5045922218 0.6910684778 0.3952935199 -0.333997128335 +1403637146738319104.0000000000 4.5849328790 -1.7876499539 0.5552545387 0.5046757868 0.6910158687 0.3954315595 -0.333816268606 +1403637146788318976.0000000000 4.5849629070 -1.7876301013 0.5552926074 0.5045460464 0.6910793256 0.3953655625 -0.333959166393 +1403637146838319104.0000000000 4.5849467893 -1.7875977901 0.5552628686 0.5046101716 0.6910219809 0.3954444508 -0.33388753051 +1403637146888318976.0000000000 4.5849676121 -1.7876188311 0.5552656969 0.5045487746 0.6910535142 0.3954396573 -0.333920727094 +1403637146938319104.0000000000 4.5849971589 -1.7875893999 0.5552673290 0.5045558480 0.6910731929 0.3954619951 -0.333842850425 +1403637146988318976.0000000000 4.5850025499 -1.7875955227 0.5553085124 0.5046401810 0.6910016947 0.3955261789 -0.333787338592 +1403637147038319104.0000000000 4.5850032830 -1.7876397185 0.5553722998 0.5044857561 0.6910505777 0.3955226753 -0.333923695165 +1403637147088318976.0000000000 4.5850146734 -1.7877037362 0.5553826558 0.5045064187 0.6910528380 0.3955356894 -0.333872381357 +1403637147138319104.0000000000 4.5850043080 -1.7877450911 0.5553619021 0.5044667196 0.6911066998 0.3955198912 -0.333839593208 +1403637147188318976.0000000000 4.5850140051 -1.7877520229 0.5553443417 0.5045129084 0.6911011619 0.3954840117 -0.333823764553 +1403637147238319104.0000000000 4.5850262345 -1.7877046105 0.5553718671 0.5045209628 0.6911094576 0.3954654728 -0.333816380028 +1403637147288318976.0000000000 4.5850196881 -1.7876562784 0.5553840362 0.5044448079 0.6911590301 0.3954258456 -0.333875772636 +1403637147338319104.0000000000 4.5849797492 -1.7876113025 0.5554024358 0.5044201471 0.6911717844 0.3954057314 -0.333910447814 +1403637147388318976.0000000000 4.5849687644 -1.7875774719 0.5554084567 0.5043847638 0.6911492764 0.3954234703 -0.33398947131 +1403637147438319104.0000000000 4.5850239685 -1.7874601508 0.5553642295 0.5044201248 0.6911357401 0.3954485749 -0.333934351428 +1403637147488318976.0000000000 4.5850640612 -1.7873580171 0.5553570579 0.5043651030 0.6911565905 0.3954237630 -0.334003679473 +1403637147538319104.0000000000 4.5852578392 -1.7872499164 0.5552870035 0.5044487281 0.6910796015 0.3954835843 -0.333965865921 +1403637147588318976.0000000000 4.5851187715 -1.7873487790 0.5553401634 0.5043187826 0.6911522059 0.3954317605 -0.334073220525 +1403637147638319104.0000000000 4.5850236722 -1.7873796040 0.5553197734 0.5044201028 0.6910836052 0.3955398114 -0.333934227248 +1403637147688318976.0000000000 4.5848843290 -1.7875026254 0.5553332862 0.5043210473 0.6911169843 0.3955030149 -0.334058319047 +1403637147738319104.0000000000 4.5847812405 -1.7875326249 0.5553424935 0.5043863538 0.6910938660 0.3954907665 -0.334022047195 +1403637147788318976.0000000000 4.5846893614 -1.7875935964 0.5553377916 0.5043088445 0.6911356738 0.3954806885 -0.334064506911 +1403637147838319104.0000000000 4.5846293341 -1.7876091121 0.5553480634 0.5043675215 0.6911080752 0.3955012028 -0.334008727631 +1403637147888318976.0000000000 4.5845881204 -1.7876748824 0.5553721525 0.5042980248 0.6911461048 0.3954758149 -0.334065029389 +1403637147938319104.0000000000 4.5845861154 -1.7876863598 0.5553617757 0.5043275687 0.6911164860 0.3955271470 -0.334020930879 +1403637147988318976.0000000000 4.5845896149 -1.7877502013 0.5553632288 0.5042846099 0.6911354756 0.3954931305 -0.334086770781 +1403637148038319104.0000000000 4.5845241373 -1.7877487610 0.5553686845 0.5042870741 0.6911370893 0.3954921656 -0.334080854892 +1403637148088318976.0000000000 4.5844436147 -1.7876994125 0.5554233931 0.5042881476 0.6911640604 0.3954642317 -0.334056502939 +1403637148138319104.0000000000 4.5844631114 -1.7875858040 0.5555223537 0.5043277627 0.6911524362 0.3954710138 -0.334012716833 +1403637148188318976.0000000000 4.5844464755 -1.7875226865 0.5555697512 0.5042660169 0.6911797264 0.3954503029 -0.334073985831 +1403637148238319104.0000000000 4.5845565343 -1.7875566481 0.5555583750 0.5041705018 0.6911549178 0.3955807957 -0.334114978419 +1403637148288318976.0000000000 4.5845881680 -1.7875836197 0.5555161805 0.5041547328 0.6911663341 0.3955667631 -0.334131770342 +1403637148338319104.0000000000 4.5845847123 -1.7876644423 0.5554891360 0.5040540950 0.6911779344 0.3956922806 -0.334110986551 +1403637148388318976.0000000000 4.5844587150 -1.7876658332 0.5555158739 0.5041047737 0.6911281862 0.3956428897 -0.33419591738 +1403637148438319104.0000000000 4.5843971281 -1.7877063062 0.5554934265 0.5039839384 0.6911247603 0.3957380969 -0.334272514781 +1403637148488318976.0000000000 4.5843756044 -1.7876822925 0.5553834055 0.5039189285 0.6911172312 0.3958917754 -0.334204111869 +1403637148538319104.0000000000 4.5843284507 -1.7876335205 0.5553704298 0.5039210314 0.6910283803 0.3959756956 -0.334285237832 +1403637148588318976.0000000000 4.5842395568 -1.7874841743 0.5553654944 0.5038072533 0.6910155793 0.3961129317 -0.334320603696 +1403637148638319104.0000000000 4.5846009625 -1.7877739780 0.5552773128 0.5034556063 0.6909944787 0.3965897120 -0.334328705398 +1403637148688318976.0000000000 4.5847414096 -1.7878965443 0.5553922345 0.5032888525 0.6908118042 0.3967325965 -0.334787438576 +1403637148738319104.0000000000 4.5850582303 -1.7879539267 0.5553434150 0.5031355999 0.6906990319 0.3972346022 -0.334655175112 +1403637148788318976.0000000000 4.5852836241 -1.7880745887 0.5553450027 0.5028514376 0.6907476947 0.3973033130 -0.334900181306 +1403637148838319104.0000000000 4.5858393016 -1.7882351551 0.5553247088 0.5027823749 0.6906510056 0.3976378908 -0.334806182446 +1403637148888318976.0000000000 4.5864260560 -1.7885333350 0.5554372253 0.5024756334 0.6905349650 0.3979806964 -0.335098590253 +1403637148938319104.0000000000 4.5870881353 -1.7887883625 0.5554284476 0.5023325799 0.6903972300 0.3983751321 -0.3351281815 +1403637148988318976.0000000000 4.5868923284 -1.7886137622 0.5554017212 0.5020445962 0.6903815517 0.3985422526 -0.335393215984 +1403637149038319104.0000000000 4.5871243396 -1.7886826908 0.5552496740 0.5019173515 0.6902722943 0.3990307843 -0.33522763181 +1403637149088318976.0000000000 4.5868183672 -1.7887468230 0.5553162359 0.5016746714 0.6902145052 0.3991665873 -0.335548053784 +1403637149138319104.0000000000 4.5864049862 -1.7886194573 0.5552810079 0.5015537634 0.6901734254 0.3993694534 -0.335571907352 +1403637149188318976.0000000000 4.5861038311 -1.7883867959 0.5552709728 0.5014779865 0.6900185618 0.3997799205 -0.335514871022 +1403637149238319104.0000000000 4.5858482333 -1.7881681559 0.5553341594 0.5013029360 0.6900011316 0.3998565719 -0.335720905908 +1403637149288318976.0000000000 4.5855766012 -1.7881070603 0.5554724779 0.5011217472 0.6898665419 0.4001591925 -0.335907382399 +1403637149338319104.0000000000 4.5855192315 -1.7881252509 0.5555123582 0.5008586973 0.6897361929 0.4006195495 -0.336018639589 +1403637149388318976.0000000000 4.5856457018 -1.7881143283 0.5555401516 0.5006144717 0.6895942047 0.4009529478 -0.336276251368 +1403637149438319104.0000000000 4.5858786869 -1.7881601094 0.5556129715 0.5003202366 0.6893287197 0.4015694447 -0.336522745465 +1403637149488318976.0000000000 4.5859917763 -1.7883037553 0.5556320341 0.4999241755 0.6890949603 0.4023709000 -0.336632757273 +1403637149538319104.0000000000 4.5861458398 -1.7883591292 0.5555166689 0.4996176822 0.6888664562 0.4032196910 -0.336539831252 +1403637149588318976.0000000000 4.5866620296 -1.7886239678 0.5552201868 0.4979611795 0.6885948124 0.4060430476 -0.33615605238 +1403637149638319104.0000000000 4.5876986665 -1.7891305042 0.5545367105 0.4942157823 0.6885352564 0.4112958279 -0.335418698306 +1403637149688318976.0000000000 4.5892074567 -1.7900249487 0.5539983799 0.4905189357 0.6871210406 0.4175833356 -0.335976200272 +1403637149738319104.0000000000 4.5905898013 -1.7899966568 0.5534961178 0.4889345298 0.6862904266 0.4206658254 -0.336137976662 +1403637149788318976.0000000000 4.5914855143 -1.7896506952 0.5529646193 0.4851585889 0.6876322134 0.4228942739 -0.336070700545 +1403637149838319104.0000000000 4.5924618822 -1.7891729229 0.5524725682 0.4810658214 0.6893122170 0.4260244253 -0.334555723362 +1403637149888318976.0000000000 4.5940251099 -1.7870997977 0.5518910411 0.4745590746 0.6935792578 0.4286215509 -0.331700262119 +1403637149938319104.0000000000 4.5962935255 -1.7836458056 0.5512632406 0.4699021195 0.6967947657 0.4331643903 -0.325634248154 +1403637149988318976.0000000000 4.5989657387 -1.7793359548 0.5520164192 0.4647654054 0.7001926761 0.4393214717 -0.317364110622 +1403637150038319104.0000000000 4.6021118231 -1.7735442048 0.5545520031 0.4617965060 0.7024313158 0.4459975195 -0.30727910157 +1403637150088318976.0000000000 4.6049942806 -1.7663935157 0.5590819923 0.4592462383 0.7049894162 0.4507965147 -0.298102864693 +1403637150138319104.0000000000 4.6062979825 -1.7578052609 0.5658055294 0.4585466634 0.7063211201 0.4542268989 -0.290729009734 +1403637150188318976.0000000000 4.6056454672 -1.7479694283 0.5748933130 0.4601564953 0.7067304633 0.4548524700 -0.286177012742 +1403637150238319104.0000000000 4.6031100659 -1.7372719315 0.5856839014 0.4627699283 0.7065524735 0.4541048485 -0.283577823908 +1403637150288318976.0000000000 4.5982290042 -1.7259319023 0.5986498428 0.4667768392 0.7055089037 0.4515725100 -0.283652670482 +1403637150338319104.0000000000 4.5916680074 -1.7140500207 0.6125459449 0.4707653961 0.7045040846 0.4487911040 -0.283972677608 +1403637150388318976.0000000000 4.5831289745 -1.7017360229 0.6278230107 0.4764423571 0.7022428135 0.4435311913 -0.288336250901 +1403637150438319104.0000000000 4.5739440174 -1.6890252817 0.6428511196 0.4811452767 0.7004075664 0.4395173156 -0.2911236729 +1403637150488318976.0000000000 4.5644780210 -1.6760013088 0.6572712169 0.4849890460 0.6991188987 0.4367097782 -0.292066705364 +1403637150538319104.0000000000 4.5547253953 -1.6628503538 0.6715308378 0.4876423121 0.6986794749 0.4341148404 -0.292568405891 +1403637150588318976.0000000000 4.5447455775 -1.6496511164 0.6850072472 0.4889130250 0.6987864166 0.4327351818 -0.292235966849 +1403637150638319104.0000000000 4.5343757631 -1.6362930018 0.6983422733 0.4903415721 0.6987517343 0.4311710714 -0.292237341274 +1403637150688318976.0000000000 4.5237845635 -1.6229356899 0.7110204343 0.4911400832 0.6989416590 0.4302486764 -0.291801391915 +1403637150738319104.0000000000 4.5129125630 -1.6094948875 0.7229531398 0.4919263506 0.6989764967 0.4299404017 -0.29084630598 +1403637150788318976.0000000000 4.5016014090 -1.5959765675 0.7344589937 0.4927348753 0.6988941321 0.4295110941 -0.290309412153 +1403637150838319104.0000000000 4.4900105916 -1.5823988108 0.7457970911 0.4945052077 0.6981453742 0.4290066659 -0.289846367357 +1403637150888318976.0000000000 4.4780639198 -1.5691888488 0.7571937446 0.4976717612 0.6961931436 0.4278637574 -0.290810126956 +1403637150938319104.0000000000 4.4661384515 -1.5563773879 0.7676941501 0.5005813975 0.6942639401 0.4265835695 -0.292305155923 +1403637150988318976.0000000000 4.4542720490 -1.5440086648 0.7770698261 0.5033984637 0.6922658919 0.4254546595 -0.293847331694 +1403637151038319104.0000000000 4.4426303316 -1.5321294346 0.7853652287 0.5056584318 0.6904393261 0.4246626513 -0.295406025505 +1403637151088318976.0000000000 4.4313541905 -1.5205930313 0.7928183555 0.5082966493 0.6882280282 0.4240611481 -0.296898703519 +1403637151138319104.0000000000 4.4204719711 -1.5096731835 0.7996174899 0.5112813166 0.6856666374 0.4233681134 -0.298683977017 +1403637151188318976.0000000000 4.4106840154 -1.4995162247 0.8053439133 0.5118428867 0.6846678771 0.4237137053 -0.299522041414 +1403637151238319104.0000000000 4.4019597807 -1.4901801610 0.8113971267 0.5094440923 0.6860058379 0.4248446121 -0.298947759117 +1403637151288318976.0000000000 4.3941527880 -1.4818579268 0.8194728837 0.5059030121 0.6879358477 0.4258253867 -0.299130660155 +1403637151338319104.0000000000 4.3872614612 -1.4740425613 0.8297689662 0.5009574135 0.6908835944 0.4259775965 -0.300440703003 +1403637151388318976.0000000000 4.3807260515 -1.4667036168 0.8430570538 0.4952520284 0.6943919865 0.4248825512 -0.303348009833 +1403637151438319104.0000000000 4.3741794860 -1.4589749822 0.8593595995 0.4908221934 0.6972769109 0.4236978879 -0.305579095941 +1403637151488318976.0000000000 4.3683510668 -1.4505996151 0.8761996639 0.4903340699 0.6971672077 0.4257874807 -0.303702824606 +1403637151538319104.0000000000 4.3627598640 -1.4419393705 0.8925427026 0.4898349027 0.6971396655 0.4269826771 -0.302892469915 +1403637151588318976.0000000000 4.3574068190 -1.4327073577 0.9077603871 0.4904338907 0.6965221159 0.4281891895 -0.301638125596 +1403637151638319104.0000000000 4.3521188966 -1.4231828376 0.9220082924 0.4909066230 0.6957934835 0.4296418551 -0.300482931445 +1403637151688318976.0000000000 4.3468947090 -1.4133699833 0.9351967356 0.4918552951 0.6948137217 0.4306312003 -0.299781637237 +1403637151738319104.0000000000 4.3418261994 -1.4034959511 0.9467986235 0.4916934072 0.6947600598 0.4315047385 -0.298914223886 +1403637151788318976.0000000000 4.3366841225 -1.3934642490 0.9570551000 0.4916948439 0.6944775105 0.4322153620 -0.298541536074 +1403637151838319104.0000000000 4.3315245339 -1.3833650176 0.9659145959 0.4918541766 0.6940970181 0.4328113925 -0.298300346978 +1403637151888318976.0000000000 4.3262728131 -1.3728959569 0.9734606506 0.4924120184 0.6935994243 0.4333908031 -0.297695573693 +1403637151938319104.0000000000 4.3208166132 -1.3624647786 0.9802224204 0.4925080658 0.6934747161 0.4340231245 -0.29690495228 +1403637151988318976.0000000000 4.3151099402 -1.3522820514 0.9876657225 0.4921911028 0.6934431256 0.4342484527 -0.297174748786 +1403637152038319104.0000000000 4.3095795822 -1.3423610664 0.9970607257 0.4916624242 0.6936711282 0.4342132134 -0.297569003472 +1403637152088318976.0000000000 4.3046013086 -1.3327720370 1.0073765091 0.4907026301 0.6941176486 0.4341866766 -0.298150211409 +1403637152138319104.0000000000 4.2994508149 -1.3229940451 1.0185838501 0.4896789497 0.6947803756 0.4341494156 -0.298343829921 +1403637152188318976.0000000000 4.2941903671 -1.3131199124 1.0295469736 0.4887297176 0.6954922768 0.4340976798 -0.29831687915 +1403637152238319104.0000000000 4.2888001070 -1.3031632313 1.0393158208 0.4875350287 0.6962719575 0.4338284805 -0.298844117316 +1403637152288318976.0000000000 4.2831878842 -1.2928429127 1.0471578473 0.4869716026 0.6966575953 0.4339157325 -0.298737326585 +1403637152338319104.0000000000 4.2775834979 -1.2823426763 1.0535500208 0.4853615958 0.6977343697 0.4335445682 -0.29938266153 +1403637152388318976.0000000000 4.2718977411 -1.2712581299 1.0582232485 0.4859201264 0.6971730413 0.4339606675 -0.299181416958 +1403637152438319104.0000000000 4.2659351717 -1.2599398129 1.0614106331 0.4855649884 0.6973915784 0.4341044008 -0.299040127003 +1403637152488318976.0000000000 4.2594197755 -1.2483249988 1.0628767035 0.4856960000 0.6971645364 0.4346797446 -0.298520559265 +1403637152538319104.0000000000 4.2524966574 -1.2364961675 1.0627783560 0.4857505007 0.6970137346 0.4345696059 -0.298944078953 +1403637152588318976.0000000000 4.2452944632 -1.2242201874 1.0610102830 0.4857976912 0.6970556880 0.4349939354 -0.298151383185 +1403637152638319104.0000000000 4.2372613720 -1.2116262490 1.0586766815 0.4864939243 0.6965469471 0.4347633114 -0.298541245149 +1403637152688318976.0000000000 4.2289895571 -1.1987015831 1.0557981823 0.4869660839 0.6962685337 0.4343821861 -0.298975380944 +1403637152738319104.0000000000 4.2201881702 -1.1854337766 1.0535657531 0.4880495981 0.6955918694 0.4334116728 -0.300189711488 +1403637152788318976.0000000000 4.2110318597 -1.1720504597 1.0528905154 0.4886166527 0.6949617607 0.4316472221 -0.30325334883 +1403637152838319104.0000000000 4.2019705154 -1.1581747566 1.0534650783 0.4900115479 0.6940469742 0.4304288113 -0.304825390807 +1403637152888318976.0000000000 4.1941849359 -1.1446202389 1.0560164023 0.4913041557 0.6929057926 0.4297939250 -0.306233524143 +1403637152938319104.0000000000 4.1876723002 -1.1310124490 1.0601920826 0.4929757701 0.6914825677 0.4299913996 -0.306486777773 +1403637152988318976.0000000000 4.1810964971 -1.1170009301 1.0663754886 0.4933816599 0.6911011279 0.4303146208 -0.306240258245 +1403637153038319104.0000000000 4.1755350820 -1.1032208499 1.0735175715 0.4940196406 0.6904472757 0.4306984195 -0.30614706544 +1403637153088318976.0000000000 4.1699292451 -1.0889779374 1.0799679191 0.4942480288 0.6905509137 0.4313016672 -0.30469196481 +1403637153138319104.0000000000 4.1645253009 -1.0748363503 1.0850887751 0.4939627543 0.6907579688 0.4320060426 -0.303685701138 +1403637153188318976.0000000000 4.1591867877 -1.0605794164 1.0885722322 0.4932150890 0.6913457455 0.4325703492 -0.302758697822 +1403637153238319104.0000000000 4.1538044375 -1.0462820247 1.0904592261 0.4933269099 0.6913913248 0.4336738009 -0.300888069402 +1403637153288318976.0000000000 4.1485179733 -1.0321966500 1.0911641308 0.4934633189 0.6912895868 0.4343224047 -0.299961178916 +1403637153338319104.0000000000 4.1431813060 -1.0179360791 1.0908103795 0.4939757035 0.6909430596 0.4347882230 -0.299240528623 +1403637153388318976.0000000000 4.1378586026 -1.0037824341 1.0901650930 0.4942350681 0.6908997835 0.4354649162 -0.297925315206 +1403637153438319104.0000000000 4.1323705458 -0.9898268408 1.0906900451 0.4936900225 0.6911932073 0.4361858600 -0.297092590514 +1403637153488318976.0000000000 4.1273853965 -0.9763155120 1.0928325181 0.4930429246 0.6917395110 0.4372134978 -0.295380230913 +1403637153538319104.0000000000 4.1222210662 -0.9632548805 1.0964450945 0.4915441975 0.6928520363 0.4381000045 -0.293953642009 +1403637153588318976.0000000000 4.1167665833 -0.9504892499 1.1017931375 0.4901903780 0.6938106485 0.4380799761 -0.293983183041 +1403637153638319104.0000000000 4.1106022282 -0.9374724780 1.1087273817 0.4900034794 0.6939377710 0.4385344953 -0.293316308064 +1403637153688318976.0000000000 4.1035724636 -0.9246173812 1.1181050593 0.4906307381 0.6933867120 0.4380359587 -0.294314194875 +1403637153738319104.0000000000 4.0965605325 -0.9120526494 1.1284428359 0.4916928540 0.6927356461 0.4379783562 -0.294160536827 +1403637153788318976.0000000000 4.0892358994 -0.8998004018 1.1386753324 0.4934480992 0.6915843508 0.4368663184 -0.295580579486 +1403637153838319104.0000000000 4.0818326606 -0.8879596951 1.1478327920 0.4938973111 0.6912429429 0.4356421668 -0.297429895066 +1403637153888318976.0000000000 4.0745394669 -0.8760359369 1.1553134811 0.4947838145 0.6907401235 0.4355023942 -0.297329318 +1403637153938319104.0000000000 4.0672393717 -0.8643816477 1.1612863658 0.4961992673 0.6898379722 0.4351196486 -0.297625184741 +1403637153988318976.0000000000 4.0597632116 -0.8531022661 1.1653904703 0.4962511304 0.6898064645 0.4343830860 -0.298685774282 +1403637154038319104.0000000000 4.0525668406 -0.8422624918 1.1672915640 0.4958313495 0.6901074033 0.4345397532 -0.298459792227 +1403637154088318976.0000000000 4.0455705954 -0.8318128041 1.1672285159 0.4935973823 0.6916672331 0.4342195009 -0.299017537732 +1403637154138319104.0000000000 4.0386597205 -0.8215648966 1.1650539400 0.4885146813 0.6951582780 0.4337071388 -0.300010820706 +1403637154188318976.0000000000 4.0317333782 -0.8114574406 1.1614339064 0.4804367811 0.7008714520 0.4313677488 -0.303119732647 +1403637154238319104.0000000000 4.0248031224 -0.8008977393 1.1569882863 0.4736163305 0.7056472185 0.4285259953 -0.306781756106 +1403637154288318976.0000000000 4.0177009538 -0.7891651577 1.1510438160 0.4679429288 0.7095580853 0.4265130918 -0.309262544733 +1403637154338319104.0000000000 4.0104207659 -0.7757680031 1.1438220362 0.4654466588 0.7113247028 0.4254212096 -0.310472815818 +1403637154388318976.0000000000 4.0028227287 -0.7603284584 1.1354502618 0.4673075705 0.7103440339 0.4262708469 -0.308752575874 +1403637154438319104.0000000000 3.9947097458 -0.7432748626 1.1267566851 0.4722957684 0.7072862158 0.4267374486 -0.307535471094 +1403637154488318976.0000000000 3.9863851368 -0.7249353260 1.1176374944 0.4779307728 0.7037328663 0.4270498025 -0.306546400364 +1403637154538319104.0000000000 3.9780989290 -0.7055620436 1.1084531354 0.4823001384 0.7011539069 0.4276436150 -0.304779779222 +1403637154588318976.0000000000 3.9700698721 -0.6854200058 1.0996420430 0.4854719438 0.6996369330 0.4289654204 -0.301353317306 +1403637154638319104.0000000000 3.9620621118 -0.6648650131 1.0910863301 0.4874574729 0.6989814004 0.4313788138 -0.296179899706 +1403637154688318976.0000000000 3.9536640968 -0.6440822274 1.0825476268 0.4878634686 0.6995777951 0.4345613350 -0.289372753906 +1403637154738319104.0000000000 3.9449185845 -0.6233670730 1.0743164117 0.4879870768 0.7011843820 0.4358113629 -0.283332898314 +1403637154788318976.0000000000 3.9352055943 -0.6023488849 1.0667822997 0.4880292962 0.7042596218 0.4344870917 -0.277609002549 +1403637154838319104.0000000000 3.9245340467 -0.5811840225 1.0604563465 0.4875818970 0.7084558619 0.4312354569 -0.272745607001 +1403637154888318976.0000000000 3.9127231791 -0.5600084941 1.0555496707 0.4878850538 0.7119338646 0.4268878526 -0.269972420757 +1403637154938319104.0000000000 3.9000084116 -0.5386394211 1.0508965299 0.4871524372 0.7156499271 0.4242086741 -0.26565896468 +1403637154988318976.0000000000 3.8853572839 -0.5168250679 1.0487220930 0.4881468246 0.7182994769 0.4191362576 -0.264732575949 +1403637155038319104.0000000000 3.8697288306 -0.4947412210 1.0486254599 0.4907509865 0.7200124563 0.4147109719 -0.262221932518 +1403637155088318976.0000000000 3.8523779840 -0.4721760618 1.0513100315 0.4932526505 0.7225889874 0.4081363765 -0.260752135681 +1403637155138319104.0000000000 3.8335536403 -0.4492136961 1.0562899516 0.4990588797 0.7231754559 0.4003828495 -0.260098189766 +1403637155188318976.0000000000 3.8143459015 -0.4267728971 1.0626462975 0.5026563697 0.7245176224 0.3936512160 -0.259710432983 +1403637155238319104.0000000000 3.7947494760 -0.4045605780 1.0709811274 0.5070786436 0.7243053881 0.3891145836 -0.258539735212 +1403637155288318976.0000000000 3.7745959452 -0.3825328136 1.0805809927 0.5100564637 0.7242435381 0.3853421526 -0.258505564436 +1403637155338319104.0000000000 3.7541051631 -0.3602821308 1.0912987275 0.5139318168 0.7236622273 0.3814774731 -0.258189864183 +1403637155388318976.0000000000 3.7334176107 -0.3376222811 1.1013124446 0.5172827851 0.7242331146 0.3760703941 -0.25782935176 +1403637155438319104.0000000000 3.7131141192 -0.3148547759 1.1094578209 0.5203605007 0.7258018907 0.3701336728 -0.255807796993 +1403637155488318976.0000000000 3.6932137471 -0.2921166601 1.1158354949 0.5240416824 0.7276212321 0.3628364492 -0.253569258704 +1403637155538319104.0000000000 3.6738285864 -0.2698872708 1.1198806929 0.5260130462 0.7303512272 0.3559103365 -0.251446202063 +1403637155588318976.0000000000 3.6544095519 -0.2478642860 1.1221735204 0.5267673726 0.7334926026 0.3491357367 -0.250217854036 +1403637155638319104.0000000000 3.6350135809 -0.2259960859 1.1229726023 0.5267525835 0.7366838130 0.3424529913 -0.250109224727 +1403637155688318976.0000000000 3.6165912944 -0.2045521092 1.1219030402 0.5258606049 0.7402743781 0.3366139725 -0.249310053587 +1403637155738319104.0000000000 3.5992884916 -0.1831550561 1.1194741818 0.5266433576 0.7431223160 0.3301024181 -0.247887859381 +1403637155788318976.0000000000 3.5828885458 -0.1612942759 1.1153744292 0.5267296050 0.7470013361 0.3226031799 -0.245910787194 +1403637155838319104.0000000000 3.5672934878 -0.1384551230 1.1101127905 0.5280081304 0.7506024118 0.3141009651 -0.243195430295 +1403637155888318976.0000000000 3.5532549991 -0.1148824687 1.1027959548 0.5280975761 0.7556648067 0.3064725947 -0.236977211529 +1403637155938319104.0000000000 3.5403511370 -0.0902516401 1.0941126167 0.5283873878 0.7607556029 0.2989081744 -0.229590035501 +1403637155988318976.0000000000 3.5281979074 -0.0648323602 1.0850096343 0.5305168248 0.7647393944 0.2899201082 -0.22287190987 +1403637156038319104.0000000000 3.5166559668 -0.0386398777 1.0761886617 0.5334148665 0.7680679037 0.2794531865 -0.217821468372 +1403637156088318976.0000000000 3.5060830339 -0.0119946680 1.0674485468 0.5363505123 0.7712401939 0.2682538149 -0.213439879114 +1403637156138319104.0000000000 3.4969130557 0.0151864595 1.0589385044 0.5398078662 0.7740202913 0.2569096104 -0.20856056279 +1403637156188318976.0000000000 3.4890535867 0.0431767654 1.0497483589 0.5424355507 0.7774396053 0.2451538657 -0.203103214276 +1403637156238319104.0000000000 3.4821390177 0.0723421596 1.0413277468 0.5451889419 0.7806880796 0.2328806894 -0.19764039195 +1403637156288318976.0000000000 3.4770334873 0.1018729939 1.0332101152 0.5477961342 0.7839747458 0.2213635078 -0.190528713565 +1403637156338319104.0000000000 3.4736317373 0.1316235021 1.0249539093 0.5497571951 0.7874993020 0.2089370449 -0.184274759798 +1403637156388318976.0000000000 3.4719175112 0.1623316405 1.0172016514 0.5518465730 0.7908702283 0.1973747161 -0.176161469469 +1403637156438319104.0000000000 3.4717784904 0.1937278944 1.0091901477 0.5536059112 0.7941757255 0.1856137623 -0.16838332297 +1403637156488318976.0000000000 3.4735305615 0.2253343415 1.0009538464 0.5560543530 0.7967382340 0.1739625699 -0.16046422445 +1403637156538319104.0000000000 3.4766740833 0.2575711113 0.9925428219 0.5593199134 0.7984503800 0.1623369655 -0.152594019405 +1403637156588318976.0000000000 3.4814415276 0.2901349258 0.9831621400 0.5614550520 0.8006316323 0.1517518943 -0.143974221941 +1403637156638319104.0000000000 3.4878228597 0.3232693666 0.9731530969 0.5644160992 0.8020661368 0.1408942260 -0.135178386808 +1403637156688318976.0000000000 3.4957955961 0.3564973036 0.9614782789 0.5664968724 0.8037955970 0.1308175859 -0.126018613681 +1403637156738319104.0000000000 3.5052477936 0.3898774103 0.9485303820 0.5691324186 0.8047862379 0.1214544414 -0.116859830728 +1403637156788318976.0000000000 3.5159965703 0.4226587733 0.9335325168 0.5692915873 0.8069611799 0.1147616915 -0.107473238581 +1403637156838319104.0000000000 3.5278524470 0.4554851428 0.9174408744 0.5685460442 0.8093052753 0.1104926416 -0.0978352856353 +1403637156888318976.0000000000 3.5403061711 0.4879701185 0.9005479078 0.5669702584 0.8117800394 0.1068365518 -0.0902432537587 +1403637156938319104.0000000000 3.5533798035 0.5202956805 0.8823737443 0.5659623673 0.8134633030 0.1055554576 -0.0825959972466 +1403637156988318976.0000000000 3.5667038446 0.5521875237 0.8626966788 0.5638789421 0.8156204386 0.1040317509 -0.0773384354172 +1403637157038319104.0000000000 3.5800105388 0.5839305002 0.8420100042 0.5618968255 0.8174420134 0.1026992112 -0.0742521671584 +1403637157088318976.0000000000 3.5932701758 0.6160330429 0.8210737691 0.5602600814 0.8188370754 0.1012200733 -0.0732733374677 +1403637157138319104.0000000000 3.6063519636 0.6488668645 0.8010938862 0.5589575744 0.8198936680 0.0993218823 -0.0739997761594 +1403637157188318976.0000000000 3.6194629886 0.6824228323 0.7827205428 0.5582648440 0.8203707468 0.0981355008 -0.0755091065084 +1403637157238319104.0000000000 3.6330421850 0.7166364951 0.7658515942 0.5579840148 0.8205498377 0.0970214750 -0.0770625497384 +1403637157288318976.0000000000 3.6473847745 0.7516300844 0.7509770296 0.5579308210 0.8204632238 0.0961944696 -0.0793720443881 +1403637157338319104.0000000000 3.6624287468 0.7875462318 0.7380241812 0.5579089602 0.8202705906 0.0954051540 -0.0824112063057 +1403637157388318976.0000000000 3.6778742666 0.8244578852 0.7278231753 0.5572178221 0.8204858232 0.0939400472 -0.0865250270287 +1403637157438319104.0000000000 3.6944990352 0.8621041099 0.7197805869 0.5562271385 0.8208199711 0.0921670316 -0.091494173529 +1403637157488318976.0000000000 3.7123020642 0.9002928980 0.7137243899 0.5554059111 0.8209795846 0.0915157808 -0.0956120153594 +1403637157538319104.0000000000 3.7315901290 0.9392292553 0.7095812163 0.5547081790 0.8210705353 0.0909834590 -0.0993177851272 +1403637157588318976.0000000000 3.7523256109 0.9792737028 0.7072130141 0.5546053328 0.8207702529 0.0912507849 -0.102090210405 +1403637157638319104.0000000000 3.7747384977 1.0201108999 0.7061048079 0.5542214019 0.8207430792 0.0924566983 -0.103301474343 +1403637157688318976.0000000000 3.7987924202 1.0618018089 0.7069952026 0.5538832248 0.8207029574 0.0932967964 -0.104669655161 +1403637157738319104.0000000000 3.8227619121 1.1045831629 0.7099644583 0.5535323666 0.8206912872 0.0942078003 -0.105795182049 +1403637157788318976.0000000000 3.8485986627 1.1486900443 0.7146256233 0.5567503208 0.8183726169 0.0953992264 -0.105803250255 +1403637157838319104.0000000000 3.8748588406 1.1931385568 0.7188258858 0.5604764440 0.8157899563 0.0973328530 -0.104303492625 +1403637157888318976.0000000000 3.9024656642 1.2381244965 0.7218450379 0.5635457937 0.8136750542 0.0984967960 -0.103186364144 +1403637157938319104.0000000000 3.9308715083 1.2834613371 0.7234529796 0.5671720418 0.8111814435 0.1003726054 -0.101123097056 +1403637157988318976.0000000000 3.9602540069 1.3285267373 0.7230994179 0.5694118041 0.8096856978 0.1025786375 -0.098269482937 +1403637158038319104.0000000000 3.9903573560 1.3735073638 0.7219109603 0.5720581758 0.8078823255 0.1057232779 -0.0943301650492 +1403637158088318976.0000000000 4.0211695422 1.4182534800 0.7214225099 0.5737633960 0.8067667509 0.1080731583 -0.0907918911867 +1403637158138319104.0000000000 4.0523239895 1.4629291823 0.7227598615 0.5747936384 0.8060082812 0.1092759840 -0.0895638505401 +1403637158188318976.0000000000 4.0837866604 1.5076893180 0.7258252911 0.5754661515 0.8055406987 0.1104997006 -0.0879358135491 +1403637158238319104.0000000000 4.1163149471 1.5516637784 0.7310613822 0.5767638610 0.8047445309 0.1095131069 -0.0879577631035 +1403637158288318976.0000000000 4.1503031803 1.5940392199 0.7367742629 0.5764726883 0.8053108108 0.1081948812 -0.0862995094403 +1403637158338319104.0000000000 4.1850774443 1.6373433850 0.7439552727 0.5770291510 0.8056011964 0.1050693193 -0.083692947332 +1403637158388318976.0000000000 4.2206427620 1.6799188989 0.7515003113 0.5773550666 0.8062893439 0.0992621233 -0.0818880439214 +1403637158438319104.0000000000 4.2570505369 1.7223176273 0.7579390951 0.5781847998 0.8067952099 0.0928395706 -0.0785152257167 +1403637158488318976.0000000000 4.2942330538 1.7647481884 0.7629207485 0.5791914023 0.8072453048 0.0845027653 -0.0758394354519 +1403637158538319104.0000000000 4.3323036286 1.8070068561 0.7664154209 0.5799195146 0.8079260399 0.0745729941 -0.0734012205143 +1403637158588318976.0000000000 4.3714788138 1.8489111518 0.7680686181 0.5799364640 0.8090699341 0.0631175283 -0.071384291264 +1403637158638319104.0000000000 4.4120895645 1.8903019406 0.7680205785 0.5798765746 0.8101864077 0.0515402383 -0.0684452098321 +1403637158688318976.0000000000 4.4544300616 1.9310989198 0.7663182911 0.5806004508 0.8107272203 0.0402365378 -0.0632891131091 +1403637158738319104.0000000000 4.4982965064 1.9706753824 0.7627149617 0.5807497770 0.8115491567 0.0297325644 -0.056865079473 +1403637158788318976.0000000000 4.5431262558 2.0093440707 0.7577542838 0.5800280691 0.8127680160 0.0210527124 -0.0503227034383 +1403637158838319104.0000000000 4.5887846353 2.0468875129 0.7510961396 0.5775557746 0.8150781318 0.0148179438 -0.043097504614 +1403637158888318976.0000000000 4.6352757940 2.0836915178 0.7448537933 0.5760620124 0.8164608743 0.0090942085 -0.0382294908181 +1403637158938319104.0000000000 4.6831455583 2.1202803127 0.7389959512 0.5750782477 0.8175105825 0.0076217298 -0.0300560438265 +1403637158988318976.0000000000 4.7314854418 2.1569988872 0.7348525958 0.5729668562 0.8192066647 0.0062020897 -0.0238946907759 +1403637159038319104.0000000000 4.7804712629 2.1939912731 0.7323964174 0.5714910302 0.8203915620 0.0054975330 -0.0180406370721 +1403637159088318976.0000000000 4.8296053986 2.2311897053 0.7323089326 0.5709136248 0.8208527339 0.0041859914 -0.0155209421412 +1403637159138319104.0000000000 4.8786809907 2.2679152689 0.7326868579 0.5709262221 0.8208489719 0.0020052095 -0.0156905484701 +1403637159188318976.0000000000 4.9277245046 2.3042235266 0.7323834936 0.5712432456 0.8205716443 -0.0011909299 -0.0184908803475 +1403637159238319104.0000000000 4.9770023097 2.3404853987 0.7304803083 0.5714122346 0.8203693120 -0.0037000499 -0.0216462403125 +1403637159288318976.0000000000 5.0270144248 2.3765456953 0.7270310901 0.5711942091 0.8204288644 -0.0052655320 -0.0246156090223 +1403637159338319104.0000000000 5.0780598389 2.4127113129 0.7223037100 0.5708398850 0.8205910035 -0.0063133525 -0.0270623783299 +1403637159388318976.0000000000 5.1301279485 2.4489676030 0.7161666989 0.5704129596 0.8208255873 -0.0063853485 -0.0288727900714 +1403637159438319104.0000000000 5.1833340610 2.4851065932 0.7088836192 0.5705413623 0.8207422192 -0.0047995542 -0.0290125476667 +1403637159488318976.0000000000 5.2374048258 2.5215269120 0.7008168245 0.5709021610 0.8204525300 -0.0037946696 -0.0302319230864 +1403637159538319104.0000000000 5.2927243603 2.5579998155 0.6912966101 0.5702306314 0.8210485773 0.0004309139 -0.0267595789819 +1403637159588318976.0000000000 5.3486879803 2.5943663329 0.6812234110 0.5691944879 0.8218392188 0.0039170140 -0.0241369081413 +1403637159638319104.0000000000 5.4052789081 2.6309556067 0.6710598879 0.5682258686 0.8225755417 0.0078440693 -0.0206715054178 +1403637159688318976.0000000000 5.4620417395 2.6680891116 0.6619535647 0.5682123953 0.8226001007 0.0108731700 -0.0185882309328 +1403637159738319104.0000000000 5.5193275229 2.7053225242 0.6542540628 0.5683421928 0.8225224362 0.0138223701 -0.015903956535 +1403637159788318976.0000000000 5.5761962544 2.7437282844 0.6485129933 0.5689322082 0.8221046430 0.0153969460 -0.0149342699286 +1403637159838319104.0000000000 5.6326789744 2.7822021303 0.6451104609 0.5698797973 0.8214711452 0.0159745105 -0.0129224350505 +1403637159888318976.0000000000 5.6894766907 2.8208828937 0.6423205949 0.5700729586 0.8214080085 0.0147778113 -0.00934461134237 +1403637159938319104.0000000000 5.7462626903 2.8601039284 0.6396080888 0.5691447317 0.8221579765 0.0092767763 -0.00666914025174 +1403637159988318976.0000000000 5.8029883221 2.8994202252 0.6360706154 0.5683574936 0.8227744057 0.0029888858 -0.00176166601886 +1403637160038319104.0000000000 5.8593713344 2.9395298814 0.6321322017 0.5702467047 0.8214490009 -0.0058329092 0.00249236982486 +1403637160088318976.0000000000 5.9153238108 2.9802132648 0.6275853774 0.5729557060 0.8194050962 -0.0160285297 0.0063350945289 +1403637160138319104.0000000000 5.9709029387 3.0205352664 0.6227804925 0.5759144265 0.8169853291 -0.0273725296 0.0104062469371 +1403637160188318976.0000000000 6.0267225559 3.0608064340 0.6173903898 0.5778013541 0.8150879456 -0.0386897673 0.0167433003026 +1403637160238319104.0000000000 6.0826969950 3.1003129993 0.6103524091 0.5784699014 0.8138062311 -0.0495795150 0.0251766357073 +1403637160288318976.0000000000 6.1389020055 3.1393787643 0.6023223846 0.5788682741 0.8124016935 -0.0619152372 0.0328863639694 +1403637160338319104.0000000000 6.1954601036 3.1779846226 0.5925657939 0.5785611298 0.8111880398 -0.0737517922 0.042445923407 +1403637160388318976.0000000000 6.2523359413 3.2160410551 0.5825095339 0.5776329626 0.8099826284 -0.0873992298 0.0512803747985 +1403637160438319104.0000000000 6.3094945923 3.2526861733 0.5709835910 0.5759353621 0.8089365269 -0.1001754717 0.0623300016316 +1403637160488318976.0000000000 6.3668718480 3.2890696161 0.5585224093 0.5734597097 0.8080299793 -0.1125797878 0.0745473360425 +1403637160538319104.0000000000 6.4241532190 3.3247913053 0.5452235381 0.5695890855 0.8077063451 -0.1248983858 0.087058181775 +1403637160588318976.0000000000 6.4812049059 3.3602413113 0.5312330422 0.5669474925 0.8061484000 -0.1378010820 0.0985198442211 +1403637160638319104.0000000000 6.5382984931 3.3953083351 0.5165116811 0.5632559277 0.8051098287 -0.1494955304 0.11041743514 +1403637160688318976.0000000000 6.5946808872 3.4302314573 0.5013509101 0.5592793683 0.8045618267 -0.1603617174 0.119041903291 +1403637160738319104.0000000000 6.6506295804 3.4655752783 0.4865698767 0.5547455520 0.8047816077 -0.1694749810 0.12594509648 +1403637160788318976.0000000000 6.7060321521 3.5012865594 0.4730379407 0.5507293483 0.8050295643 -0.1760850252 0.132735261006 +1403637160838319104.0000000000 6.7612426296 3.5380337604 0.4620422992 0.5484604974 0.8045496758 -0.1818258497 0.137223402691 +1403637160888318976.0000000000 6.8156768926 3.5757286573 0.4528581140 0.5464370187 0.8042558036 -0.1870813901 0.13992762564 +1403637160938319104.0000000000 6.8698162416 3.6145866091 0.4460048399 0.5435867848 0.8048784246 -0.1915120451 0.141447041514 +1403637160988318976.0000000000 6.9233397633 3.6538752320 0.4427844151 0.5418852038 0.8050952584 -0.1958432901 0.140810001284 +1403637161038319104.0000000000 6.9764213434 3.6939675533 0.4426405450 0.5405602400 0.8053221901 -0.2001748321 0.138494887015 +1403637161088318976.0000000000 7.0298605683 3.7363725427 0.4459526819 0.5409149621 0.8045543569 -0.2044282488 0.135323248458 +1403637161138319104.0000000000 7.0837172161 3.7799849292 0.4525089448 0.5428230400 0.8028516974 -0.2089228583 0.130856939152 +1403637161188318976.0000000000 7.1366461824 3.8234140465 0.4613957559 0.5460600560 0.8002110205 -0.2148318110 0.123806425027 +1403637161238319104.0000000000 7.1905776479 3.8672315759 0.4730344161 0.5516202870 0.7960050412 -0.2200033799 0.11700233429 +1403637161288318976.0000000000 7.2456944786 3.9102220868 0.4857750578 0.5551912632 0.7932006315 -0.2246973377 0.110029659182 +1403637161338319104.0000000000 7.2988950542 3.9502396528 0.4999566032 0.5578372771 0.7912322113 -0.2269833754 0.106055208884 +1403637161388318976.0000000000 7.3564172144 3.9903208982 0.5152999143 0.5585806187 0.7908758079 -0.2260847841 0.106718410943 +1403637161438319104.0000000000 7.4163032574 4.0292795224 0.5313517931 0.5576255368 0.7915188257 -0.2239571331 0.111332438037 +1403637161488318976.0000000000 7.4779574454 4.0676143502 0.5488688249 0.5572627885 0.7911711685 -0.2239398817 0.115573768831 +1403637161538319104.0000000000 7.5414540763 4.1052601759 0.5664388377 0.5546037989 0.7918273180 -0.2255998640 0.1205355806 +1403637161588318976.0000000000 7.6062548446 4.1423322281 0.5839358650 0.5536011071 0.7907927831 -0.2289903433 0.125443258505 +1403637161638319104.0000000000 7.6719230577 4.1783611070 0.6000676218 0.5527847566 0.7894953626 -0.2325855749 0.130499178857 +1403637161688318976.0000000000 7.7387134808 4.2140532023 0.6156147639 0.5539632112 0.7867652359 -0.2359593959 0.135824842206 +1403637161738319104.0000000000 7.8064786890 4.2496531325 0.6301082047 0.5568141294 0.7830626340 -0.2380596886 0.141769253661 +1403637161788318976.0000000000 7.8748317732 4.2845116595 0.6436790978 0.5617497640 0.7779840093 -0.2383581622 0.149544208973 +1403637161838319104.0000000000 7.9433509992 4.3184420095 0.6564618255 0.5684048961 0.7715379586 -0.2387294186 0.157013748157 +1403637161888318976.0000000000 8.0115887271 4.3508403394 0.6680071958 0.5745909175 0.7652567500 -0.2388365441 0.164877194269 +1403637161938319104.0000000000 8.0789544454 4.3815517282 0.6786961207 0.5814625758 0.7585227501 -0.2396172967 0.17066945139 +1403637161988318976.0000000000 8.1451412078 4.4100776992 0.6879620604 0.5872192232 0.7527967483 -0.2396944970 0.176116972016 +1403637162038319104.0000000000 8.2098019468 4.4360544100 0.6957334804 0.5920338680 0.7479082282 -0.2399931459 0.180367600671 +1403637162088318976.0000000000 8.2725979231 4.4592763031 0.7014907111 0.5946248366 0.7449477624 -0.2408713668 0.182907407445 +1403637162138319104.0000000000 8.3334036405 4.4799042018 0.7055904597 0.5966539761 0.7427627085 -0.2427978325 0.182638452158 +1403637162188318976.0000000000 8.3921161998 4.4976144424 0.7077226967 0.5965822289 0.7425398059 -0.2465667381 0.178687225289 +1403637162238319104.0000000000 8.4491532102 4.5125041569 0.7081816962 0.5949229544 0.7437324558 -0.2509042246 0.173135157062 +1403637162288318976.0000000000 8.5050905257 4.5245405476 0.7073267575 0.5931793766 0.7451205983 -0.2544301488 0.167925044538 +1403637162338319104.0000000000 8.5603687437 4.5336253451 0.7047477030 0.5909011196 0.7470174482 -0.2565588968 0.164250818612 +1403637162388318976.0000000000 8.6151849662 4.5399818591 0.7011292250 0.5891996506 0.7484697319 -0.2594790290 0.159083203382 +1403637162438319104.0000000000 8.6696890502 4.5435942222 0.6960783282 0.5864579983 0.7507627730 -0.2627253262 0.152962995404 +1403637162488318976.0000000000 8.7247962992 4.5443571191 0.6896048987 0.5790071272 0.7567493722 -0.2636820717 0.15017622824 +1403637162538319104.0000000000 8.7806547163 4.5422983968 0.6842916168 0.5715957014 0.7626675976 -0.2625980827 0.150528192079 +1403637162588318976.0000000000 8.8375185218 4.5382579266 0.6819061616 0.5679452488 0.7657258495 -0.2604809272 0.152485423411 +1403637162638319104.0000000000 8.8951701431 4.5324840739 0.6821788922 0.5686623996 0.7654610339 -0.2570922389 0.156831315809 +1403637162688318976.0000000000 8.9194554107 4.4925053787 0.6806182852 0.5750452264 0.7604810333 -0.2557792675 0.159901694506 +1403637162738319104.0000000000 8.9778518812 4.4834856797 0.6846979484 0.5842288150 0.7523593431 -0.2576703715 0.161981759009 +1403637162788318976.0000000000 9.0363397523 4.4717462388 0.6875209214 0.5909297477 0.7449550992 -0.2617842302 0.165266300939 +1403637162838319104.0000000000 9.0952141451 4.4573433996 0.6878595705 0.5923261259 0.7406983900 -0.2667035160 0.171420215095 +1403637162888318976.0000000000 9.1539976141 4.4399403037 0.6863521819 0.5926145777 0.7363922586 -0.2730525061 0.178820392295 +1403637162938319104.0000000000 9.2128279079 4.4195590064 0.6830132594 0.5906830901 0.7328865647 -0.2798498859 0.188824817706 +1403637162988318976.0000000000 9.2710095840 4.3961957307 0.6782791620 0.5871622710 0.7298669498 -0.2874429724 0.199777978519 +1403637163038319104.0000000000 9.3288624257 4.3703451895 0.6722828576 0.5828682617 0.7264864719 -0.2966491080 0.210905908825 +1403637163088318976.0000000000 9.3853380747 4.3418130247 0.6655820325 0.5780325539 0.7223989253 -0.3072492449 0.222746629262 +1403637163138319104.0000000000 9.4408231717 4.3109872014 0.6577972679 0.5727875927 0.7176218202 -0.3180836180 0.236127314702 +1403637163188318976.0000000000 9.4943657714 4.2779402707 0.6492801905 0.5672084331 0.7123150720 -0.3304133353 0.248412679914 +1403637163238319104.0000000000 9.5461485638 4.2428729751 0.6401401250 0.5620292856 0.7060333175 -0.3425129948 0.261390292763 +1403637163288318976.0000000000 9.5953329682 4.2059035567 0.6304088865 0.5570192837 0.6996473869 -0.3547417559 0.272729422953 +1403637163338319104.0000000000 9.6418460476 4.1672325912 0.6200509087 0.5525296627 0.6927833334 -0.3678138828 0.281913412901 +1403637163388318976.0000000000 9.6856591511 4.1269807199 0.6091213315 0.5480730746 0.6862277174 -0.3813274141 0.28861189849 +1403637163438319104.0000000000 9.7265386644 4.0846700163 0.5973022195 0.5431909212 0.6800913349 -0.3951989236 0.293661727439 +1403637163488318976.0000000000 9.7648142144 4.0408482831 0.5848519778 0.5384616671 0.6747343671 -0.4087199317 0.296210371819 +1403637163538319104.0000000000 9.8143210951 4.0004925610 0.5676255154 0.5323095735 0.6713543793 -0.4210361308 0.297755590741 +1403637163588318976.0000000000 9.8494024106 3.9540132681 0.5554892071 0.5261559668 0.6692695055 -0.4331886936 0.295948954038 +1403637163638319104.0000000000 9.8830178707 3.9055340532 0.5449772727 0.5181912372 0.6694039176 -0.4439133680 0.293797819187 +1403637163688318976.0000000000 9.9159497951 3.8557165447 0.5376089682 0.5129283522 0.6686826093 -0.4528010280 0.291100158977 +1403637163738319104.0000000000 9.9485262617 3.8042219821 0.5322589544 0.5077155584 0.6686068017 -0.4614450956 0.286807043433 +1403637163788318976.0000000000 9.9820949065 3.7509777848 0.5297651877 0.5042071261 0.6681450372 -0.4669472655 0.285162470369 +1403637163838319104.0000000000 10.0155544818 3.6957776810 0.5304236817 0.5024435311 0.6672318673 -0.4722012893 0.281741150149 +1403637163888318976.0000000000 10.0490907128 3.6385912684 0.5340531223 0.5029158025 0.6650829170 -0.4768813175 0.27807304459 +1403637163938319104.0000000000 10.0837066932 3.5791108959 0.5398934693 0.5048524858 0.6624171066 -0.4794775448 0.27645764339 +1403637163988318976.0000000000 10.1196850799 3.5172285461 0.5471210564 0.5068652547 0.6600606443 -0.4808536915 0.276020446377 +1403637164038319104.0000000000 10.1570646428 3.4530099688 0.5558057058 0.5078565456 0.6592193923 -0.4805567191 0.276725065049 +1403637164088318976.0000000000 10.1955132176 3.3862320365 0.5667072465 0.5096922597 0.6579921161 -0.4791546491 0.278695170064 +1403637164138319104.0000000000 10.2349566889 3.3169146021 0.5792135889 0.5112620934 0.6575710844 -0.4768052913 0.280834568561 +1403637164188318976.0000000000 10.2747739454 3.2446095974 0.5927524646 0.5124831700 0.6576009322 -0.4738703154 0.283494159835 +1403637164238319104.0000000000 10.3148650246 3.1697521892 0.6072159243 0.5119328205 0.6591802003 -0.4707136241 0.286068059967 +1403637164288318976.0000000000 10.3554232013 3.0926794927 0.6227665017 0.5107382319 0.6615945482 -0.4652598376 0.291500250084 +1403637164338319104.0000000000 10.3958879005 3.0137742204 0.6378510072 0.5078357796 0.6652954199 -0.4610463185 0.294823875197 +1403637164388318976.0000000000 10.4361498194 2.9335515771 0.6520979143 0.5061306265 0.6680451443 -0.4583520636 0.29573782306 +1403637164438319104.0000000000 10.4762814754 2.8522707785 0.6642481999 0.5035346933 0.6714342598 -0.4566250594 0.295165042907 +1403637164488318976.0000000000 10.5158305115 2.7700231350 0.6749824966 0.5033609362 0.6730013367 -0.4570844257 0.291154248612 +1403637164538319104.0000000000 10.5542326291 2.6926038091 0.6923535761 0.5056495770 0.6726689425 -0.4585467106 0.285604469895 +1403637164588318976.0000000000 10.5946796962 2.6094473262 0.7000512032 0.5068750210 0.6732634223 -0.4592896602 0.280797231555 +1403637164638319104.0000000000 10.6357302349 2.5249310356 0.7058386309 0.5079090463 0.6737679731 -0.4599173978 0.276660633747 +1403637164688318976.0000000000 10.6775684027 2.4386106494 0.7094393392 0.5070239177 0.6759040447 -0.4578779807 0.276456549737 +1403637164738319104.0000000000 10.7205181387 2.3507148736 0.7115302395 0.5058852913 0.6779885179 -0.4534182670 0.280755261423 +1403637164788318976.0000000000 10.7647090405 2.2615888046 0.7120734843 0.5048626457 0.6789286184 -0.4482319140 0.288544262352 +1403637164838319104.0000000000 10.8091682480 2.1715719739 0.7113170505 0.5044947424 0.6783380393 -0.4449100795 0.29563081802 +1403637164888318976.0000000000 10.8539478723 2.0805653288 0.7090784420 0.5026784430 0.6774328284 -0.4431809900 0.303298130554 +1403637164938319104.0000000000 10.8985586174 1.9883140467 0.7091976801 0.5008219018 0.6756704452 -0.4437898701 0.309350001496 +1403637164988318976.0000000000 10.9425334625 1.8961331662 0.7053848738 0.4986505110 0.6732896096 -0.4463874800 0.314272154586 +1403637165038319104.0000000000 10.9869068408 1.8041120094 0.7005984042 0.4962487457 0.6701293964 -0.4499470338 0.319705241168 +1403637165088318976.0000000000 11.0312119107 1.7122517637 0.6955417302 0.4948519436 0.6653145279 -0.4545832569 0.325318605861 +1403637165138319104.0000000000 11.0754291384 1.6203207794 0.6904447191 0.4947695981 0.6583874998 -0.4594494276 0.332618652941 +1403637165188318976.0000000000 11.1187987822 1.5280639920 0.6841441553 0.4912826859 0.6529128571 -0.4651404048 0.340573820771 +1403637165238319104.0000000000 11.1608855863 1.4347316349 0.6771224087 0.4873410079 0.6472583830 -0.4721983703 0.347252108333 +1403637165288318976.0000000000 11.2010984907 1.3418086226 0.6716345797 0.4805382183 0.6430121183 -0.4802441957 0.353530690372 +1403637165338319104.0000000000 11.2389408272 1.2490012674 0.6683003279 0.4723929625 0.6399775611 -0.4897132209 0.357007803298 +1403637165388318976.0000000000 11.2752445035 1.1565016211 0.6668762585 0.4636365767 0.6380618262 -0.4984043668 0.359876809378 +1403637165438319104.0000000000 11.3110777952 1.0649942935 0.6676548875 0.4558467902 0.6363507840 -0.5070392701 0.360794348788 +1403637165488318976.0000000000 11.3465321021 0.9743771284 0.6715670270 0.4504540571 0.6341104693 -0.5136414797 0.362170519889 +1403637165538319104.0000000000 11.3811637746 0.8841672534 0.6774416211 0.4447951826 0.6326071606 -0.5178220047 0.365822084298 +1403637165588318976.0000000000 11.4156368604 0.7950876214 0.6850102478 0.4397985630 0.6312620163 -0.5220476731 0.368173488652 +1403637165638319104.0000000000 11.4501572101 0.7065921066 0.6931236689 0.4332229588 0.6315655595 -0.5226088816 0.37459680841 +1403637165688318976.0000000000 11.4845522171 0.6195778025 0.7009177056 0.4274759951 0.6321156815 -0.5221308512 0.380885039041 +1403637165738319104.0000000000 11.5188834066 0.5342115267 0.7077353102 0.4219945374 0.6331210899 -0.5209081385 0.386953494702 +1403637165788318976.0000000000 11.5535013001 0.4509265966 0.7133936185 0.4165497746 0.6346890963 -0.5189125392 0.392919601192 +1403637165838319104.0000000000 11.5876316636 0.3699180910 0.7177606971 0.4117623661 0.6361658290 -0.5163857778 0.398861530216 +1403637165888318976.0000000000 11.6206624711 0.2917524395 0.7205935426 0.4081656771 0.6384207540 -0.5135106157 0.402649436214 +1403637165938319104.0000000000 11.6531558898 0.2167251272 0.7219822955 0.4057841643 0.6416168999 -0.5089856403 0.405709974935 +1403637165988318976.0000000000 11.6848866142 0.1448982467 0.7215908382 0.4037316808 0.6458644737 -0.5036616379 0.407657657949 +1403637166038319104.0000000000 11.7171206162 0.0766928524 0.7188747426 0.4033526106 0.6501423087 -0.4981335893 0.408025216248 +1403637166088318976.0000000000 11.7495933763 0.0115760178 0.7122191907 0.4023158461 0.6543982936 -0.4927662563 0.408761849882 +1403637166138319104.0000000000 11.7814675668 -0.0502929542 0.7016797303 0.4028696233 0.6574471407 -0.4883755105 0.408593544354 +1403637166188318976.0000000000 11.8127730156 -0.1088418646 0.6874549230 0.4033976206 0.6602896032 -0.4845392811 0.40805598219 +1403637166238319104.0000000000 11.8439798723 -0.1636092781 0.6709761170 0.4074009191 0.6608125581 -0.4811447260 0.407248090072 +1403637166288318976.0000000000 11.8743654643 -0.2145410518 0.6535592976 0.4142784498 0.6592285097 -0.4783838694 0.406128072843 +1403637166338319104.0000000000 11.9041161174 -0.2615862409 0.6385257774 0.4254190921 0.6550500496 -0.4723191304 0.408463789966 +1403637166388318976.0000000000 11.9323387262 -0.3045218491 0.6260906863 0.4410355362 0.6482783386 -0.4647794635 0.411342803201 +1403637166438319104.0000000000 11.9572752973 -0.3448387774 0.6142965912 0.4552027029 0.6426845547 -0.4578385186 0.41246933615 +1403637166488318976.0000000000 11.9781632824 -0.3833216170 0.6027161848 0.4632103028 0.6407417064 -0.4522546943 0.412737171141 +1403637166538319104.0000000000 11.9949337648 -0.4199733140 0.5922981492 0.4677814624 0.6408866350 -0.4493168996 0.410559555072 +1403637166588318976.0000000000 12.0073686815 -0.4553200665 0.5816557924 0.4664154349 0.6449072380 -0.4484552182 0.406742195752 +1403637166638319104.0000000000 12.0157016326 -0.4891474333 0.5709712608 0.4608794004 0.6514813660 -0.4499147964 0.400922541222 +1403637166688318976.0000000000 12.0205883827 -0.5213632256 0.5600888993 0.4513531495 0.6603998656 -0.4532592426 0.393329900918 +1403637166738319104.0000000000 12.0239462397 -0.5517540009 0.5490372638 0.4418464656 0.6687597858 -0.4530179296 0.390265044697 +1403637166788318976.0000000000 12.0261797531 -0.5795172577 0.5373587081 0.4340134493 0.6757068602 -0.4515454988 0.388792010517 +1403637166838319104.0000000000 12.0277202368 -0.6044034311 0.5249509468 0.4276184204 0.6811856317 -0.4478544773 0.390582883362 +1403637166888318976.0000000000 12.0286153996 -0.6260642418 0.5118125203 0.4232790322 0.6850046190 -0.4416386484 0.395675166165 +1403637166938319104.0000000000 12.0286326311 -0.6437729600 0.4979483440 0.4203515386 0.6878216163 -0.4345497417 0.401711998996 +1403637166988318976.0000000000 12.0274970878 -0.6569817987 0.4846845582 0.4200471752 0.6883035933 -0.4267455482 0.409495752282 +1403637167038319104.0000000000 12.0236310637 -0.6654304474 0.4728917102 0.4195239013 0.6889743248 -0.4188929138 0.416944603974 +1403637167088318976.0000000000 12.0156126856 -0.6690242528 0.4631513275 0.4200907036 0.6891637546 -0.4111767861 0.423687114017 +1403637167138319104.0000000000 12.0031284279 -0.6675017256 0.4559934557 0.4208235490 0.6886564453 -0.4043098784 0.43034098476 +1403637167188318976.0000000000 11.9870288472 -0.6599829858 0.4517372024 0.4223878685 0.6875676844 -0.3984237015 0.436001974851 +1403637167238319104.0000000000 11.9668053534 -0.6462696045 0.4504979041 0.4231059501 0.6868122400 -0.3943474814 0.440182196174 +1403637167288318976.0000000000 11.9418278649 -0.6266876159 0.4513421608 0.4232629047 0.6864204688 -0.3929936974 0.44184998275 +1403637167338319104.0000000000 11.9134253775 -0.6011508938 0.4529697798 0.4225599150 0.6864915848 -0.3946981967 0.440892000089 +1403637167388318976.0000000000 11.8809505438 -0.5703400156 0.4539276743 0.4215408695 0.6870082758 -0.3995950147 0.436631135583 +1403637167438319104.0000000000 11.8448454658 -0.5340400260 0.4536661431 0.4224704543 0.6874462072 -0.4090243029 0.4261872207 +1403637167488318976.0000000000 11.8061035017 -0.4926474378 0.4531093892 0.4275900021 0.6856396829 -0.4207177199 0.4123852757 +1403637167538319104.0000000000 11.7655063116 -0.4473076027 0.4516114405 0.4332535625 0.6833366830 -0.4335679051 0.396687786404 +1403637167588318976.0000000000 11.7239490873 -0.3990076684 0.4495190284 0.4401522037 0.6798325856 -0.4451367658 0.382030041877 +1403637167638319104.0000000000 11.6817561606 -0.3487599118 0.4465846665 0.4474449616 0.6758766422 -0.4547903774 0.368984394702 +1403637167688318976.0000000000 11.6392202670 -0.2974982573 0.4419414605 0.4528382730 0.6736637425 -0.4606612438 0.359034648829 +1403637167738319104.0000000000 11.5964231624 -0.2456971726 0.4349007945 0.4555192736 0.6741337896 -0.4632553562 0.351340717895 +1403637167788318976.0000000000 11.5534866992 -0.1934013469 0.4260685793 0.4564931188 0.6766641929 -0.4638990477 0.34429242812 +1403637167838319104.0000000000 11.5106791947 -0.1408402555 0.4156764043 0.4565976973 0.6808789109 -0.4625522630 0.337591255142 +1403637167888318976.0000000000 11.4686342603 -0.0880890621 0.4054147474 0.4551382545 0.6862556625 -0.4601240027 0.33194613579 +1403637167938319104.0000000000 11.4277144042 -0.0352665820 0.3965268269 0.4533339148 0.6913748916 -0.4565284916 0.328741322699 +1403637167988318976.0000000000 11.3880985681 0.0177234697 0.3893586415 0.4512704905 0.6963729164 -0.4504616847 0.329399417616 +1403637168038319104.0000000000 11.3502371532 0.0718097411 0.3842727558 0.4502737229 0.7003666163 -0.4442301628 0.330756314675 +1403637168088318976.0000000000 11.3131624577 0.1271787976 0.3805191044 0.4512323600 0.7027626420 -0.4404103080 0.329473499594 +1403637168138319104.0000000000 11.2767372582 0.1835578642 0.3753953680 0.4532539209 0.7038453351 -0.4403563295 0.324420915745 +1403637168188318976.0000000000 11.2417450786 0.2404938198 0.3668308342 0.4556537027 0.7042145902 -0.4398934049 0.320866493309 +1403637168238319104.0000000000 11.2080562414 0.2980291578 0.3552069760 0.4594369759 0.7033091750 -0.4378646755 0.320231783865 +1403637168288318976.0000000000 11.1151843572 0.3819259842 0.3874498138 0.4625065910 0.7024825874 -0.4348617635 0.321715890695 +1403637168338319104.0000000000 11.0811723499 0.4421172899 0.3685476767 0.4665676972 0.7005904910 -0.4313868715 0.32464274975 +1403637168388318976.0000000000 11.0469551385 0.5022178308 0.3466484695 0.4718716445 0.6976844243 -0.4270255731 0.328972270985 +1403637168438319104.0000000000 11.0125790421 0.5626546410 0.3232178903 0.4767683909 0.6948210124 -0.4229504767 0.333209478344 +1403637168488318976.0000000000 10.9775368571 0.6233910481 0.2990845763 0.4833753822 0.6907905372 -0.4211914473 0.334296931404 +1403637168538319104.0000000000 10.9415482448 0.6838902969 0.2734887986 0.4868153367 0.6886568847 -0.4211323253 0.333781497088 +1403637168588318976.0000000000 10.9045143154 0.7442796031 0.2482652387 0.4869820821 0.6890086556 -0.4228750169 0.330593775403 +1403637168638319104.0000000000 10.8665402118 0.8040544626 0.2241678492 0.4854388314 0.6903103902 -0.4242733343 0.328348662098 +1403637168688318976.0000000000 10.8268433810 0.8654887562 0.2011233691 0.4823951152 0.6923881674 -0.4254336363 0.32695534797 +1403637168738319104.0000000000 10.7876547018 0.9251852312 0.1811169760 0.4793756754 0.6944641280 -0.4258191682 0.326491305857 +1403637168788318976.0000000000 10.7483198224 0.9850776654 0.1632680282 0.4782905735 0.6949751771 -0.4277380015 0.324480866416 +1403637168838319104.0000000000 10.7097644181 1.0449404685 0.1469951694 0.4753296953 0.6965101377 -0.4271263214 0.326340948168 +1403637168888318976.0000000000 10.6715804051 1.1052783178 0.1315017784 0.4733115028 0.6978056491 -0.4263293279 0.327546640186 +1403637168938319104.0000000000 10.6332452866 1.1654860807 0.1152732560 0.4703188376 0.6992994736 -0.4252321726 0.330087922448 +1403637168988318976.0000000000 10.5949967140 1.2264007335 0.0980363371 0.4686953790 0.6998149724 -0.4249385816 0.331678832519 +1403637169038319104.0000000000 10.5568869376 1.2878021087 0.0798377942 0.4667545520 0.7006999271 -0.4231623781 0.334803527695 +1403637169088318976.0000000000 10.5187999617 1.3500742850 0.0613787837 0.4643285562 0.7023900013 -0.4201141472 0.338454400503 +1403637169138319104.0000000000 10.4802586572 1.4142749570 0.0447210056 0.4650037494 0.7032319930 -0.4170389703 0.339580291464 +1403637169188318976.0000000000 10.4408376059 1.4801377437 0.0301951572 0.4670326764 0.7046697585 -0.4120594744 0.339894101514 +1403637169238319104.0000000000 10.4006834048 1.5476994545 0.0180089638 0.4704615551 0.7066190917 -0.4061998396 0.338167229009 +1403637169288318976.0000000000 10.3594654424 1.6167979750 0.0087570965 0.4755919334 0.7087744828 -0.3993229338 0.334652416744 +1403637169338319104.0000000000 10.3168291932 1.6868989034 0.0014018447 0.4815413983 0.7112607030 -0.3920578408 0.329418796557 +1403637169388318976.0000000000 10.2725645627 1.7580061372 -0.0034860487 0.4872507948 0.7146259635 -0.3833358480 0.323959909385 +1403637169438319104.0000000000 10.2270890241 1.8301721350 -0.0072913074 0.4925580087 0.7191292744 -0.3731893790 0.31775679724 +1403637169488318976.0000000000 10.1803932058 1.9030812633 -0.0090369147 0.4989048966 0.7232112474 -0.3622994491 0.311124581119 +1403637169538319104.0000000000 10.1319817533 1.9761261838 -0.0095521174 0.5045718931 0.7281859931 -0.3487763837 0.305789794294 +1403637169588318976.0000000000 10.0820694787 2.0498859307 -0.0085293757 0.5114764069 0.7327263377 -0.3348941312 0.298914570094 +1403637169638319104.0000000000 10.0308383111 2.1237510378 -0.0061736732 0.5173779079 0.7379343129 -0.3178725539 0.294499727835 +1403637169688318976.0000000000 9.9775804679 2.1980529075 -0.0028295643 0.5242990757 0.7423590796 -0.3033968927 0.286293209144 +1403637169738319104.0000000000 9.9222200901 2.2721574057 -0.0002077874 0.5297952314 0.7475732209 -0.2892747295 0.277076565234 +1403637169788318976.0000000000 9.8652117671 2.3460681005 0.0009219609 0.5345229790 0.7525806688 -0.2760138352 0.267813152441 +1403637169838319104.0000000000 9.8063038920 2.4195417599 0.0002384163 0.5393565880 0.7568808767 -0.2630549934 0.258897431308 +1403637169888318976.0000000000 9.7461752409 2.4926698620 -0.0025724690 0.5421212002 0.7615537716 -0.2486610712 0.253590474903 +1403637169938319104.0000000000 9.6871843958 2.5662695643 -0.0104453323 0.5461343453 0.7649203201 -0.2355586830 0.247277753955 +1403637169988318976.0000000000 9.6239594129 2.6395740616 -0.0168213969 0.5495436043 0.7680155309 -0.2222187083 0.242431056246 +1403637170038319104.0000000000 9.5582507870 2.7127421266 -0.0249110317 0.5521809549 0.7713604663 -0.2104485810 0.236242711528 +1403637170088318976.0000000000 9.4898807810 2.7855292738 -0.0344044153 0.5543742692 0.7748751021 -0.1991804953 0.229270312308 +1403637170138319104.0000000000 9.4189995337 2.8582757268 -0.0448815610 0.5578970516 0.7772045737 -0.1879456016 0.22221696907 +1403637170188318976.0000000000 9.3457205765 2.9308930523 -0.0565999376 0.5619028849 0.7789906779 -0.1767653109 0.214924862531 +1403637170238319104.0000000000 9.2699204884 3.0027577257 -0.0698601389 0.5650151864 0.7810839057 -0.1651213372 0.208328383496 +1403637170288318976.0000000000 9.1915194681 3.0742781713 -0.0843557350 0.5680140210 0.7829908516 -0.1527954821 0.202333731455 +1403637170338319104.0000000000 9.1099482103 3.1454754066 -0.0992816415 0.5729190468 0.7837620436 -0.1418974450 0.193250976442 +1403637170388318976.0000000000 9.0250171420 3.2163981298 -0.1145815923 0.5791969013 0.7839666603 -0.1334162495 0.179240981463 +1403637170438319104.0000000000 8.9374524165 3.2865177756 -0.1301556295 0.5875624787 0.7825023297 -0.1255364422 0.163404526577 +1403637170488318976.0000000000 8.8476663301 3.3552203715 -0.1461999143 0.5966053589 0.7803041461 -0.1178587983 0.145934193943 +1403637170538319104.0000000000 8.7562255390 3.4217678456 -0.1631557663 0.6061652508 0.7771056103 -0.1088115097 0.1297328585 +1403637170588318976.0000000000 8.6634899038 3.4855253251 -0.1811530682 0.6159749219 0.7730605990 -0.0992481131 0.114464046526 +1403637170638319104.0000000000 8.5701072405 3.5465128911 -0.2007452578 0.6240203443 0.7699167650 -0.0886009589 0.0998832067035 +1403637170688318976.0000000000 8.4762871148 3.6037141114 -0.2216205900 0.6319761792 0.7662631359 -0.0766958215 0.0869750904396 +1403637170738319104.0000000000 8.3819656998 3.6566788410 -0.2432363579 0.6374775526 0.7641395536 -0.0638354494 0.0750876018511 +1403637170788318976.0000000000 8.2868874283 3.7049893427 -0.2646052220 0.6404860948 0.7638241525 -0.0512047360 0.0610598182051 +1403637170838319104.0000000000 8.1919380575 3.7479623326 -0.2858261595 0.6382678564 0.7673133646 -0.0378120422 0.0491385136867 +1403637170888318976.0000000000 8.0970479130 3.7864636315 -0.3047722392 0.6368684769 0.7697523338 -0.0230505556 0.0367227394501 +1403637170938319104.0000000000 8.0027169139 3.8206350003 -0.3218378265 0.6336747986 0.7731558918 -0.0076759424 0.0250458876012 +1403637170988318976.0000000000 7.9091326130 3.8500421460 -0.3367676955 0.6298070543 0.7766044057 0.0071869187 0.0133048681795 +1403637171038319104.0000000000 7.8161016428 3.8761363362 -0.3491052193 0.6271907821 0.7785809793 0.0210490904 0.000563287489622 +1403637171088318976.0000000000 7.7240770689 3.8989999352 -0.3599270649 0.6237124607 0.7808214181 0.0334465678 -0.0134909792079 +1403637171138319104.0000000000 7.6339275150 3.9190610000 -0.3693139223 0.6197536942 0.7830845154 0.0462071990 -0.0234285081286 +1403637171188318976.0000000000 7.5455001867 3.9365435799 -0.3764240311 0.6177450135 0.7836498349 0.0568087692 -0.0325084338989 +1403637171238319104.0000000000 7.4586299567 3.9516738468 -0.3805576735 0.6175564562 0.7827547873 0.0644552744 -0.0420057615054 +1403637171288318976.0000000000 7.3738245390 3.9642211756 -0.3827220297 0.6187611555 0.7807613101 0.0721778998 -0.0483400429215 +1403637171338319104.0000000000 7.2908991234 3.9744499926 -0.3826147358 0.6201550068 0.7787190007 0.0794429529 -0.0518970400923 +1403637171388318976.0000000000 7.2099061864 3.9820044874 -0.3813376261 0.6213943370 0.7768972310 0.0874290579 -0.0515357179944 +1403637171438319104.0000000000 7.1304825929 3.9862407925 -0.3778833170 0.6229185321 0.7749689522 0.0948514100 -0.0489779078053 +1403637171488318976.0000000000 7.0516417336 3.9867852967 -0.3727113899 0.6227639250 0.7745188345 0.1000025657 -0.0478033011995 +1403637171538319104.0000000000 6.9727227609 3.9841004216 -0.3661740531 0.6223940728 0.7743755325 0.1039259549 -0.0465569409458 +1403637171588318976.0000000000 6.8942229779 3.9785511443 -0.3596086462 0.6220339577 0.7743947405 0.1065282108 -0.0451473320826 +1403637171638319104.0000000000 6.8155525935 3.9695121582 -0.3540389286 0.6224873517 0.7738186417 0.1093568437 -0.0418961506938 +1403637171688318976.0000000000 6.7367402286 3.9575171777 -0.3494907080 0.6229687046 0.7734262254 0.1102475543 -0.0395896912282 +1403637171738319104.0000000000 6.6577611622 3.9426438436 -0.3460399620 0.6239560920 0.7727458353 0.1102584612 -0.037225542148 +1403637171788318976.0000000000 6.5788071244 3.9246454207 -0.3437400075 0.6250250600 0.7720416557 0.1100817696 -0.0343126838942 +1403637171838319104.0000000000 6.5003370596 3.9040844318 -0.3430021264 0.6264605390 0.7710700499 0.1097616676 -0.0308309502445 +1403637171888318976.0000000000 6.4217131898 3.8799967834 -0.3438334724 0.6278443318 0.7701937239 0.1086508441 -0.0284273951195 +1403637171938319104.0000000000 6.3440814084 3.8531717969 -0.3459681853 0.6284586298 0.7699818627 0.1070232637 -0.0267152140745 +1403637171988318976.0000000000 6.2663377608 3.8232382739 -0.3490124171 0.6299718960 0.7690291161 0.1054212377 -0.0248191772452 +1403637172038319104.0000000000 6.1886386672 3.7894975187 -0.3537774063 0.6307488842 0.7686681819 0.1038117317 -0.0229825042258 +1403637172088318976.0000000000 6.1108291049 3.7529899248 -0.3591853075 0.6319013430 0.7679902872 0.1021116004 -0.0215599757989 +1403637172138319104.0000000000 6.0319854816 3.7132049363 -0.3654709080 0.6308492717 0.7692707774 0.0984889281 -0.0234861339656 +1403637172188318976.0000000000 5.9524286987 3.6698578190 -0.3716885050 0.6281300320 0.7719963669 0.0930139998 -0.0286821920165 +1403637172238319104.0000000000 5.8719765840 3.6231198940 -0.3768848562 0.6213251571 0.7779308332 0.0865132693 -0.0359739091574 +1403637172288318976.0000000000 5.7917878718 3.5734500716 -0.3799941182 0.6139689209 0.7840790747 0.0793519644 -0.044333221868 +1403637172338319104.0000000000 5.7123680912 3.5218686678 -0.3805990078 0.6076563024 0.7891960229 0.0727073621 -0.0513526539526 +1403637172388318976.0000000000 5.6341382290 3.4688080373 -0.3785610189 0.6023933414 0.7933150823 0.0662687043 -0.0581541173966 +1403637172438319104.0000000000 5.5578870593 3.4145475569 -0.3745924570 0.5981780530 0.7965330802 0.0605888758 -0.0636164847058 +1403637172488318976.0000000000 5.4841104766 3.3583837583 -0.3691962463 0.5939497922 0.7996333483 0.0545309105 -0.0695451822669 +1403637172538319104.0000000000 5.4128759209 3.3009127806 -0.3613266939 0.5921466486 0.8009340511 0.0502001098 -0.0731227822515 +1403637172588318976.0000000000 5.3444732889 3.2422568793 -0.3518590620 0.5904859585 0.8021526479 0.0466241489 -0.0755225198458 +1403637172638319104.0000000000 5.2787603932 3.1832950421 -0.3406436885 0.5893862490 0.8029550055 0.0434850350 -0.0774348783228 +1403637172688318976.0000000000 5.2158457559 3.1241931580 -0.3279066358 0.5870275885 0.8046406180 0.0405461186 -0.0794235379736 +1403637172738319104.0000000000 5.1562607689 3.0651701263 -0.3137191899 0.5848849126 0.8062702570 0.0381238255 -0.0799029763543 +1403637172788318976.0000000000 5.1002527194 3.0063129296 -0.2986437986 0.5805245873 0.8096451551 0.0347492515 -0.0791101508219 +1403637172838319104.0000000000 5.0473612360 2.9472559776 -0.2827443745 0.5731704221 0.8152011533 0.0301433420 -0.0775507944336 +1403637172888318976.0000000000 4.9986211373 2.8890626785 -0.2680371427 0.5629319065 0.8227912409 0.0253070930 -0.0740391353268 +1403637172938319104.0000000000 4.9530615834 2.8323309704 -0.2561367808 0.5516082836 0.8309326050 0.0202845904 -0.0697699273868 +1403637172988318976.0000000000 4.9104367735 2.7773043024 -0.2478281052 0.5412361734 0.8381252216 0.0151672402 -0.0661775818823 +1403637173038319104.0000000000 4.8702824544 2.7246513604 -0.2437042341 0.5316744956 0.8445087753 0.0101093899 -0.0634425667718 +1403637173088318976.0000000000 4.8328438522 2.6760893506 -0.2434297087 0.5257235632 0.8485436919 0.0045229038 -0.0597317454362 +1403637173138319104.0000000000 4.7978652803 2.6309334916 -0.2464296723 0.5204069947 0.8520562037 -0.0032798218 -0.0562674721317 +1403637173188318976.0000000000 4.7654356004 2.5890384780 -0.2521744588 0.5176368844 0.8538786420 -0.0130823118 -0.0526514363851 +1403637173238319104.0000000000 4.7359260572 2.5508601147 -0.2599338398 0.5182235160 0.8536514216 -0.0232584378 -0.0467191913828 +1403637173288318976.0000000000 4.7094946323 2.5173735102 -0.2675531900 0.5216944011 0.8514718610 -0.0346002775 -0.0404158701717 +1403637173338319104.0000000000 4.6859675821 2.4871824448 -0.2756307600 0.5268899036 0.8480992806 -0.0454889128 -0.0323326248535 +1403637173388318976.0000000000 4.6657515077 2.4601976948 -0.2837766604 0.5315131918 0.8447466575 -0.0570873042 -0.0252557161297 +1403637173438319104.0000000000 4.6487906576 2.4361937201 -0.2920745160 0.5355652407 0.8415218683 -0.0684551023 -0.0180199108385 +1403637173488318976.0000000000 4.6349249413 2.4140910428 -0.3014241681 0.5388091178 0.8385527473 -0.0800220867 -0.0105114351806 +1403637173538319104.0000000000 4.6239427554 2.3935720844 -0.3117542969 0.5412652689 0.8358402510 -0.0915695028 -0.00424378341757 +1403637173588318976.0000000000 4.6157354269 2.3748324138 -0.3228583496 0.5424925009 0.8335586244 -0.1043155180 0.000422910290121 +1403637173638319104.0000000000 4.6103909940 2.3579761369 -0.3353291513 0.5425760225 0.8316140481 -0.1184205820 0.00242910799291 +1403637173688318976.0000000000 4.6082662150 2.3422734380 -0.3495186267 0.5414843281 0.8302572308 -0.1320994649 0.00416946822616 +1403637173738319104.0000000000 4.6098016102 2.3277443422 -0.3651038152 0.5389038367 0.8296735054 -0.1455710977 0.00579523240639 +1403637173788318976.0000000000 4.6149488209 2.3141152636 -0.3826820356 0.5346463511 0.8301450436 -0.1579417190 0.00817919604704 +1403637173838319104.0000000000 4.6246373361 2.3030593776 -0.4014496858 0.5281808881 0.8317974454 -0.1704137656 0.00985432333683 +1403637173888318976.0000000000 4.6393298705 2.2943928242 -0.4202918533 0.5206070463 0.8344212481 -0.1803629071 0.0133680870262 +1403637173938319104.0000000000 4.6594688424 2.2875767086 -0.4379212137 0.5133707727 0.8378317310 -0.1844363561 0.0217179830033 +1403637173988318976.0000000000 4.6853874109 2.2833884535 -0.4521905381 0.5111423651 0.8388364293 -0.1841640114 0.0342132197426 +1403637174038319104.0000000000 4.7168190746 2.2825664243 -0.4621431863 0.5142370006 0.8372631036 -0.1785824880 0.051566439205 +1403637174088318976.0000000000 4.7522373500 2.2856180908 -0.4666640774 0.5233492723 0.8315656305 -0.1737861084 0.0663515631024 +1403637174138319104.0000000000 4.7906205692 2.2915642981 -0.4665596268 0.5363837228 0.8231432354 -0.1682421183 0.0801392884465 +1403637174188318976.0000000000 4.8304830698 2.2996725868 -0.4623909729 0.5504732995 0.8135208585 -0.1651187272 0.0888749973464 +1403637174238319104.0000000000 4.8712279359 2.3085091030 -0.4554316520 0.5635161915 0.8043131445 -0.1632880917 0.0941640413538 +1403637174288318976.0000000000 4.9125319125 2.3170695064 -0.4465721923 0.5738834548 0.7966999557 -0.1637794712 0.0954109309016 +1403637174338319104.0000000000 4.9539036769 2.3242284191 -0.4375136329 0.5779546548 0.7936698174 -0.1650076251 0.0939634050192 +1403637174388318976.0000000000 4.9954473733 2.3298773103 -0.4266141243 0.5811904526 0.7911838911 -0.1676460944 0.0902246941315 +1403637174438319104.0000000000 5.0377369476 2.3346047683 -0.4140028466 0.5837253314 0.7889134881 -0.1729494791 0.0834788803372 +1403637174488318976.0000000000 5.0836694460 2.3408452449 -0.4005910001 0.5873036006 0.7853239015 -0.1807123564 0.0753916096882 +1403637174538319104.0000000000 5.1296191704 2.3423043871 -0.3852137957 0.5887527671 0.7831821155 -0.1861064644 0.0732143225704 +1403637174588318976.0000000000 5.1776423135 2.3412565947 -0.3685367488 0.5889904772 0.7814592168 -0.1924932021 0.0731988891224 +1403637174638319104.0000000000 5.2289998802 2.3390123754 -0.3524127025 0.5885372438 0.7801711722 -0.1960616749 0.0807259214482 +1403637174688318976.0000000000 5.2829611552 2.3351058432 -0.3367520739 0.5897154433 0.7769866151 -0.2001723892 0.0919701611823 +1403637174738319104.0000000000 5.3386529153 2.3293027152 -0.3226385300 0.5902678405 0.7736231673 -0.2051263691 0.104948769513 +1403637174788318976.0000000000 5.3954308231 2.3215772213 -0.3096818511 0.5906846799 0.7697784282 -0.2106032329 0.119075853148 +1403637174838319104.0000000000 5.4522448034 2.3117134911 -0.2990727057 0.5870432997 0.7683541113 -0.2191569657 0.130316339738 +1403637174888318976.0000000000 5.5087940429 2.2996342031 -0.2903146318 0.5805334984 0.7685132757 -0.2313100106 0.137345845863 +1403637174938319104.0000000000 5.5657783042 2.2862751033 -0.2824837066 0.5737299367 0.7683887652 -0.2444274221 0.143763349043 +1403637174988318976.0000000000 5.6231960138 2.2714151232 -0.2753653084 0.5678946747 0.7674542564 -0.2561678741 0.151286559485 +1403637175038319104.0000000000 5.6810178326 2.2555910597 -0.2691938347 0.5639925410 0.7654675738 -0.2666999171 0.157616501114 +1403637175088318976.0000000000 5.7393396839 2.2391159773 -0.2632501955 0.5635656901 0.7614166675 -0.2748444500 0.164617434559 +1403637175138319104.0000000000 5.7980893790 2.2219391922 -0.2579809152 0.5659696468 0.7556993998 -0.2820561690 0.170414476148 +1403637175188318976.0000000000 5.8567866897 2.2032863052 -0.2534363409 0.5703188869 0.7489268738 -0.2887101650 0.174617712723 +1403637175238319104.0000000000 5.9156236971 2.1830285063 -0.2494431608 0.5760373110 0.7413427270 -0.2944716065 0.178545373895 +1403637175288318976.0000000000 5.9743898880 2.1605182205 -0.2465570354 0.5819765305 0.7340648976 -0.2981271548 0.18322730021 +1403637175338319104.0000000000 6.0330125176 2.1354171460 -0.2450114712 0.5864743664 0.7282108028 -0.3001289803 0.188890019414 +1403637175388318976.0000000000 6.0907695892 2.1076137970 -0.2444748715 0.5900227094 0.7236404021 -0.3017504794 0.192780753942 +1403637175438319104.0000000000 6.1472916399 2.0769503841 -0.2455238817 0.5906653672 0.7219901166 -0.3046732707 0.192402946296 +1403637175488318976.0000000000 6.2029352641 2.0431851073 -0.2480955180 0.5885158053 0.7227199106 -0.3086492799 0.189896550126 +1403637175538319104.0000000000 6.2575677296 2.0060983677 -0.2519598930 0.5849773265 0.7249623934 -0.3128850559 0.185294353692 +1403637175588318976.0000000000 6.3119300343 1.9661067275 -0.2570556963 0.5804843990 0.7283100535 -0.3162366411 0.180545604537 +1403637175638319104.0000000000 6.3666723096 1.9234542777 -0.2626369869 0.5739810873 0.7333504301 -0.3186773424 0.17660014024 +1403637175688318976.0000000000 6.4221896049 1.8780398497 -0.2666176227 0.5693521389 0.7369973586 -0.3201444078 0.173725627106 +1403637175738319104.0000000000 6.4787528818 1.8304115753 -0.2685347981 0.5663811104 0.7395267983 -0.3211273904 0.170850084951 +1403637175788318976.0000000000 6.5365180274 1.7801896548 -0.2683167027 0.5636045175 0.7421068854 -0.3198053790 0.171323781541 +1403637175838319104.0000000000 6.5956462253 1.7279805560 -0.2658763756 0.5621392836 0.7438385518 -0.3168101021 0.174169440282 +1403637175888318976.0000000000 6.6561979009 1.6737735616 -0.2615975710 0.5604024240 0.7457486793 -0.3122309377 0.179777284251 +1403637175938319104.0000000000 6.7176220925 1.6182192013 -0.2550215085 0.5605901475 0.7463568649 -0.3066823595 0.186107622404 +1403637175988318976.0000000000 6.7792558500 1.5613031788 -0.2453193872 0.5630769379 0.7450991340 -0.3022266159 0.190868318773 +1403637176038319104.0000000000 6.8405696931 1.5030515848 -0.2327584793 0.5679004199 0.7420341885 -0.2998416378 0.192274201332 +1403637176088318976.0000000000 6.9019740240 1.4434447163 -0.2186895875 0.5727788928 0.7390305176 -0.2969570463 0.193842066234 +1403637176138319104.0000000000 6.9628224951 1.3821767242 -0.2052818596 0.5763110804 0.7370329817 -0.2930438705 0.196909147808 +1403637176188318976.0000000000 7.0227210169 1.3192874278 -0.1926896214 0.5800701990 0.7348621969 -0.2901193186 0.198310102271 +1403637176238319104.0000000000 7.0819680422 1.2544337815 -0.1819065889 0.5823817294 0.7332402404 -0.2880103082 0.20059993378 +1403637176288318976.0000000000 7.1405608675 1.1876549381 -0.1728180703 0.5833179027 0.7319817004 -0.2881069477 0.20232993189 +1403637176338319104.0000000000 7.1980857847 1.1187645110 -0.1653422494 0.5837671486 0.7308914556 -0.2894842409 0.203008548466 +1403637176388318976.0000000000 7.2548064730 1.0478301512 -0.1594627023 0.5827152100 0.7310836395 -0.2897008278 0.205019819443 +1403637176438319104.0000000000 7.3105353754 0.9748570318 -0.1547903776 0.5801514914 0.7322516036 -0.2916316282 0.205384589272 +1403637176488318976.0000000000 7.3655899805 0.9000169963 -0.1515220020 0.5751938867 0.7345299207 -0.2930893493 0.209084723399 +1403637176538319104.0000000000 7.4194637423 0.8237166392 -0.1485255394 0.5708690719 0.7356708760 -0.2967034519 0.21181106342 +1403637176588318976.0000000000 7.4728003381 0.7465320547 -0.1459374165 0.5671058956 0.7357080094 -0.3027881872 0.213175847165 +1403637176638319104.0000000000 7.5253646620 0.6682405313 -0.1445794853 0.5623536794 0.7363109533 -0.3092374647 0.214421803127 +1403637176688318976.0000000000 7.5774169737 0.5891507630 -0.1443387333 0.5575365416 0.7370249798 -0.3151533556 0.215929494022 +1403637176738319104.0000000000 7.6283724015 0.5091909807 -0.1450726956 0.5529302619 0.7378296897 -0.3210439184 0.216347583675 +1403637176788318976.0000000000 7.6786143892 0.4286072827 -0.1465362547 0.5491090187 0.7383648724 -0.3254699426 0.217637123024 +1403637176838319104.0000000000 7.7281957059 0.3474601892 -0.1487639470 0.5451909818 0.7390826349 -0.3295315188 0.218935219393 +1403637176888318976.0000000000 7.7774811503 0.2658632446 -0.1522233692 0.5397812201 0.7413015545 -0.3334798892 0.218859323057 +1403637176938319104.0000000000 7.8263436283 0.1840384640 -0.1564471856 0.5346112475 0.7436209812 -0.3362902045 0.219379918549 +1403637176988318976.0000000000 7.8749330546 0.1022129498 -0.1619064273 0.5283394039 0.7470590045 -0.3384208336 0.219617069834 +1403637177038319104.0000000000 7.9234056196 0.0208603018 -0.1684510040 0.5210772281 0.7511987502 -0.3418916932 0.217460410833 +1403637177088318976.0000000000 7.9722351939 -0.0600716736 -0.1766664475 0.5107882575 0.7576262165 -0.3445648082 0.215343829789 +1403637177138319104.0000000000 8.0215980878 -0.1399437130 -0.1857187926 0.5014442596 0.7632204645 -0.3482579858 0.21157635103 +1403637177188318976.0000000000 8.0721618009 -0.2184492410 -0.1957569350 0.4933002944 0.7679282644 -0.3512857019 0.208660863689 +1403637177238319104.0000000000 8.1245216636 -0.2950294376 -0.2067787692 0.4865267745 0.7718508810 -0.3534180421 0.206479061238 +1403637177288318976.0000000000 8.1791100965 -0.3694368370 -0.2186004237 0.4826042946 0.7740175020 -0.3549682165 0.204908678966 +1403637177338319104.0000000000 8.2360719018 -0.4415066534 -0.2318436471 0.4786048165 0.7763678124 -0.3559335309 0.203719834941 +1403637177388318976.0000000000 8.2957447393 -0.5112545605 -0.2460765061 0.4758386158 0.7780006722 -0.3556318511 0.204495848912 +1403637177438319104.0000000000 8.3583011048 -0.5787441018 -0.2617988293 0.4724638133 0.7803215781 -0.3527356200 0.20845566031 +1403637177488318976.0000000000 8.4238368900 -0.6436955392 -0.2788758260 0.4681316939 0.7826558699 -0.3498592039 0.214245289045 +1403637177538319104.0000000000 8.4922465987 -0.7055424545 -0.2959733952 0.4655744337 0.7833466315 -0.3478996663 0.220395834271 +1403637177588318976.0000000000 8.5632347129 -0.7641611488 -0.3121980332 0.4624399555 0.7845272493 -0.3436199923 0.229328549177 +1403637177638319104.0000000000 8.6359117787 -0.8190072884 -0.3263861390 0.4617605946 0.7843827709 -0.3388700311 0.238092259506 +1403637177688318976.0000000000 8.7099046398 -0.8689636680 -0.3373327967 0.4626276532 0.7831773407 -0.3346198269 0.246248815352 +1403637177738319104.0000000000 8.7848568898 -0.9142149849 -0.3456040274 0.4637580714 0.7817915922 -0.3299991764 0.254619129548 +1403637177788318976.0000000000 8.8602791700 -0.9544588970 -0.3512960814 0.4673556539 0.7781241864 -0.3293478614 0.260060434401 +1403637177838319104.0000000000 8.9346996116 -0.9911693725 -0.3565034627 0.4689232524 0.7748612302 -0.3341961667 0.260794899316 +1403637177888318976.0000000000 9.0088470576 -1.0244692949 -0.3622020488 0.4696100913 0.7711030448 -0.3403422024 0.262742538976 +1403637177938319104.0000000000 9.0824993895 -1.0548948587 -0.3691049073 0.4689457663 0.7671376143 -0.3471819378 0.266560407891 +1403637177988318976.0000000000 9.1552030885 -1.0828903097 -0.3778421453 0.4653434244 0.7642793930 -0.3526600797 0.273794402737 +1403637178038319104.0000000000 9.2274766046 -1.1083622712 -0.3878201726 0.4606561172 0.7613308519 -0.3556513694 0.285803042495 +1403637178088318976.0000000000 9.2978925144 -1.1306888490 -0.3987934198 0.4548720776 0.7585060809 -0.3568588581 0.300685340078 +1403637178138319104.0000000000 9.3669454811 -1.1493258353 -0.4108053814 0.4498841392 0.7551816888 -0.3610592113 0.311353696207 +1403637178188318976.0000000000 9.4347310104 -1.1638147263 -0.4220781432 0.4446265379 0.7524171651 -0.3650068111 0.320851491139 +1403637178238319104.0000000000 9.5012229227 -1.1738900288 -0.4309470177 0.4420459925 0.7487450979 -0.3666356892 0.330990015517 +1403637178288318976.0000000000 9.5662255577 -1.1790352216 -0.4379804190 0.4410656579 0.7449748760 -0.3667773127 0.340511266306 +1403637178338319104.0000000000 9.6295074214 -1.1791102987 -0.4434095920 0.4412762112 0.7408249241 -0.3654175406 0.350604846185 +1403637178388318976.0000000000 9.6913712932 -1.1737969526 -0.4478088753 0.4388310287 0.7389226134 -0.3637755687 0.359288234119 +1403637178438319104.0000000000 9.7498969605 -1.1632505885 -0.4494378106 0.4385629948 0.7363020529 -0.3626180609 0.366100981092 +1403637178488318976.0000000000 9.8047522037 -1.1477152291 -0.4494274480 0.4370138956 0.7350587945 -0.3635524368 0.369509200772 +1403637178538319104.0000000000 9.8562169782 -1.1267433987 -0.4474717107 0.4375644469 0.7332708140 -0.3657398103 0.370250805918 +1403637178588318976.0000000000 9.9045868465 -1.1008084167 -0.4448846114 0.4382141289 0.7317959668 -0.3678088056 0.370350810372 +1403637178638319104.0000000000 9.9496253955 -1.0696601875 -0.4423415359 0.4431531555 0.7286037810 -0.3724995418 0.366054507551 +1403637178688318976.0000000000 9.9920215601 -1.0341553189 -0.4406143553 0.4501125249 0.7246750949 -0.3771122046 0.360598262411 +1403637178738319104.0000000000 10.0321174726 -0.9953324275 -0.4394409268 0.4593191334 0.7189745946 -0.3813989543 0.355859949636 +1403637178788318976.0000000000 10.0701645578 -0.9535723090 -0.4394923603 0.4686604573 0.7133329307 -0.3847697741 0.351376901101 +1403637178838319104.0000000000 10.1062158892 -0.9098492970 -0.4409295519 0.4768592433 0.7081552595 -0.3873491925 0.347968380168 +1403637178888318976.0000000000 10.1399247290 -0.8643246661 -0.4437125453 0.4845917771 0.7034419554 -0.3917613946 0.341852650476 +1403637178938319104.0000000000 10.1714003450 -0.8179204496 -0.4480790686 0.4910629790 0.6995173240 -0.3951422027 0.336742191625 +1403637178988318976.0000000000 10.2010089016 -0.7710108040 -0.4535532429 0.4963885183 0.6962334480 -0.3967751706 0.333806663719 +1403637179038319104.0000000000 10.2280475945 -0.7240142936 -0.4601836824 0.5012286337 0.6933748933 -0.3979644579 0.331097273158 +1403637179088318976.0000000000 10.3087638808 -0.6681947060 -0.4690911118 0.5017025067 0.6935222818 -0.3990119886 0.328802178208 +1403637179138319104.0000000000 10.3355296826 -0.6210841720 -0.4801972920 0.4989309344 0.6960220590 -0.4003881691 0.326052955917 +1403637179188318976.0000000000 10.3607332818 -0.5736584589 -0.4914433853 0.4975494930 0.6975977633 -0.4010859834 0.323931931984 +1403637179238319104.0000000000 10.3833413819 -0.5262226440 -0.5021165861 0.4937474633 0.7010292137 -0.4005296248 0.323028642096 +1403637179288318976.0000000000 10.4045047679 -0.4784982123 -0.5084567323 0.4912106777 0.7034664050 -0.3995940009 0.322756443138 +1403637179338319104.0000000000 10.4233772439 -0.4309517251 -0.5092628125 0.4891176562 0.7051588180 -0.3981252327 0.324054407373 +1403637179388318976.0000000000 10.4401278541 -0.3827847813 -0.5047961344 0.4872910513 0.7069400735 -0.3971776236 0.32408810383 +1403637179438319104.0000000000 10.4550966015 -0.3339111316 -0.4956695003 0.4862709168 0.7081336020 -0.3962473729 0.324153384517 +1403637179488318976.0000000000 10.4685280344 -0.2842267413 -0.4849944510 0.4860944470 0.7085303910 -0.3966062106 0.323110487763 +1403637179538319104.0000000000 10.4809449952 -0.2339349111 -0.4755264740 0.4865918279 0.7084590503 -0.3964907964 0.322659596878 +1403637179588318976.0000000000 10.4922393270 -0.1834680444 -0.4677225131 0.4871093177 0.7078783413 -0.3960842567 0.323651090135 +1403637179638319104.0000000000 10.5019245410 -0.1325202759 -0.4629247996 0.4878722831 0.7073405021 -0.3964167461 0.323270494934 +1403637179688318976.0000000000 10.5110794389 -0.0792757180 -0.4586065575 0.4883645621 0.7065945136 -0.3957519150 0.324968721033 +1403637179738319104.0000000000 10.5193050995 -0.0270592870 -0.4635859572 0.4875128888 0.7065185400 -0.3943951306 0.328047583232 +1403637179788318976.0000000000 10.5265945347 0.0252073976 -0.4761136307 0.4844763736 0.7077368928 -0.3915113296 0.333331685997 +1403637179838319104.0000000000 10.5330437828 0.0777487484 -0.4958238558 0.4815335596 0.7086836992 -0.3864903329 0.341347430242 +1403637179888318976.0000000000 10.5378015705 0.1312487597 -0.5207045451 0.4793293098 0.7090704434 -0.3811717228 0.349529164489 +1403637179938319104.0000000000 10.5395526076 0.1860847033 -0.5482305359 0.4785221610 0.7086780304 -0.3771809702 0.355705645687 +1403637179988318976.0000000000 10.5379562236 0.2427571658 -0.5776503845 0.4785344452 0.7084780065 -0.3759718838 0.357363738563 +1403637180038319104.0000000000 10.5329244263 0.3014951416 -0.6076796812 0.4799057239 0.7077507979 -0.3792728204 0.353456407402 +1403637180088318976.0000000000 10.5253085676 0.3621738959 -0.6368167225 0.4815406106 0.7073305132 -0.3831372107 0.347862132411 +1403637180138319104.0000000000 10.5146386847 0.4240803016 -0.6643434037 0.4847054708 0.7059924334 -0.3878214601 0.340924926612 +1403637180188318976.0000000000 10.5008210563 0.4865671437 -0.6908125399 0.4870227160 0.7052609355 -0.3927895153 0.333365090518 +1403637180238319104.0000000000 10.4905016959 0.5539982619 -0.7055184744 0.4892631848 0.7044350037 -0.3962463248 0.327691488545 +1403637180288318976.0000000000 10.4742123365 0.6182248068 -0.7256676524 0.4906585545 0.7042288240 -0.3996709034 0.321837094457 +1403637180338319104.0000000000 10.4569281326 0.6827314280 -0.7433516250 0.4916463960 0.7040784058 -0.4017030292 0.31810705135 +1403637180388318976.0000000000 10.4384380129 0.7471005191 -0.7601986481 0.4888386718 0.7065319687 -0.4056251228 0.31195767321 +1403637180438319104.0000000000 10.4191663416 0.8111933275 -0.7760366192 0.4832854277 0.7106360062 -0.4089635128 0.306888428137 +1403637180488318976.0000000000 10.3992182020 0.8750527702 -0.7904189621 0.4761505085 0.7154992827 -0.4130730804 0.301184494876 +1403637180538319104.0000000000 10.3797026118 0.9391066405 -0.8023561068 0.4707260364 0.7190376263 -0.4157488493 0.29758156018 +1403637180588318976.0000000000 10.3620840539 1.0041315519 -0.8111502811 0.4670392612 0.7212470772 -0.4161325283 0.297507480699 +1403637180638319104.0000000000 10.3466079795 1.0700190380 -0.8168484424 0.4661933337 0.7214881457 -0.4108575808 0.305474515322 +1403637180688318976.0000000000 10.3316138085 1.1372665017 -0.8201734991 0.4693565610 0.7189826515 -0.4058832278 0.313092910881 +1403637180738319104.0000000000 10.3161073857 1.2054621804 -0.8214095827 0.4728407929 0.7160561319 -0.4041690184 0.316753224263 +1403637180788318976.0000000000 10.3004777590 1.2742387482 -0.8203779679 0.4756031757 0.7132527517 -0.4015422681 0.322235842724 +1403637180838319104.0000000000 10.2845635511 1.3439860602 -0.8182552708 0.4758619851 0.7120229887 -0.3993543815 0.327253285391 +1403637180888318976.0000000000 10.2682573415 1.4142759059 -0.8144943177 0.4745784107 0.7114053484 -0.3949351120 0.335714193575 +1403637180938319104.0000000000 10.2504008876 1.4860715839 -0.8095626620 0.4723772709 0.7114532582 -0.3926503183 0.341349824609 +1403637180988318976.0000000000 10.2312048291 1.5594691546 -0.8030121318 0.4699945046 0.7114168659 -0.3899940965 0.347700752364 +1403637181038319104.0000000000 10.2101326950 1.6345215658 -0.7945866583 0.4663572149 0.7120653856 -0.3876384558 0.35385062147 +1403637181088318976.0000000000 10.1870294882 1.7124122497 -0.7834447778 0.4661786850 0.7111042312 -0.3887919795 0.354752029945 +1403637181138319104.0000000000 10.1614753612 1.7926036424 -0.7701424462 0.4686568327 0.7087685297 -0.3929471597 0.351568590919 +1403637181188318976.0000000000 10.1336803466 1.8746190001 -0.7548368519 0.4727924309 0.7056697693 -0.3988821861 0.345529297722 +1403637181238319104.0000000000 10.1043788332 1.9580130249 -0.7370192701 0.4783582306 0.7013956662 -0.4041824027 0.340373483133 +1403637181288318976.0000000000 10.0738418742 2.0419926806 -0.7181227137 0.4839085952 0.6970466469 -0.4087261385 0.336008016619 +1403637181338319104.0000000000 10.0429434523 2.1261376048 -0.6974927360 0.4883689364 0.6931911064 -0.4104751994 0.335398245037 +1403637181388318976.0000000000 10.0107874220 2.2098404661 -0.6754739012 0.4912401769 0.6902835116 -0.4100855138 0.337670895514 +1403637181438319104.0000000000 9.9770587797 2.2931105134 -0.6521521877 0.4920981337 0.6889107578 -0.4092950325 0.340174912385 +1403637181488318976.0000000000 9.9413180862 2.3759055777 -0.6273979209 0.4898871738 0.6896907131 -0.4095799207 0.341440427697 +1403637181538319104.0000000000 9.9036415111 2.4584872675 -0.6014094805 0.4866530609 0.6911028500 -0.4108187289 0.341721554716 +1403637181588318976.0000000000 9.8640324916 2.5412238845 -0.5734694822 0.4841826176 0.6919938536 -0.4131742418 0.340585885272 +1403637181638319104.0000000000 9.8226675451 2.6239287693 -0.5438139385 0.4811573183 0.6930657449 -0.4153437819 0.340054482726 +1403637181688318976.0000000000 9.7795151680 2.7067020239 -0.5121693951 0.4800716294 0.6928720168 -0.4174823416 0.339364248836 +1403637181738319104.0000000000 9.7332972855 2.7787347480 -0.4848724291 0.4802461678 0.6919048161 -0.4210065046 0.336726694599 +1403637181788318976.0000000000 9.6898480060 2.8616715273 -0.4542182063 0.4823782980 0.6894654307 -0.4237459938 0.335243091273 +1403637181838319104.0000000000 9.6462712362 2.9445780598 -0.4249935071 0.4848429492 0.6871177209 -0.4257927050 0.333911851404 +1403637181888318976.0000000000 9.6021906948 3.0269782784 -0.3974434182 0.4862540141 0.6855590888 -0.4273006055 0.33313655176 +1403637181938319104.0000000000 9.5576854676 3.1089541494 -0.3717640484 0.4865877382 0.6849847160 -0.4285867225 0.332177261642 +1403637181988318976.0000000000 9.5129672866 3.1905344715 -0.3473759956 0.4875191940 0.6841248860 -0.4288532561 0.332239462673 +1403637182038319104.0000000000 9.4675736975 3.2716608051 -0.3238681076 0.4890879197 0.6830170423 -0.4283698604 0.332836280161 +1403637182088318976.0000000000 9.4216753899 3.3523297786 -0.3007668853 0.4928200098 0.6804626154 -0.4267297106 0.334665237278 +1403637182138319104.0000000000 9.3746920822 3.4322964559 -0.2785340202 0.4963241252 0.6783791269 -0.4263784497 0.334163942822 +1403637182188318976.0000000000 9.3266848652 3.5113398229 -0.2570557944 0.5016464102 0.6753070832 -0.4268739123 0.331797958818 +1403637182238319104.0000000000 9.2775246877 3.5891364713 -0.2367141862 0.5072518492 0.6721613934 -0.4272729894 0.329138899593 +1403637182288318976.0000000000 9.2273994533 3.6653673761 -0.2175278969 0.5124856494 0.6693684611 -0.4280812270 0.325654395885 +1403637182338319104.0000000000 9.1763830282 3.7396070695 -0.1993084759 0.5176680393 0.6665910193 -0.4281515966 0.323051736297 +1403637182388318976.0000000000 9.1242264237 3.8113195847 -0.1823059500 0.5212090450 0.6647305001 -0.4272121843 0.322434866706 +1403637182438319104.0000000000 9.0708529522 3.8810523844 -0.1652120565 0.5268016574 0.6616495914 -0.4265470573 0.320558013175 +1403637182488318976.0000000000 9.0166629655 3.9475322688 -0.1476283163 0.5292590638 0.6601735140 -0.4217656142 0.32583667906 +1403637182538319104.0000000000 8.9607844458 4.0115456730 -0.1291823913 0.5299297867 0.6603137191 -0.4180855969 0.329187860184 +1403637182588318976.0000000000 8.9030780973 4.0729601502 -0.1086267693 0.5295710682 0.6608493057 -0.4145528238 0.333134560105 +1403637182638319104.0000000000 8.8426933440 4.1320320802 -0.0867206441 0.5286312687 0.6619017713 -0.4126923841 0.334843281264 +1403637182688318976.0000000000 8.7796493621 4.1887265577 -0.0628670835 0.5282678046 0.6626274604 -0.4128390479 0.333799185011 +1403637182738319104.0000000000 8.7140049636 4.2430940106 -0.0380414314 0.5297817355 0.6619192519 -0.4132147507 0.332336856805 +1403637182788318976.0000000000 8.6462922651 4.2953150793 -0.0144759171 0.5305693767 0.6614582301 -0.4154492168 0.329197652724 +1403637182838319104.0000000000 8.5765525518 4.3450427400 0.0080671176 0.5320566811 0.6602422822 -0.4180327249 0.32595161882 +1403637182888318976.0000000000 8.5049746007 4.3921354125 0.0285931391 0.5332946943 0.6590661983 -0.4200078096 0.323762189371 +1403637182938319104.0000000000 8.4314248766 4.4363007305 0.0478165589 0.5356312587 0.6569709980 -0.4224848190 0.320928091998 +1403637182988318976.0000000000 8.3560188385 4.4778928288 0.0642885584 0.5379599505 0.6549286539 -0.4254650756 0.317249144078 +1403637183038319104.0000000000 8.2788805388 4.5167394512 0.0767625992 0.5405532370 0.6526347571 -0.4289266804 0.312876932144 +1403637183088318976.0000000000 8.2003776626 4.5524360438 0.0848740072 0.5431865760 0.6503077825 -0.4315685232 0.309510486741 +1403637183138319104.0000000000 8.1212648432 4.5853572882 0.0889355057 0.5452020843 0.6486742074 -0.4344557081 0.305327197417 +1403637183188318976.0000000000 8.0409310676 4.6146534551 0.0883716707 0.5462385071 0.6477498283 -0.4362557969 0.302860583393 +1403637183238319104.0000000000 7.9594319182 4.6402625121 0.0846806426 0.5469827331 0.6471585695 -0.4381236699 0.300072200436 +1403637183288318976.0000000000 7.8809896832 4.6640366011 0.0791530825 0.5472629064 0.6468799491 -0.4395829161 0.298020976711 +1403637183338319104.0000000000 7.8011797355 4.6837711723 0.0724608733 0.5475229454 0.6465308746 -0.4414690038 0.295502235542 +1403637183388318976.0000000000 7.7207131779 4.6997974333 0.0646167409 0.5478462596 0.6461420323 -0.4431801362 0.293183077524 +1403637183438319104.0000000000 7.6459542761 4.7150898289 0.0551740797 0.5481354442 0.6456087158 -0.4436490273 0.293108276028 +1403637183488318976.0000000000 7.5685107974 4.7252213471 0.0453550302 0.5484514038 0.6451031390 -0.4439149113 0.293227811272 +1403637183538319104.0000000000 7.4907716074 4.7315856749 0.0345236611 0.5486499528 0.6448462799 -0.4455810024 0.290884985685 +1403637183588318976.0000000000 7.4127397422 4.7336911895 0.0229325908 0.5493647683 0.6441821185 -0.4465716698 0.289484875867 +1403637183638319104.0000000000 7.3342513793 4.7315785413 0.0105471306 0.5504305398 0.6431531480 -0.4480273089 0.287492225212 +1403637183688318976.0000000000 7.2552298396 4.7252244924 -0.0026692045 0.5514537903 0.6420726643 -0.4489232435 0.286547260091 +1403637183738319104.0000000000 7.1746892198 4.7140506503 -0.0167219073 0.5511365438 0.6421355795 -0.4516732983 0.282668780116 +1403637183788318976.0000000000 7.0931584592 4.6979978774 -0.0303629571 0.5499885575 0.6430806346 -0.4555291932 0.276501425224 +1403637183838319104.0000000000 7.0127533890 4.6774806494 -0.0428828584 0.5482008691 0.6443308622 -0.4592422601 0.270942971302 +1403637183888318976.0000000000 6.9341378518 4.6525967856 -0.0530622510 0.5468479156 0.6451199056 -0.4630414210 0.265274022612 +1403637183938319104.0000000000 6.8562047732 4.6224489061 -0.0616368060 0.5457637207 0.6454788287 -0.4666544092 0.260255077301 +1403637183988318976.0000000000 6.7793578848 4.5870624092 -0.0687280484 0.5440596933 0.6463015474 -0.4700597474 0.255611411887 +1403637184038319104.0000000000 6.7039398905 4.5464260650 -0.0727937836 0.5428690672 0.6467108667 -0.4730826419 0.251497603843 +1403637184088318976.0000000000 6.6304603075 4.5004333528 -0.0744177324 0.5416044169 0.6470634574 -0.4748246677 0.250030143396 +1403637184138319104.0000000000 6.5575485417 4.4480726223 -0.0745646724 0.5395408301 0.6482976968 -0.4749761312 0.251004907816 +1403637184188318976.0000000000 6.4872268959 4.3908123005 -0.0723607920 0.5367002681 0.6503748070 -0.4744906842 0.252634168823 +1403637184238319104.0000000000 6.4192131148 4.3288543222 -0.0697872223 0.5334338837 0.6528862770 -0.4714482647 0.25869738051 +1403637184288318976.0000000000 6.3521362880 4.2630209562 -0.0708604818 0.5275884328 0.6577193230 -0.4667907827 0.266762259184 +1403637184338319104.0000000000 6.2863862046 4.1943635801 -0.0756785491 0.5206358047 0.6631948159 -0.4618635134 0.27530544847 +1403637184388318976.0000000000 6.2214088971 4.1233805245 -0.0845651290 0.5130140503 0.6690513999 -0.4578082328 0.282131938052 +1403637184438319104.0000000000 6.1567135733 4.0503956654 -0.0956321203 0.5058935164 0.6745243208 -0.4546598705 0.287007130158 +1403637184488318976.0000000000 6.0929159148 3.9764373153 -0.1081509590 0.4990807714 0.6798035161 -0.4533731125 0.288510630679 +1403637184538319104.0000000000 6.0298242309 3.9012039578 -0.1222384849 0.4928158549 0.6845860910 -0.4527706377 0.288917231726 +1403637184588318976.0000000000 5.9678347252 3.8255623310 -0.1374429117 0.4861420415 0.6895864709 -0.4531300598 0.287766508653 +1403637184638319104.0000000000 5.9074641452 3.7498415704 -0.1530797165 0.4807349538 0.6936630497 -0.4534331191 0.286572650905 +1403637184688318976.0000000000 5.8486579528 3.6739492566 -0.1688750555 0.4761154024 0.6971102975 -0.4541542793 0.284772272645 +1403637184738319104.0000000000 5.7919399697 3.5981021880 -0.1840853133 0.4721509900 0.7000982992 -0.4554895250 0.281895559867 +1403637184788318976.0000000000 5.7382306342 3.5227106091 -0.1984184112 0.4684894671 0.7027274419 -0.4561124055 0.280451840927 +1403637184838319104.0000000000 5.6882158899 3.4486366335 -0.2107697476 0.4656723410 0.7048570080 -0.4564153163 0.279304364723 +1403637184888318976.0000000000 5.6404570539 3.3748876787 -0.2197356394 0.4638975097 0.7059895115 -0.4570497277 0.278358503524 +1403637184938319104.0000000000 5.5965488064 3.3021121843 -0.2268188441 0.4612628310 0.7080906047 -0.4558541665 0.279358685268 +1403637184988318976.0000000000 5.5563583891 3.2310864471 -0.2310600031 0.4606302107 0.7084595304 -0.4574599191 0.276830860248 +1403637185038319104.0000000000 5.5195057829 3.1606191547 -0.2341155419 0.4574830302 0.7107118150 -0.4565292842 0.277811097381 +1403637185088318976.0000000000 5.4860090982 3.0914259324 -0.2350059641 0.4563973248 0.7114049333 -0.4569927356 0.277059817311 +1403637185138319104.0000000000 5.4558384464 3.0232670708 -0.2325909354 0.4558122267 0.7114058579 -0.4582133398 0.276002635138 +1403637185188318976.0000000000 5.4286078485 2.9557829582 -0.2280490344 0.4550775366 0.7117895506 -0.4581170392 0.276385328405 +1403637185238319104.0000000000 5.4039909715 2.8891071911 -0.2227566943 0.4531266803 0.7129738778 -0.4582478496 0.276321134698 +1403637185288318976.0000000000 5.3838668252 2.8241899129 -0.2158223816 0.4501773895 0.7147122044 -0.4587079567 0.275887283628 +1403637185338319104.0000000000 5.3666544266 2.7601913092 -0.2066759903 0.4461747126 0.7173089241 -0.4580865852 0.276681610732 +1403637185388318976.0000000000 5.3522476351 2.6971680773 -0.1952264451 0.4411706063 0.7204821599 -0.4568774576 0.27845456008 +1403637185438319104.0000000000 5.3398419299 2.6353828137 -0.1816726165 0.4366432265 0.7232287065 -0.4562925329 0.279428086019 +1403637185488318976.0000000000 5.3310827340 2.5757447700 -0.1657363453 0.4339088329 0.7249002128 -0.4551002750 0.281294411351 +1403637185538319104.0000000000 5.3254022979 2.5180146746 -0.1480188195 0.4335732299 0.7248740108 -0.4541340158 0.283432917117 +1403637185588318976.0000000000 5.3245535559 2.4635625298 -0.1281693685 0.4365377612 0.7226591165 -0.4534260987 0.285663013843 +1403637185638319104.0000000000 5.3263332964 2.4110977659 -0.1070712468 0.4428619652 0.7185008729 -0.4518190673 0.288945160563 +1403637185688318976.0000000000 5.3311118430 2.3604259731 -0.0857564781 0.4503890856 0.7133187893 -0.4494823814 0.293754259821 +1403637185738319104.0000000000 5.3378495465 2.3109564570 -0.0656501605 0.4568930544 0.7088631502 -0.4470183866 0.298221952833 +1403637185788318976.0000000000 5.3509184571 2.2648031444 -0.0485089947 0.4608228703 0.7060524857 -0.4438375939 0.303546306146 +1403637185838319104.0000000000 5.3621435762 2.2180581629 -0.0332030615 0.4619962577 0.7050246256 -0.4413714846 0.307718942861 +1403637185888318976.0000000000 5.3744494972 2.1726709581 -0.0191033982 0.4645062919 0.7033202005 -0.4390079527 0.311201892316 +1403637185938319104.0000000000 5.3874482256 2.1287264234 -0.0063805180 0.4663641985 0.7017581160 -0.4380088091 0.313350066445 +1403637185988318976.0000000000 5.4004048270 2.0858750368 0.0054067446 0.4696684127 0.6995340647 -0.4369164798 0.314908977478 +1403637186038319104.0000000000 5.4135112116 2.0440362438 0.0161881672 0.4731914425 0.6970884510 -0.4360560028 0.316247865647 +1403637186088318976.0000000000 5.4264953349 2.0029657494 0.0272482227 0.4755851532 0.6954039055 -0.4350377365 0.317764595322 +1403637186138319104.0000000000 5.4390152764 1.9626378311 0.0395392422 0.4770385871 0.6944828501 -0.4347467309 0.317998486168 +1403637186188318976.0000000000 5.4505213425 1.9226454968 0.0535823750 0.4779583673 0.6939114627 -0.4345511629 0.318131997651 +1403637186238319104.0000000000 5.4622071898 1.8834004598 0.0686379867 0.4772971759 0.6944182960 -0.4345898469 0.317965880299 +1403637186288318976.0000000000 5.4754735603 1.8456549435 0.0859920487 0.4767027304 0.6949820178 -0.4340774994 0.318325660525 +1403637186338319104.0000000000 5.4889464085 1.8091067820 0.1067401672 0.4788055776 0.6934992162 -0.4331838649 0.319618202032 +1403637186388318976.0000000000 5.5014541467 1.7733044620 0.1291570859 0.4804385073 0.6921594857 -0.4335857215 0.319527008492 +1403637186438319104.0000000000 5.5134716739 1.7381720705 0.1537121403 0.4826423892 0.6905456689 -0.4346980418 0.318183305489 +1403637186488318976.0000000000 5.5253002558 1.7036715283 0.1798297644 0.4846993327 0.6889168200 -0.4364143491 0.316232015993 +1403637186538319104.0000000000 5.5369033205 1.6696886413 0.2072924239 0.4877996129 0.6865392484 -0.4384329343 0.313834287851 +1403637186588318976.0000000000 5.5484308053 1.6356248511 0.2347007269 0.4891124264 0.6853043496 -0.4394009627 0.313135396641 +1403637186638319104.0000000000 5.5596226853 1.6014207675 0.2608010584 0.4894624878 0.6847281478 -0.4404918583 0.312315160348 +1403637186688318976.0000000000 5.5705558365 1.5670643771 0.2851590958 0.4891924994 0.6845019670 -0.4422222976 0.310784805276 +1403637186738319104.0000000000 5.5809594279 1.5325044430 0.3074338123 0.4880150440 0.6849733202 -0.4453130762 0.307163037505 +1403637186788318976.0000000000 5.5910328817 1.4976338116 0.3275971060 0.4876425700 0.6848754611 -0.4493623236 0.302032827547 +1403637186838319104.0000000000 5.6015148946 1.4628296525 0.3457777133 0.4884493583 0.6840142490 -0.4543858150 0.295085178733 +1403637186888318976.0000000000 5.6125227406 1.4273558670 0.3618981825 0.4897150127 0.6827474471 -0.4591800069 0.288424775312 +1403637186938319104.0000000000 5.6245136595 1.3911189765 0.3762674982 0.4923847433 0.6803578114 -0.4638983275 0.281902207838 +1403637186988318976.0000000000 5.6377280569 1.3536186630 0.3883484866 0.4942174350 0.6786631211 -0.4674697716 0.276834801943 +1403637187038319104.0000000000 5.6526235129 1.3145959435 0.3989684444 0.4974075804 0.6760439429 -0.4694601104 0.274148665944 +1403637187088318976.0000000000 5.6689730846 1.2737458094 0.4075270463 0.5000029202 0.6740664986 -0.4695479159 0.274146292963 +1403637187138319104.0000000000 5.6866143676 1.2309336873 0.4139974851 0.5013551719 0.6731831428 -0.4679143664 0.276628982049 +1403637187188318976.0000000000 5.7054893252 1.1860747799 0.4182924619 0.5003965365 0.6731830172 -0.4664226252 0.280852036395 +1403637187238319104.0000000000 5.7254494875 1.1390310433 0.4206855717 0.4961634517 0.6745830115 -0.4666019147 0.284679193291 +1403637187288318976.0000000000 5.7463492532 1.0904551740 0.4206851463 0.4878970859 0.6783223148 -0.4676675504 0.288309439838 +1403637187338319104.0000000000 5.7686066238 1.0411667919 0.4199040548 0.4798348286 0.6818729560 -0.4687817462 0.291635874994 +1403637187388318976.0000000000 5.7920498046 0.9913719906 0.4181072150 0.4715860908 0.6859342703 -0.4685891188 0.295846199092 +1403637187438319104.0000000000 5.8170070560 0.9416814323 0.4161835756 0.4648732387 0.6888142763 -0.4689381191 0.299206960312 +1403637187488318976.0000000000 5.8431363547 0.8924639049 0.4141970319 0.4599989253 0.6905225312 -0.4700096343 0.301115536392 +1403637187538319104.0000000000 5.8701596299 0.8436122132 0.4116587412 0.4557483069 0.6920352219 -0.4713448839 0.302017768978 +1403637187588318976.0000000000 5.8986472599 0.7954194519 0.4087111612 0.4531867768 0.6924738041 -0.4727124430 0.302728793178 +1403637187638319104.0000000000 5.9290481326 0.7481829596 0.4052802594 0.4516504273 0.6924006236 -0.4746845011 0.302105763449 +1403637187688318976.0000000000 5.9607622841 0.7014723537 0.4016005522 0.4514346800 0.6915743087 -0.4765922166 0.301316385531 +1403637187738319104.0000000000 5.9939975898 0.6551753192 0.3968877175 0.4502435327 0.6915273750 -0.4784927873 0.300192110772 +1403637187788318976.0000000000 6.0292356791 0.6093922223 0.3918733607 0.4495481608 0.6913535677 -0.4794518013 0.300104424918 +1403637187838319104.0000000000 6.0662381747 0.5641635874 0.3860364453 0.4480995630 0.6918336350 -0.4813449211 0.298127606979 +1403637187888318976.0000000000 6.1056757122 0.5194844493 0.3797298551 0.4463807906 0.6926861159 -0.4812920674 0.298811111649 +1403637187938319104.0000000000 6.1474978940 0.4756006694 0.3729506536 0.4445147668 0.6937328581 -0.4801560169 0.30098429046 +1403637187988318976.0000000000 6.1914933141 0.4327098782 0.3660638024 0.4446262282 0.6935820921 -0.4788955535 0.303167359009 +1403637188038319104.0000000000 6.2380155197 0.3906692483 0.3585338313 0.4444212134 0.6936610600 -0.4768417429 0.306506233432 +1403637188088318976.0000000000 6.2866039296 0.3495664554 0.3504361498 0.4444528881 0.6935765776 -0.4749143847 0.309627983896 +1403637188138319104.0000000000 6.3373908336 0.3094784536 0.3419072813 0.4454989609 0.6929556913 -0.4727396110 0.312826383009 +1403637188188318976.0000000000 6.3907056926 0.2702410915 0.3326298670 0.4460066961 0.6926295104 -0.4681833470 0.319604039276 +1403637188238319104.0000000000 6.4454522758 0.2323634154 0.3229340563 0.4475117261 0.6915043234 -0.4626354230 0.327907747895 +1403637188288318976.0000000000 6.5010104604 0.1963119680 0.3125400663 0.4499024593 0.6898130299 -0.4588022549 0.333535982811 +1403637188338319104.0000000000 6.5572271830 0.1620520296 0.3009765637 0.4521062580 0.6880236946 -0.4575805941 0.335921608456 +1403637188388318976.0000000000 6.6136248166 0.1292166112 0.2892338404 0.4567554897 0.6846957995 -0.4565959703 0.337766494285 +1403637188438319104.0000000000 6.6693930736 0.0974940016 0.2768268190 0.4609641670 0.6816406595 -0.4563771305 0.338523208817 +1403637188488318976.0000000000 6.7245129738 0.0664847501 0.2634222352 0.4642107776 0.6786385390 -0.4566135289 0.339797252226 +1403637188538319104.0000000000 6.7783390364 0.0362424607 0.2494612754 0.4675266283 0.6744675398 -0.4587702099 0.340649796873 +1403637188588318976.0000000000 6.8314380909 0.0067380925 0.2343077708 0.4693832979 0.6704254419 -0.4632159815 0.340058819959 +1403637188638319104.0000000000 6.8822509760 -0.0223314412 0.2187246035 0.4709293798 0.6656146154 -0.4680097174 0.340807287756 +1403637188688318976.0000000000 6.9319307775 -0.0512376479 0.2024032288 0.4730800287 0.6594749382 -0.4756172490 0.339229015143 +1403637188738319104.0000000000 6.9808033325 -0.0802063363 0.1850443307 0.4749955268 0.6524392291 -0.4840022434 0.338295921018 +1403637188788318976.0000000000 7.0287321838 -0.1097750513 0.1667232349 0.4763779437 0.6451786836 -0.4937648941 0.336161791751 +1403637188838319104.0000000000 7.0754790203 -0.1406681627 0.1475330522 0.4758216200 0.6389510732 -0.5027056463 0.335592528522 +1403637188888318976.0000000000 7.1220310776 -0.1727857933 0.1287182618 0.4740645570 0.6340884141 -0.5098685304 0.336494815241 +1403637188938319104.0000000000 7.1681962077 -0.2062720531 0.1106416744 0.4714296163 0.6308209489 -0.5155190676 0.337726425344 +1403637188988318976.0000000000 7.2133288241 -0.2416500692 0.0932473589 0.4659120275 0.6303354861 -0.5192109029 0.340621778472 +1403637189038319104.0000000000 7.2586960428 -0.2784066579 0.0778270047 0.4585131171 0.6320524486 -0.5207381529 0.345119109615 +1403637189088318976.0000000000 7.3038031614 -0.3159754702 0.0649710193 0.4511128418 0.6342168118 -0.5226801187 0.347953636388 +1403637189138319104.0000000000 7.3497677072 -0.3537269729 0.0523476306 0.4423994885 0.6378484772 -0.5253474093 0.348485454822 +1403637189188318976.0000000000 7.3960963176 -0.3913792615 0.0402820082 0.4365905170 0.6398336782 -0.5284436243 0.347489453954 +1403637189238319104.0000000000 7.4433544537 -0.4290666322 0.0261529960 0.4322597936 0.6410137877 -0.5319648142 0.345349433567 +1403637189288318976.0000000000 7.4917956790 -0.4663858222 0.0098956279 0.4319942176 0.6400123981 -0.5350459156 0.342769593827 +1403637189338319104.0000000000 7.5411283754 -0.5037955391 -0.0098283161 0.4353636916 0.6369361540 -0.5368417715 0.341425986268 +1403637189388318976.0000000000 7.5915975939 -0.5415361902 -0.0315479860 0.4403025260 0.6332205796 -0.5358891144 0.34349416322 +1403637189438319104.0000000000 7.6431930489 -0.5797740820 -0.0532950347 0.4459630847 0.6294251167 -0.5332109520 0.347314022352 +1403637189488318976.0000000000 7.6956771320 -0.6184393984 -0.0739237804 0.4501315627 0.6268274562 -0.5303819616 0.350947134556 +1403637189538319104.0000000000 7.7484133500 -0.6579537046 -0.0933000832 0.4518098219 0.6261987519 -0.5269744873 0.355022390459 +1403637189588318976.0000000000 7.8021709621 -0.6978300071 -0.1109393978 0.4524859399 0.6265916334 -0.5232610535 0.358939088156 +1403637189638319104.0000000000 7.8557161168 -0.7382408208 -0.1259533534 0.4520128188 0.6274785209 -0.5203501633 0.362202740082 +1403637189688318976.0000000000 7.9083166028 -0.7789989008 -0.1379214090 0.4523586417 0.6279898891 -0.5172122805 0.365365317733 +1403637189738319104.0000000000 7.9598895088 -0.8198174994 -0.1481285116 0.4507931267 0.6300151169 -0.5162815515 0.365129934321 +1403637189788318976.0000000000 8.0108525073 -0.8607787451 -0.1564897041 0.4494529534 0.6316176377 -0.5159577761 0.364470541619 +1403637189838319104.0000000000 8.0609525645 -0.9020058009 -0.1629889946 0.4468209854 0.6339356184 -0.5151888916 0.364769851726 +1403637189888318976.0000000000 8.1112989286 -0.9427477643 -0.1654622687 0.4472363993 0.6339451326 -0.5143343052 0.365449578644 +1403637189938319104.0000000000 8.1603742884 -0.9833310238 -0.1649304012 0.4487669585 0.6330599650 -0.5139129574 0.365700382728 +1403637189988318976.0000000000 8.2082536216 -1.0241257931 -0.1633370663 0.4487232235 0.6330575705 -0.5124889498 0.367750809071 +1403637190038319104.0000000000 8.2545627122 -1.0649919267 -0.1598475382 0.4501075109 0.6318507360 -0.5116875561 0.369247506386 +1403637190088318976.0000000000 8.3046733435 -1.1055065044 -0.1550787337 0.4505681452 0.6311056356 -0.5104542160 0.371659140258 +1403637190138319104.0000000000 8.3507532329 -1.1456207941 -0.1483385224 0.4512927765 0.6303275101 -0.5104803296 0.372064366761 +1403637190188318976.0000000000 8.3969990862 -1.1852279928 -0.1404223345 0.4516632501 0.6295844026 -0.5099127437 0.37364793897 +1403637190238319104.0000000000 8.4428792988 -1.2241618026 -0.1305781242 0.4530921660 0.6283221746 -0.5105452371 0.373178636682 +1403637190288318976.0000000000 8.4871176592 -1.2635003995 -0.1195084369 0.4534468534 0.6274680527 -0.5106228580 0.374077653359 +1403637190338319104.0000000000 8.5304474341 -1.3026816784 -0.1066686060 0.4533742548 0.6270737658 -0.5110950416 0.374181955483 +1403637190388318976.0000000000 8.5726014575 -1.3415347997 -0.0917614595 0.4536139892 0.6263463949 -0.5121965752 0.373603012143 +1403637190438319104.0000000000 8.6135202518 -1.3800827588 -0.0751676068 0.4547092490 0.6252685839 -0.5132891613 0.372576077782 +1403637190488318976.0000000000 8.6540126976 -1.4186616239 -0.0587140600 0.4553902620 0.6242217767 -0.5132873679 0.373500951406 +1403637190538319104.0000000000 8.6927599705 -1.4573678002 -0.0431599472 0.4537405918 0.6246811391 -0.5131165551 0.374972466565 +1403637190588318976.0000000000 8.7306354353 -1.4957862582 -0.0290301587 0.4524889263 0.6253816323 -0.5117816532 0.377135420129 +1403637190638319104.0000000000 8.7672785287 -1.5340339582 -0.0170143992 0.4501234569 0.6281188701 -0.5084397231 0.37992710694 +1403637190688318976.0000000000 8.8024227443 -1.5715273665 -0.0063089360 0.4491831599 0.6316713699 -0.5039380478 0.381145921188 +1403637190738319104.0000000000 8.8359795322 -1.6076829872 0.0033044776 0.4509567862 0.6349643752 -0.5008183348 0.377676071111 +1403637190788318976.0000000000 8.8684796351 -1.6430038220 0.0119476043 0.4540853552 0.6375592512 -0.4974623487 0.37397313134 +1403637190838319104.0000000000 8.9002681126 -1.6777754551 0.0192868978 0.4575744952 0.6399415282 -0.4947299613 0.36924610669 +1403637190888318976.0000000000 8.9310993497 -1.7121254380 0.0252203478 0.4615877611 0.6415033864 -0.4925469438 0.364427842297 +1403637190938319104.0000000000 8.9610196893 -1.7463531423 0.0296036148 0.4652989888 0.6427154350 -0.4902991545 0.360583499048 +1403637190988318976.0000000000 8.9901348060 -1.7806706588 0.0322967745 0.4684632339 0.6437188363 -0.4882484292 0.357465704283 +1403637191038319104.0000000000 9.0182056274 -1.8152039848 0.0331156662 0.4707876788 0.6450448396 -0.4858936738 0.355223104759 +1403637191088318976.0000000000 9.0456346103 -1.8499802505 0.0328670768 0.4732933255 0.6456643887 -0.4839439824 0.353424881816 +1403637191138319104.0000000000 9.0723974428 -1.8850645076 0.0309756040 0.4748062105 0.6464446030 -0.4823055457 0.352207039023 +1403637191188318976.0000000000 9.0981672292 -1.9204053933 0.0278681544 0.4755897285 0.6473804209 -0.4803432882 0.352112661331 +1403637191238319104.0000000000 9.1230555559 -1.9559830752 0.0235540894 0.4758808545 0.6480246357 -0.4792903453 0.351969101967 +1403637191288318976.0000000000 9.1471923779 -1.9915010947 0.0176385379 0.4755080843 0.6490976537 -0.4778400958 0.352467219149 +1403637191338319104.0000000000 9.1702560590 -2.0271308846 0.0107300923 0.4762834291 0.6491313802 -0.4769714842 0.352534749599 +1403637191388318976.0000000000 9.1926589776 -2.0631167814 0.0029572315 0.4755854186 0.6497563181 -0.4751541615 0.354772828148 +1403637191438319104.0000000000 9.2142460075 -2.0988937046 -0.0043048590 0.4749492284 0.6502878663 -0.4738689758 0.356366545956 +1403637191488318976.0000000000 9.2342453500 -2.1346312052 -0.0096390769 0.4750148144 0.6499996044 -0.4738520339 0.356827255677 +1403637191538319104.0000000000 9.2525841354 -2.1705901723 -0.0138414097 0.4731280301 0.6508870077 -0.4726171801 0.359345198109 +1403637191588318976.0000000000 9.2701925150 -2.2063187519 -0.0158302041 0.4703662808 0.6522155638 -0.4715881129 0.361904783054 +1403637191638319104.0000000000 9.2863078776 -2.2414083741 -0.0158944072 0.4655004413 0.6549470261 -0.4726834060 0.361834395628 +1403637191688318976.0000000000 9.3008259726 -2.2759409477 -0.0144121244 0.4600477151 0.6579083143 -0.4751130962 0.360250323696 +1403637191738319104.0000000000 9.3145161926 -2.3094476501 -0.0105893417 0.4561098260 0.6600707294 -0.4773279066 0.358369262516 +1403637191788318976.0000000000 9.3276424519 -2.3420141248 -0.0052985211 0.4514981984 0.6625388490 -0.4791141619 0.35726918464 +1403637191838319104.0000000000 9.3413508997 -2.3735842468 0.0012633993 0.4469879648 0.6649100488 -0.4777234541 0.360384083628 +1403637191888318976.0000000000 9.3545394997 -2.4037919273 0.0097211530 0.4425396155 0.6672671433 -0.4754788699 0.364462745077 +1403637191938319104.0000000000 9.3677064929 -2.4321765161 0.0197704231 0.4385656988 0.6691363044 -0.4727446652 0.369363256686 +1403637191988318976.0000000000 9.3802388210 -2.4581748489 0.0323725253 0.4351744289 0.6708367720 -0.4705950626 0.373016794285 +1403637192038319104.0000000000 9.3918080605 -2.4817849024 0.0470222938 0.4320671862 0.6721494915 -0.4720454759 0.372432646807 +1403637192088318976.0000000000 9.4024970541 -2.5029755487 0.0631505242 0.4288596114 0.6736670377 -0.4754708362 0.369025256479 +1403637192138319104.0000000000 9.4129389556 -2.5218324022 0.0809345626 0.4256417194 0.6753825208 -0.4780427229 0.36628231244 +1403637192188318976.0000000000 9.4235272377 -2.5384173446 0.1003164212 0.4225876618 0.6769940097 -0.4794991065 0.364937509496 +1403637192238319104.0000000000 9.4349922346 -2.5523359324 0.1214780452 0.4198984387 0.6783773987 -0.4795915572 0.365350987833 +1403637192288318976.0000000000 9.4468707536 -2.5638079817 0.1441496408 0.4164287203 0.6801912054 -0.4776106003 0.368531083525 +1403637192338319104.0000000000 9.4593872160 -2.5723533563 0.1674366533 0.4140378884 0.6814846274 -0.4747260591 0.372540599768 +1403637192388318976.0000000000 9.4724383152 -2.5776776436 0.1904748914 0.4145116423 0.6809362250 -0.4728881371 0.375343530058 +1403637192438319104.0000000000 9.4852253003 -2.5799300653 0.2121226061 0.4153381632 0.6801877146 -0.4747145350 0.373476897994 +1403637192488318976.0000000000 9.4978465547 -2.5791973603 0.2319280035 0.4168264261 0.6790334272 -0.4797635554 0.367418380373 +1403637192538319104.0000000000 9.5105129289 -2.5762258492 0.2503203622 0.4185734226 0.6777392315 -0.4849714131 0.360927350742 +1403637192588318976.0000000000 9.5237044673 -2.5711896707 0.2670204937 0.4200334709 0.6766852624 -0.4901725784 0.354118317058 +1403637192638319104.0000000000 9.5378241688 -2.5646449487 0.2818817068 0.4205459694 0.6762042438 -0.4940250286 0.349038936883 +1403637192688318976.0000000000 9.5535418345 -2.5566710187 0.2950281408 0.4208569121 0.6760230059 -0.4965757092 0.345376490325 +1403637192738319104.0000000000 9.5707306337 -2.5476155475 0.3066522426 0.4216253210 0.6754584467 -0.4978118746 0.343760546121 +1403637192788318976.0000000000 9.5892748738 -2.5373354472 0.3166575814 0.4224365216 0.6750873510 -0.4977911096 0.343523601766 +1403637192838319104.0000000000 9.6093403567 -2.5257943189 0.3266598424 0.4243239166 0.6742223766 -0.4965138967 0.344742441578 +1403637192888318976.0000000000 9.6310817305 -2.5129198825 0.3375275612 0.4269954545 0.6726743499 -0.4946195758 0.347182338396 +1403637192938319104.0000000000 9.6540552685 -2.4985158773 0.3505584968 0.4303339665 0.6709312217 -0.4932520755 0.348376754451 +1403637192988318976.0000000000 9.6774215760 -2.4833012538 0.3647970862 0.4328151980 0.6697933500 -0.4914111189 0.350089966725 +1403637193038319104.0000000000 9.7021154040 -2.4667221771 0.3808224995 0.4353605104 0.6683845395 -0.4917422265 0.349160301265 +1403637193088318976.0000000000 9.7270614852 -2.4490791343 0.3988212206 0.4376875201 0.6669812807 -0.4949306642 0.344396927464 +1403637193138319104.0000000000 9.7518446906 -2.4309432337 0.4180117870 0.4401791968 0.6651426768 -0.5018262411 0.334660899979 +1403637193188318976.0000000000 9.7783349210 -2.4124012890 0.4386882283 0.4427381569 0.6630959054 -0.5094918712 0.323581176496 +1403637193238319104.0000000000 9.8060459549 -2.3950195397 0.4592110205 0.4439991598 0.6619964510 -0.5144408840 0.31618985087 +1403637193288318976.0000000000 9.8357531909 -2.3786759565 0.4767200664 0.4448339048 0.6610638926 -0.5174477700 0.312033864138 +1403637193338319104.0000000000 9.8684638523 -2.3639150487 0.4899345792 0.4426199152 0.6626797584 -0.5138526462 0.317645409871 +1403637193388318976.0000000000 9.9032880044 -2.3497242208 0.4991997785 0.4418897656 0.6633355434 -0.5089992077 0.32502184302 +1403637193438319104.0000000000 9.9392484570 -2.3357474227 0.5058249332 0.4411884850 0.6638646917 -0.5036830905 0.333076171747 +1403637193488318976.0000000000 9.9761600554 -2.3217579468 0.5117084751 0.4402888205 0.6647234794 -0.4989140514 0.339666335981 +1403637193538319104.0000000000 10.0133830141 -2.3076035801 0.5186843928 0.4389367759 0.6658744137 -0.4945968595 0.345426864151 +1403637193588318976.0000000000 10.0509315675 -2.2927562616 0.5268882543 0.4369778579 0.6675810707 -0.4914468337 0.349092932483 +1403637193638319104.0000000000 10.0893205495 -2.2768721154 0.5368677472 0.4358442552 0.6685067121 -0.4892923088 0.35175502504 +1403637193688318976.0000000000 10.1284163476 -2.2598505709 0.5483616351 0.4344407401 0.6696085959 -0.4878450905 0.353401668518 +1403637193738319104.0000000000 10.1686261095 -2.2417467940 0.5618234820 0.4332169103 0.6706708050 -0.4859645760 0.355474627526 +1403637193788318976.0000000000 10.2089161019 -2.2224263338 0.5764464360 0.4324595231 0.6712282686 -0.4851431757 0.356465245714 +1403637193838319104.0000000000 10.2492811546 -2.2020126029 0.5925071255 0.4314875121 0.6721227577 -0.4842515176 0.357169418171 +1403637193888318976.0000000000 10.2898986062 -2.1799904013 0.6094410375 0.4314460003 0.6720543331 -0.4843082620 0.357271366751 +1403637193938319104.0000000000 10.3310104873 -2.1566270458 0.6258615964 0.4334157213 0.6708147027 -0.4839891579 0.357649188818 +1403637193988318976.0000000000 10.3724713833 -2.1324154233 0.6391010946 0.4364639786 0.6687776990 -0.4824951418 0.359769402144 +1403637194038319104.0000000000 10.4136560497 -2.1074408392 0.6482785738 0.4398476349 0.6664379293 -0.4813524902 0.36151670037 +1403637194088318976.0000000000 10.4542852338 -2.0818517852 0.6533176066 0.4422576773 0.6645744416 -0.4809169050 0.362585009155 +1403637194138319104.0000000000 10.4945727032 -2.0555891607 0.6547276251 0.4434504298 0.6635780953 -0.4803248171 0.363736027644 +1403637194188318976.0000000000 10.5353210839 -2.0281523837 0.6537277217 0.4438373992 0.6631926132 -0.4805717145 0.363640960477 +1403637194238319104.0000000000 10.5750931654 -2.0000364673 0.6519466099 0.4432468419 0.6635897614 -0.4822954531 0.36134742528 +1403637194288318976.0000000000 10.6141771276 -1.9711931152 0.6508477272 0.4428318798 0.6637476034 -0.4830721463 0.360527872178 +1403637194338319104.0000000000 10.6528993687 -1.9420638948 0.6498758957 0.4411905495 0.6646424445 -0.4841630771 0.35942653596 +1403637194388318976.0000000000 10.6907102293 -1.9118817378 0.6507974642 0.4401087471 0.6654308059 -0.4847191555 0.358543544949 +1403637194438319104.0000000000 10.7288017918 -1.8807626430 0.6534888156 0.4386575587 0.6663199150 -0.4847629961 0.358611425873 +1403637194488318976.0000000000 10.7675831907 -1.8481491915 0.6582899463 0.4392710640 0.6658166954 -0.4858017197 0.357387394414 +1403637194538319104.0000000000 10.8067220390 -1.8146543513 0.6646529973 0.4385857044 0.6662031209 -0.4863521946 0.356759757267 +1403637194588318976.0000000000 10.8456446693 -1.7803366569 0.6728318716 0.4382047812 0.6663109368 -0.4868982886 0.356281295839 +1403637194638319104.0000000000 10.8841680537 -1.7453175353 0.6831797822 0.4371287894 0.6667174544 -0.4871449013 0.356505403353 +1403637194688318976.0000000000 10.9225771778 -1.7095004186 0.6943999780 0.4345378419 0.6681634577 -0.4885009706 0.355107391376 +1403637194738319104.0000000000 10.9613141129 -1.6727928983 0.7064036726 0.4320696732 0.6694157962 -0.4902508146 0.353344630855 +1403637194788318976.0000000000 10.9998802784 -1.6357347739 0.7180087597 0.4303082957 0.6702142494 -0.4916844353 0.351985861324 +1403637194838319104.0000000000 11.0396053245 -1.5973448347 0.7283063843 0.4292095514 0.6704667373 -0.4930206681 0.350975976359 +1403637194888318976.0000000000 11.0795899839 -1.5581832871 0.7370098911 0.4281028054 0.6709230487 -0.4939600434 0.35013386913 +1403637194938319104.0000000000 11.1205216263 -1.5179456025 0.7454584989 0.4309225495 0.6689081017 -0.4942099160 0.35017747883 +1403637194988318976.0000000000 11.1620188121 -1.4771207868 0.7524421472 0.4343625846 0.6661959848 -0.4936443128 0.35189110155 +1403637195038319104.0000000000 11.2036853852 -1.4357557762 0.7578842957 0.4380388589 0.6635385330 -0.4915382206 0.35528685737 +1403637195088318976.0000000000 11.2451239895 -1.3938143670 0.7617092410 0.4415048651 0.6609741858 -0.4900382185 0.357839522881 +1403637195138319104.0000000000 11.2861310271 -1.3514799527 0.7639928006 0.4447712884 0.6583778180 -0.4884872739 0.360690078855 +1403637195188318976.0000000000 11.3264173311 -1.3086610049 0.7648416910 0.4479412598 0.6561408022 -0.4868512415 0.363047853733 +1403637195238319104.0000000000 11.3660916317 -1.2656497231 0.7644323652 0.4503652299 0.6542773766 -0.4857656476 0.364861631022 +1403637195288318976.0000000000 11.4048903956 -1.2225297844 0.7624452467 0.4520739261 0.6530448717 -0.4846110773 0.366488287006 +1403637195338319104.0000000000 11.4429969327 -1.1792585198 0.7593635597 0.4543082970 0.6515697185 -0.4841614665 0.366944883621 +1403637195388318976.0000000000 11.4801156376 -1.1360783830 0.7552202569 0.4543242189 0.6517352171 -0.4829959019 0.368165275029 +1403637195438319104.0000000000 11.5163513754 -1.0922446495 0.7520010216 0.4563793764 0.6515404793 -0.4822192692 0.366984257227 +1403637195488318976.0000000000 11.5515155126 -1.0478365277 0.7501214487 0.4576744097 0.6533161440 -0.4805386996 0.36441008349 +1403637195538319104.0000000000 11.5859307023 -1.0033533201 0.7493882609 0.4585244029 0.6559475075 -0.4788092161 0.360873903039 +1403637195588318976.0000000000 11.6190424020 -0.9590447141 0.7514783288 0.4596749540 0.6582308463 -0.4759373105 0.35904702481 +1403637195638319104.0000000000 11.6515497081 -0.9145518206 0.7556712620 0.4613096806 0.6599633443 -0.4733203393 0.357224886055 +1403637195688318976.0000000000 11.6832699665 -0.8701036479 0.7618128082 0.4633138278 0.6610842358 -0.4708257007 0.35585262352 +1403637195738319104.0000000000 11.7140551352 -0.8260675697 0.7690214353 0.4645866937 0.6622318442 -0.4679292262 0.355879794065 +1403637195788318976.0000000000 11.7433736446 -0.7823678078 0.7763372191 0.4639377040 0.6644866420 -0.4657858758 0.355334810153 +1403637195838319104.0000000000 11.7722871683 -0.7388895806 0.7848776306 0.4631906241 0.6663977543 -0.4608341793 0.35916617046 +1403637195888318976.0000000000 11.8004385069 -0.6951270345 0.7936288553 0.4606877742 0.6691527731 -0.4567023221 0.362524936933 +1403637195938319104.0000000000 11.8274468223 -0.6508812393 0.8021209556 0.4581972717 0.6716360129 -0.4528203206 0.365942732744 +1403637195988318976.0000000000 11.8531561401 -0.6061207296 0.8091123174 0.4551717496 0.6740968707 -0.4476742775 0.371483281679 +1403637196038319104.0000000000 11.8770666573 -0.5604001971 0.8145729617 0.4527559033 0.6759760544 -0.4426141718 0.377042651166 +1403637196088318976.0000000000 11.8997645498 -0.5129236921 0.8191961655 0.4524873530 0.6760093247 -0.4366454480 0.384197008242 +1403637196138319104.0000000000 11.9207091885 -0.4639979044 0.8227853415 0.4531101889 0.6751383565 -0.4304971752 0.391856528044 +1403637196188318976.0000000000 11.9394039650 -0.4130879818 0.8256598340 0.4549286313 0.6733291253 -0.4239293476 0.399939667643 +1403637196238319104.0000000000 11.9552871052 -0.3599983106 0.8277222653 0.4579194645 0.6705884199 -0.4187612996 0.406521720195 +1403637196288318976.0000000000 11.9679886850 -0.3046945378 0.8286188500 0.4605075133 0.6681195811 -0.4141931739 0.412302159008 +1403637196338319104.0000000000 11.9773295457 -0.2471636144 0.8279034045 0.4619808380 0.6660905784 -0.4101328160 0.417957078886 +1403637196388318976.0000000000 11.9826013899 -0.1874254853 0.8259291127 0.4631241130 0.6642597921 -0.4072824658 0.422369479993 +1403637196438319104.0000000000 11.9828917227 -0.1258979305 0.8226783156 0.4638874969 0.6630074136 -0.4058817041 0.424840678342 +1403637196488318976.0000000000 11.9787424175 -0.0616467462 0.8185545300 0.4648864552 0.6620162061 -0.4068327331 0.424384558955 +1403637196538319104.0000000000 11.9703308011 0.0048144388 0.8128697026 0.4650108542 0.6615069432 -0.4083585100 0.42357619954 +1403637196588318976.0000000000 11.9580336928 0.0740218983 0.8065343721 0.4672540947 0.6599406726 -0.4105166696 0.421459349965 +1403637196638319104.0000000000 11.9415370037 0.1448135979 0.7986486281 0.4670262632 0.6598584370 -0.4136352519 0.418782987934 +1403637196688318976.0000000000 11.9207832401 0.2173857861 0.7898593171 0.4683666785 0.6588880884 -0.4168264920 0.415637843534 +1403637196738319104.0000000000 11.8961814241 0.2914576459 0.7796133819 0.4702231693 0.6575714447 -0.4196950534 0.412729970208 +1403637196788318976.0000000000 11.8678301146 0.3666837233 0.7672015491 0.4712854047 0.6568368302 -0.4233600664 0.408927499627 +1403637196838319104.0000000000 11.8359116179 0.4419513980 0.7560175275 0.4708788036 0.6566415470 -0.4240843783 0.408959009103 +1403637196888318976.0000000000 11.8005363686 0.5186979770 0.7423706716 0.4713924972 0.6554646857 -0.4232855340 0.411077262972 +1403637196938319104.0000000000 11.7615128394 0.5968855749 0.7279700197 0.4730919732 0.6539970088 -0.4244876930 0.410222008047 +1403637196988318976.0000000000 11.7188339089 0.6766747633 0.7144375284 0.4777749111 0.6513124798 -0.4284941095 0.404865392514 +1403637197038319104.0000000000 11.6724270522 0.7574628219 0.7008659336 0.4812790871 0.6509176200 -0.4319872976 0.397572216145 +1403637197088318976.0000000000 11.6230494040 0.8391155558 0.6887263162 0.4841582307 0.6521539152 -0.4336138128 0.390211660325 +1403637197138319104.0000000000 11.5700423306 0.9207474298 0.6777123711 0.4871716366 0.6545146493 -0.4334112819 0.38266046441 +1403637197188318976.0000000000 11.5130220717 1.0021057709 0.6673694358 0.4895278548 0.6588614432 -0.4323093577 0.373326529115 +1403637197238319104.0000000000 11.4559103387 1.0842401015 0.6609301380 0.4927204154 0.6639357753 -0.4280474164 0.364953816009 +1403637197288318976.0000000000 11.3945918485 1.1654637913 0.6553013335 0.4947807643 0.6711368425 -0.4237839681 0.353800059817 +1403637197338319104.0000000000 11.3310288317 1.2462687675 0.6518030124 0.4976106701 0.6786919440 -0.4175682541 0.342633359864 +1403637197388318976.0000000000 11.2658026694 1.3267880607 0.6506577651 0.5023621621 0.6859610063 -0.4091941787 0.331134232773 +1403637197438319104.0000000000 11.1988049039 1.4064121289 0.6511257823 0.5062909464 0.6948298632 -0.3988967397 0.319002084531 +1403637197488318976.0000000000 11.1298426820 1.4846543898 0.6530880741 0.5081607390 0.7057305622 -0.3850656070 0.308936102226 +1403637197538319104.0000000000 11.0598669894 1.5624237687 0.6567214300 0.5113833559 0.7161058217 -0.3698508164 0.298144074122 +1403637197588318976.0000000000 10.9886357989 1.6394403789 0.6612734574 0.5132586297 0.7277559418 -0.3522424438 0.287857827647 +1403637197638319104.0000000000 10.9164773944 1.7161343013 0.6677846105 0.5173912864 0.7375637222 -0.3343041656 0.276670810371 +1403637197688318976.0000000000 10.8437291033 1.7921424390 0.6759038617 0.5228842814 0.7458087466 -0.3164411788 0.265002494434 +1403637197738319104.0000000000 10.7708944640 1.8673548215 0.6855884142 0.5274080526 0.7536882959 -0.2975996076 0.255400024053 +1403637197788318976.0000000000 10.6968480050 1.9415907714 0.6969180651 0.5328983739 0.7600152332 -0.2783013858 0.246869413024 +1403637197838319104.0000000000 10.6212334061 2.0147006617 0.7096906048 0.5386417454 0.7653120838 -0.2577046731 0.240313932133 +1403637197888318976.0000000000 10.5443074807 2.0875520370 0.7243073433 0.5425065294 0.7709043560 -0.2388297778 0.233138320907 +1403637197938319104.0000000000 10.4658187038 2.1602787752 0.7401926178 0.5471157381 0.7751726630 -0.2220111810 0.224683659972 +1403637197988318976.0000000000 10.3856723238 2.2323760422 0.7574009776 0.5507143456 0.7792379675 -0.2057872762 0.217148558751 +1403637198038319104.0000000000 10.3031062372 2.3033376057 0.7766730306 0.5547383019 0.7824146024 -0.1913473504 0.208516181142 +1403637198088318976.0000000000 10.2184781229 2.3736475303 0.7980344177 0.5586165527 0.7850913618 -0.1779729646 0.199761669544 +1403637198138319104.0000000000 10.1320572289 2.4435002581 0.8208715845 0.5617153594 0.7878261673 -0.1647672405 0.191461592712 +1403637198188318976.0000000000 10.0435979973 2.5134996360 0.8458451653 0.5642358208 0.7905928237 -0.1529476440 0.182230469027 +1403637198238319104.0000000000 9.9531819419 2.5825098021 0.8722287287 0.5655033095 0.7938427969 -0.1407809302 0.173782480515 +1403637198288318976.0000000000 9.8609936309 2.6507682958 0.9003984269 0.5694603337 0.7946474495 -0.1268295199 0.167823217325 +1403637198338319104.0000000000 9.7669334138 2.7182538435 0.9283014384 0.5716231895 0.7964003899 -0.1146751659 0.160757439833 +1403637198388318976.0000000000 9.6616363357 2.7901907373 0.9831068128 0.5753927275 0.7962388029 -0.1007345277 0.15741516102 +1403637198438319104.0000000000 9.5633801853 2.8568271399 1.0120159945 0.5788692511 0.7956243522 -0.0896034192 0.154478178261 +1403637198488318976.0000000000 9.4625443556 2.9219344271 1.0384881066 0.5814844004 0.7949592633 -0.0803111461 0.153185448214 +1403637198538319104.0000000000 9.3590424448 2.9859753528 1.0614397590 0.5838787030 0.7939464826 -0.0723751035 0.153285639411 +1403637198588318976.0000000000 9.2525962976 3.0490357856 1.0805605101 0.5859060944 0.7928448773 -0.0658959263 0.154171255722 +1403637198638319104.0000000000 9.1431360014 3.1105401876 1.0951227874 0.5871868884 0.7920297880 -0.0608940463 0.155538702878 +1403637198688318976.0000000000 9.0307029603 3.1705908081 1.1050431844 0.5884229197 0.7914944711 -0.0587613578 0.154408784016 +1403637198738319104.0000000000 8.9145144581 3.2286602077 1.1102875697 0.5892940535 0.7912246245 -0.0578181184 0.152817463998 +1403637198788318976.0000000000 8.7959691584 3.2852023873 1.1110633966 0.5912819202 0.7899477190 -0.0574442008 0.151883033795 +1403637198838319104.0000000000 8.6747735411 3.3406509212 1.1083139232 0.5962051304 0.7865546476 -0.0580329155 0.150011364455 +1403637198888318976.0000000000 8.5510867245 3.3949799652 1.1022026643 0.6016303106 0.7826606874 -0.0597394498 0.148035184736 +1403637198938319104.0000000000 8.4291738570 3.4495329009 1.0948609465 0.6071523303 0.7791376905 -0.0644337460 0.1419816866 +1403637198988318976.0000000000 8.3038647289 3.5014288126 1.0881148642 0.6138443810 0.7748698687 -0.0682489261 0.134587690934 +1403637199038319104.0000000000 8.1759629564 3.5505437506 1.0820426535 0.6176882988 0.7729942130 -0.0712341573 0.125963514871 +1403637199088318976.0000000000 8.0462030204 3.5965213481 1.0767014972 0.6184385439 0.7736441930 -0.0727419073 0.117119789421 +1403637199138319104.0000000000 7.9325191660 3.6463063109 1.0710974185 0.6177480497 0.7754997330 -0.0721836029 0.108522065295 +1403637199188318976.0000000000 7.8064830206 3.6877894269 1.0676439270 0.6160571534 0.7781744758 -0.0696557236 0.100330200515 +1403637199238319104.0000000000 7.6792615049 3.7266282245 1.0658456796 0.6152831017 0.7801969448 -0.0645114810 0.0925078421249 +1403637199288318976.0000000000 7.5505797967 3.7622697928 1.0661847697 0.6153627877 0.7813822239 -0.0569850555 0.0867361699641 +1403637199338319104.0000000000 7.4201659356 3.7943629611 1.0686714948 0.6169556051 0.7814377530 -0.0479229666 0.0801511618935 +1403637199388318976.0000000000 7.2883216117 3.8222698049 1.0725991599 0.6179953597 0.7817784965 -0.0372308093 0.0742831378256 +1403637199438319104.0000000000 7.1547173875 3.8467854644 1.0777126241 0.6195607912 0.7816861752 -0.0259708562 0.0666082880311 +1403637199488318976.0000000000 7.0201250621 3.8682936207 1.0831399327 0.6209090332 0.7815077351 -0.0139980647 0.0593438007499 +1403637199538319104.0000000000 6.8844559638 3.8863939402 1.0877538802 0.6215865817 0.7817077076 -0.0026235049 0.0505598509617 +1403637199588318976.0000000000 6.7481432259 3.9016501395 1.0904976463 0.6230459342 0.7810165223 0.0088023207 0.0418267251338 +1403637199638319104.0000000000 6.6109798453 3.9131667805 1.0914726159 0.6251876026 0.7797153468 0.0176011889 0.0295742736545 +1403637199688318976.0000000000 6.4731227794 3.9219187377 1.0908955583 0.6278716990 0.7776914913 0.0266175325 0.0162659428722 +1403637199738319104.0000000000 6.3353594131 3.9275435532 1.0876779703 0.6292462934 0.7763884839 0.0355528187 0.00245385216821 +1403637199788318976.0000000000 6.1978268268 3.9301824410 1.0811114298 0.6309225908 0.7744905051 0.0429985547 -0.0158828894357 +1403637199838319104.0000000000 6.0610368953 3.9304432122 1.0690340598 0.6332345666 0.7714618607 0.0518239564 -0.0342762113476 +1403637199888318976.0000000000 5.9254532008 3.9282896543 1.0508307724 0.6358736053 0.7674910138 0.0596569338 -0.0553475562962 +1403637199938319104.0000000000 5.7919325319 3.9235795742 1.0282631960 0.6385364690 0.7627542575 0.0684302115 -0.0761211312807 +1403637199988318976.0000000000 5.6612946744 3.9155071896 1.0044357063 0.6434474478 0.7552531943 0.0779148061 -0.0974539762449 +1403637200038319104.0000000000 5.5345329798 3.9032003489 0.9790777833 0.6468413905 0.7482620437 0.0887611874 -0.117565220344 +1403637200088318976.0000000000 5.4124462148 3.8866359694 0.9522438828 0.6497291902 0.7411475134 0.1026372293 -0.13423092783 +1403637200138319104.0000000000 5.2953097088 3.8659147717 0.9248788882 0.6525290083 0.7335400597 0.1177662637 -0.14918438684 +1403637200188318976.0000000000 5.1838808904 3.8404478017 0.8948480896 0.6496376823 0.7310004372 0.1351455289 -0.159200906451 +1403637200238319104.0000000000 5.0777084115 3.8105574460 0.8639987501 0.6449785140 0.7297928820 0.1522917302 -0.167965159272 +1403637200288318976.0000000000 4.9773342753 3.7773108582 0.8312996115 0.6391515113 0.7305472002 0.1724627001 -0.167459699592 +1403637200338319104.0000000000 4.8821991153 3.7400680463 0.7981307828 0.6296306998 0.7348007614 0.1915831706 -0.164100310022 +1403637200388318976.0000000000 4.7812475945 3.6947794588 0.7642388882 0.6188956908 0.7401106476 0.2070983269 -0.162217866574 +1403637200438319104.0000000000 4.6950898509 3.6515545548 0.7345685337 0.6070702700 0.7466388918 0.2194472858 -0.16074495705 +1403637200488318976.0000000000 4.6115999315 3.6062038973 0.7073481608 0.5964744393 0.7526424333 0.2295617802 -0.158268758376 +1403637200538319104.0000000000 4.5310532035 3.5590802091 0.6828083763 0.5873930860 0.7576328041 0.2332735971 -0.162927362965 +1403637200588318976.0000000000 4.4509588608 3.5108228316 0.6618062974 0.5820116906 0.7603355753 0.2336181610 -0.169040704676 +1403637200638319104.0000000000 4.3730914092 3.4615033966 0.6429119734 0.5775312745 0.7628085559 0.2336730109 -0.173140572671 +1403637200688318976.0000000000 4.2975511171 3.4116589253 0.6265386781 0.5748348160 0.7645341746 0.2326488513 -0.175860575852 +1403637200738319104.0000000000 4.2239669720 3.3612714384 0.6117778846 0.5721034156 0.7666050907 0.2309009297 -0.178042347258 +1403637200788318976.0000000000 4.1522437007 3.3103093867 0.5992518976 0.5715882010 0.7675253716 0.2264724419 -0.181388989405 +1403637200838319104.0000000000 4.0822073948 3.2597032233 0.5889794283 0.5722019172 0.7683681435 0.2198086552 -0.184063894034 +1403637200888318976.0000000000 4.0148693489 3.2085863873 0.5810266240 0.5734893574 0.7689931177 0.2142753434 -0.183971788699 +1403637200938319104.0000000000 3.9501488886 3.1572363549 0.5739817666 0.5741657721 0.7702027211 0.2100093250 -0.181707231432 +1403637200988318976.0000000000 3.8882128435 3.1054137011 0.5683417127 0.5747134045 0.7715339072 0.2062926044 -0.178558937499 +1403637201038319104.0000000000 3.8291389508 3.0529833689 0.5642659429 0.5760091811 0.7723621774 0.2026171977 -0.174975316406 +1403637201088318976.0000000000 3.7724433654 3.0005976114 0.5623846723 0.5764201499 0.7736687702 0.1995241962 -0.171366682524 +1403637201138319104.0000000000 3.7180989490 2.9482418756 0.5623402785 0.5766288773 0.7751570515 0.1968794614 -0.166940591376 +1403637201188318976.0000000000 3.6655347287 2.8958044586 0.5647659040 0.5768639074 0.7764028761 0.1927045548 -0.165201576598 +1403637201238319104.0000000000 3.6148911185 2.8427199827 0.5689368742 0.5751522753 0.7788726447 0.1885553479 -0.164329377404 +1403637201288318976.0000000000 3.5669146393 2.7892615870 0.5755260785 0.5735469231 0.7813538572 0.1811041209 -0.16652739791 +1403637201338319104.0000000000 3.5216330448 2.7361025065 0.5823683809 0.5704009702 0.7849200780 0.1701925541 -0.171981681743 +1403637201388318976.0000000000 3.4792875465 2.6834058714 0.5876203845 0.5658101286 0.7897640959 0.1592575490 -0.175409817909 +1403637201438319104.0000000000 3.4404387549 2.6316423043 0.5913450203 0.5604946186 0.7950788513 0.1477410254 -0.178516083738 +1403637201488318976.0000000000 3.4048453625 2.5817185727 0.5932747866 0.5551946723 0.8003953590 0.1363286985 -0.180390218873 +1403637201538319104.0000000000 3.3727747596 2.5334904552 0.5935291770 0.5506531626 0.8049259378 0.1256076660 -0.181928676618 +1403637201588318976.0000000000 3.3446114550 2.4871032439 0.5925181072 0.5477852490 0.8079692496 0.1163689567 -0.183235582029 +1403637201638319104.0000000000 3.3208528763 2.4428304159 0.5904468898 0.5457703829 0.8101856434 0.1083459442 -0.184377516758 +1403637201688318976.0000000000 3.3017813457 2.4010999168 0.5872397549 0.5462956693 0.8107102545 0.1022004517 -0.184024434869 +1403637201738319104.0000000000 3.2874676942 2.3619721144 0.5828886060 0.5506542817 0.8090034301 0.0999860021 -0.179711188855 +1403637201788318976.0000000000 3.2777326890 2.3248135752 0.5774795672 0.5553775758 0.8071140220 0.1004046052 -0.173325182692 +1403637201838319104.0000000000 3.2723459700 2.2892394907 0.5727851898 0.5587765409 0.8056641132 0.0999753028 -0.169348908809 +1403637201888318976.0000000000 3.2713014900 2.2549282803 0.5692977482 0.5616617503 0.8043854634 0.1004409998 -0.165564821409 +1403637201938319104.0000000000 3.2741837918 2.2221677336 0.5674204842 0.5628960633 0.8039608606 0.1007766697 -0.163214642193 +1403637201988318976.0000000000 3.2807682563 2.1905632386 0.5672644107 0.5605102011 0.8055799672 0.1002511535 -0.163764884045 +1403637202038319104.0000000000 3.2910375022 2.1605342142 0.5685279709 0.5562074813 0.8082258939 0.0990152947 -0.166132819094 +1403637202088318976.0000000000 3.3053862893 2.1318961397 0.5710465123 0.5497646712 0.8121006410 0.0983125138 -0.169073962575 +1403637202138319104.0000000000 3.3242705038 2.1046313356 0.5743224845 0.5425009077 0.8166710804 0.0995393668 -0.169802903737 +1403637202188318976.0000000000 3.3477136658 2.0798487128 0.5787718810 0.5371185774 0.8204682055 0.1038865322 -0.165961278438 +1403637202238319104.0000000000 3.3753823179 2.0576446836 0.5830364428 0.5346836074 0.8228469180 0.1121731716 -0.156376370109 +1403637202288318976.0000000000 3.4055613012 2.0393305117 0.5861315443 0.5327985061 0.8247821821 0.1221542817 -0.144701193463 +1403637202338319104.0000000000 3.4376929674 2.0230236031 0.5883375671 0.5311562373 0.8262179190 0.1304961407 -0.134936130184 +1403637202388318976.0000000000 3.4710124641 2.0094970705 0.5893818841 0.5307056577 0.8266600207 0.1377574620 -0.126521131546 +1403637202438319104.0000000000 3.5050274473 1.9987402405 0.5899427048 0.5314844353 0.8261890946 0.1424314573 -0.121033693496 +1403637202488318976.0000000000 3.5392136713 1.9907446094 0.5905513076 0.5343970222 0.8242468911 0.1448453686 -0.11856097281 +1403637202538319104.0000000000 3.5735420082 1.9851362053 0.5916921692 0.5380884078 0.8217538772 0.1462068886 -0.117494580416 +1403637202588318976.0000000000 3.6077320737 1.9821897186 0.5941392889 0.5424003507 0.8188117662 0.1460181395 -0.118439241517 +1403637202638319104.0000000000 3.6424057092 1.9812137468 0.5984891227 0.5479178520 0.8150328283 0.1464028633 -0.118632701407 +1403637202688318976.0000000000 3.6776308828 1.9814358873 0.6045329371 0.5522285215 0.8120649263 0.1473784707 -0.117787103707 +1403637202738319104.0000000000 3.7133450653 1.9826882122 0.6130100696 0.5566458205 0.8089452638 0.1483481893 -0.117242506894 +1403637202788318976.0000000000 3.7498488443 1.9846549126 0.6219180018 0.5597405691 0.8067585455 0.1516632018 -0.113267020044 +1403637202838319104.0000000000 3.7865587818 1.9872503672 0.6307724615 0.5623744719 0.8049508436 0.1546426870 -0.108971244427 +1403637202888318976.0000000000 3.8227269170 1.9907338231 0.6381646236 0.5642067507 0.8036574194 0.1578681234 -0.104322338282 +1403637202938319104.0000000000 3.8583916447 1.9945047624 0.6440126448 0.5657022088 0.8025664219 0.1606928094 -0.100229588296 +1403637202988318976.0000000000 3.8935005761 1.9981763878 0.6484198273 0.5666166271 0.8019139828 0.1627011486 -0.0969943205531 +1403637203038319104.0000000000 3.9279059033 2.0018772530 0.6518971217 0.5673522854 0.8014054967 0.1637224632 -0.0951607538662 +1403637203088318976.0000000000 3.9614828266 2.0054466455 0.6546238466 0.5676329824 0.8012532604 0.1636994179 -0.0948077556057 +1403637203138319104.0000000000 3.9939736673 2.0092034121 0.6566456110 0.5678604149 0.8011902092 0.1622621207 -0.0964354809923 +1403637203188318976.0000000000 4.0263025648 2.0127946062 0.6570079426 0.5679482334 0.8011396671 0.1634060870 -0.0943847905988 +1403637203238319104.0000000000 4.0575761641 2.0162101791 0.6571346613 0.5689749258 0.8005277166 0.1630339748 -0.0940363325251 +1403637203288318976.0000000000 4.0878849564 2.0196811343 0.6564392524 0.5694917070 0.8002403405 0.1631563240 -0.0931375706101 +1403637203338319104.0000000000 4.1173116868 2.0228745602 0.6551593743 0.5699929416 0.7999206409 0.1631062306 -0.0929051796829 +1403637203388318976.0000000000 4.1462325625 2.0257259979 0.6530135556 0.5698360958 0.8001287953 0.1621435577 -0.0937560743493 +1403637203438319104.0000000000 4.1748652327 2.0283571915 0.6494979479 0.5697598064 0.8002512125 0.1625574968 -0.0924490141554 +1403637203488318976.0000000000 4.2023800772 2.0307789454 0.6451331290 0.5697349542 0.8003273976 0.1622982255 -0.0923981847062 +1403637203538319104.0000000000 4.2292076864 2.0329109372 0.6397614585 0.5705458058 0.7997932976 0.1624214949 -0.0918009941667 +1403637203588318976.0000000000 4.2553035498 2.0351025643 0.6334055983 0.5715235425 0.7991515966 0.1628499883 -0.0905397561627 +1403637203638319104.0000000000 4.2806375374 2.0371498260 0.6261243517 0.5720357185 0.7988586268 0.1637118970 -0.0883088096633 +1403637203688318976.0000000000 4.3043617779 2.0387751659 0.6182681652 0.5721820793 0.7988362364 0.1631676615 -0.0885700275616 +1403637203738319104.0000000000 4.3268833203 2.0400087792 0.6097827957 0.5730524208 0.7983709390 0.1622238509 -0.0888717557727 +1403637203788318976.0000000000 4.3485469047 2.0408340524 0.6002805419 0.5731273702 0.7984326831 0.1616718495 -0.088839636835 +1403637203838319104.0000000000 4.3692679033 2.0412425579 0.5899694674 0.5732117205 0.7984602873 0.1610586139 -0.0891606191601 +1403637203888318976.0000000000 4.3890995695 2.0411235081 0.5787853299 0.5738214380 0.7980703732 0.1610003633 -0.088834225795 +1403637203938319104.0000000000 4.4080992071 2.0404279685 0.5666412862 0.5742192329 0.7978493592 0.1608151955 -0.0885841152859 +1403637203988318976.0000000000 4.4262493522 2.0391810808 0.5534972945 0.5740439828 0.7980182474 0.1608705601 -0.0880967966256 +1403637204038319104.0000000000 4.4436171299 2.0377138940 0.5404376257 0.5741546842 0.7980041434 0.1610497927 -0.0871708096091 +1403637204088318976.0000000000 4.4600446898 2.0356761283 0.5284273550 0.5740394556 0.7981952546 0.1601624843 -0.0878123996591 +1403637204138319104.0000000000 4.4759636158 2.0331328469 0.5184182818 0.5742553221 0.7980617504 0.1603081107 -0.0873474511179 +1403637204188318976.0000000000 4.4907108389 2.0307581468 0.5113787171 0.5736569079 0.7985670468 0.1598724505 -0.0874598387864 +1403637204238319104.0000000000 4.5050449009 2.0274261205 0.5059125971 0.5740449310 0.7983183752 0.1601449858 -0.0866820190134 +1403637204288318976.0000000000 4.5184602960 2.0233317633 0.5018381098 0.5727099182 0.7993907812 0.1593888508 -0.0870225417624 +1403637204338319104.0000000000 4.5309839620 2.0188113770 0.5002847880 0.5728423799 0.7993541787 0.1583275985 -0.088413100179 +1403637204388318976.0000000000 4.5427506106 2.0136780012 0.5008024901 0.5735241857 0.7990636977 0.1560804585 -0.0905875593903 +1403637204438319104.0000000000 4.5545895860 2.0083566095 0.5025552053 0.5753939757 0.7979173507 0.1549448864 -0.0907841189183 +1403637204488318976.0000000000 4.5655112427 2.0031373326 0.5069470850 0.5776723601 0.7965177662 0.1517910063 -0.0938806844427 +1403637204538319104.0000000000 4.5762423826 1.9976453613 0.5130318522 0.5789419085 0.7958035208 0.1505225992 -0.0941592801215 +1403637204588318976.0000000000 4.5868327470 1.9915080740 0.5206845340 0.5786228728 0.7963163211 0.1491831869 -0.0939162637896 +1403637204638319104.0000000000 4.5972300910 1.9847131479 0.5300440353 0.5776125205 0.7973189266 0.1480867628 -0.0933628199387 +1403637204688318976.0000000000 4.6075848642 1.9777249406 0.5400064396 0.5768752580 0.7980991484 0.1485588675 -0.090459653445 +1403637204738319104.0000000000 4.6175131425 1.9701209170 0.5501732679 0.5764734032 0.7986132713 0.1475026599 -0.0902121031691 +1403637204788318976.0000000000 4.6271965761 1.9622013173 0.5585669346 0.5750408664 0.7998885850 0.1471086216 -0.0886865658745 +1403637204838319104.0000000000 4.6366692446 1.9535274221 0.5657381011 0.5736173923 0.8011007361 0.1461276829 -0.0885855414342 +1403637204888318976.0000000000 4.6457128411 1.9448784192 0.5710719404 0.5732463361 0.8015329787 0.1460160129 -0.0872516254552 +1403637204938319104.0000000000 4.6544113969 1.9359208275 0.5746776015 0.5716766570 0.8027291801 0.1461304384 -0.086357154863 +1403637204988318976.0000000000 4.6626706806 1.9267949722 0.5764581360 0.5689145800 0.8047663836 0.1461565835 -0.0855892608545 +1403637205038319104.0000000000 4.6704766556 1.9176413015 0.5768741588 0.5662877706 0.8066451689 0.1464547202 -0.0848100657831 +1403637205088318976.0000000000 4.6776615227 1.9088575008 0.5760009853 0.5645648820 0.8078439551 0.1468570495 -0.0841881539892 +1403637205138319104.0000000000 4.6843006053 1.9002913428 0.5742097996 0.5643115026 0.8080378639 0.1467471089 -0.0842177215367 +1403637205188318976.0000000000 4.6904704789 1.8920588987 0.5710986540 0.5644255981 0.8078924926 0.1474096957 -0.0836889853792 +1403637205238319104.0000000000 4.6958420969 1.8837778098 0.5668663532 0.5635544581 0.8081587750 0.1487733662 -0.0845709912115 +1403637205288318976.0000000000 4.7005988745 1.8755580884 0.5619751435 0.5628054063 0.8080763766 0.1513377647 -0.0857876748782 +1403637205338319104.0000000000 4.7042840314 1.8677322343 0.5580577474 0.5633919694 0.8067877349 0.1547752935 -0.087907042455 +1403637205388318976.0000000000 4.7074199275 1.8602942390 0.5553615858 0.5633176014 0.8059919185 0.1582934241 -0.0894063712268 +1403637205438319104.0000000000 4.7098569324 1.8533029259 0.5546320761 0.5641399190 0.8046018619 0.1616359593 -0.0907513761094 +1403637205488318976.0000000000 4.7114476202 1.8465000587 0.5559208118 0.5660352153 0.8024282859 0.1645716956 -0.0928931539442 +1403637205538319104.0000000000 4.7123849980 1.8398576465 0.5586046759 0.5682224937 0.8001008444 0.1670537124 -0.0951572052409 +1403637205588318976.0000000000 4.7128668469 1.8333230903 0.5607722062 0.5695398087 0.7984896854 0.1696313473 -0.0962488165955 +1403637205638319104.0000000000 4.7126554415 1.8266238145 0.5614926451 0.5705528108 0.7972041311 0.1711315803 -0.0982295560297 +1403637205688318976.0000000000 4.7121118210 1.8196044716 0.5601777522 0.5708518786 0.7965373097 0.1727952781 -0.0989860536212 +1403637205738319104.0000000000 4.7109020083 1.8126358636 0.5570150244 0.5703344129 0.7965609475 0.1736155684 -0.100334185758 +1403637205788318976.0000000000 4.7092816660 1.8052975460 0.5522181500 0.5703618810 0.7962661401 0.1745446015 -0.100904612857 +1403637205838319104.0000000000 4.7070808383 1.7976547396 0.5462365034 0.5702541648 0.7961458904 0.1754282434 -0.10092987761 +1403637205888318976.0000000000 4.7042513463 1.7898864730 0.5393232463 0.5700347310 0.7961623785 0.1754382450 -0.10201614887 +1403637205938319104.0000000000 4.7009886733 1.7821205210 0.5319948314 0.5702131839 0.7959523954 0.1755892484 -0.102396899047 +1403637205988318976.0000000000 4.6973415273 1.7739335912 0.5255093820 0.5706706784 0.7954750767 0.1761571933 -0.102581783744 +1403637206038319104.0000000000 4.6931938407 1.7650969591 0.5204501140 0.5707094784 0.7953702849 0.1758645047 -0.103674862101 +1403637206088318976.0000000000 4.6888476139 1.7553919126 0.5170169285 0.5704919674 0.7954701066 0.1752364147 -0.105159039818 +1403637206138319104.0000000000 4.6842253016 1.7447921142 0.5145845096 0.5697105630 0.7959834842 0.1735825156 -0.108209415393 +1403637206188318976.0000000000 4.6790641671 1.7343757656 0.5146113980 0.5688350468 0.7965478489 0.1710240964 -0.112645338786 +1403637206238319104.0000000000 4.6741413504 1.7240229442 0.5166976763 0.5682868805 0.7968750786 0.1699581098 -0.114692508021 +1403637206288318976.0000000000 4.6693936072 1.7138713335 0.5212006501 0.5684120308 0.7967893730 0.1684836657 -0.116823425272 +1403637206338319104.0000000000 4.6648372872 1.7038114381 0.5272518131 0.5686798189 0.7966441949 0.1671593450 -0.118402042718 +1403637206388318976.0000000000 4.6604095281 1.6940466462 0.5351786318 0.5686746987 0.7966036596 0.1672661816 -0.118548391757 +1403637206438319104.0000000000 4.6561575515 1.6847465505 0.5445647946 0.5685449899 0.7967694797 0.1670204754 -0.118402497643 +1403637206488318976.0000000000 4.6522685547 1.6755087465 0.5546488030 0.5687885932 0.7966271166 0.1670918296 -0.118089347023 +1403637206538319104.0000000000 4.6487623973 1.6662307382 0.5641552612 0.5691512761 0.7964629612 0.1667043098 -0.117996819637 +1403637206588318976.0000000000 4.6456115823 1.6569528790 0.5722473415 0.5694948288 0.7963059709 0.1669707331 -0.117018011129 +1403637206638319104.0000000000 4.6430620654 1.6469379241 0.5787881633 0.5697854722 0.7961843366 0.1674006091 -0.115810422236 +1403637206688318976.0000000000 4.6408644127 1.6369396746 0.5836261220 0.5701960145 0.7960220664 0.1678867318 -0.114190280103 +1403637206738319104.0000000000 4.6388414035 1.6267394300 0.5871220155 0.5708463339 0.7956410210 0.1679610088 -0.113485365841 +1403637206788318976.0000000000 4.6371354187 1.6163101811 0.5892321738 0.5719183949 0.7949692976 0.1680449183 -0.112667967619 +1403637206838319104.0000000000 4.6355177594 1.6055826922 0.5909244546 0.5720893774 0.7949451692 0.1679773258 -0.112069354689 +1403637206888318976.0000000000 4.6340425084 1.5945282828 0.5940033799 0.5731541857 0.7943011299 0.1676135641 -0.111739373351 +1403637206938319104.0000000000 4.6329455518 1.5824373190 0.5980421732 0.5744593102 0.7933748505 0.1670955719 -0.112391802592 +1403637206988318976.0000000000 4.6319451012 1.5704400854 0.6027702546 0.5747213463 0.7933248046 0.1666533660 -0.112061519378 +1403637207038319104.0000000000 4.6309031352 1.5590040948 0.6095944930 0.5751392552 0.7931800089 0.1660704764 -0.111807457232 +1403637207088318976.0000000000 4.6301078476 1.5467251917 0.6168523592 0.5744394305 0.7938183637 0.1655881720 -0.111589889813 +1403637207138319104.0000000000 4.6294244808 1.5341392052 0.6233921879 0.5756565793 0.7931634950 0.1645422701 -0.111521362677 +1403637207188318976.0000000000 4.6288848678 1.5209261144 0.6280943271 0.5755601082 0.7934392350 0.1637456901 -0.111229902449 +1403637207238319104.0000000000 4.6283978952 1.5073957700 0.6314141078 0.5769666525 0.7925693690 0.1628180371 -0.111505892441 +1403637207288318976.0000000000 4.6282390664 1.4934214105 0.6323592687 0.5765571545 0.7930501947 0.1621160878 -0.111227740709 +1403637207338319104.0000000000 4.6284702445 1.4790741147 0.6316211134 0.5762131859 0.7934476517 0.1615270566 -0.111032420459 +1403637207388318976.0000000000 4.6291788319 1.4643941824 0.6293110261 0.5763139206 0.7934730409 0.1614713113 -0.110407490403 +1403637207438319104.0000000000 4.6302412663 1.4492665848 0.6257373047 0.5765043351 0.7934803647 0.1610240642 -0.110013241256 +1403637207488318976.0000000000 4.6315571051 1.4335387428 0.6206489929 0.5761203832 0.7939016256 0.1604130196 -0.109878005784 +1403637207538319104.0000000000 4.6332204991 1.4171517967 0.6139171809 0.5742971813 0.7953388966 0.1597850855 -0.109943229454 +1403637207588318976.0000000000 4.6347762960 1.4003752877 0.6065628310 0.5705910502 0.7981242699 0.1578569793 -0.111824314818 +1403637207638319104.0000000000 4.6364833032 1.3833533294 0.5994895890 0.5642089343 0.8026769919 0.1556565483 -0.114668933019 +1403637207688318976.0000000000 4.6389786464 1.3667452293 0.5941175658 0.5593581834 0.8061088685 0.1539457366 -0.11665172511 +1403637207738319104.0000000000 4.6419423263 1.3515746625 0.5905400773 0.5568736061 0.8078672172 0.1538490172 -0.116502472268 +1403637207788318976.0000000000 4.6456802046 1.3374027930 0.5896922097 0.5572372349 0.8076807075 0.1544394011 -0.115269294342 +1403637207838319104.0000000000 4.6502568799 1.3236008704 0.5913342473 0.5588459783 0.8066756607 0.1552997349 -0.113347003484 +1403637207888318976.0000000000 4.6554520729 1.3105289611 0.5949075558 0.5607241409 0.8054860758 0.1567361044 -0.110518835889 +1403637207938319104.0000000000 4.6602979934 1.2991379307 0.6016153057 0.5630199323 0.8039424733 0.1577603070 -0.108612803288 +1403637207988318976.0000000000 4.6654313800 1.2877953848 0.6111197429 0.5646814652 0.8028364907 0.1586215614 -0.106900011232 +1403637208038319104.0000000000 4.6709493239 1.2759987787 0.6224952669 0.5659424054 0.8019894155 0.1596399418 -0.105058365783 +1403637208088318976.0000000000 4.6760357645 1.2649791393 0.6352381046 0.5665424544 0.8016235309 0.1604320152 -0.103396956463 +1403637208138319104.0000000000 4.6809279105 1.2539439202 0.6499142290 0.5667513123 0.8015159988 0.1609895354 -0.1022126364 +1403637208188318976.0000000000 4.6855391880 1.2432980039 0.6658605283 0.5683394975 0.8004651737 0.1615213698 -0.10077980144 +1403637208238319104.0000000000 4.6899556734 1.2324033679 0.6812485762 0.5673386732 0.8012889264 0.1612699075 -0.100274140563 +1403637208288318976.0000000000 4.6935909814 1.2214414741 0.6961132735 0.5666444899 0.8019541347 0.1580210291 -0.103985298138 +1403637208338319104.0000000000 4.6972932916 1.2108528166 0.7094512676 0.5664771553 0.8022322474 0.1546043679 -0.107817175089 +1403637208388318976.0000000000 4.7011747284 1.2005920653 0.7208366224 0.5664881951 0.8023467622 0.1519553005 -0.11063627185 +1403637208438319104.0000000000 4.7054957948 1.1907178405 0.7302873750 0.5674252402 0.8018643331 0.1507770416 -0.110943552824 +1403637208488318976.0000000000 4.7104883919 1.1810413528 0.7373291423 0.5677257565 0.8017610336 0.1506846080 -0.110276286445 +1403637208538319104.0000000000 4.7158919840 1.1719028438 0.7429384432 0.5691048642 0.8008756193 0.1508048189 -0.109434009656 +1403637208588318976.0000000000 4.7221362500 1.1627533687 0.7468617048 0.5698970307 0.8004536459 0.1520423544 -0.106651102302 +1403637208638319104.0000000000 4.7285927716 1.1535807083 0.7496107941 0.5706692254 0.7999236245 0.1530854190 -0.104993736295 +1403637208688318976.0000000000 4.7351979203 1.1444905172 0.7509797900 0.5716035432 0.7993181644 0.1542506538 -0.102793955898 +1403637208738319104.0000000000 4.7417910208 1.1353242527 0.7513379380 0.5729585623 0.7983651788 0.1546852510 -0.10200000141 +1403637208788318976.0000000000 4.7483488293 1.1258549854 0.7504571758 0.5740475666 0.7975799958 0.1549008500 -0.10169202646 +1403637208838319104.0000000000 4.7550118795 1.1162079795 0.7480902466 0.5744706135 0.7973004530 0.1552787178 -0.10091591374 +1403637208888318976.0000000000 4.7618370191 1.1064270066 0.7441051981 0.5745108257 0.7972740669 0.1565307851 -0.0989418350423 +1403637208938319104.0000000000 4.7687969290 1.0965318569 0.7383785903 0.5754593202 0.7965184945 0.1595518711 -0.0945941813425 +1403637208988318976.0000000000 4.7756369360 1.0862783861 0.7309814843 0.5763332062 0.7958096157 0.1632215873 -0.0888020518014 +1403637209038319104.0000000000 4.7819583020 1.0756621345 0.7218664382 0.5771894638 0.7950241253 0.1670097680 -0.0830463751995 +1403637209088318976.0000000000 4.7871419344 1.0643222237 0.7118613677 0.5779231743 0.7940900039 0.1710338740 -0.0785702502782 +1403637209138319104.0000000000 4.7905891677 1.0518124854 0.7026422756 0.5789262664 0.7926141624 0.1747885296 -0.0778211891501 +1403637209188318976.0000000000 4.7917747543 1.0378859196 0.6943355260 0.5766194995 0.7931653142 0.1776897531 -0.082614095675 +1403637209238319104.0000000000 4.7909614948 1.0228093572 0.6882201577 0.5736637995 0.7938497586 0.1797950028 -0.0915759952957 +1403637209288318976.0000000000 4.7892762877 1.0069004644 0.6836180759 0.5687281245 0.7955592784 0.1836401093 -0.0995493101107 +1403637209338319104.0000000000 4.7872389794 0.9903799646 0.6810298111 0.5643399647 0.7967976836 0.1879131142 -0.106407317497 +1403637209388318976.0000000000 4.7850109332 0.9736289386 0.6797757901 0.5597932265 0.7982583139 0.1925565715 -0.111072834897 +1403637209438319104.0000000000 4.7822109085 0.9573798721 0.6799745899 0.5552479807 0.7998776506 0.1971188292 -0.114191028774 +1403637209488318976.0000000000 4.7787997364 0.9414434851 0.6812777988 0.5488821881 0.8027497900 0.2021930277 -0.115927122831 +1403637209538319104.0000000000 4.7747387545 0.9261785385 0.6838172201 0.5414163520 0.8063906208 0.2076020640 -0.116206210783 +1403637209588318976.0000000000 4.7696789759 0.9124810534 0.6879010954 0.5333081099 0.8105394072 0.2126605154 -0.115688523811 +1403637209638319104.0000000000 4.7631152786 0.9005753281 0.6942177832 0.5257774175 0.8143725999 0.2167419712 -0.115664573792 +1403637209688318976.0000000000 4.7553087957 0.8898746322 0.7025797487 0.5201812209 0.8170847949 0.2198186210 -0.116033224594 +1403637209738319104.0000000000 4.7451589948 0.8823712699 0.7124685830 0.5159424042 0.8191202325 0.2219929046 -0.116467293826 +1403637209788318976.0000000000 4.7325146794 0.8785235226 0.7237717024 0.5133380956 0.8203336866 0.2235090001 -0.116534841079 +1403637209838319104.0000000000 4.7180168217 0.8769263958 0.7349707635 0.5109808838 0.8215406892 0.2246494731 -0.116198307231 +1403637209888318976.0000000000 4.7014985746 0.8775475357 0.7453833306 0.5081272501 0.8231997796 0.2245552358 -0.117148481595 +1403637209938319104.0000000000 4.6835484850 0.8802834796 0.7530045068 0.5046148755 0.8253196671 0.2249206352 -0.116713248639 +1403637209988318976.0000000000 4.6643668847 0.8853408013 0.7557112608 0.5003953618 0.8277852161 0.2260026338 -0.115320975777 +1403637210038319104.0000000000 4.6437066622 0.8922873698 0.7542661975 0.4951496141 0.8308552906 0.2272093645 -0.113500001539 +1403637210088318976.0000000000 4.6212254509 0.9021789786 0.7491037781 0.4902251495 0.8338056675 0.2280954520 -0.11144449934 +1403637210138319104.0000000000 4.5967727004 0.9145928776 0.7402672249 0.4851374821 0.8368451755 0.2281313856 -0.11085056002 +1403637210188318976.0000000000 4.5701433141 0.9305086397 0.7285209000 0.4796729964 0.8400161503 0.2287973563 -0.109263230358 +1403637210238319104.0000000000 4.5407756934 0.9501542587 0.7152874096 0.4750234211 0.8426808593 0.2292474067 -0.108108026191 +1403637210288318976.0000000000 4.5085909893 0.9741273034 0.7014398791 0.4713732761 0.8446782073 0.2301395437 -0.10659151546 +1403637210338319104.0000000000 4.4733676119 1.0025342898 0.6875878945 0.4690326178 0.8459915882 0.2301804264 -0.106412440222 +1403637210388318976.0000000000 4.4350826528 1.0352698301 0.6735759783 0.4671955673 0.8470212567 0.2303368649 -0.105963301223 +1403637210438319104.0000000000 4.3934375766 1.0730188982 0.6599679359 0.4687244850 0.8461202163 0.2303264077 -0.106431586345 +1403637210488318976.0000000000 4.3484872757 1.1159719844 0.6472028835 0.4740510389 0.8430812912 0.2301368918 -0.107361818057 +1403637210538319104.0000000000 4.3006068793 1.1630708287 0.6351065135 0.4812723159 0.8389213495 0.2293940681 -0.109390533229 +1403637210588318976.0000000000 4.2503022960 1.2133614167 0.6225614602 0.4873438473 0.8353995339 0.2281573206 -0.112017098088 +1403637210638319104.0000000000 4.1978192952 1.2666478490 0.6095928582 0.4933536633 0.8318329402 0.2266842488 -0.115197108764 +1403637210688318976.0000000000 4.1436876950 1.3226525946 0.5956639341 0.4981693592 0.8288362057 0.2260429303 -0.117313372486 +1403637210738319104.0000000000 4.0877230023 1.3811818508 0.5808124565 0.5009698153 0.8270401166 0.2251547813 -0.119746457822 +1403637210788318976.0000000000 4.0297662600 1.4419376364 0.5655800123 0.5026164682 0.8260644223 0.2218433218 -0.125617660562 +1403637210838319104.0000000000 3.9707160254 1.5048510895 0.5495093384 0.5046118691 0.8248620262 0.2189219101 -0.130547679308 +1403637210888318976.0000000000 3.9108046448 1.5697438171 0.5326664852 0.5065621065 0.8237673534 0.2150402871 -0.136234557918 +1403637210938319104.0000000000 3.8499453326 1.6369948113 0.5154993024 0.5108277822 0.8211759444 0.2104847775 -0.142902777219 +1403637210988318976.0000000000 3.7891842073 1.7063361963 0.4972090738 0.5161189893 0.8179263294 0.2066214595 -0.148071878087 +1403637211038319104.0000000000 3.7287867969 1.7774810910 0.4783253794 0.5216785183 0.8144641537 0.2029209227 -0.152717926618 +1403637211088318976.0000000000 3.6690067170 1.8501975727 0.4586307755 0.5262675279 0.8116322919 0.1988312905 -0.157358284796 +1403637211138319104.0000000000 3.6104839481 1.9243388419 0.4371916345 0.5297454722 0.8095871486 0.1980003600 -0.157271233687 +1403637211188318976.0000000000 3.5528910369 2.0002645263 0.4148261671 0.5340778226 0.8070955411 0.1992837621 -0.153764914969 +1403637211238319104.0000000000 3.4840278010 2.0685834818 0.3982008004 0.5389800048 0.8041640988 0.2000157002 -0.151044285902 +1403637211288318976.0000000000 3.4271998513 2.1458772483 0.3750846235 0.5449615382 0.8006167884 0.2003809857 -0.147909230714 +1403637211338319104.0000000000 3.3711120452 2.2235321436 0.3512594694 0.5508080811 0.7971261897 0.1999998448 -0.145603425849 +1403637211388318976.0000000000 3.3156212466 2.3011712837 0.3267105316 0.5555405968 0.7942434623 0.1992438133 -0.144408693227 +1403637211438319104.0000000000 3.2609545966 2.3781608812 0.3010737905 0.5581142321 0.7927623812 0.1987811150 -0.143256340657 +1403637211488318976.0000000000 3.2068833424 2.4549394262 0.2745998747 0.5594596758 0.7920707072 0.1980182835 -0.142890256478 +1403637211538319104.0000000000 3.1537254665 2.5307788561 0.2479422326 0.5574546865 0.7935722638 0.1975109888 -0.143096974298 +1403637211588318976.0000000000 3.1015542755 2.6063452211 0.2222970442 0.5548943005 0.7955051835 0.1972835354 -0.142628976927 +1403637211638319104.0000000000 3.0502233831 2.6817031813 0.1989932398 0.5524289281 0.7972026544 0.1970874440 -0.142992120791 +1403637211688318976.0000000000 2.9996184533 2.7565532177 0.1776692749 0.5503519872 0.7986185951 0.1962616862 -0.144230302673 +1403637211738319104.0000000000 2.9494469568 2.8318372353 0.1576118715 0.5446490054 0.8024692567 0.1954701696 -0.145574605637 +1403637211788318976.0000000000 2.9000892717 2.9070323797 0.1404334373 0.5387635216 0.8063353886 0.1938326348 -0.148276830451 +1403637211838319104.0000000000 2.8515074188 2.9827337619 0.1252792067 0.5332092027 0.8099406048 0.1913468470 -0.151889917461 +1403637211888318976.0000000000 2.8040181064 3.0601694423 0.1121012222 0.5297100981 0.8122700542 0.1907540038 -0.152438449843 +1403637211938319104.0000000000 2.7581514739 3.1384723549 0.1007790446 0.5289800052 0.8128503010 0.1914927842 -0.150947195514 +1403637211988318976.0000000000 2.7128949797 3.2186128144 0.0914854264 0.5312166670 0.8114536927 0.1928812689 -0.148823967742 +1403637212038319104.0000000000 2.6682652655 3.3006292398 0.0849700863 0.5363911136 0.8082401798 0.1946588640 -0.145397083044 +1403637212088318976.0000000000 2.6241565343 3.3833819078 0.0804746263 0.5439321872 0.8033259482 0.1952424563 -0.143824823539 +1403637212138319104.0000000000 2.5807932504 3.4659310473 0.0779145410 0.5515676970 0.7981504123 0.1951948623 -0.143624373248 +1403637212188318976.0000000000 2.5383552020 3.5481241985 0.0769159038 0.5582413323 0.7937094646 0.1951253005 -0.142541284218 +1403637212238319104.0000000000 2.4968575328 3.6293832625 0.0768414329 0.5631185529 0.7904112613 0.1944632039 -0.142588904563 +1403637212288318976.0000000000 2.4562864494 3.7098227422 0.0778102029 0.5661026796 0.7883824994 0.1945962427 -0.141820636948 +1403637212338319104.0000000000 2.4164526278 3.7893834369 0.0805888985 0.5688206509 0.7865951302 0.1938831462 -0.141846726576 +1403637212388318976.0000000000 2.3776344572 3.8677217326 0.0850197874 0.5702532385 0.7857972922 0.1932414570 -0.141391650287 +1403637212438319104.0000000000 2.3400420144 3.9444219461 0.0907462837 0.5713124401 0.7852871936 0.1929787601 -0.140304374721 +1403637212488318976.0000000000 2.2959630955 4.0220489227 0.0995092380 0.5694980263 0.7867847104 0.1930919733 -0.139130541252 +1403637212538319104.0000000000 2.2595588669 4.0964885847 0.1073101933 0.5665270026 0.7891561437 0.1934375753 -0.1373376884 +1403637212588318976.0000000000 2.2242233965 4.1703835439 0.1158411576 0.5628693381 0.7919984656 0.1932948709 -0.136211716382 +1403637212638319104.0000000000 2.1893076413 4.2436622894 0.1248557655 0.5587277063 0.7951677510 0.1938459867 -0.133997505482 +1403637212688318976.0000000000 2.1549136090 4.3169960013 0.1344310564 0.5550569995 0.7977868479 0.1944027128 -0.132873842054 +1403637212738319104.0000000000 2.1207431414 4.3907567992 0.1443784901 0.5528710310 0.7993957690 0.1956789347 -0.130421555134 +1403637212788318976.0000000000 2.0867475669 4.4647565404 0.1552476759 0.5522038113 0.7998695266 0.1967047747 -0.128790227647 +1403637212838319104.0000000000 2.0528312381 4.5388352759 0.1660957340 0.5502295144 0.8012212491 0.1980385069 -0.126778315269 +1403637212888318976.0000000000 2.0186910588 4.6129817262 0.1778657875 0.5502848591 0.8011306045 0.1993381811 -0.125062455947 +1403637212938319104.0000000000 1.9844848249 4.6869876137 0.1902918033 0.5506557214 0.8007344332 0.2011759646 -0.123007622569 +1403637212988318976.0000000000 1.9501257751 4.7605501943 0.2032022251 0.5509232945 0.8002732247 0.2030832466 -0.121669570554 +1403637213038319104.0000000000 1.9149213658 4.8340349622 0.2166225481 0.5505129652 0.8003455767 0.2037283786 -0.121972049193 +1403637213088318976.0000000000 1.8790170553 4.9071777348 0.2297352458 0.5501585224 0.8003457802 0.2034333281 -0.124044803773 +1403637213138319104.0000000000 1.8429638483 4.9798961216 0.2411653950 0.5487621238 0.8010317009 0.2033105025 -0.125988829901 +1403637213188318976.0000000000 1.8064675836 5.0527507209 0.2508012629 0.5480412877 0.8012653232 0.2029180170 -0.128253292885 +1403637213238319104.0000000000 1.7697474545 5.1252146054 0.2589262078 0.5480915409 0.8010244245 0.2028499722 -0.129643445248 +1403637213288318976.0000000000 1.7328515965 5.1976570729 0.2656819394 0.5476170363 0.8011733625 0.2028182570 -0.130773007151 +1403637213338319104.0000000000 1.6956659667 5.2701778629 0.2715738884 0.5487193019 0.8003520425 0.2027034006 -0.1313585444 +1403637213388318976.0000000000 1.6585600058 5.3427047639 0.2761124220 0.5500456892 0.7993691171 0.2029980038 -0.13134140597 +1403637213438319104.0000000000 1.6213304568 5.4153749983 0.2796218407 0.5520383710 0.7979482989 0.2027873426 -0.131944847805 +1403637213488318976.0000000000 1.5844428558 5.4877227791 0.2816817100 0.5538316296 0.7967587769 0.2027983673 -0.131600911036 +1403637213538319104.0000000000 1.5477699121 5.5603266671 0.2826960341 0.5555728220 0.7954774195 0.2034145822 -0.13106113932 +1403637213588318976.0000000000 1.5112924970 5.6328413698 0.2822109733 0.5590359049 0.7929498801 0.2071926165 -0.125620716247 +1403637213638319104.0000000000 1.4746761558 5.7043797132 0.2800204458 0.5608381356 0.7915220229 0.2104898866 -0.121026775982 +1403637213688318976.0000000000 1.4378564015 5.7747702325 0.2760962381 0.5612454932 0.7909328427 0.2145758820 -0.115697561264 +1403637213738319104.0000000000 1.4003224049 5.8439776068 0.2712594347 0.5619542239 0.7902262992 0.2172823608 -0.11197420242 +1403637213788318976.0000000000 1.3619822200 5.9117351629 0.2645693739 0.5606251652 0.7909184944 0.2196603383 -0.109071972504 +1403637213838319104.0000000000 1.3226065601 5.9782587441 0.2568489117 0.5602849752 0.7908378113 0.2215324426 -0.107608919714 +1403637213888318976.0000000000 1.2820665742 6.0439722589 0.2481307660 0.5601966361 0.7906824357 0.2229593155 -0.106255157137 +1403637213938319104.0000000000 1.2400797183 6.1081810021 0.2384295395 0.5592658446 0.7911813157 0.2238242753 -0.105624498028 +1403637213988318976.0000000000 1.1960761975 6.1720511140 0.2300619108 0.5616685024 0.7892610833 0.2244600577 -0.105892012631 +1403637214038319104.0000000000 1.1500167664 6.2344155078 0.2236306544 0.5640906526 0.7869468985 0.2250450185 -0.108954367644 +1403637214088318976.0000000000 1.1022588914 6.2952802951 0.2186838439 0.5663955649 0.7843040887 0.2255505238 -0.114848254701 +1403637214138319104.0000000000 1.0529909618 6.3548402084 0.2156585325 0.5669724278 0.7826614221 0.2254182298 -0.123166497562 +1403637214188318976.0000000000 1.0031092018 6.4128482681 0.2141196828 0.5678392539 0.7802291469 0.2271686407 -0.131131493549 +1403637214238319104.0000000000 0.9529355642 6.4696660180 0.2143342153 0.5686487532 0.7773985899 0.2309039289 -0.137743978424 +1403637214288318976.0000000000 0.9025625143 6.5251489127 0.2161823616 0.5701814497 0.7734827323 0.2367137967 -0.143471793822 +1403637214338319104.0000000000 0.8520339849 6.5783234304 0.2197809782 0.5718271975 0.7688293592 0.2437865373 -0.149943979169 +1403637214388318976.0000000000 0.8018386966 6.6295486075 0.2243414143 0.5743958813 0.7627596914 0.2537071619 -0.154595280575 +1403637214438319104.0000000000 0.7519265078 6.6781903098 0.2296014464 0.5760635395 0.7565817602 0.2661361838 -0.157817521705 +1403637214488318976.0000000000 0.7022994872 6.7240022864 0.2360623329 0.5771179782 0.7501844444 0.2794788870 -0.161399164655 +1403637214538319104.0000000000 0.6525783920 6.7671658755 0.2440349857 0.5783902175 0.7432962182 0.2930371404 -0.164635119726 +1403637214588318976.0000000000 0.6030786879 6.8075048111 0.2532432160 0.5794947236 0.7367715426 0.3059414970 -0.166593396311 +1403637214638319104.0000000000 0.5531432188 6.8448292829 0.2641192149 0.5817279620 0.7295922282 0.3178004381 -0.168198217072 +1403637214688318976.0000000000 0.5025167123 6.8790387034 0.2765114318 0.5838706551 0.7230689826 0.3280925755 -0.169179095845 +1403637214738319104.0000000000 0.4510779555 6.9099708999 0.2902210943 0.5859978661 0.7171056612 0.3375873007 -0.16852532767 +1403637214788318976.0000000000 0.3988688049 6.9366321675 0.3057077896 0.5876527743 0.7122485360 0.3441447854 -0.170089995373 +1403637214838319104.0000000000 0.3455739551 6.9590597087 0.3222998478 0.5875685537 0.7096381305 0.3485701871 -0.172266488338 +1403637214888318976.0000000000 0.2916613139 6.9771486807 0.3384544978 0.5869345396 0.7081881380 0.3515418864 -0.174343653382 +1403637214938319104.0000000000 0.2368854091 6.9911842285 0.3535260627 0.5868924846 0.7067857986 0.3534203696 -0.176366348433 +1403637214988318976.0000000000 0.1816842458 7.0010434617 0.3674374724 0.5875180923 0.7053819082 0.3541021073 -0.178523254423 +1403637215038319104.0000000000 0.1262601209 7.0068591039 0.3797729173 0.5878506207 0.7045395908 0.3540729499 -0.180798116767 +1403637215088318976.0000000000 0.0706769574 7.0085651104 0.3909365127 0.5894894522 0.7029971579 0.3537129715 -0.182165626728 +1403637215138319104.0000000000 0.0152933640 7.0062386073 0.4005749559 0.5911287581 0.7016794574 0.3529045122 -0.183496963505 +1403637215188318976.0000000000 -0.0407357552 6.9998364718 0.4089296015 0.5924492189 0.7008243425 0.3514654829 -0.185259758688 +1403637215238319104.0000000000 -0.0975768495 6.9894615031 0.4162453513 0.5926082367 0.7008551653 0.3490265093 -0.189203622942 +1403637215288318976.0000000000 -0.1543737457 6.9749217152 0.4219428452 0.5920019076 0.7006823678 0.3479976634 -0.193586123022 +1403637215338319104.0000000000 -0.2108135776 6.9559888669 0.4265186955 0.5915909481 0.6995901897 0.3468839382 -0.200662029636 +1403637215388318976.0000000000 -0.2666536526 6.9330324170 0.4298827944 0.5917350188 0.6972305623 0.3469803821 -0.208143760139 +1403637215438319104.0000000000 -0.3217756217 6.9054634643 0.4331987091 0.5917851410 0.6938545743 0.3465933370 -0.219611555674 +1403637215488318976.0000000000 -0.3751820070 6.8737544190 0.4372213942 0.5924227059 0.6889730642 0.3478178159 -0.231028615567 +1403637215538319104.0000000000 -0.4261059591 6.8376151717 0.4414253104 0.5919355107 0.6841194313 0.3513871039 -0.241081019706 +1403637215588318976.0000000000 -0.4742605812 6.7974724704 0.4458597917 0.5893583270 0.6802577775 0.3570635045 -0.249823482118 +1403637215638319104.0000000000 -0.5197806199 6.7528111829 0.4518914037 0.5848363830 0.6768833583 0.3645660267 -0.25862508884 +1403637215688318976.0000000000 -0.5622617229 6.7044301259 0.4591995384 0.5799965742 0.6729225012 0.3747850057 -0.265170663407 +1403637215738319104.0000000000 -0.6016904389 6.6522815265 0.4669777419 0.5711326043 0.6717791872 0.3863743405 -0.270619919924 +1403637215788318976.0000000000 -0.6391068483 6.5972993082 0.4762445603 0.5609372629 0.6711582805 0.3982784531 -0.276170641936 +1403637215838319104.0000000000 -0.6736019261 6.5389092966 0.4869539676 0.5507723745 0.6702165968 0.4100424550 -0.281646391713 +1403637215888318976.0000000000 -0.7064520765 6.4786052011 0.4997418621 0.5417085445 0.6685705516 0.4203784747 -0.287831909991 +1403637215938319104.0000000000 -0.7379082903 6.4167646783 0.5145683874 0.5332972717 0.6672473701 0.4285546306 -0.294475628427 +1403637215988318976.0000000000 -0.7668903538 6.3531859879 0.5310121151 0.5251947468 0.6662776947 0.4360337188 -0.300198446973 +1403637216038319104.0000000000 -0.7945977821 6.2884637136 0.5494021161 0.5184921413 0.6641291197 0.4418641275 -0.307984584905 +1403637216088318976.0000000000 -0.8207951280 6.2230215921 0.5686220277 0.5119243989 0.6616970601 0.4483611341 -0.314742281732 +1403637216138319104.0000000000 -0.8453762133 6.1571513239 0.5872355688 0.5061674005 0.6591040202 0.4539127411 -0.321464891862 +1403637216188318976.0000000000 -0.8687033539 6.0914319038 0.6049046861 0.5022479285 0.6559929188 0.4581523592 -0.327897430019 +1403637216238319104.0000000000 -0.8905316039 6.0263730819 0.6207152465 0.4981009942 0.6542863224 0.4612197383 -0.333288405075 +1403637216288318976.0000000000 -0.9107535876 5.9616523637 0.6353509604 0.4958009612 0.6521736608 0.4627076525 -0.338751459449 +1403637216338319104.0000000000 -0.9296413775 5.8975898158 0.6480611797 0.4949802425 0.6500303684 0.4638498903 -0.342488480113 +1403637216388318976.0000000000 -0.9473744525 5.8337385206 0.6596416518 0.4957398061 0.6474239201 0.4636717966 -0.346544048149 +1403637216438319104.0000000000 -0.9630905546 5.7698336944 0.6695857822 0.4981150988 0.6442781152 0.4628591353 -0.35006924959 +1403637216488318976.0000000000 -0.9767531608 5.7062250814 0.6777132538 0.5003709892 0.6417006936 0.4624242099 -0.352154714662 +1403637216538319104.0000000000 -0.9885624292 5.6429006259 0.6847094399 0.5029415337 0.6395173217 0.4607802663 -0.354610991266 +1403637216588318976.0000000000 -0.9979163259 5.5796830723 0.6903236413 0.5030964673 0.6391609819 0.4587872693 -0.357605124748 +1403637216638319104.0000000000 -1.0049703800 5.5167251147 0.6954105144 0.5038648616 0.6387160007 0.4562845085 -0.360508694748 +1403637216688318976.0000000000 -1.0091634503 5.4537127259 0.6997639046 0.5053976611 0.6380422537 0.4524682450 -0.364345679142 +1403637216738319104.0000000000 -1.0102415234 5.3906480768 0.7029561978 0.5083355086 0.6364275104 0.4490688214 -0.367276773427 +1403637216788318976.0000000000 -1.0083950186 5.3280088773 0.7056489046 0.5117508227 0.6347277750 0.4462222188 -0.368941023099 +1403637216838319104.0000000000 -1.0031532027 5.2657802593 0.7093283859 0.5156714255 0.6327060592 0.4443059994 -0.369267115267 +1403637216888318976.0000000000 -0.9944472715 5.2037020443 0.7144256766 0.5194746504 0.6308855841 0.4427696558 -0.368896325933 +1403637216938319104.0000000000 -0.9817098958 5.1416496332 0.7213432416 0.5225229958 0.6298865323 0.4419689153 -0.367254888512 +1403637216988318976.0000000000 -0.9648709177 5.0791020865 0.7300173677 0.5226633896 0.6311547985 0.4416199089 -0.365292290611 +1403637217038319104.0000000000 -0.9434199737 5.0154860822 0.7391255207 0.5187541599 0.6351822514 0.4410968454 -0.364515023088 +1403637217088318976.0000000000 -0.9185112530 4.9513849582 0.7487873758 0.5119809155 0.6411562455 0.4393647927 -0.365722285325 +1403637217138319104.0000000000 -0.8903906482 4.8869365748 0.7580431198 0.5060024239 0.6465173127 0.4373419244 -0.367027182325 +1403637217188318976.0000000000 -0.8594735011 4.8230861367 0.7664534141 0.5006011807 0.6512800220 0.4338737563 -0.370116676902 +1403637217238319104.0000000000 -0.8258102048 4.7601447796 0.7732635413 0.4964182480 0.6551070448 0.4299892380 -0.373514307897 +1403637217288318976.0000000000 -0.7894190595 4.6989305673 0.7775846172 0.4934745384 0.6581743691 0.4275394678 -0.374832473688 +1403637217338319104.0000000000 -0.7505490632 4.6396134205 0.7795788287 0.4906298000 0.6611246383 0.4252541074 -0.375972813012 +1403637217388318976.0000000000 -0.7091422034 4.5823712857 0.7795371271 0.4889040060 0.6632582652 0.4227913587 -0.377238404102 +1403637217438319104.0000000000 -0.6650802884 4.5273026690 0.7774846542 0.4875450766 0.6652261159 0.4207799849 -0.37778064705 +1403637217488318976.0000000000 -0.6181994317 4.4740934540 0.7736749612 0.4867575018 0.6662302044 0.4198385319 -0.378074141294 +1403637217538319104.0000000000 -0.5689827773 4.4246791520 0.7681588062 0.4880211322 0.6646918743 0.4204921457 -0.378426270439 +1403637217588318976.0000000000 -0.5170516485 4.3765293584 0.7619239794 0.4900756761 0.6612613109 0.4231347038 -0.378835495654 +1403637217638319104.0000000000 -0.4619808409 4.3307304339 0.7541308252 0.4936314074 0.6557090870 0.4284211339 -0.377927187246 +1403637217688318976.0000000000 -0.4045264943 4.2861132260 0.7457562198 0.5001993249 0.6464187556 0.4366909419 -0.37582502438 +1403637217738319104.0000000000 -0.3439411881 4.2428059274 0.7374172303 0.5059597254 0.6358829879 0.4475602788 -0.373292618179 +1403637217788318976.0000000000 -0.2798786847 4.1988103725 0.7310112613 0.5103151197 0.6245483911 0.4590783223 -0.37251158347 +1403637217838319104.0000000000 -0.2126712063 4.1535761667 0.7255447623 0.5082389076 0.6163767359 0.4713399716 -0.373646307877 +1403637217888318976.0000000000 -0.1425507650 4.1080085780 0.7217181024 0.5066585878 0.6073729374 0.4831993192 -0.375384613644 +1403637217938319104.0000000000 -0.0696783590 4.0615618627 0.7196138463 0.5022586062 0.6016102680 0.4929208111 -0.37792916256 +1403637217988318976.0000000000 0.0057903424 4.0143723189 0.7190373610 0.4971434175 0.5967410587 0.5018001783 -0.380716577354 +1403637218038319104.0000000000 0.0845824967 3.9681278202 0.7195551797 0.4918256224 0.5931122960 0.5086876995 -0.384138238023 +1403637218088318976.0000000000 0.1647550263 3.9205385666 0.7210182607 0.4850334106 0.5916497951 0.5149276128 -0.386707465933 +1403637218138319104.0000000000 0.2468887813 3.8728487752 0.7226004121 0.4807698478 0.5892726583 0.5199584721 -0.388923224938 +1403637218188318976.0000000000 0.3307478111 3.8250001670 0.7228731227 0.4768212808 0.5876843334 0.5242119226 -0.390474647923 +1403637218238319104.0000000000 0.4155799338 3.7769818333 0.7214452495 0.4739719801 0.5862729893 0.5278011327 -0.391229482992 +1403637218288318976.0000000000 0.5014068409 3.7285942358 0.7187037434 0.4718162220 0.5849478050 0.5301594691 -0.392627629435 +1403637218338319104.0000000000 0.5882147938 3.6804652021 0.7140889461 0.4719801597 0.5827961832 0.5326824067 -0.392215235875 +1403637218388318976.0000000000 0.6765860824 3.6317471108 0.7083508605 0.4709036866 0.5821698582 0.5332741840 -0.393632593699 +1403637218438319104.0000000000 0.7667574636 3.5828034090 0.7013618079 0.4701818653 0.5818066177 0.5336743666 -0.394489218561 +1403637218488318976.0000000000 0.8583581368 3.5336589474 0.6943754519 0.4709585391 0.5807467727 0.5338931414 -0.394828258812 +1403637218538319104.0000000000 0.9517660571 3.4840164658 0.6875668102 0.4708565106 0.5805503299 0.5344160846 -0.394531252749 +1403637218588318976.0000000000 1.0456618557 3.4341639214 0.6820680550 0.4713510020 0.5805334758 0.5344031569 -0.393982718237 +1403637218638319104.0000000000 1.1436107742 3.3702974566 0.6870842563 0.4695863260 0.5825314162 0.5350056315 -0.392319774952 +1403637218688318976.0000000000 1.2386098073 3.3160395496 0.6866553028 0.4693240950 0.5835072129 0.5362437830 -0.389482774397 +1403637218738319104.0000000000 1.3354945929 3.2602845487 0.6876896152 0.4660463163 0.5867289887 0.5364847935 -0.388244756919 +1403637218788318976.0000000000 1.4331381706 3.2037396676 0.6882309991 0.4650240761 0.5884880516 0.5359797987 -0.387504938213 +1403637218838319104.0000000000 1.5315955962 3.1470889505 0.6843626647 0.4662514059 0.5885696806 0.5380545897 -0.383004720617 +1403637218888318976.0000000000 1.6296692855 3.0900304260 0.6762923932 0.4678974002 0.5883726104 0.5403081355 -0.378096301191 +1403637218938319104.0000000000 1.7283521398 3.0323845276 0.6641762992 0.4705206443 0.5870115469 0.5417095787 -0.374937994289 +1403637218988318976.0000000000 1.8276287425 2.9743768240 0.6482508380 0.4728356607 0.5858845100 0.5437919651 -0.370750694771 +1403637219038319104.0000000000 1.9267471875 2.9157914607 0.6303172366 0.4746694631 0.5850160663 0.5451653461 -0.367749708963 +1403637219088318976.0000000000 2.0261127923 2.8561942842 0.6110316445 0.4755137416 0.5847026569 0.5457111402 -0.36634524149 +1403637219138319104.0000000000 2.1258612799 2.7954064093 0.5924123306 0.4762662612 0.5842518162 0.5457312197 -0.366056962104 +1403637219188318976.0000000000 2.2258934994 2.7336337885 0.5745351410 0.4758572075 0.5848551445 0.5457974308 -0.365526391015 +1403637219238319104.0000000000 2.3262860139 2.6705894511 0.5585686356 0.4751985558 0.5858057467 0.5450383186 -0.365993430181 +1403637219288318976.0000000000 2.4281936712 2.6062326636 0.5440856570 0.4737662193 0.5872158238 0.5448323147 -0.365897382523 +1403637219338319104.0000000000 2.5309092007 2.5408267685 0.5314970322 0.4725205459 0.5886356566 0.5436153787 -0.367035035699 +1403637219388318976.0000000000 2.6336698927 2.4745718598 0.5197172720 0.4708895981 0.5903505917 0.5440001910 -0.365804534396 +1403637219438319104.0000000000 2.7360572067 2.4069673158 0.5099392058 0.4690772490 0.5918687608 0.5438583486 -0.365890695533 +1403637219488318976.0000000000 2.8387036390 2.3381302356 0.5010796587 0.4623206050 0.5971368311 0.5457679842 -0.363076535312 +1403637219538319104.0000000000 2.9408349999 2.2683260904 0.4950594939 0.4575014010 0.6010260589 0.5474296901 -0.360251133116 +1403637219588318976.0000000000 3.0429439086 2.1979442819 0.4899172838 0.4512800244 0.6059196669 0.5494284323 -0.356841834078 +1403637219638319104.0000000000 3.1433591197 2.1272722723 0.4865101110 0.4464641382 0.6097813181 0.5505507259 -0.354584849627 +1403637219688318976.0000000000 3.2413623623 2.0555250169 0.4849269143 0.4428178658 0.6127977736 0.5518056342 -0.351996830102 +1403637219738319104.0000000000 3.3380113247 1.9836029865 0.4850096974 0.4409196193 0.6144841108 0.5520357463 -0.351077913966 +1403637219788318976.0000000000 3.4325999152 1.9116211837 0.4870777747 0.4387514831 0.6164812050 0.5521664199 -0.350086138844 +1403637219838319104.0000000000 3.5235420248 1.8387948183 0.4914099356 0.4374993122 0.6174952796 0.5532905881 -0.348085415727 +1403637219888318976.0000000000 3.6126947117 1.7663082193 0.4971069440 0.4349327263 0.6192309582 0.5539617183 -0.347149764009 +1403637219938319104.0000000000 3.6989351713 1.6940921647 0.5051883699 0.4347591750 0.6194957280 0.5535246287 -0.347591697452 +1403637219988318976.0000000000 3.7837560709 1.6219754242 0.5153147159 0.4347391103 0.6195455177 0.5534929280 -0.347578532416 +1403637220038319104.0000000000 3.8662028965 1.5499551834 0.5275762597 0.4338114057 0.6201111329 0.5536980002 -0.347402319509 +1403637220088318976.0000000000 3.9461498846 1.4782675477 0.5416901816 0.4329335617 0.6209499954 0.5534652043 -0.34736997841 +1403637220138319104.0000000000 4.0246824560 1.4070267743 0.5574973030 0.4341726619 0.6202065377 0.5543326158 -0.345764806406 +1403637220188318976.0000000000 4.1013867349 1.3354087609 0.5748047227 0.4324197083 0.6212269587 0.5536706544 -0.347187367545 +1403637220238319104.0000000000 4.1762412288 1.2639480850 0.5938796237 0.4316155219 0.6219726464 0.5523785607 -0.348906855844 +1403637220288318976.0000000000 4.2491674596 1.1927000243 0.6153246890 0.4307048665 0.6230178638 0.5494647864 -0.35274708777 +1403637220338319104.0000000000 4.3200928675 1.1219278923 0.6392744543 0.4295625367 0.6241141896 0.5463247409 -0.357052913375 +1403637220388318976.0000000000 4.3898480856 1.0517523642 0.6650620463 0.4280040049 0.6256709596 0.5422172331 -0.362420879898 +1403637220438319104.0000000000 4.4581112197 0.9828461987 0.6901326385 0.4277373389 0.6264264164 0.5388194439 -0.366475538731 +1403637220488318976.0000000000 4.5247259661 0.9150884962 0.7138064361 0.4272515980 0.6272344852 0.5363179379 -0.369318347972 +1403637220538319104.0000000000 4.5892452761 0.8486310846 0.7365875678 0.4275588494 0.6273638445 0.5333276172 -0.37305453975 +1403637220588318976.0000000000 4.6514759540 0.7834476344 0.7578680774 0.4276850671 0.6278066079 0.5306074392 -0.376032035799 +1403637220638319104.0000000000 4.7127517393 0.7197594858 0.7768497927 0.4284335930 0.6274619526 0.5309285976 -0.375301183876 +1403637220688318976.0000000000 4.7733324863 0.6571681318 0.7943278213 0.4276535697 0.6281613288 0.5310045195 -0.374913282736 +1403637220738319104.0000000000 4.8293637124 0.5953162321 0.8114223846 0.4283210811 0.6278984657 0.5315621068 -0.3737998058 +1403637220788318976.0000000000 4.8856889129 0.5349693961 0.8268390460 0.4278803832 0.6284081272 0.5319452441 -0.37290194515 +1403637220838319104.0000000000 4.9407261030 0.4760120832 0.8411589926 0.4272994831 0.6287929231 0.5323287343 -0.372371763489 +1403637220888318976.0000000000 4.9942337669 0.4189071534 0.8541010578 0.4274106709 0.6289770058 0.5327989284 -0.37125913662 +1403637220938319104.0000000000 5.0469935589 0.3631106892 0.8653818732 0.4266625966 0.6296911176 0.5330233174 -0.370586384313 +1403637220988318976.0000000000 5.0991930010 0.3089723445 0.8749416885 0.4264084088 0.6308742671 0.5326342471 -0.369424264012 +1403637221038319104.0000000000 5.1508763268 0.2563743597 0.8824588921 0.4259606913 0.6331170909 0.5327624146 -0.365902238671 +1403637221088318976.0000000000 5.2013550507 0.2051800379 0.8889824471 0.4265621801 0.6359369237 0.5307431569 -0.36323633761 +1403637221138319104.0000000000 5.2507974576 0.1556392131 0.8936471589 0.4268881307 0.6397641652 0.5288078154 -0.358929841634 +1403637221188318976.0000000000 5.2990623107 0.1079231149 0.8970442379 0.4287589405 0.6435723350 0.5258679799 -0.354179740197 +1403637221238319104.0000000000 5.3461326918 0.0618534290 0.8990303104 0.4312421161 0.6478372194 0.5218960521 -0.349230132229 +1403637221288318976.0000000000 5.3918475644 0.0172025045 0.8996817557 0.4344571156 0.6518268578 0.5174808213 -0.344357897926 +1403637221338319104.0000000000 5.4366096947 -0.0264275318 0.8990131951 0.4369079729 0.6559817029 0.5123717502 -0.340990642467 +1403637221388318976.0000000000 5.4803569259 -0.0692635546 0.8968275850 0.4387455833 0.6596218877 0.5082689993 -0.337733478715 +1403637221438319104.0000000000 5.5229688934 -0.1111540409 0.8937141965 0.4413815675 0.6622144449 0.5035893845 -0.336232170824 +1403637221488318976.0000000000 5.5647388258 -0.1519588031 0.8886969341 0.4425593760 0.6650756260 0.5007015261 -0.333337054878 +1403637221538319104.0000000000 5.6051309489 -0.1918233317 0.8828468075 0.4424354941 0.6682436423 0.4971731806 -0.332445629447 +1403637221588318976.0000000000 5.6442440201 -0.2302120318 0.8757795754 0.4432446047 0.6704848292 0.4948064044 -0.330379987805 +1403637221638319104.0000000000 5.6816458395 -0.2672032034 0.8675714615 0.4444240120 0.6721753481 0.4928092927 -0.328339154057 +1403637221688318976.0000000000 5.7174552034 -0.3032012713 0.8581893249 0.4441487160 0.6745238822 0.4909125248 -0.326732831978 +1403637221738319104.0000000000 5.7508374782 -0.3379489480 0.8483488750 0.4447326787 0.6760159071 0.4890139468 -0.325700318814 +1403637221788318976.0000000000 5.7816950038 -0.3714396913 0.8373511111 0.4449181400 0.6775174288 0.4871620096 -0.325101766704 +1403637221838319104.0000000000 5.8106614988 -0.4032037686 0.8252557064 0.4450712100 0.6796174349 0.4851095321 -0.323574569626 +1403637221888318976.0000000000 5.8375651247 -0.4332754405 0.8123390096 0.4453348816 0.6824072586 0.4819345284 -0.322081180563 +1403637221938319104.0000000000 5.8624791557 -0.4615535267 0.7984245511 0.4458543753 0.6863263827 0.4773616778 -0.319837147728 +1403637221988318976.0000000000 5.8856324295 -0.4877716521 0.7834133078 0.4484527471 0.6898808263 0.4725079679 -0.315738498337 +1403637222038319104.0000000000 5.9073872706 -0.5121499132 0.7675111513 0.4515279311 0.6944501907 0.4657872853 -0.311293535043 +1403637222088318976.0000000000 5.9276842433 -0.5346425967 0.7502857444 0.4545370840 0.6998709535 0.4586681180 -0.305287152211 +1403637222138319104.0000000000 5.9467367713 -0.5556565514 0.7325011641 0.4580291160 0.7053571308 0.4504988035 -0.299552123925 +1403637222188318976.0000000000 5.9646479346 -0.5749777688 0.7141269029 0.4620510057 0.7109046880 0.4417500628 -0.293223932776 +1403637222238319104.0000000000 5.9812959166 -0.5930103673 0.6954033129 0.4676843101 0.7147293855 0.4325721202 -0.288642776623 +1403637222288318976.0000000000 5.9967529041 -0.6097651262 0.6757774898 0.4737263873 0.7170708019 0.4251487592 -0.283974131671 +1403637222338319104.0000000000 6.0112392638 -0.6255979202 0.6554627065 0.4805712303 0.7179242527 0.4170564487 -0.28231184631 +1403637222388318976.0000000000 6.0249359611 -0.6404331942 0.6348811598 0.4873739492 0.7181490244 0.4094301713 -0.281239306001 +1403637222438319104.0000000000 6.0378256274 -0.6542912166 0.6151284641 0.4937810144 0.7177752484 0.4029581799 -0.280363527809 +1403637222488318976.0000000000 6.0505033538 -0.6675600350 0.5975056224 0.4995741836 0.7169679667 0.3981386367 -0.27904873366 +1403637222538319104.0000000000 6.0633402266 -0.6806835856 0.5811639303 0.5023002932 0.7176786397 0.3936690522 -0.278669092274 +1403637222588318976.0000000000 6.0763568692 -0.6934580976 0.5666161865 0.5042649926 0.7183911405 0.3906969785 -0.27746505642 +1403637222638319104.0000000000 6.0894291921 -0.7054570574 0.5537095352 0.5069535124 0.7181805620 0.3886892633 -0.27592657212 +1403637222688318976.0000000000 6.1028334966 -0.7172019954 0.5423735770 0.5075549378 0.7188158402 0.3882148795 -0.273826551345 +1403637222738319104.0000000000 6.1159613883 -0.7285729491 0.5330171687 0.5066130115 0.7202262977 0.3874920037 -0.272886943176 +1403637222788318976.0000000000 6.1290897081 -0.7394292214 0.5253816794 0.5045889270 0.7220954635 0.3883419788 -0.270478583102 +1403637222838319104.0000000000 6.1418756184 -0.7498759289 0.5196308811 0.5013641726 0.7243738292 0.3896870304 -0.268440943936 +1403637222888318976.0000000000 6.1542582039 -0.7597990159 0.5161326270 0.4972431573 0.7270739641 0.3912214102 -0.266568005132 +1403637222938319104.0000000000 6.1659319885 -0.7688719603 0.5148196779 0.4926257236 0.7298199186 0.3934718277 -0.264315538002 +1403637222988318976.0000000000 6.1767803310 -0.7767786560 0.5155631458 0.4892095402 0.7317627320 0.3953769180 -0.26243936912 +1403637223038319104.0000000000 6.1863481285 -0.7837806561 0.5182565803 0.4863230868 0.7331861501 0.3968169639 -0.261656686783 +1403637223088318976.0000000000 6.1947439422 -0.7895163786 0.5229940058 0.4842450779 0.7339483287 0.3984524622 -0.26088731412 +1403637223138319104.0000000000 6.2016088983 -0.7939608806 0.5297602787 0.4836644663 0.7337453259 0.3996551677 -0.260695661063 +1403637223188318976.0000000000 6.2070358836 -0.7972534169 0.5389884224 0.4836872811 0.7330123177 0.4005279541 -0.261375045183 +1403637223238319104.0000000000 6.2106179163 -0.7990125057 0.5503421646 0.4851346636 0.7313779921 0.4012337112 -0.262187146648 +1403637223288318976.0000000000 6.2128297571 -0.7996830683 0.5641233392 0.4881891155 0.7285441416 0.4016240346 -0.263804768797 +1403637223338319104.0000000000 6.2138016122 -0.7994853210 0.5798499323 0.4917308252 0.7252030554 0.4018051645 -0.26614645168 +1403637223388318976.0000000000 6.2138127351 -0.7985142512 0.5969074916 0.4951305811 0.7220448405 0.4023771063 -0.267562367039 +1403637223438319104.0000000000 6.2127961791 -0.7970462242 0.6158178085 0.4977928736 0.7193518477 0.4024079478 -0.269820343589 +1403637223488318976.0000000000 6.2110273684 -0.7950158614 0.6362243407 0.4999033847 0.7170841060 0.4028787481 -0.271248419783 +1403637223538319104.0000000000 6.2088022334 -0.7925493865 0.6569773712 0.5020773746 0.7149903005 0.4031515327 -0.272352752727 +1403637223588318976.0000000000 6.2062558909 -0.7899084158 0.6770090169 0.5037055214 0.7134076054 0.4032053666 -0.273415011538 +1403637223638319104.0000000000 6.2035194473 -0.7871542605 0.6954650916 0.5051440700 0.7120664311 0.4033479606 -0.274046143735 +1403637223688318976.0000000000 6.2006915558 -0.7843481583 0.7122696010 0.5058310707 0.7112900881 0.4034582972 -0.274632009804 +1403637223738319104.0000000000 6.1979189953 -0.7814457872 0.7269988688 0.5063739695 0.7106406278 0.4041171805 -0.274343954979 +1403637223788318976.0000000000 6.1947554203 -0.7785985182 0.7403356106 0.5070049429 0.7100424737 0.4038707652 -0.27508921894 +1403637223838319104.0000000000 6.1912655919 -0.7757580222 0.7518417087 0.5075715957 0.7095024438 0.4040053810 -0.275239912642 +1403637223888318976.0000000000 6.1877713954 -0.7728700810 0.7618358954 0.5085121426 0.7087721898 0.4040621483 -0.275301950834 +1403637223938319104.0000000000 6.1840989580 -0.7699726462 0.7697630278 0.5093560604 0.7080939497 0.4047405567 -0.274489423859 +1403637223988318976.0000000000 6.1805255853 -0.7673410097 0.7761522804 0.5094362298 0.7080922791 0.4043015199 -0.274991514638 +1403637224038319104.0000000000 6.1774003971 -0.7649434318 0.7808755963 0.5097722640 0.7079933109 0.4039455510 -0.275146692576 +1403637224088318976.0000000000 6.1742584598 -0.7627959981 0.7838201953 0.5095712081 0.7080979955 0.4040636214 -0.275076357472 +1403637224138319104.0000000000 6.1708860705 -0.7606317870 0.7852259226 0.5105952534 0.7074696855 0.4043207926 -0.274415429578 +1403637224188318976.0000000000 6.1674309976 -0.7588368484 0.7848598268 0.5107805018 0.7073781675 0.4041993024 -0.2744855751 +1403637224238319104.0000000000 6.1638321276 -0.7572144133 0.7827611461 0.5116770381 0.7068137955 0.4044534041 -0.273894707958 +1403637224288318976.0000000000 6.1604424401 -0.7559075345 0.7792427529 0.5125653725 0.7062403638 0.4042983278 -0.273941872568 +1403637224338319104.0000000000 6.1571300664 -0.7550909324 0.7744238938 0.5127818881 0.7060740976 0.4040325812 -0.274357025147 +1403637224388318976.0000000000 6.1537940104 -0.7545870490 0.7680680560 0.5130288332 0.7058852225 0.4044919243 -0.273703767136 +1403637224438319104.0000000000 6.1505510222 -0.7543081570 0.7602718038 0.5137756371 0.7055144685 0.4048838098 -0.272677520301 +1403637224488318976.0000000000 6.1471409246 -0.7545686223 0.7511692625 0.5141329713 0.7052034422 0.4051582392 -0.272400796714 +1403637224538319104.0000000000 6.1436158113 -0.7551272218 0.7408817225 0.5150460637 0.7046082800 0.4051670443 -0.27220284762 +1403637224588318976.0000000000 6.1396428833 -0.7562002296 0.7303600278 0.5148855778 0.7047953778 0.4045453149 -0.272945791999 +1403637224638319104.0000000000 6.1357414971 -0.7580410551 0.7211626055 0.5140327299 0.7053432830 0.4031869919 -0.275138974497 +1403637224688318976.0000000000 6.1318341091 -0.7604084641 0.7139986949 0.5124674234 0.7064611756 0.4006816664 -0.278826020075 +1403637224738319104.0000000000 6.1283851150 -0.7629998045 0.7074817541 0.5094714072 0.7085885990 0.3988398064 -0.281545540673 +1403637224788318976.0000000000 6.1255451076 -0.7653910708 0.7022938310 0.5084502208 0.7093173918 0.3982632742 -0.282371342413 +1403637224838319104.0000000000 6.1240069315 -0.7675981672 0.6985774465 0.5082399670 0.7095679902 0.3984477953 -0.281859464251 +1403637224888318976.0000000000 6.1229604085 -0.7693916389 0.6958832829 0.5102834673 0.7081299855 0.3993211564 -0.280544685629 +1403637224938319104.0000000000 6.1221135763 -0.7710157698 0.6921479630 0.5123732940 0.7067733801 0.4007227132 -0.278147989144 +1403637224988318976.0000000000 6.1213606633 -0.7730341086 0.6868526108 0.5136544392 0.7058601516 0.4017629933 -0.276599097435 +1403637225038319104.0000000000 6.1209067490 -0.7754730058 0.6801397011 0.5142660382 0.7053803975 0.4024557524 -0.275677899402 +1403637225088318976.0000000000 6.1205505545 -0.7782840472 0.6721653762 0.5150908159 0.7047914530 0.4033584010 -0.274321817291 +1403637225138319104.0000000000 6.1199621559 -0.7814348038 0.6633455933 0.5165536672 0.7036108171 0.4035955260 -0.27425312819 +1403637225188318976.0000000000 6.1197223852 -0.7851953575 0.6528720244 0.5169302817 0.7032293964 0.4037146388 -0.274346478615 +1403637225238319104.0000000000 6.1194115916 -0.7893032441 0.6409489053 0.5175545139 0.7024920971 0.4041174973 -0.274465347498 +1403637225288318976.0000000000 6.1190748594 -0.7941016402 0.6284745183 0.5169843184 0.7025802324 0.4040874458 -0.275357163854 +1403637225338319104.0000000000 6.1187883540 -0.7992727896 0.6163400706 0.5179477145 0.7017010683 0.4043302962 -0.275432001486 +1403637225388318976.0000000000 6.1183120342 -0.8049341134 0.6060376110 0.5185709472 0.7010105235 0.4044384771 -0.275858544968 +1403637225438319104.0000000000 6.1191453095 -0.8115135118 0.5977378881 0.5194363828 0.6999873782 0.4045744954 -0.276627894836 +1403637225488318976.0000000000 6.1212394692 -0.8191906012 0.5908938696 0.5198444851 0.6994879526 0.4047069843 -0.276930627274 +1403637225538319104.0000000000 6.1236893958 -0.8277224916 0.5861046096 0.5197916757 0.6991682572 0.4055696054 -0.276574867155 +1403637225588318976.0000000000 6.1265659548 -0.8369936895 0.5830626827 0.5186235914 0.6996377431 0.4063721424 -0.276402389154 +1403637225638319104.0000000000 6.1298643344 -0.8469329531 0.5820212166 0.5175985776 0.7001233145 0.4075868111 -0.275303556795 +1403637225688318976.0000000000 6.1328258357 -0.8574005518 0.5831964698 0.5143870810 0.7023124170 0.4086151065 -0.274220521771 +1403637225738319104.0000000000 6.1364363666 -0.8684573882 0.5853390020 0.5132326244 0.7029480470 0.4098522049 -0.272905636768 +1403637225788318976.0000000000 6.1391559926 -0.8796819746 0.5897213649 0.5105746823 0.7047660730 0.4111914146 -0.271182404877 +1403637225838319104.0000000000 6.1415629964 -0.8915125722 0.5963985823 0.5077462108 0.7067401598 0.4118577087 -0.270343040717 +1403637225888318976.0000000000 6.1431032695 -0.9034168547 0.6059404731 0.5058910095 0.7078538513 0.4128709781 -0.26935992117 +1403637225938319104.0000000000 6.1439191092 -0.9155890755 0.6181046132 0.5074206126 0.7065052655 0.4124331488 -0.27069083754 +1403637225988318976.0000000000 6.1446595850 -0.9282172395 0.6317579254 0.5100570892 0.7046270813 0.4112612675 -0.272408905732 +1403637226038319104.0000000000 6.1444620870 -0.9409069804 0.6474944651 0.5129356763 0.7024038228 0.4099720452 -0.274679420093 +1403637226088318976.0000000000 6.1444581748 -0.9538158364 0.6627298431 0.5149284152 0.7009058451 0.4092340620 -0.275875345193 +1403637226138319104.0000000000 6.1445015684 -0.9673389328 0.6763665930 0.5170196005 0.6993624492 0.4081621790 -0.277464471528 +1403637226188318976.0000000000 6.1448093486 -0.9813771462 0.6881503182 0.5181253496 0.6986300148 0.4076302794 -0.278028379457 +1403637226238319104.0000000000 6.1456264870 -0.9961206644 0.6985663295 0.5190360593 0.6979168949 0.4073347635 -0.278553347432 +1403637226288318976.0000000000 6.1471173970 -1.0113722871 0.7071749971 0.5186798622 0.6982385207 0.4080229409 -0.277401240836 +1403637226338319104.0000000000 6.1491196690 -1.0271924267 0.7141868600 0.5162528628 0.6999805518 0.4093913523 -0.275515751664 +1403637226388318976.0000000000 6.1513814947 -1.0435995130 0.7200685329 0.5131691738 0.7021456727 0.4113804942 -0.272791023109 +1403637226438319104.0000000000 6.1536067595 -1.0605833091 0.7245886721 0.5083713071 0.7055785581 0.4137394766 -0.269327232225 +1403637226488318976.0000000000 6.1554591790 -1.0779562278 0.7283509013 0.5041649027 0.7084915088 0.4152913667 -0.267190219777 +1403637226538319104.0000000000 6.1567860395 -1.0954402848 0.7314126306 0.5017692528 0.7100498417 0.4169272758 -0.265006577131 +1403637226588318976.0000000000 6.1571445745 -1.1129689095 0.7337103255 0.4997506126 0.7113510162 0.4186408208 -0.26261934458 +1403637226638319104.0000000000 6.1563491370 -1.1306331412 0.7353519399 0.4986385283 0.7120435681 0.4193041265 -0.261796914988 +1403637226688318976.0000000000 6.1547135910 -1.1484408022 0.7359081669 0.4977225671 0.7127163361 0.4193132496 -0.261694610475 +1403637226738319104.0000000000 6.1520510396 -1.1664372888 0.7351661828 0.4964853270 0.7135245257 0.4191171455 -0.262156231413 +1403637226788318976.0000000000 6.1484186221 -1.1841543725 0.7333895459 0.4957650563 0.7138039048 0.4191757581 -0.262664573764 +1403637226838319104.0000000000 6.1438904569 -1.2016272238 0.7304613566 0.4961029055 0.7136002577 0.4189909315 -0.262874834507 +1403637226888318976.0000000000 6.1380353538 -1.2191948560 0.7267489413 0.4953127897 0.7143229593 0.4175793021 -0.264642167403 +1403637226938319104.0000000000 6.1310015866 -1.2366520832 0.7227407045 0.4943348795 0.7153457657 0.4150472204 -0.267673807643 +1403637226988318976.0000000000 6.1226649898 -1.2536760200 0.7182894919 0.4934608725 0.7162709656 0.4117199998 -0.271917106707 +1403637227038319104.0000000000 6.1132702852 -1.2701377039 0.7138691758 0.4915689579 0.7178583772 0.4067870209 -0.27850247667 +1403637227088318976.0000000000 6.1037553485 -1.2857507985 0.7099119814 0.4899858908 0.7192914884 0.4017473060 -0.284837995541 +1403637227138319104.0000000000 6.0940247820 -1.3000274128 0.7073232655 0.4886863486 0.7205572378 0.3968468997 -0.290681024271 +1403637227188318976.0000000000 6.0847543666 -1.3126654611 0.7058889438 0.4885341490 0.7209528324 0.3949933700 -0.292475018293 +1403637227238319104.0000000000 6.0758478195 -1.3237093167 0.7064677439 0.4892276460 0.7207952295 0.3938904412 -0.293190838697 +1403637227288318976.0000000000 6.0679666087 -1.3332034915 0.7086237542 0.4919226646 0.7193362999 0.3957705742 -0.289711981695 +1403637227338319104.0000000000 6.0604927773 -1.3415051039 0.7129005445 0.4938000355 0.7184170954 0.3978186786 -0.285969755359 +1403637227388318976.0000000000 6.0528210381 -1.3485306683 0.7180512067 0.4960299649 0.7173569362 0.3994404316 -0.282490073472 +1403637227438319104.0000000000 6.0451051157 -1.3547420539 0.7223429874 0.4967670269 0.7171087516 0.4016749431 -0.278630220028 +1403637227488318976.0000000000 6.0370203141 -1.3602591742 0.7259330994 0.4972583058 0.7170745100 0.4023975670 -0.276793284711 +1403637227538319104.0000000000 6.0290881265 -1.3653348539 0.7279222239 0.4974190020 0.7175133886 0.4020965997 -0.275802824788 +1403637227588318976.0000000000 6.0211477748 -1.3700285522 0.7287081090 0.4962905653 0.7186894119 0.4013539219 -0.27585545755 +1403637227638319104.0000000000 6.0128782913 -1.3742257414 0.7283231299 0.4949678982 0.7199037432 0.3992383230 -0.278126125445 +1403637227688318976.0000000000 6.0043348333 -1.3774868723 0.7262757721 0.4933723843 0.7213454554 0.3980000109 -0.278998952957 +1403637227738319104.0000000000 5.9955340856 -1.3800050755 0.7233268614 0.4923026799 0.7222298053 0.3965431939 -0.280670046571 +1403637227788318976.0000000000 5.9866463846 -1.3816188280 0.7195231977 0.4910558931 0.7232778912 0.3950444794 -0.282264169349 +1403637227838319104.0000000000 5.9780835949 -1.3817252183 0.7145332972 0.4926977134 0.7224955784 0.3956225708 -0.280592023796 +1403637227888318976.0000000000 5.9693436501 -1.3809149001 0.7093081893 0.4964879350 0.7198676675 0.3951367170 -0.281348976433 +1403637227938319104.0000000000 5.9606590301 -1.3790314985 0.7030442292 0.5025979491 0.7157697694 0.3955410099 -0.280385891714 +1403637227988318976.0000000000 5.9521367693 -1.3768047533 0.6958068158 0.5075277946 0.7121888192 0.3960638749 -0.279885745619 +1403637228038319104.0000000000 5.9440494888 -1.3743762338 0.6879369304 0.5130090334 0.7081495712 0.3968791727 -0.278985373709 +1403637228088318976.0000000000 5.9364006701 -1.3725293374 0.6792050345 0.5154323242 0.7061451856 0.3973976728 -0.278861230101 +1403637228138319104.0000000000 5.9292143639 -1.3710275951 0.6706248701 0.5176998812 0.7040610016 0.3969297395 -0.280591733494 +1403637228188318976.0000000000 5.9227881030 -1.3699115587 0.6620530319 0.5188927340 0.7027692195 0.3974478388 -0.280893164906 +1403637228238319104.0000000000 5.9170634561 -1.3695061008 0.6550619875 0.5200808117 0.7013760614 0.3973038558 -0.282377789595 +1403637228288318976.0000000000 5.9121730535 -1.3695817157 0.6499237086 0.5208714393 0.7004603341 0.3981029948 -0.282067845722 +1403637228338319104.0000000000 5.9080040153 -1.3701564122 0.6468480064 0.5212655467 0.6998736689 0.3976452088 -0.283438468509 +1403637228388318976.0000000000 5.9048811744 -1.3710511517 0.6452089851 0.5219682156 0.6990185988 0.3995520834 -0.281567599519 +1403637228438319104.0000000000 5.9021363461 -1.3726535430 0.6452549776 0.5227663100 0.6981117041 0.4000626895 -0.281611928511 +1403637228488318976.0000000000 5.9003317281 -1.3750129247 0.6469607221 0.5242364024 0.6969173026 0.4009866520 -0.280521251774 +1403637228538319104.0000000000 5.8995019927 -1.3784263802 0.6502148371 0.5254844153 0.6955985717 0.4021417288 -0.279804907629 +1403637228588318976.0000000000 5.8995068234 -1.3826141469 0.6550863561 0.5269180386 0.6944173720 0.4032109438 -0.278501039193 +1403637228638319104.0000000000 5.8998451076 -1.3877886859 0.6617247124 0.5271791917 0.6939641296 0.4042283927 -0.277660391679 +1403637228688318976.0000000000 5.9010833102 -1.3941173864 0.6691351927 0.5247196148 0.6958162527 0.4050790629 -0.276441713748 +1403637228738319104.0000000000 5.9029190471 -1.4018175247 0.6760229599 0.5208554744 0.6987217755 0.4054762596 -0.275837738726 +1403637228788318976.0000000000 5.9049984755 -1.4104943289 0.6822335956 0.5159706507 0.7022450373 0.4052006728 -0.276475333344 +1403637228838319104.0000000000 5.9070810753 -1.4195536474 0.6871248353 0.5113549651 0.7057054743 0.4048844316 -0.276702873559 +1403637228888318976.0000000000 5.9092183460 -1.4287247332 0.6909779574 0.5077515622 0.7084165477 0.4041067130 -0.277546591637 +1403637228938319104.0000000000 5.9112373658 -1.4370535237 0.6937167253 0.5073761651 0.7089107877 0.4040800667 -0.277009425554 +1403637228988318976.0000000000 5.9134613830 -1.4454449545 0.6953953181 0.5094493690 0.7076566871 0.4051045016 -0.274906705098 +1403637229038319104.0000000000 5.9157020011 -1.4543036714 0.6962756013 0.5116541326 0.7061464553 0.4059431679 -0.273454524131 +1403637229088318976.0000000000 5.9178995700 -1.4632966651 0.6965217863 0.5149731101 0.7038187790 0.4058509332 -0.273362108402 +1403637229138319104.0000000000 5.9202426538 -1.4727572058 0.6960749886 0.5181768315 0.7015773166 0.4056976023 -0.273297449008 +1403637229188318976.0000000000 5.9229300046 -1.4828231319 0.6941686767 0.5203954462 0.6999340946 0.4062796232 -0.272429276189 +1403637229238319104.0000000000 5.9255295965 -1.4936117880 0.6911639271 0.5216551529 0.6992603759 0.4061551992 -0.271935254024 +1403637229288318976.0000000000 5.9282431155 -1.5049164359 0.6869637151 0.5224972302 0.6995312650 0.4055529812 -0.270516973885 +1403637229338319104.0000000000 5.9309625942 -1.5166861466 0.6813641222 0.5228356319 0.7011209963 0.4039055506 -0.268202454858 +1403637229388318976.0000000000 5.9335415240 -1.5288728265 0.6749903683 0.5203513984 0.7061101297 0.3996021324 -0.266385139849 +1403637229438319104.0000000000 5.9372911187 -1.5419531253 0.6668886948 0.5153132764 0.7138823245 0.3936354288 -0.26433956034 +1403637229488318976.0000000000 5.9412246360 -1.5552775708 0.6582442053 0.5093950926 0.7233959394 0.3847427345 -0.263036086211 +1403637229538319104.0000000000 5.9450514029 -1.5680474360 0.6497427141 0.5037688885 0.7334112643 0.3738000757 -0.261912824842 +1403637229588318976.0000000000 5.9486954529 -1.5794862324 0.6403981499 0.4993515466 0.7432401526 0.3619363557 -0.259314833487 +1403637229638319104.0000000000 5.9522489163 -1.5889539020 0.6306704914 0.4964355920 0.7526340731 0.3487450310 -0.255872152409 +1403637229688318976.0000000000 5.9558773404 -1.5962807669 0.6201299084 0.4951620370 0.7611946768 0.3352874665 -0.250957239225 +1403637229738319104.0000000000 5.9599204754 -1.6011271582 0.6090689147 0.4971392389 0.7676909797 0.3232133686 -0.242973774745 +1403637229788318976.0000000000 5.9640953302 -1.6028650834 0.5973170695 0.5048435583 0.7704883785 0.3136821943 -0.23039991578 +1403637229838319104.0000000000 5.9680712809 -1.6024192137 0.5853411420 0.5149414097 0.7714690742 0.3038496945 -0.217591762938 +1403637229888318976.0000000000 5.9722169678 -1.6005420306 0.5731481324 0.5257613505 0.7715195070 0.2944209826 -0.204080713388 +1403637229938319104.0000000000 5.9761584877 -1.5976038905 0.5608311889 0.5353879246 0.7720021746 0.2842785418 -0.191201786802 +1403637229988318976.0000000000 5.9794488114 -1.5938478558 0.5482813165 0.5444252494 0.7724189644 0.2732296036 -0.179765611386 +1403637230038319104.0000000000 5.9828079026 -1.5905265645 0.5351771204 0.5489813509 0.7755181524 0.2621698927 -0.168695047586 +1403637230088318976.0000000000 5.9862026824 -1.5883782891 0.5238877144 0.5497563260 0.7807812736 0.2497447460 -0.160549514539 +1403637230138319104.0000000000 5.9896298005 -1.5867952512 0.5131771042 0.5480308829 0.7872437126 0.2376937474 -0.153007094108 +1403637230188318976.0000000000 5.9927847493 -1.5848130674 0.5040537491 0.5469615255 0.7925670367 0.2269807267 -0.145431536244 +1403637230238319104.0000000000 5.9953474125 -1.5824827996 0.4971233113 0.5465469861 0.7965121703 0.2183846877 -0.138430064295 +1403637230288318976.0000000000 5.9971073629 -1.5796031353 0.4925027473 0.5466629860 0.7992845739 0.2121829376 -0.131461593782 +1403637230338319104.0000000000 5.9980459493 -1.5763554968 0.4898495849 0.5482046094 0.8003788961 0.2072281514 -0.126181702589 +1403637230388318976.0000000000 5.9976739399 -1.5722805792 0.4896453852 0.5509882191 0.8001849089 0.2020176165 -0.123713284064 +1403637230438319104.0000000000 5.9964869875 -1.5675843369 0.4917011761 0.5563993111 0.7978326049 0.1979836810 -0.12118334532 +1403637230488318976.0000000000 5.9945493481 -1.5627909659 0.4957075563 0.5625755363 0.7944526421 0.1949433405 -0.119795073154 +1403637230538319104.0000000000 5.9922150252 -1.5581798127 0.5013816696 0.5684905562 0.7911865944 0.1915078183 -0.119025273955 +1403637230588318976.0000000000 5.9897315613 -1.5534528974 0.5091833471 0.5750086774 0.7876992795 0.1874289474 -0.117325426456 +1403637230638319104.0000000000 5.9872033632 -1.5494851322 0.5188764309 0.5796049574 0.7860769464 0.1802442657 -0.116846619515 +1403637230688318976.0000000000 5.9851830531 -1.5465678549 0.5290704942 0.5824043985 0.7859792809 0.1728618399 -0.114719095497 +1403637230738319104.0000000000 5.9836317591 -1.5445473612 0.5401701554 0.5818862101 0.7886519781 0.1638003428 -0.112276193852 +1403637230788318976.0000000000 5.9827337566 -1.5434566993 0.5522722714 0.5787146881 0.7933970100 0.1543027784 -0.108633083598 +1403637230838319104.0000000000 5.9825013844 -1.5428323183 0.5644968777 0.5723938277 0.8005912120 0.1430515311 -0.104667458044 +1403637230888318976.0000000000 5.9831305320 -1.5417340724 0.5757413904 0.5665684144 0.8075222801 0.1313964969 -0.0981985717501 +1403637230938319104.0000000000 5.9846218816 -1.5403007847 0.5853718771 0.5610931096 0.8141335571 0.1183775336 -0.0913664768894 +1403637230988318976.0000000000 5.9871999720 -1.5380528136 0.5934450812 0.5571750137 0.8195421747 0.1051008654 -0.0828277492345 +1403637231038319104.0000000000 5.9908432224 -1.5347282562 0.6004629114 0.5543465022 0.8240755710 0.0910358672 -0.072882643016 +1403637231088318976.0000000000 5.9951620805 -1.5304367540 0.6057671030 0.5531297780 0.8272459482 0.0753566838 -0.0635055907244 +1403637231138319104.0000000000 6.0007204552 -1.5249289890 0.6074392476 0.5524748152 0.8297539875 0.0594451542 -0.052403935219 +1403637231188318976.0000000000 6.0070446056 -1.5177966666 0.6055897365 0.5523368374 0.8314842347 0.0411117129 -0.0432181970544 +1403637231238319104.0000000000 6.0146094991 -1.5091259101 0.5998739403 0.5529671596 0.8322647555 0.0224316816 -0.0325502200995 +1403637231288318976.0000000000 6.0231467731 -1.4994308916 0.5900420393 0.5532489361 0.8327241006 0.0032314780 -0.0218115710363 +1403637231338319104.0000000000 6.0328656235 -1.4887628030 0.5765287384 0.5545372016 0.8319262309 -0.0166299889 -0.0105205442123 +1403637231388318976.0000000000 6.0438317116 -1.4773102628 0.5594598541 0.5567672713 0.8298636024 -0.0365124942 0.00185599850966 +1403637231438319104.0000000000 6.0551268996 -1.4634701077 0.5388777409 0.5581399627 0.8276707452 -0.0570215325 0.0137646093063 +1403637231488318976.0000000000 6.0676956360 -1.4502204399 0.5137200731 0.5575197729 0.8260226522 -0.0792476289 0.0240435880478 +1403637231538319104.0000000000 6.0818229980 -1.4369739324 0.4845065054 0.5554654582 0.8245477643 -0.1018577154 0.0347003601286 +1403637231588318976.0000000000 6.0962619934 -1.4226083497 0.4517151622 0.5520983441 0.8232675932 -0.1238046246 0.0457198353601 +1403637231638319104.0000000000 6.1134559455 -1.4087957370 0.4167858363 0.5493013663 0.8210717557 -0.1434815135 0.059348430408 +1403637231688318976.0000000000 6.1328052001 -1.3945436871 0.3824810243 0.5467267111 0.8181702287 -0.1617684317 0.0742856289693 +1403637231738319104.0000000000 6.1537474834 -1.3796261257 0.3502331136 0.5453238289 0.8140493749 -0.1800642066 0.0867318761462 +1403637231788318976.0000000000 6.1749104865 -1.3626296023 0.3190921130 0.5441583399 0.8094177742 -0.1970879561 0.0994530312803 +1403637231838319104.0000000000 6.1985891283 -1.3461362472 0.2897962836 0.5414702228 0.8056806506 -0.2131162904 0.110770635867 +1403637231888318976.0000000000 6.2234951049 -1.3294222177 0.2624845485 0.5373704882 0.8028127505 -0.2281811722 0.12107022206 +1403637231938319104.0000000000 6.2499467703 -1.3121658233 0.2381885540 0.5342869365 0.7991653689 -0.2432724520 0.12919247928 +1403637231988318976.0000000000 6.2784405346 -1.2943807793 0.2157648861 0.5319805458 0.7949850350 -0.2569489635 0.137741508093 +1403637232038319104.0000000000 6.3098001830 -1.2750661380 0.1978858671 0.5354049911 0.7867374974 -0.2702237647 0.146166763417 +1403637232088318976.0000000000 6.3439385962 -1.2552071480 0.1829014989 0.5403420000 0.7771153094 -0.2832213001 0.154622165684 +1403637232138319104.0000000000 6.3798337530 -1.2366622573 0.1693000290 0.5445848107 0.7677424311 -0.2955689222 0.163211383127 +1403637232188318976.0000000000 6.4168218305 -1.2203486910 0.1571772758 0.5476772234 0.7590444744 -0.3078342428 0.170702149202 +1403637232238319104.0000000000 6.4555156885 -1.2058130911 0.1463991522 0.5475452127 0.7528092029 -0.3181548005 0.179583036495 +1403637232288318976.0000000000 6.4959091067 -1.1927883214 0.1374340880 0.5463230670 0.7473568987 -0.3273142787 0.189351882551 +1403637232338319104.0000000000 6.5375993057 -1.1819178347 0.1301361077 0.5453037853 0.7416163423 -0.3354486454 0.20030773528 +1403637232388318976.0000000000 6.5805340089 -1.1725840718 0.1246077895 0.5436433832 0.7361238469 -0.3426632949 0.212498047533 +1403637232438319104.0000000000 6.6245009968 -1.1645666330 0.1203813636 0.5416161061 0.7305481374 -0.3515205703 0.222226688747 +1403637232488318976.0000000000 6.6687808342 -1.1586885670 0.1173525619 0.5391710068 0.7248625478 -0.3621251504 0.229639473144 +1403637232538319104.0000000000 6.7129130864 -1.1544787748 0.1156123692 0.5342997280 0.7203988942 -0.3772038756 0.230795299514 +1403637232588318976.0000000000 6.7575365098 -1.1521576920 0.1150264060 0.5278410285 0.7166564716 -0.3921419660 0.232404881368 +1403637232638319104.0000000000 6.8036148343 -1.1518597713 0.1160255847 0.5208930751 0.7127237619 -0.4075743796 0.2336201377 +1403637232688318976.0000000000 6.8516626629 -1.1529157686 0.1194673917 0.5145490573 0.7080911104 -0.4223943837 0.235434134227 +1403637232738319104.0000000000 6.8999455516 -1.1566357276 0.1231239534 0.5067948513 0.7044538371 -0.4366019478 0.237239350138 +1403637232788318976.0000000000 6.9495959936 -1.1626374080 0.1286773439 0.4995619667 0.7005120500 -0.4502385336 0.238759234806 +1403637232838319104.0000000000 7.0009013641 -1.1706064994 0.1353327573 0.4908591262 0.6989828260 -0.4604008759 0.241891216478 +1403637232888318976.0000000000 7.0545596211 -1.1802664991 0.1434176834 0.4820017623 0.6986771433 -0.4680018852 0.24596500967 +1403637232938319104.0000000000 7.1106675008 -1.1911095077 0.1530911817 0.4731504266 0.6993403602 -0.4742130257 0.249346627353 +1403637232988318976.0000000000 7.1697321846 -1.2033381399 0.1642330164 0.4660365007 0.7001173376 -0.4777264367 0.253817149356 +1403637233038319104.0000000000 7.2319389927 -1.2163917134 0.1766033554 0.4590181770 0.7017278481 -0.4801298399 0.257595957287 +1403637233088318976.0000000000 7.2975236479 -1.2299445453 0.1902221216 0.4527736333 0.7036132200 -0.4814108725 0.261090109709 +1403637233138319104.0000000000 7.3664321901 -1.2435290416 0.2037362340 0.4470451576 0.7058990788 -0.4820912710 0.263524427754 +1403637233188318976.0000000000 7.4381607539 -1.2572892822 0.2158495563 0.4407472841 0.7091729947 -0.4827609002 0.264116278034 +1403637233238319104.0000000000 7.5129583523 -1.2707542311 0.2268144397 0.4364518562 0.7115016956 -0.4832633536 0.264067501634 +1403637233288318976.0000000000 7.5916349438 -1.2837854017 0.2360733549 0.4316827430 0.7146809478 -0.4829344080 0.263923302895 +1403637233338319104.0000000000 7.6737282699 -1.2961709498 0.2441372388 0.4280306750 0.7174371263 -0.4828710492 0.262505735229 +1403637233388318976.0000000000 7.7595554822 -1.3077341420 0.2499950928 0.4241919061 0.7205552343 -0.4825754727 0.260734144713 +1403637233438319104.0000000000 7.8501075693 -1.3184138309 0.2521574179 0.4205751953 0.7238200599 -0.4808401169 0.260756223372 +1403637233488318976.0000000000 7.9438102433 -1.3285455863 0.2506481025 0.4174656287 0.7274789793 -0.4751998475 0.26586065601 +1403637233538319104.0000000000 8.0409398341 -1.3375175887 0.2462759760 0.4154598704 0.7312284386 -0.4647342895 0.276983946965 +1403637233588318976.0000000000 8.1405903750 -1.3451915997 0.2388385852 0.4155288009 0.7337890139 -0.4498661261 0.29412576771 +1403637233638319104.0000000000 8.2426180221 -1.3503209930 0.2281494792 0.4175333510 0.7347732977 -0.4329917015 0.313516009572 +1403637233688318976.0000000000 8.3460168788 -1.3520378303 0.2145106290 0.4203178125 0.7343294579 -0.4172935390 0.33160109481 +1403637233738319104.0000000000 8.4496333466 -1.3497441423 0.1991757912 0.4228435982 0.7335147644 -0.4027132045 0.3478238877 +1403637233788318976.0000000000 8.5512968884 -1.3430583673 0.1828033096 0.4252143731 0.7319949913 -0.3902651206 0.362034812184 +1403637233838319104.0000000000 8.6508177108 -1.3315465697 0.1655193020 0.4268058775 0.7306752207 -0.3812464005 0.372292421054 +1403637233888318976.0000000000 8.7460866745 -1.3150878963 0.1475532927 0.4277441676 0.7296443158 -0.3743622559 0.380140764605 +1403637233938319104.0000000000 8.8385328979 -1.2931691130 0.1285854360 0.4274595461 0.7293580537 -0.3696328837 0.385599140635 +1403637233988318976.0000000000 8.9274160589 -1.2660223488 0.1087328260 0.4264001651 0.7295467908 -0.3658732423 0.389975832343 +1403637234038319104.0000000000 9.0131459376 -1.2336862811 0.0883300278 0.4257707579 0.7293053625 -0.3607560398 0.395838388323 +1403637234088318976.0000000000 9.0954985706 -1.1961496894 0.0673013605 0.4262402662 0.7284214432 -0.3556455878 0.401544085299 +1403637234138319104.0000000000 9.1741985324 -1.1534187234 0.0451529662 0.4256735761 0.7275238030 -0.3498502290 0.408798165247 +1403637234188318976.0000000000 9.2488121950 -1.1049770592 0.0222790405 0.4255208207 0.7263649026 -0.3453149223 0.414829680528 +1403637234238319104.0000000000 9.3188774213 -1.0503045871 -0.0009362012 0.4268235496 0.7247380560 -0.3438674362 0.417530351012 +1403637234288318976.0000000000 9.3843930841 -0.9897213199 -0.0250013624 0.4301354676 0.7221196487 -0.3443840424 0.418241943975 +1403637234338319104.0000000000 9.4461452132 -0.9228703597 -0.0495932069 0.4350491727 0.7191884519 -0.3466093832 0.416367774415 +1403637234388318976.0000000000 9.5024028174 -0.8502875720 -0.0745331067 0.4412878776 0.7161890543 -0.3506450712 0.411565646842 +1403637234438319104.0000000000 9.5536263985 -0.7720612667 -0.0996392542 0.4496125438 0.7133451568 -0.3548260750 0.403838710593 +1403637234488318976.0000000000 9.5999194060 -0.6894804468 -0.1251626516 0.4574645877 0.7113732799 -0.3567535508 0.396738089633 +1403637234538319104.0000000000 9.6415206528 -0.6027239051 -0.1510119367 0.4674652499 0.7089236648 -0.3578784381 0.388363877241 +1403637234588318976.0000000000 9.6784462195 -0.5129311413 -0.1781058036 0.4767281556 0.7074961767 -0.3588239002 0.378714713404 +1403637234638319104.0000000000 9.7112498085 -0.4205825176 -0.2063433557 0.4857222065 0.7065628503 -0.3579300611 0.369768776397 +1403637234688318976.0000000000 9.7398705374 -0.3266990641 -0.2357698939 0.4939368749 0.7065030599 -0.3556077911 0.36114109271 +1403637234738319104.0000000000 9.7643555073 -0.2312601001 -0.2663506185 0.5019449438 0.7070612645 -0.3540172673 0.350410353854 +1403637234788318976.0000000000 9.7847192773 -0.1348881892 -0.2979811327 0.5101008818 0.7079269660 -0.3521257471 0.338591138989 +1403637234838319104.0000000000 9.8014672251 -0.0380369580 -0.3299028091 0.5176091842 0.7091293357 -0.3494190106 0.327296001616 +1403637234888318976.0000000000 9.8144656302 0.0587211344 -0.3610790316 0.5248936757 0.7108444306 -0.3479584886 0.313227896142 +1403637234938319104.0000000000 9.8242553011 0.1547887843 -0.3908843868 0.5323052715 0.7125065571 -0.3442941510 0.300744146211 +1403637234988318976.0000000000 9.8313235633 0.2492897378 -0.4195909135 0.5374587979 0.7153233983 -0.3390689855 0.290659077988 +1403637235038319104.0000000000 9.8361217702 0.3420247651 -0.4466910179 0.5412752733 0.7187971095 -0.3310940621 0.284127640167 +1403637235088318976.0000000000 9.8386573118 0.4334223231 -0.4723069909 0.5443589509 0.7229156907 -0.3220881795 0.278074524815 +1403637235138319104.0000000000 9.8385350730 0.5235268345 -0.4961828666 0.5469148449 0.7274227773 -0.3125721323 0.272100932694 +1403637235188318976.0000000000 9.8363142724 0.6126499063 -0.5175768857 0.5499175891 0.7313380002 -0.3029825960 0.266339860142 +1403637235238319104.0000000000 9.8311542302 0.6997607938 -0.5370870576 0.5520566610 0.7352389547 -0.2945931390 0.260522561427 +1403637235288318976.0000000000 9.8231066894 0.7846331510 -0.5549715635 0.5516102928 0.7401580816 -0.2874111358 0.255513087943 +1403637235338319104.0000000000 9.8130515298 0.8680568603 -0.5722407005 0.5488735986 0.7459013491 -0.2815411615 0.251204149096 +1403637235388318976.0000000000 9.8013643883 0.9509740776 -0.5881328313 0.5432002854 0.7530353367 -0.2794025051 0.244551572835 +1403637235438319104.0000000000 9.7876280613 1.0328319461 -0.6024593671 0.5377141577 0.7598328094 -0.2777042220 0.237482528661 +1403637235488318976.0000000000 9.7722877565 1.1140013199 -0.6157059070 0.5319955329 0.7668414672 -0.2752332688 0.230611285255 +1403637235538319104.0000000000 9.7559585323 1.1953146787 -0.6269301843 0.5279522398 0.7726501723 -0.2727014039 0.223410134162 +1403637235588318976.0000000000 9.7392361692 1.2769268882 -0.6363375509 0.5250251178 0.7775650521 -0.2673725398 0.219665974559 +1403637235638319104.0000000000 9.7215607307 1.3586318138 -0.6435126470 0.5247139038 0.7808847366 -0.2620801614 0.214961243872 +1403637235688318976.0000000000 9.7031166750 1.4404847166 -0.6483467384 0.5267614019 0.7826216564 -0.2554293024 0.211616728688 +1403637235738319104.0000000000 9.6847084319 1.5235628507 -0.6508253917 0.5316287273 0.7825304913 -0.2466825987 0.210153805428 +1403637235788318976.0000000000 9.6658615246 1.6069877420 -0.6518029983 0.5368712447 0.7820106625 -0.2348393727 0.21231829733 +1403637235838319104.0000000000 9.6454272118 1.6902945782 -0.6504778198 0.5438406275 0.7801023142 -0.2201214194 0.217311555285 +1403637235888318976.0000000000 9.6226877418 1.7736372195 -0.6478272771 0.5488799898 0.7794756947 -0.2061283342 0.22058900259 +1403637235938319104.0000000000 9.5975696415 1.8573112204 -0.6440152358 0.5520175542 0.7798565045 -0.1905502970 0.225368667858 +1403637235988318976.0000000000 9.5687794612 1.9410880820 -0.6390347974 0.5533885461 0.7819333148 -0.1785939063 0.224601034959 +1403637236038319104.0000000000 9.5365974373 2.0255588181 -0.6322292574 0.5551685530 0.7835215551 -0.1651655529 0.224949306826 +1403637236088318976.0000000000 9.5004642773 2.1103136003 -0.6234088544 0.5562351195 0.7858354506 -0.1545465887 0.221766742939 +1403637236138319104.0000000000 9.4599838768 2.1947339033 -0.6129908937 0.5573583464 0.7879849944 -0.1432520427 0.218883929208 +1403637236188318976.0000000000 9.4155131233 2.2797044162 -0.6004609599 0.5573862117 0.7909962730 -0.1331035716 0.214310397394 +1403637236238319104.0000000000 9.3666156405 2.3648516693 -0.5859173380 0.5592206396 0.7924803100 -0.1225740911 0.210292241407 +1403637236288318976.0000000000 9.3128405131 2.4502074228 -0.5694263964 0.5610800717 0.7942985719 -0.1139255467 0.203223772386 +1403637236338319104.0000000000 9.2548410702 2.5355840344 -0.5503786363 0.5633802722 0.7957231549 -0.1052665064 0.195822093157 +1403637236388318976.0000000000 9.1917229681 2.6205232357 -0.5297636938 0.5659451302 0.7969778989 -0.0976224281 0.18708874837 +1403637236438319104.0000000000 9.1242913065 2.7053516045 -0.5075424998 0.5683602743 0.7981590187 -0.0915448858 0.177562139175 +1403637236488318976.0000000000 9.0532718568 2.7901177471 -0.4840748016 0.5716584733 0.7984411700 -0.0868637482 0.167788489783 +1403637236538319104.0000000000 8.9796360212 2.8754793391 -0.4599673265 0.5742797125 0.7985934915 -0.0829137157 0.159926742519 +1403637236588318976.0000000000 8.9034768161 2.9606874379 -0.4364590909 0.5772596507 0.7980300128 -0.0799753755 0.153373184142 +1403637236638319104.0000000000 8.8248847534 3.0449096406 -0.4144950034 0.5816318261 0.7958936249 -0.0766732515 0.149596020408 +1403637236688318976.0000000000 8.7432957514 3.1279655114 -0.3942471415 0.5850029279 0.7943876619 -0.0734557054 0.146027656025 +1403637236738319104.0000000000 8.6584775037 3.2098893077 -0.3742195676 0.5912494536 0.7908106108 -0.0694262490 0.142206389759 +1403637236788318976.0000000000 8.5702582097 3.2899659635 -0.3541846890 0.5970229777 0.7876676959 -0.0649277282 0.137577450741 +1403637236838319104.0000000000 8.4782831209 3.3676901711 -0.3331527866 0.6036635742 0.7840970461 -0.0605918548 0.130808022092 +1403637236888318976.0000000000 8.3831797649 3.4433783586 -0.3099613866 0.6121582241 0.7791574650 -0.0554922933 0.122868054598 +1403637236938319104.0000000000 8.2854277632 3.5159295775 -0.2850793956 0.6215182096 0.7732857663 -0.0504320566 0.114894936441 +1403637236988318976.0000000000 8.1856804427 3.5851575279 -0.2590683328 0.6311707922 0.7666331424 -0.0452659487 0.108848747787 +1403637237038319104.0000000000 8.0834738361 3.6504967085 -0.2316317877 0.6417223761 0.7589424870 -0.0414374548 0.102379835591 +1403637237088318976.0000000000 7.9787837344 3.7104032517 -0.2027955908 0.6512086372 0.7518836367 -0.0379565663 0.0956953856842 +1403637237138319104.0000000000 7.8717642378 3.7651591167 -0.1719333928 0.6603288091 0.7450864271 -0.0346138989 0.0872579973555 +1403637237188318976.0000000000 7.7628600395 3.8140412443 -0.1397042785 0.6661868901 0.7410723880 -0.0315497855 0.0775329237344 +1403637237238319104.0000000000 7.6523397251 3.8555977269 -0.1067268300 0.6689765398 0.7396888458 -0.0273567645 0.0676934853426 +1403637237288318976.0000000000 7.5405033731 3.8903226119 -0.0724168100 0.6691512785 0.7405172545 -0.0226438823 0.0579483984451 +1403637237338319104.0000000000 7.4278572132 3.9184297762 -0.0369466573 0.6680996761 0.7421028355 -0.0172669725 0.0512645684322 +1403637237388318976.0000000000 7.3142019060 3.9399458975 0.0006201904 0.6669919431 0.7436567426 -0.0133309648 0.0438027673924 +1403637237438319104.0000000000 7.2000844513 3.9548108961 0.0399722429 0.6664781888 0.7445441932 -0.0101045286 0.036860097022 +1403637237488318976.0000000000 7.0861939719 3.9632662818 0.0803051919 0.6654146670 0.7457463311 -0.0065323323 0.0322964274846 +1403637237538319104.0000000000 6.9723828553 3.9654764995 0.1224247908 0.6645553721 0.7467518038 -0.0045116539 0.0265997358588 +1403637237588318976.0000000000 6.8595458287 3.9616865103 0.1662157089 0.6636251040 0.7477494727 -0.0031933048 0.0215000061426 +1403637237638319104.0000000000 6.7476956844 3.9522089122 0.2123407737 0.6637280466 0.7478109122 -0.0033967578 0.0152440740157 +1403637237688318976.0000000000 6.6372249971 3.9373150480 0.2591889899 0.6640096186 0.7476602441 -0.0040469864 0.00888862863177 +1403637237738319104.0000000000 6.5294741212 3.9173895738 0.3059594051 0.6629526482 0.7486330262 -0.0059983049 0.00252957472329 +1403637237788318976.0000000000 6.4231065667 3.8924188098 0.3517075183 0.6615301232 0.7498659126 -0.0082692302 -0.00326022063118 +1403637237838319104.0000000000 6.3195613477 3.8632239750 0.3954215473 0.6582671689 0.7526461807 -0.0122495976 -0.00761632347067 +1403637237888318976.0000000000 6.2179841817 3.8291836749 0.4368525051 0.6537685261 0.7564153858 -0.0176838425 -0.0104766470343 +1403637237938319104.0000000000 6.1189503012 3.7902087551 0.4762081424 0.6490090716 0.7602780801 -0.0247449006 -0.0123351448917 +1403637237988318976.0000000000 6.0221545836 3.7465062324 0.5129619545 0.6429427162 0.7651013693 -0.0330215882 -0.0124150360464 +1403637238038319104.0000000000 5.9273856657 3.6990467658 0.5482991525 0.6362554381 0.7701433585 -0.0434249177 -0.013133979179 +1403637238088318976.0000000000 5.8353270948 3.6485863953 0.5820295102 0.6286506514 0.7754361584 -0.0571078600 -0.0153562730699 +1403637238138319104.0000000000 5.7471377847 3.5958941657 0.6144087862 0.6217447715 0.7797780713 -0.0715958623 -0.015925802132 +1403637238188318976.0000000000 5.6631085630 3.5410062445 0.6461845473 0.6156140785 0.7829256563 -0.0881507793 -0.0166181584913 +1403637238238319104.0000000000 5.5837243547 3.4841729902 0.6767706421 0.6099949382 0.7851237382 -0.1059232579 -0.0163448635293 +1403637238288318976.0000000000 5.5095133956 3.4254826927 0.7063447098 0.6052204871 0.7859578000 -0.1254075027 -0.01585739365 +1403637238338319104.0000000000 5.4401870179 3.3647306701 0.7342693151 0.6001001504 0.7865185878 -0.1451488009 -0.0141473001291 +1403637238388318976.0000000000 5.3771876605 3.3029908613 0.7612260657 0.5972915760 0.7846136094 -0.1658469521 -0.0109108072146 +1403637238438319104.0000000000 5.3187466861 3.2378260490 0.7865739243 0.5943247830 0.7823443349 -0.1862077296 -0.00648655565695 +1403637238488318976.0000000000 5.2657801361 3.1699078509 0.8108422735 0.5922291642 0.7789881528 -0.2060141871 -0.000479073363982 +1403637238538319104.0000000000 5.2184176199 3.0989642573 0.8335929467 0.5889949737 0.7762939085 -0.2245032178 0.00714099760965 +1403637238588318976.0000000000 5.1769517965 3.0247129449 0.8547634754 0.5847601022 0.7740724805 -0.2422062736 0.0142667039241 +1403637238638319104.0000000000 5.1395946584 2.9469968719 0.8745015436 0.5768239418 0.7741716938 -0.2600559485 0.0174135646801 +1403637238688318976.0000000000 5.1091119894 2.8669424922 0.8930026444 0.5651597875 0.7776002100 -0.2748014488 0.020408130694 +1403637238738319104.0000000000 5.0849766729 2.7846860409 0.9104081576 0.5512684081 0.7827478459 -0.2880213327 0.0212758996328 +1403637238788318976.0000000000 5.0680670550 2.7008287267 0.9270894180 0.5362821830 0.7887773100 -0.2996027917 0.0216781625616 +1403637238838319104.0000000000 5.0588157415 2.6160105449 0.9433630730 0.5206705229 0.7952714931 -0.3098333501 0.0211838139951 +1403637238888318976.0000000000 5.0578821101 2.5308334472 0.9594172744 0.5049319443 0.8020405090 -0.3183546922 0.0206165823406 +1403637238938319104.0000000000 5.0660576499 2.4463835138 0.9754223305 0.4893802746 0.8089092218 -0.3252208801 0.0201046471038 +1403637238988318976.0000000000 5.0839982255 2.3631497666 0.9918360694 0.4757653027 0.8150601762 -0.3299622736 0.0211939599945 +1403637239038319104.0000000000 5.1123526608 2.2817298255 1.0090853098 0.4663680105 0.8200745849 -0.3305120601 0.0272090465407 +1403637239088318976.0000000000 5.1513121913 2.2034411531 1.0270400321 0.4605295464 0.8238974360 -0.3283140502 0.0362689427783 +1403637239138319104.0000000000 5.2013255098 2.1294657744 1.0461546041 0.4610583619 0.8248610055 -0.3231836134 0.0508120127986 +1403637239188318976.0000000000 5.2605324462 2.0591262061 1.0665068992 0.4652474036 0.8235099487 -0.3176080666 0.0670919801851 +1403637239238319104.0000000000 5.3275450718 1.9922856840 1.0872767099 0.4723496778 0.8195765124 -0.3134655971 0.0831831815962 +1403637239288318976.0000000000 5.4004797968 1.9279907769 1.1076562520 0.4785109329 0.8151557172 -0.3118895432 0.0962982692358 +1403637239338319104.0000000000 5.4788006937 1.8660965795 1.1268282141 0.4827980700 0.8106919449 -0.3133280715 0.107285198036 +1403637239388318976.0000000000 5.5661449784 1.8015509301 1.1389157496 0.4858056811 0.8057800148 -0.3183701856 0.115550131051 +1403637239438319104.0000000000 5.6557660452 1.7433840852 1.1526169141 0.4873300366 0.8008270776 -0.3256006635 0.123165072745 +1403637239488318976.0000000000 5.7495003891 1.6865671566 1.1626048727 0.4881050326 0.7957053631 -0.3335717873 0.131667440738 +1403637239538319104.0000000000 5.8472174223 1.6308372845 1.1686176425 0.4895084927 0.7894598860 -0.3424033341 0.141047795792 +1403637239588318976.0000000000 5.9483850438 1.5760455276 1.1696027272 0.4898850929 0.7833292170 -0.3516430847 0.150847852116 +1403637239638319104.0000000000 6.0526153965 1.5219330438 1.1654686397 0.4894965320 0.7771455762 -0.3611624019 0.161243970553 +1403637239688318976.0000000000 6.1600498267 1.4686986469 1.1576140989 0.4903893042 0.7696565954 -0.3708072655 0.172188929079 +1403637239738319104.0000000000 6.2709064672 1.4161297356 1.1465492640 0.4932170697 0.7609049865 -0.3780118239 0.18672863924 +1403637239788318976.0000000000 6.3842176757 1.3642203855 1.1325098411 0.4977771499 0.7505842581 -0.3845277459 0.20243416988 +1403637239838319104.0000000000 6.4992254364 1.3123743352 1.1145732659 0.5018184985 0.7401728881 -0.3889918786 0.221376622036 +1403637239888318976.0000000000 6.6152205077 1.2608890029 1.0935989177 0.5050518899 0.7296697522 -0.3944864074 0.238506007421 +1403637239938319104.0000000000 6.7309767632 1.2088465449 1.0710186031 0.5069900916 0.7194192541 -0.4016252519 0.253168206627 +1403637239988318976.0000000000 6.8469890057 1.1566301431 1.0471442704 0.5072129737 0.7097186770 -0.4085049665 0.26862258125 +1403637240038319104.0000000000 6.9628618710 1.1044913809 1.0216339001 0.5059483280 0.7006018261 -0.4165655030 0.282217207912 +1403637240088318976.0000000000 7.0773127163 1.0518622920 0.9949441734 0.5037581534 0.6918143245 -0.4262180097 0.293187434096 +1403637240138319104.0000000000 7.1903887083 0.9984186390 0.9667445342 0.4993107416 0.6839644113 -0.4369153790 0.3032926293 +1403637240188318976.0000000000 7.3018037738 0.9440124852 0.9383441158 0.4946454902 0.6763536335 -0.4477486980 0.312078042985 +1403637240238319104.0000000000 7.4116502535 0.8890400938 0.9089575218 0.4878340363 0.6703966967 -0.4588085420 0.319501085835 +1403637240288318976.0000000000 7.5242659236 0.8334826165 0.8637812816 0.4786576923 0.6667097166 -0.4704314302 0.324159277052 +1403637240338319104.0000000000 7.6338547984 0.7787854530 0.8301345616 0.4681117147 0.6656602788 -0.4799390256 0.327759588068 +1403637240388318976.0000000000 7.7425528060 0.7240038819 0.7967918206 0.4567030456 0.6660481248 -0.4885092995 0.33039504809 +1403637240438319104.0000000000 7.8507386789 0.6697123015 0.7650122520 0.4443894295 0.6682068498 -0.4947201583 0.333570990684 +1403637240488318976.0000000000 7.9587777124 0.6164147024 0.7350495804 0.4341197306 0.6701548312 -0.4995045134 0.336047322341 +1403637240538319104.0000000000 8.0678043769 0.5646144801 0.7072161322 0.4263959910 0.6714816611 -0.5027559792 0.338430588185 +1403637240588318976.0000000000 8.1771730704 0.5148797684 0.6818065907 0.4228610020 0.6710116934 -0.5053715256 0.339899251833 +1403637240638319104.0000000000 8.2871713894 0.4666041339 0.6584776164 0.4201893822 0.6709456022 -0.5059684291 0.34244536894 +1403637240688318976.0000000000 8.3978557251 0.4199818458 0.6374905015 0.4187894057 0.6709174075 -0.5053217622 0.345159648006 +1403637240738319104.0000000000 8.5092580641 0.3752013609 0.6189461566 0.4193515732 0.6697888943 -0.5052811454 0.346724760081 +1403637240788318976.0000000000 8.6213163292 0.3322198685 0.6025086221 0.4211534714 0.6685933301 -0.5029008050 0.35029058328 +1403637240838319104.0000000000 8.7345586718 0.2912071406 0.5885642577 0.4251819025 0.6665159048 -0.4966026874 0.358277363582 +1403637240888318976.0000000000 8.8466884296 0.2520285991 0.5769532528 0.4325140262 0.6623376166 -0.4910451238 0.364849537688 +1403637240938319104.0000000000 8.9590275530 0.2147679352 0.5668732010 0.4378318956 0.6595573069 -0.4854737024 0.37094834459 +1403637240988318976.0000000000 9.0701476173 0.1791986215 0.5570748470 0.4416681689 0.6579463882 -0.4816258126 0.374262415177 +1403637241038319104.0000000000 9.1794098442 0.1450671720 0.5459534288 0.4433550973 0.6577660120 -0.4806688193 0.373814950696 +1403637241088318976.0000000000 9.2868533699 0.1127956322 0.5326661746 0.4441169641 0.6586389598 -0.4812389315 0.37062640716 +1403637241138319104.0000000000 9.3929082031 0.0816926026 0.5174461147 0.4438269435 0.6603067808 -0.4808349071 0.36852461459 +1403637241188318976.0000000000 9.4975033990 0.0519293734 0.5004740931 0.4435735254 0.6618781445 -0.4801852003 0.36685422561 +1403637241238319104.0000000000 9.6015679736 0.0233416044 0.4823361875 0.4424757070 0.6638973114 -0.4771237085 0.368522150545 +1403637241288318976.0000000000 9.7045470978 -0.0040754386 0.4629518177 0.4408281943 0.6662614317 -0.4739697720 0.370295642646 +1403637241338319104.0000000000 9.8072551627 -0.0293881720 0.4426603758 0.4405469024 0.6676841577 -0.4707129935 0.372217100764 +1403637241388318976.0000000000 9.9089465905 -0.0531311602 0.4211467268 0.4391152847 0.6695820098 -0.4665295926 0.375749701401 +1403637241438319104.0000000000 10.0090326700 -0.0749970570 0.3994068873 0.4375426965 0.6715709745 -0.4628636506 0.378557863229 +1403637241488318976.0000000000 10.1072829908 -0.0943874642 0.3788096065 0.4366213649 0.6729225642 -0.4586523036 0.382328485288 +1403637241538319104.0000000000 10.2040871026 -0.1108967804 0.3598972341 0.4368087598 0.6733656742 -0.4532238312 0.387769177409 +1403637241588318976.0000000000 10.2985716325 -0.1241729543 0.3424517099 0.4369460644 0.6740500522 -0.4491152771 0.391190659184 +1403637241638319104.0000000000 10.3911434566 -0.1338663574 0.3270877186 0.4390188208 0.6733054118 -0.4459414122 0.393774750805 +1403637241688318976.0000000000 10.4817415230 -0.1401195482 0.3134320945 0.4430329740 0.6712287499 -0.4425195701 0.396673895432 +1403637241738319104.0000000000 10.5632789211 -0.1452410453 0.3011603512 0.4468207045 0.6692097496 -0.4389917101 0.399744728038 +1403637241788318976.0000000000 10.6443496805 -0.1458720951 0.2904761827 0.4510652895 0.6665618082 -0.4362452504 0.402399729158 +1403637241838319104.0000000000 10.7217510925 -0.1435520988 0.2815830637 0.4563516322 0.6632534377 -0.4346542084 0.403625797339 +1403637241888318976.0000000000 10.7951321601 -0.1380083895 0.2753433398 0.4635213752 0.6589254074 -0.4360090364 0.401075257729 +1403637241938319104.0000000000 10.8639413663 -0.1302566656 0.2709471646 0.4736993240 0.6526936920 -0.4387020512 0.39640939081 +1403637241988318976.0000000000 10.9296626152 -0.1210133322 0.2672783379 0.4816920550 0.6475689337 -0.4403511100 0.393342268458 +1403637242038319104.0000000000 10.9915645378 -0.1114382851 0.2643657174 0.4869723897 0.6437455706 -0.4409721798 0.392419505952 +1403637242088318976.0000000000 11.0416839824 -0.1018858729 0.2644444222 0.4869460516 0.6430979475 -0.4411249193 0.39334130018 +1403637242138319104.0000000000 11.0944833212 -0.0917817932 0.2633408412 0.4838196664 0.6447327188 -0.4407124003 0.394982065336 +1403637242188318976.0000000000 11.1434873484 -0.0808122823 0.2635217855 0.4788373906 0.6475074297 -0.4399591459 0.397347243417 +1403637242238319104.0000000000 11.1889293672 -0.0683257950 0.2659128748 0.4747526965 0.6497295326 -0.4387222765 0.39998021908 +1403637242288318976.0000000000 11.2305210640 -0.0545445016 0.2685462126 0.4710953041 0.6514844541 -0.4375563372 0.402717856975 +1403637242338319104.0000000000 11.2721897840 -0.0390595544 0.2721452619 0.4673513947 0.6529991968 -0.4347554835 0.407630215439 +1403637242388318976.0000000000 11.3083282115 -0.0222176809 0.2733840888 0.4644198969 0.6539046615 -0.4312120295 0.413254205775 +1403637242438319104.0000000000 11.3410253436 -0.0034707791 0.2729162526 0.4625305281 0.6541449427 -0.4274453148 0.418868007091 +1403637242488318976.0000000000 11.3701302117 0.0173739021 0.2706844312 0.4612563938 0.6539097285 -0.4243320323 0.423776984391 +1403637242538319104.0000000000 11.3948654279 0.0409631924 0.2678767753 0.4618245200 0.6536503371 -0.4219277065 0.425953471662 +1403637242588318976.0000000000 11.4145726729 0.0676864617 0.2656602526 0.4645491597 0.6536303143 -0.4190777454 0.425834866698 +1403637242638319104.0000000000 11.4294595765 0.0977907948 0.2644503998 0.4678024805 0.6552293049 -0.4166754184 0.422157545224 +1403637242688318976.0000000000 11.4391510670 0.1306286892 0.2643595290 0.4719671376 0.6577521804 -0.4137153876 0.416471689669 +1403637242738319104.0000000000 11.4437059407 0.1661485453 0.2660297758 0.4776962423 0.6606025737 -0.4106043528 0.408429437309 +1403637242788318976.0000000000 11.4435997346 0.2037778492 0.2696865045 0.4848756882 0.6624849175 -0.4085781481 0.398839814998 +1403637242838319104.0000000000 11.4390432150 0.2427067220 0.2758360342 0.4926862057 0.6630669210 -0.4056578399 0.391208739551 +1403637242888318976.0000000000 11.4302359419 0.2825462617 0.2830702679 0.4994394960 0.6637550294 -0.4028485328 0.384320843134 +1403637242938319104.0000000000 11.4178501137 0.3225242416 0.2911512363 0.5048013630 0.6642641412 -0.3983440729 0.381117743114 +1403637242988318976.0000000000 11.4020356691 0.3629172344 0.3003121310 0.5089464892 0.6649227376 -0.3939996476 0.378966359701 +1403637243038319104.0000000000 11.3832706001 0.4036660198 0.3090602601 0.5090678062 0.6677890191 -0.3903038119 0.377585393139 +1403637243088318976.0000000000 11.3607370180 0.4444912110 0.3163554908 0.5073751233 0.6711092951 -0.3867269373 0.37765735037 +1403637243138319104.0000000000 11.3316695583 0.4862157948 0.3230298845 0.5046846275 0.6747510355 -0.3840787101 0.377475842055 +1403637243188318976.0000000000 11.3002380506 0.5284520200 0.3270660002 0.5015989820 0.6786400235 -0.3847337420 0.373933319559 +1403637243238319104.0000000000 11.2654066077 0.5714328816 0.3294927204 0.4988347170 0.6822407575 -0.3870900493 0.36860923427 +1403637243288318976.0000000000 11.2263637288 0.6150490759 0.3310747459 0.4974398283 0.6844433367 -0.3895720795 0.363764389463 +1403637243338319104.0000000000 11.1849296992 0.6591639072 0.3307068593 0.4959950092 0.6864588325 -0.3919367333 0.359372813786 +1403637243388318976.0000000000 11.1407496488 0.7038595553 0.3290268668 0.4956788930 0.6872758558 -0.3940305009 0.355941424008 +1403637243438319104.0000000000 11.0941865520 0.7489503325 0.3262300337 0.4958691066 0.6873234206 -0.3964870803 0.352843222536 +1403637243488318976.0000000000 11.0448356344 0.7941051452 0.3239195959 0.4960140201 0.6873615523 -0.3970294581 0.351954255213 +1403637243538319104.0000000000 10.9934555351 0.8401401576 0.3228262039 0.4958598099 0.6875237894 -0.3992964029 0.349279931467 +1403637243588318976.0000000000 10.9392854234 0.8863906764 0.3221000775 0.4944651494 0.6887489320 -0.4033233147 0.34417935515 +1403637243638319104.0000000000 10.8838366662 0.9331165812 0.3230435778 0.4930735535 0.6898546049 -0.4073734134 0.339154827417 +1403637243688318976.0000000000 10.8237915803 0.9802908630 0.3268218197 0.4902586372 0.6917760503 -0.4121350288 0.333522237533 +1403637243738319104.0000000000 10.7664474793 1.0279413223 0.3332920684 0.4899774998 0.6915985058 -0.4164612244 0.328897560198 +1403637243788318976.0000000000 10.7087326876 1.0758703929 0.3415113858 0.4887835799 0.6921795012 -0.4229396589 0.321092190821 +1403637243838319104.0000000000 10.6507051414 1.1236580118 0.3520277582 0.4888833374 0.6917819791 -0.4303049611 0.311878848786 +1403637243888318976.0000000000 10.5933357918 1.1703777684 0.3644450702 0.4877521079 0.6918602611 -0.4357643544 0.305837682143 +1403637243938319104.0000000000 10.5358063338 1.2159169548 0.3794829868 0.4879419361 0.6911410331 -0.4408430705 0.299823492294 +1403637243988318976.0000000000 10.4795481160 1.2600826001 0.3967310704 0.4874566665 0.6907246974 -0.4430559086 0.298306641668 +1403637244038319104.0000000000 10.4247367141 1.3030346084 0.4163870207 0.4870355823 0.6902671024 -0.4443046748 0.298196285732 +1403637244088318976.0000000000 10.3707437546 1.3444950279 0.4381110940 0.4867685532 0.6896272994 -0.4453505127 0.298552314316 +1403637244138319104.0000000000 10.3177211286 1.3845761691 0.4612968104 0.4856595761 0.6896343683 -0.4454694561 0.300160253788 +1403637244188318976.0000000000 10.2663582415 1.4238683442 0.4860471659 0.4859746117 0.6886177738 -0.4453273174 0.302188383064 +1403637244238319104.0000000000 10.2160938320 1.4621691695 0.5125923589 0.4861765829 0.6876717119 -0.4456606075 0.303523590187 +1403637244288318976.0000000000 10.1668038057 1.4996517389 0.5400759446 0.4853959394 0.6877420969 -0.4468099618 0.302923172112 +1403637244338319104.0000000000 10.1179396654 1.5356898212 0.5683658506 0.4838274393 0.6881656186 -0.4481237201 0.302529704129 +1403637244388318976.0000000000 10.0694264017 1.5706621927 0.5976231347 0.4823140528 0.6894948380 -0.4493315752 0.300118573869 +1403637244438319104.0000000000 10.0215509261 1.6045828095 0.6278708963 0.4806283656 0.6919833308 -0.4485308323 0.298287674053 +1403637244488318976.0000000000 9.9753507559 1.6378815223 0.6591726296 0.4788817783 0.6954133897 -0.4454449497 0.297743608915 +1403637244538319104.0000000000 9.9306699341 1.6707277027 0.6908649498 0.4769653789 0.7000487771 -0.4391780848 0.299263005949 +1403637244588318976.0000000000 9.8871130496 1.7033335212 0.7215022722 0.4747211828 0.7055315807 -0.4320812717 0.300284468268 +1403637244638319104.0000000000 9.8649239362 1.7389281906 0.7581849707 0.4724483708 0.7114752152 -0.4243000305 0.300940258573 +1403637244688318976.0000000000 9.8253346824 1.7720529485 0.7872469804 0.4713642973 0.7170205002 -0.4167414321 0.30003979795 +1403637244738319104.0000000000 9.7865264438 1.8057660451 0.8147381829 0.4710508138 0.7219952584 -0.4098185793 0.298132034032 +1403637244788318976.0000000000 9.7489452130 1.8403171141 0.8409827479 0.4711856999 0.7260055260 -0.4040326573 0.29607030281 +1403637244838319104.0000000000 9.7125035734 1.8756773567 0.8659563715 0.4716006291 0.7292697525 -0.3992453420 0.293873495936 +1403637244888318976.0000000000 9.6771245379 1.9119516656 0.8897302032 0.4724223563 0.7320339861 -0.3950254432 0.291373059288 +1403637244938319104.0000000000 9.6425941105 1.9495167211 0.9122249682 0.4730896743 0.7343311817 -0.3927973497 0.287496291626 +1403637244988318976.0000000000 9.6090275204 1.9878189875 0.9333238237 0.4733347457 0.7364490102 -0.3917758660 0.283034882506 +1403637245038319104.0000000000 9.5761289360 2.0269323305 0.9529234026 0.4734337851 0.7378320449 -0.3940364370 0.276042769967 +1403637245088318976.0000000000 9.5444144751 2.0669225126 0.9708583425 0.4731026749 0.7391104811 -0.3992921875 0.265434181442 +1403637245138319104.0000000000 9.5137779698 2.1068215932 0.9870358897 0.4718803607 0.7405835375 -0.4043012575 0.255744877404 +1403637245188318976.0000000000 9.4866650216 2.1475011892 1.0016274928 0.4695625020 0.7423146384 -0.4077404591 0.249454910558 +1403637245238319104.0000000000 9.4624393683 2.1880247800 1.0153695297 0.4686795428 0.7434451889 -0.4061069593 0.250411411471 +1403637245288318976.0000000000 9.4416183626 2.2291603719 1.0286284068 0.4694841770 0.7432920991 -0.4022557808 0.255522503376 +1403637245338319104.0000000000 9.4236560836 2.2709572435 1.0405022716 0.4693025226 0.7436081394 -0.3975302406 0.262243751431 +1403637245388318976.0000000000 9.4075221458 2.3138062647 1.0517940589 0.4704504191 0.7431591186 -0.3938451046 0.266977454452 +1403637245438319104.0000000000 9.3928370784 2.3573930724 1.0615634144 0.4711510650 0.7435443941 -0.3897581761 0.270641778284 +1403637245488318976.0000000000 9.3792951795 2.4025655491 1.0702159536 0.4718843401 0.7446056148 -0.3857186277 0.272229293354 +1403637245538319104.0000000000 9.3665916666 2.4493451637 1.0778810710 0.4732940944 0.7460780369 -0.3818874686 0.271149818956 +1403637245588318976.0000000000 9.3553190959 2.4967509242 1.0838852651 0.4740346095 0.7485221739 -0.3765975306 0.270518103249 +1403637245638319104.0000000000 9.3446416939 2.5456263146 1.0885783301 0.4752895059 0.7513916227 -0.3720198931 0.266667797126 +1403637245688318976.0000000000 9.3348217147 2.5954092855 1.0916691236 0.4765675322 0.7547819074 -0.3659272913 0.263220206474 +1403637245738319104.0000000000 9.3261379125 2.6469289587 1.0939842163 0.4807878775 0.7569751395 -0.3588985831 0.258888899155 +1403637245788318976.0000000000 9.3185703053 2.7001462748 1.0954510409 0.4884907200 0.7577448142 -0.3498223628 0.25460543511 +1403637245838319104.0000000000 9.3114401557 2.7544238690 1.0962048766 0.4984734221 0.7577587501 -0.3378877840 0.251312096067 +1403637245888318976.0000000000 9.3044012853 2.8091747934 1.0951590125 0.5078588847 0.7586280975 -0.3253615347 0.24637904664 +1403637245938319104.0000000000 9.2968146920 2.8642995247 1.0925914324 0.5167333209 0.7603927759 -0.3121659765 0.239461697408 +1403637245988318976.0000000000 9.2883797945 2.9190893568 1.0883642432 0.5243962487 0.7633142884 -0.2974349252 0.2321472308 +1403637246038319104.0000000000 9.2794708044 2.9740348206 1.0829601537 0.5313438656 0.7670412697 -0.2816307789 0.223619076636 +1403637246088318976.0000000000 9.2696154813 3.0290317159 1.0764573551 0.5383102138 0.7710134624 -0.2652282928 0.213106328308 +1403637246138319104.0000000000 9.2590123692 3.0842318030 1.0683481540 0.5446860674 0.7753882383 -0.2472950616 0.202324789357 +1403637246188318976.0000000000 9.2470811179 3.1383939488 1.0591240874 0.5504690817 0.7800313522 -0.2289008413 0.190103352278 +1403637246238319104.0000000000 9.2342786154 3.1921622926 1.0484215448 0.5563485325 0.7842606737 -0.2101160625 0.176812743997 +1403637246288318976.0000000000 9.2206431506 3.2454550606 1.0363420728 0.5606101019 0.7891341567 -0.1901920725 0.1637393414 +1403637246338319104.0000000000 9.2061025567 3.2982307159 1.0235050058 0.5656463212 0.7929364447 -0.1689740703 0.150810468665 +1403637246388318976.0000000000 9.1909894845 3.3500678981 1.0096597082 0.5696818553 0.7966165196 -0.1464414891 0.139354205829 +1403637246438319104.0000000000 9.1752106017 3.4013525126 0.9947046115 0.5731244656 0.7998124621 -0.1228120038 0.12940472997 +1403637246488318976.0000000000 9.1584867759 3.4520814315 0.9785337824 0.5778147570 0.8011754452 -0.0996362527 0.119668833332 +1403637246538319104.0000000000 9.1402364026 3.5018638880 0.9613973286 0.5831125193 0.8012900327 -0.0784824447 0.108418537389 +1403637246588318976.0000000000 9.1209501915 3.5504267971 0.9432856177 0.5887931755 0.8001600441 -0.0570087559 0.0990782619149 +1403637246638319104.0000000000 9.0997314746 3.5974253086 0.9243097542 0.5940640254 0.7987623413 -0.0378073504 0.0873914189858 +1403637246688318976.0000000000 9.0766762358 3.6428693861 0.9053189360 0.6007488933 0.7955903879 -0.0193956853 0.0758980185953 +1403637246738319104.0000000000 9.0514875417 3.6863589214 0.8862581995 0.6046164165 0.7938374016 -0.0010881277 0.0652685583331 +1403637246788318976.0000000000 9.0238337040 3.7273761791 0.8689726282 0.6078981895 0.7920689010 0.0157801985 0.0532694343067 +1403637246838319104.0000000000 8.9944818245 3.7653311880 0.8528386811 0.6099013397 0.7906985816 0.0325671480 0.041898565148 +1403637246888318976.0000000000 8.9628191193 3.8000381192 0.8383583664 0.6096345992 0.7906074365 0.0483532936 0.0307814197567 +1403637246938319104.0000000000 8.9291703380 3.8322904580 0.8254193409 0.6061682787 0.7926678069 0.0621722293 0.0192971424986 +1403637246988318976.0000000000 8.8939242014 3.8625091654 0.8141494881 0.6002724559 0.7962375123 0.0746685761 0.0101688910247 +1403637247038319104.0000000000 8.8570576833 3.8905858082 0.8047826985 0.5947327615 0.7995060563 0.0841506119 0.00129720362306 +1403637247088318976.0000000000 8.8190419200 3.9175168814 0.7959958408 0.5880923591 0.8036258317 0.0910755528 -0.00617604146141 +1403637247138319104.0000000000 8.7796496213 3.9431957396 0.7869704080 0.5819712807 0.8074834609 0.0953555964 -0.0136820711276 +1403637247188318976.0000000000 8.7394793056 3.9678216486 0.7766282859 0.5771395505 0.8104189248 0.0988917296 -0.0187491674272 +1403637247238319104.0000000000 8.6980376562 3.9923956489 0.7657941748 0.5734995097 0.8126993865 0.1001819878 -0.0241161540025 +1403637247288318976.0000000000 8.6559040106 4.0156242363 0.7532415161 0.5729910265 0.8128248950 0.1010546338 -0.0280166842943 +1403637247338319104.0000000000 8.6126950961 4.0386301476 0.7407708279 0.5773562705 0.8096336743 0.1008839635 -0.0312326146 +1403637247388318976.0000000000 8.5682668028 4.0621571044 0.7292691403 0.5883656804 0.8016208588 0.1006175696 -0.0332555190128 +1403637247438319104.0000000000 8.5229545585 4.0851621520 0.7174031661 0.6001012150 0.7929180751 0.0996525791 -0.035054550337 +1403637247488318976.0000000000 8.4772645151 4.1064485641 0.7035945218 0.6064274379 0.7882223264 0.0979691348 -0.03678825003 +1403637247538319104.0000000000 8.4312849756 4.1251551976 0.6876169162 0.6084676637 0.7865977478 0.0984217319 -0.0366639882006 +1403637247588318976.0000000000 8.3844019825 4.1413398685 0.6700641807 0.6088327090 0.7860452582 0.1004215989 -0.0370281904998 +1403637247638319104.0000000000 8.3369923409 4.1545984193 0.6515659678 0.6087997563 0.7855674035 0.1041693164 -0.037355922082 +1403637247688318976.0000000000 8.2891125046 4.1654698565 0.6325468296 0.6101585466 0.7836761025 0.1108464761 -0.0356563188359 +1403637247738319104.0000000000 8.2404399686 4.1735757695 0.6133513892 0.6110070955 0.7819386677 0.1186099498 -0.0342626482191 +1403637247788318976.0000000000 8.1906834299 4.1789240234 0.5950362434 0.6111293728 0.7805372353 0.1273374655 -0.0326754319481 +1403637247838319104.0000000000 8.1389375595 4.1815494880 0.5792656454 0.6121776118 0.7782662757 0.1358208268 -0.0330587170011 +1403637247888318976.0000000000 8.0851548008 4.1805566849 0.5661365626 0.6123697758 0.7768526127 0.1415976400 -0.0381232767218 +1403637247938319104.0000000000 8.0291497949 4.1762245587 0.5562616023 0.6140676378 0.7741943942 0.1460148657 -0.0471554367526 +1403637247988318976.0000000000 7.9722112716 4.1683544193 0.5478059797 0.6147727501 0.7722611298 0.1496829083 -0.0571160231722 +1403637248038319104.0000000000 7.9147094158 4.1568367596 0.5398508915 0.6112568797 0.7734105434 0.1542579019 -0.066375131818 +1403637248088318976.0000000000 7.8569529033 4.1423248227 0.5330284006 0.6051496148 0.7762493533 0.1610298097 -0.0728030610585 +1403637248138319104.0000000000 7.7987718578 4.1253092909 0.5275422714 0.5983373645 0.7794651753 0.1676429969 -0.0795126672451 +1403637248188318976.0000000000 7.7409713918 4.1068937890 0.5225971659 0.5917913150 0.7825027894 0.1738864638 -0.0850642216543 +1403637248238319104.0000000000 7.6828844507 4.0871496495 0.5160186705 0.5856853399 0.7853413936 0.1801343883 -0.0881089120374 +1403637248288318976.0000000000 7.6238488268 4.0661948778 0.5087929461 0.5813302045 0.7872032674 0.1831469514 -0.0939329724378 +1403637248338319104.0000000000 7.5649092020 4.0446266284 0.4993671809 0.5786442503 0.7878929253 0.1874383301 -0.0962415827437 +1403637248388318976.0000000000 7.5050727756 4.0224919928 0.4893195060 0.5775608834 0.7878395637 0.1893361749 -0.0994186134265 +1403637248438319104.0000000000 7.4449966926 3.9996455460 0.4780761752 0.5776208947 0.7871791621 0.1901067761 -0.102773938785 +1403637248488318976.0000000000 7.3848719228 3.9760884085 0.4661743353 0.5792321123 0.7855392781 0.1910788834 -0.104436884886 +1403637248538319104.0000000000 7.3240634733 3.9520144396 0.4547464889 0.5834084082 0.7821888742 0.1908404052 -0.106747993746 +1403637248588318976.0000000000 7.2631272875 3.9269002298 0.4443505426 0.5868899569 0.7794505611 0.1910692143 -0.107282601644 +1403637248638319104.0000000000 7.2024060954 3.9002075879 0.4351473652 0.5876172595 0.7789323833 0.1914240950 -0.106428917313 +1403637248688318976.0000000000 7.1417378110 3.8714463158 0.4270023955 0.5852214709 0.7808912589 0.1916897362 -0.104784143287 +1403637248738319104.0000000000 7.0807485614 3.8412110517 0.4208882466 0.5817912943 0.7837159518 0.1917506578 -0.102663927385 +1403637248788318976.0000000000 7.0198044880 3.8099841841 0.4170812850 0.5782207762 0.7867102198 0.1917726370 -0.099854993134 +1403637248838319104.0000000000 6.9576594281 3.7769814955 0.4159806025 0.5755214540 0.7891640189 0.1906502313 -0.0982226886895 +1403637248888318976.0000000000 6.8951333348 3.7435062512 0.4166566127 0.5733818865 0.7912548428 0.1889111220 -0.0972706228042 +1403637248938319104.0000000000 6.8320529750 3.7097792605 0.4196697929 0.5720118797 0.7927972698 0.1865471769 -0.0973398646087 +1403637248988318976.0000000000 6.7690419104 3.6751003952 0.4239320907 0.5709448774 0.7940955733 0.1845006218 -0.0969210400799 +1403637249038319104.0000000000 6.7054302744 3.6406238729 0.4304953444 0.5715023780 0.7941306037 0.1832068797 -0.0957959055899 +1403637249088318976.0000000000 6.6408972895 3.6059028939 0.4385436427 0.5713043865 0.7946981836 0.1821274469 -0.0943169547609 +1403637249138319104.0000000000 6.5752894611 3.5707128966 0.4487542022 0.5720469316 0.7945523482 0.1807127084 -0.0937645507854 +1403637249188318976.0000000000 6.5090584554 3.5344914404 0.4604005482 0.5717602755 0.7950341887 0.1800615550 -0.0926750373002 +1403637249238319104.0000000000 6.4422050106 3.4980423677 0.4740488861 0.5723792498 0.7948978064 0.1787709003 -0.0925226298365 +1403637249288318976.0000000000 6.3745970997 3.4619314824 0.4890567636 0.5730231838 0.7947394969 0.1772715082 -0.0927813302573 +1403637249338319104.0000000000 6.3089203661 3.4260113471 0.5046052738 0.5747725085 0.7937326616 0.1768176650 -0.0914359813883 +1403637249388318976.0000000000 6.2417773310 3.3895421097 0.5172153583 0.5746731274 0.7940340695 0.1757043033 -0.0915897966673 +1403637249438319104.0000000000 6.1740517753 3.3529280733 0.5261610176 0.5745351451 0.7942658816 0.1748262133 -0.0921242179085 +1403637249488318976.0000000000 6.1112771299 3.3174257097 0.5307058072 0.5750407448 0.7940257120 0.1742701387 -0.0920935899264 +1403637249538319104.0000000000 6.0447975134 3.2811098986 0.5303147942 0.5747438692 0.7942829747 0.1739614155 -0.0923117917005 +1403637249588318976.0000000000 5.9786613872 3.2438205177 0.5254323898 0.5747795668 0.7942352017 0.1736874786 -0.0930137289156 +1403637249638319104.0000000000 5.9124022154 3.2060077709 0.5163369375 0.5751336514 0.7939161616 0.1738242879 -0.0932927025907 +1403637249688318976.0000000000 5.8457306169 3.1684300019 0.5060266112 0.5769645497 0.7925413185 0.1737930653 -0.0937343976736 +1403637249738319104.0000000000 5.7823162651 3.1313463671 0.4952609296 0.5806561138 0.7897105675 0.1732727351 -0.0957718979197 +1403637249788318976.0000000000 5.7172357468 3.0937739139 0.4854456210 0.5843203784 0.7866967127 0.1741200918 -0.0967479777947 +1403637249838319104.0000000000 5.6518757371 3.0552910473 0.4771476936 0.5873318711 0.7838549077 0.1754839875 -0.099086462598 +1403637249888318976.0000000000 5.5863296297 3.0156601518 0.4703629800 0.5884805371 0.7819799306 0.1781223112 -0.102325401748 +1403637249938319104.0000000000 5.5322176021 2.9773560213 0.4618503346 0.5876352251 0.7811339620 0.1827840001 -0.105378294544 +1403637249988318976.0000000000 5.4687855801 2.9345094532 0.4574753652 0.5845285700 0.7817575821 0.1863924059 -0.111531631164 +1403637250038319104.0000000000 5.4049738947 2.8899207313 0.4550907748 0.5800144748 0.7834781531 0.1890806642 -0.118294949997 +1403637250088318976.0000000000 5.3406132818 2.8442770634 0.4552805102 0.5757103371 0.7849957310 0.1912133848 -0.125605539293 +1403637250138319104.0000000000 5.2775600372 2.7985056501 0.4565881222 0.5708486307 0.7867629735 0.1950214465 -0.130776525918 +1403637250188318976.0000000000 5.2118964222 2.7505744283 0.4590789847 0.5681221996 0.7867750075 0.1991952353 -0.136174565057 +1403637250238319104.0000000000 5.1478097482 2.7028537874 0.4604690900 0.5655086465 0.7865477052 0.2026823729 -0.143047313695 +1403637250288318976.0000000000 5.0841551377 2.6550681120 0.4604991999 0.5630304105 0.7864033907 0.2055506059 -0.149383440906 +1403637250338319104.0000000000 5.0216208932 2.6080839683 0.4593126899 0.5611093626 0.7860181128 0.2071657434 -0.156250325914 +1403637250388318976.0000000000 4.9593465281 2.5613378896 0.4564791599 0.5591248821 0.7859908738 0.2092312752 -0.160685985771 +1403637250438319104.0000000000 4.8988696950 2.5156055820 0.4522021302 0.5565077032 0.7866456062 0.2097417138 -0.165820022761 +1403637250488318976.0000000000 4.8409160324 2.4709923215 0.4464576552 0.5536169979 0.7875972701 0.2099861506 -0.170600634061 +1403637250538319104.0000000000 4.7852909246 2.4274258222 0.4397015939 0.5501899600 0.7892312749 0.2109169414 -0.172971230228 +1403637250588318976.0000000000 4.7319469369 2.3848012289 0.4337903374 0.5475812770 0.7903891646 0.2114675009 -0.175274669045 +1403637250638319104.0000000000 4.6804729618 2.3435061844 0.4293911903 0.5456132251 0.7907185903 0.2151969298 -0.175387003556 +1403637250688318976.0000000000 4.6306006657 2.3031995179 0.4267166826 0.5440743127 0.7907951738 0.2176858350 -0.176745615234 +1403637250738319104.0000000000 4.5819951980 2.2639767808 0.4259378348 0.5430861104 0.7906609335 0.2202034244 -0.177265949494 +1403637250788318976.0000000000 4.5342425089 2.2265986183 0.4269976760 0.5425657793 0.7903019927 0.2234230657 -0.176429218593 +1403637250838319104.0000000000 4.4879796381 2.1907147596 0.4307850309 0.5429846804 0.7894848644 0.2242882693 -0.177696533415 +1403637250888318976.0000000000 4.4424346739 2.1563526153 0.4361655260 0.5441260366 0.7882786354 0.2247621813 -0.17895700905 +1403637250938319104.0000000000 4.3983739598 2.1234483440 0.4422118604 0.5431233452 0.7886566819 0.2244958907 -0.180663402469 +1403637250988318976.0000000000 4.3557384445 2.0917074868 0.4502196708 0.5431063453 0.7884043669 0.2240318572 -0.182383603765 +1403637251038319104.0000000000 4.3143912632 2.0610476913 0.4600231255 0.5423135252 0.7882799680 0.2247521682 -0.184383283844 +1403637251088318976.0000000000 4.2742444319 2.0312112459 0.4715744421 0.5401155518 0.7887197479 0.2259216927 -0.187498636848 +1403637251138319104.0000000000 4.2350473726 2.0029760422 0.4848493124 0.5366886420 0.7896933355 0.2273851355 -0.191430764436 +1403637251188318976.0000000000 4.1977940784 1.9762817182 0.5002985588 0.5338909761 0.7902051328 0.2289304677 -0.19526165704 +1403637251238319104.0000000000 4.1622731949 1.9514129711 0.5174362565 0.5315145714 0.7904497550 0.2309268718 -0.198378993662 +1403637251288318976.0000000000 4.1289924878 1.9280455728 0.5362795300 0.5304722731 0.7898156562 0.2331542144 -0.201070905442 +1403637251338319104.0000000000 4.0979358304 1.9064253110 0.5575263972 0.5315732120 0.7874468314 0.2378010425 -0.202010079551 +1403637251388318976.0000000000 4.0691001119 1.8874583118 0.5806150584 0.5361126402 0.7827052050 0.2450720826 -0.199738512582 +1403637251438319104.0000000000 4.0412054936 1.8695086683 0.6047692290 0.5381387412 0.7791139238 0.2511981077 -0.200717960302 +1403637251488318976.0000000000 4.0145965590 1.8526875264 0.6279345088 0.5401298121 0.7751177576 0.2583508329 -0.201759993729 +1403637251538319104.0000000000 3.9890445638 1.8364580629 0.6496361503 0.5408269359 0.7716292861 0.2651057204 -0.204483317736 +1403637251588318976.0000000000 3.9647150092 1.8209098334 0.6694867303 0.5410485634 0.7683129053 0.2720278390 -0.207274181824 +1403637251638319104.0000000000 3.9412466746 1.8061079639 0.6878116840 0.5409988615 0.7654033086 0.2778569936 -0.210412685246 +1403637251688318976.0000000000 3.9187403485 1.7916724822 0.7044695418 0.5398368579 0.7634122275 0.2826124797 -0.214261812068 +1403637251738319104.0000000000 3.8972092334 1.7779060397 0.7197599133 0.5387672943 0.7617270077 0.2865128144 -0.217743370582 +1403637251788318976.0000000000 3.8766769633 1.7648704619 0.7339622686 0.5382608168 0.7600070996 0.2897467787 -0.220706379251 +1403637251838319104.0000000000 3.8575007022 1.7526081258 0.7468798442 0.5380919438 0.7584988043 0.2932881913 -0.221627301429 +1403637251888318976.0000000000 3.8393850531 1.7411010854 0.7592519954 0.5406388160 0.7553929335 0.2957366721 -0.222780177396 +1403637251938319104.0000000000 3.8223093592 1.7302502504 0.7701978535 0.5441057632 0.7517751727 0.2995953268 -0.22141736224 +1403637251988318976.0000000000 3.8061313069 1.7197668735 0.7803464906 0.5492108773 0.7472085618 0.3030780259 -0.219523319304 +1403637252038319104.0000000000 3.7904276152 1.7088871176 0.7896211025 0.5525214456 0.7442227800 0.3050902411 -0.21856909805 +1403637252088318976.0000000000 3.7760952304 1.6972476146 0.7980820527 0.5560696021 0.7409317640 0.3066048671 -0.218632509654 +1403637252138319104.0000000000 3.7624018461 1.6847365507 0.8055780001 0.5584628836 0.7387297654 0.3066250733 -0.219951371546 +1403637252188318976.0000000000 3.7494772922 1.6710667213 0.8122016484 0.5598178053 0.7373335509 0.3052706771 -0.223053969275 +1403637252238319104.0000000000 3.7379740682 1.6565593817 0.8170793994 0.5592045134 0.7375537963 0.3040881782 -0.225466382567 +1403637252288318976.0000000000 3.7279830294 1.6413369324 0.8201361356 0.5580023402 0.7382332887 0.3033819546 -0.227165995234 +1403637252338319104.0000000000 3.7193760986 1.6255186746 0.8212090806 0.5559747531 0.7396376142 0.3028654367 -0.228255998489 +1403637252388318976.0000000000 3.7126316998 1.6088703044 0.8202447674 0.5524849423 0.7421835612 0.3028482715 -0.228488236943 +1403637252438319104.0000000000 3.7068244074 1.5917912695 0.8174569235 0.5480234391 0.7455569450 0.3030065837 -0.228039825815 +1403637252488318976.0000000000 3.7019899479 1.5744470393 0.8132950625 0.5449327870 0.7479355709 0.3031184324 -0.227507923803 +1403637252538319104.0000000000 3.6981407096 1.5569757943 0.8075039141 0.5425559919 0.7497709820 0.3032848392 -0.226924605581 +1403637252588318976.0000000000 3.6951291716 1.5394788219 0.8005755850 0.5403580014 0.7515024620 0.3032056739 -0.226547123882 +1403637252638319104.0000000000 3.6924705393 1.5219803409 0.7924278306 0.5375694509 0.7536179461 0.3027017228 -0.22682756398 +1403637252688318976.0000000000 3.6907043737 1.5046795823 0.7829209579 0.5328816847 0.7570001773 0.3025105743 -0.226881453751 +1403637252738319104.0000000000 3.6897844404 1.4878368157 0.7732497318 0.5272792622 0.7609392371 0.3017258591 -0.227836702676 +1403637252788318976.0000000000 3.6896360980 1.4721057686 0.7649907706 0.5215916796 0.7649642399 0.3005306452 -0.229026554524 +1403637252838319104.0000000000 3.6908267190 1.4577271862 0.7580565571 0.5188012426 0.7669537194 0.3012568027 -0.227753379427 +1403637252888318976.0000000000 3.6923428856 1.4455021809 0.7534315305 0.5213117997 0.7654271525 0.3024194729 -0.225605283957 +1403637252938319104.0000000000 3.6939002724 1.4351475946 0.7517169452 0.5264691713 0.7621720064 0.3028718349 -0.224037264578 +1403637252988318976.0000000000 3.6958325675 1.4259766148 0.7519958079 0.5311308166 0.7590736267 0.3043048294 -0.221598411056 +1403637253038319104.0000000000 3.6988468071 1.4170390283 0.7535038936 0.5349737853 0.7565766408 0.3051224724 -0.21976149008 +1403637253088318976.0000000000 3.7024814636 1.4079033762 0.7566862635 0.5375872282 0.7548868260 0.3049466825 -0.219438767925 +1403637253138319104.0000000000 3.7066083361 1.3990550091 0.7611204546 0.5398903062 0.7534394332 0.3049992422 -0.218684567648 +1403637253188318976.0000000000 3.7110977181 1.3901547800 0.7647509680 0.5408529924 0.7529048557 0.3048689638 -0.218328270815 +1403637253238319104.0000000000 3.7154780582 1.3814759276 0.7679193450 0.5420663030 0.7521970944 0.3044081600 -0.218401754762 +1403637253288318976.0000000000 3.7201170025 1.3727705184 0.7693083712 0.5422973904 0.7522435166 0.3042976811 -0.217821379533 +1403637253338319104.0000000000 3.7250632832 1.3640017251 0.7693494862 0.5416658184 0.7528442008 0.3033518131 -0.21863537678 +1403637253388318976.0000000000 3.7306051533 1.3554584759 0.7677118226 0.5424413704 0.7523923200 0.3038334648 -0.217596833925 +1403637253438319104.0000000000 3.7366266855 1.3466753749 0.7647987806 0.5421048223 0.7527218862 0.3022786150 -0.21945332657 +1403637253488318976.0000000000 3.7434130918 1.3382183256 0.7597540068 0.5429386443 0.7522438225 0.3024056843 -0.218855345266 +1403637253538319104.0000000000 3.7507671239 1.3297070031 0.7529426291 0.5421452273 0.7529524648 0.3028481337 -0.217770857078 +1403637253588318976.0000000000 3.7586914449 1.3208104994 0.7462673174 0.5422027453 0.7529506622 0.3031762359 -0.217176548749 +1403637253638319104.0000000000 3.7670354713 1.3121118139 0.7404343835 0.5428694558 0.7524753745 0.3043870640 -0.215457838145 +1403637253688318976.0000000000 3.7756278717 1.3035167996 0.7363679417 0.5444348582 0.7513380347 0.3053938156 -0.214047799028 +1403637253738319104.0000000000 3.7850837723 1.2946705886 0.7342459247 0.5456219664 0.7504916624 0.3062013304 -0.212837214033 +1403637253788318976.0000000000 3.7946657563 1.2857558399 0.7342003422 0.5481892430 0.7485984278 0.3075587749 -0.210942048078 +1403637253838319104.0000000000 3.8043997894 1.2763017781 0.7356589994 0.5488915527 0.7482368271 0.3076950754 -0.210198607414 +1403637253888318976.0000000000 3.8140167279 1.2662911999 0.7385800594 0.5495610679 0.7476454021 0.3082352810 -0.209761762414 +1403637253938319104.0000000000 3.8239423536 1.2554373804 0.7427990582 0.5497661061 0.7475405740 0.3080798367 -0.209826435548 +1403637253988318976.0000000000 3.8339830916 1.2441421092 0.7482506249 0.5500243095 0.7474689384 0.3081666880 -0.209276700813 +1403637254038319104.0000000000 3.8439058960 1.2323149538 0.7558675350 0.5513549397 0.7464402498 0.3089045181 -0.208357103768 +1403637254088318976.0000000000 3.8541231604 1.2192333817 0.7646038009 0.5516551468 0.7460079530 0.3090226606 -0.208934746483 +1403637254138319104.0000000000 3.8643551634 1.2051177563 0.7747028008 0.5522242661 0.7445395109 0.3108576583 -0.20994473777 +1403637254188318976.0000000000 3.8747897278 1.1898328556 0.7860461543 0.5509703491 0.7438362855 0.3132480498 -0.212167184229 +1403637254238319104.0000000000 3.8856323435 1.1736007406 0.7984605379 0.5488514267 0.7432286860 0.3174990899 -0.213465593618 +1403637254288318976.0000000000 3.8967678871 1.1564438866 0.8121942522 0.5461101402 0.7427598526 0.3226338146 -0.21442699885 +1403637254338319104.0000000000 3.9081002439 1.1383939153 0.8266095322 0.5428626525 0.7427205489 0.3274257038 -0.215542884763 +1403637254388318976.0000000000 3.9191824442 1.1200480255 0.8409512510 0.5393805986 0.7428326921 0.3320568981 -0.216809542714 +1403637254438319104.0000000000 3.9299878158 1.1014641026 0.8545449400 0.5367105439 0.7426389982 0.3354904808 -0.218804130881 +1403637254488318976.0000000000 3.9407178118 1.0827739248 0.8665289708 0.5343086165 0.7426420367 0.3391894486 -0.218969462628 +1403637254538319104.0000000000 3.9507942751 1.0639096117 0.8774195191 0.5321978613 0.7424465402 0.3418333348 -0.220654804154 +1403637254588318976.0000000000 3.9602432760 1.0450820529 0.8870018834 0.5318161593 0.7412481704 0.3440775825 -0.222111097633 +1403637254638319104.0000000000 3.9691062526 1.0262315070 0.8951121385 0.5319305926 0.7401283695 0.3450715827 -0.224021079614 +1403637254688318976.0000000000 3.9776031746 1.0073640828 0.9013952342 0.5326887792 0.7385753045 0.3465533494 -0.225055460211 +1403637254738319104.0000000000 3.9855797177 0.9884837806 0.9067830257 0.5342936759 0.7366852148 0.3470703652 -0.226643605231 +1403637254788318976.0000000000 3.9931933146 0.9691349291 0.9109554045 0.5357031994 0.7351597014 0.3466773046 -0.228860529706 +1403637254838319104.0000000000 4.0007984937 0.9493043406 0.9138994200 0.5365055717 0.7341127456 0.3456770596 -0.231835326601 +1403637254888318976.0000000000 4.0085145452 0.9293313110 0.9149314859 0.5377581212 0.7328563687 0.3452325708 -0.23356416255 +1403637254938319104.0000000000 4.0160668702 0.9090713798 0.9146273601 0.5384207130 0.7321703702 0.3446027166 -0.235114126614 +1403637254988318976.0000000000 4.0236488277 0.8883394932 0.9133491046 0.5400808717 0.7308449483 0.3441360881 -0.236111555196 +1403637255038319104.0000000000 4.0316175363 0.8669461356 0.9106497092 0.5399907757 0.7305412610 0.3446829896 -0.236459436016 +1403637255088318976.0000000000 4.0398363895 0.8449530103 0.9081132113 0.5401600502 0.7292001978 0.3459272591 -0.238387338542 +1403637255138319104.0000000000 4.0485085067 0.8215520723 0.9057823667 0.5386148882 0.7283740209 0.3481771896 -0.24111808825 +1403637255188318976.0000000000 4.0572321985 0.7978742335 0.9042045927 0.5374579749 0.7267215543 0.3518198362 -0.243387573055 +1403637255238319104.0000000000 4.0660236578 0.7738592869 0.9046164983 0.5361507717 0.7249300392 0.3553127153 -0.246519091765 +1403637255288318976.0000000000 4.0755470292 0.7492531694 0.9072523983 0.5350636080 0.7231847865 0.3579400444 -0.250179184988 +1403637255338319104.0000000000 4.0854899856 0.7245138289 0.9115250232 0.5343077520 0.7212577548 0.3605424847 -0.253597306755 +1403637255388318976.0000000000 4.0960977579 0.6988280755 0.9160553925 0.5313879300 0.7204860093 0.3637980185 -0.257250422852 +1403637255438319104.0000000000 4.1073351359 0.6726324638 0.9197358508 0.5294663404 0.7186690137 0.3683549396 -0.259797770697 +1403637255488318976.0000000000 4.1188110757 0.6461566468 0.9221140744 0.5272302439 0.7166362220 0.3733377915 -0.262830151612 +1403637255538319104.0000000000 4.1308631135 0.6191123397 0.9229110139 0.5253528843 0.7138709770 0.3792808359 -0.265591081579 +1403637255588318976.0000000000 4.1429346369 0.5920540313 0.9219734695 0.5237873502 0.7103715569 0.3862253773 -0.268046676546 +1403637255638319104.0000000000 4.1555450468 0.5642515398 0.9197810218 0.5221673364 0.7065970058 0.3927872230 -0.271625001736 +1403637255688318976.0000000000 4.1685778741 0.5359227151 0.9163710149 0.5192210270 0.7031229613 0.4008515978 -0.274491571734 +1403637255738319104.0000000000 4.1819107080 0.5069239049 0.9131207669 0.5154759130 0.6996799088 0.4092656933 -0.277910418458 +1403637255788318976.0000000000 4.1953097454 0.4775576153 0.9111257095 0.5118244013 0.6958276682 0.4181895576 -0.281028703829 +1403637255838319104.0000000000 4.2085614706 0.4477862668 0.9110390803 0.5070649606 0.6924089008 0.4268500037 -0.285051072759 +1403637255888318976.0000000000 4.2217283286 0.4170275820 0.9128686858 0.5022846459 0.6887100538 0.4356582579 -0.289120180213 +1403637255938319104.0000000000 4.2342602984 0.3865359377 0.9174279294 0.4987910633 0.6843672533 0.4432787678 -0.293858591601 +1403637255988318976.0000000000 4.2463833260 0.3558320783 0.9241373850 0.4947833864 0.6810277843 0.4498647617 -0.298349214276 +1403637256038319104.0000000000 4.2586238084 0.3251817275 0.9331174618 0.4922523564 0.6773972806 0.4559418771 -0.301558529438 +1403637256088318976.0000000000 4.2714361276 0.2943919142 0.9439963167 0.4902191573 0.6744498995 0.4611316484 -0.30357884268 +1403637256138319104.0000000000 4.2835792036 0.2635482743 0.9556295855 0.4893847840 0.6715511052 0.4645817437 -0.306080789423 +1403637256188318976.0000000000 4.2950770526 0.2328251840 0.9671024216 0.4900296084 0.6684120895 0.4667673186 -0.308584723804 +1403637256238319104.0000000000 4.3061774493 0.2019639539 0.9773821654 0.4917543411 0.6650419854 0.4676362922 -0.31179019211 +1403637256288318976.0000000000 4.3169140706 0.1709883048 0.9860818940 0.4923474384 0.6631253149 0.4682396606 -0.314022987971 +1403637256338319104.0000000000 4.3276147241 0.1396392698 0.9926271779 0.4933291278 0.6614024005 0.4689994020 -0.314980629843 +1403637256388318976.0000000000 4.3382096923 0.1077571536 0.9975907867 0.4942925049 0.6601523702 0.4691503674 -0.315866586444 +1403637256438319104.0000000000 4.3490987667 0.0753638749 1.0007668392 0.4954272172 0.6591489345 0.4698136608 -0.315197840532 +1403637256488318976.0000000000 4.3600445826 0.0423698423 1.0027359347 0.4964574679 0.6587517653 0.4694819843 -0.314901191947 +1403637256538319104.0000000000 4.3710104261 0.0087536514 1.0035051664 0.4969566925 0.6587821722 0.4683565610 -0.3157249233 +1403637256588318976.0000000000 4.3823354335 -0.0252328848 1.0025636587 0.4971112380 0.6592596645 0.4676365284 -0.315552197068 +1403637256638319104.0000000000 4.3939228469 -0.0597102057 0.9997814163 0.4949773016 0.6617675774 0.4671261688 -0.31441101569 +1403637256688318976.0000000000 4.4057847488 -0.0952602340 0.9958396938 0.4894999095 0.6664779953 0.4655001804 -0.315446512679 +1403637256738319104.0000000000 4.4180850191 -0.1312816468 0.9906800665 0.4824564062 0.6722977826 0.4637102454 -0.31658224187 +1403637256788318976.0000000000 4.4302630977 -0.1670249579 0.9849432068 0.4765840642 0.6774881404 0.4610504624 -0.318292193659 +1403637256838319104.0000000000 4.4418732006 -0.2018508010 0.9787217305 0.4727080743 0.6810640040 0.4582091538 -0.320535911139 +1403637256888318976.0000000000 4.4530369888 -0.2357633074 0.9718204571 0.4717985175 0.6817038354 0.4570894936 -0.322110593642 +1403637256938319104.0000000000 4.4630940105 -0.2683451595 0.9647133348 0.4747305967 0.6787216670 0.4578919051 -0.322959382296 +1403637256988318976.0000000000 4.4737755722 -0.3006375386 0.9586134388 0.4759005490 0.6759205320 0.4600004358 -0.324113716233 +1403637257038319104.0000000000 4.4850743510 -0.3327221746 0.9540887898 0.4781219554 0.6712361465 0.4637507886 -0.325233204776 +1403637257088318976.0000000000 4.4939390669 -0.3638951658 0.9512850093 0.4795729392 0.6670682477 0.4674072218 -0.326435656653 +1403637257138319104.0000000000 4.5046626956 -0.3953300596 0.9501895065 0.4803142342 0.6636160290 0.4711165757 -0.327049192827 +1403637257188318976.0000000000 4.5147063813 -0.4266921759 0.9512093299 0.4803404577 0.6607578092 0.4742834823 -0.32821843455 +1403637257238319104.0000000000 4.5252095659 -0.4581416563 0.9536747497 0.4792744797 0.6589398465 0.4775309831 -0.328722393465 +1403637257288318976.0000000000 4.5355574097 -0.4896322164 0.9577565984 0.4778131097 0.6573689359 0.4808304621 -0.329185025466 +1403637257338319104.0000000000 4.5461365435 -0.5211028681 0.9639493499 0.4762759122 0.6560603883 0.4841231738 -0.329197167387 +1403637257388318976.0000000000 4.5563769694 -0.5523491485 0.9711012582 0.4756130386 0.6543266880 0.4874861641 -0.328642758497 +1403637257438319104.0000000000 4.5662871296 -0.5836061940 0.9784090898 0.4748223541 0.6530951550 0.4898954134 -0.328653213185 +1403637257488318976.0000000000 4.5759355968 -0.6148948709 0.9846749137 0.4741439676 0.6521417764 0.4915963730 -0.328985725445 +1403637257538319104.0000000000 4.5855338864 -0.6461111441 0.9894460243 0.4746359611 0.6504776838 0.4943715987 -0.32740832266 +1403637257588318976.0000000000 4.5948703309 -0.6779188552 0.9927586015 0.4723740727 0.6510897197 0.4956017671 -0.327603114581 +1403637257638319104.0000000000 4.6036791376 -0.7100693885 0.9946172356 0.4696735982 0.6523573282 0.4964000303 -0.327755453767 +1403637257688318976.0000000000 4.6119227589 -0.7426377899 0.9946535057 0.4657281005 0.6544229631 0.4978302676 -0.327097762812 +1403637257738319104.0000000000 4.6192534834 -0.7753453661 0.9938035920 0.4628094172 0.6552095131 0.4993975420 -0.327276690767 +1403637257788318976.0000000000 4.6262164317 -0.8081831637 0.9915257795 0.4590101602 0.6558843550 0.5015879928 -0.327925099999 +1403637257838319104.0000000000 4.6326008350 -0.8408705835 0.9877999384 0.4555906999 0.6557356508 0.5044093108 -0.328662619676 +1403637257888318976.0000000000 4.6379893638 -0.8736074013 0.9827606026 0.4517139601 0.6552074058 0.5076084235 -0.330138519495 +1403637257938319104.0000000000 4.6423246650 -0.9062211324 0.9767956610 0.4479129251 0.6538937294 0.5108452756 -0.332917567264 +1403637257988318976.0000000000 4.6454655055 -0.9385114115 0.9699759862 0.4448109357 0.6514186889 0.5147637755 -0.335879708629 +1403637258038319104.0000000000 4.6473627051 -0.9706730219 0.9629694345 0.4409173454 0.6483279429 0.5191003983 -0.340290389986 +1403637258088318976.0000000000 4.6479812305 -1.0026095000 0.9569220372 0.4371194865 0.6443435713 0.5240980917 -0.345063917118 +1403637258138319104.0000000000 4.6474486898 -1.0341455111 0.9527451728 0.4350115581 0.6382359956 0.5295714156 -0.350676309517 +1403637258188318976.0000000000 4.6455278613 -1.0650820981 0.9508641364 0.4348909313 0.6299097104 0.5355470007 -0.356753478835 +1403637258238319104.0000000000 4.6425300537 -1.0953350901 0.9504619673 0.4360023088 0.6214746303 0.5412683045 -0.361524401828 +1403637258288318976.0000000000 4.6383624861 -1.1251504313 0.9504147694 0.4371328454 0.6140223095 0.5453994472 -0.366648226402 +1403637258338319104.0000000000 4.6336212093 -1.1548820322 0.9493649374 0.4378720326 0.6073534812 0.5491849425 -0.371195003919 +1403637258388318976.0000000000 4.6288298698 -1.1845930721 0.9468616296 0.4365372675 0.6030743069 0.5520594611 -0.375455651016 +1403637258438319104.0000000000 4.6238254285 -1.2143825701 0.9429177217 0.4334589323 0.6008197357 0.5536021508 -0.380333613886 +1403637258488318976.0000000000 4.6189398679 -1.2440466923 0.9371878649 0.4284822651 0.6005783678 0.5550668162 -0.38419969048 +1403637258538319104.0000000000 4.6136188478 -1.2733790517 0.9301687739 0.4226745212 0.6017169751 0.5559438076 -0.387568592359 +1403637258588318976.0000000000 4.6078036138 -1.3017584120 0.9222317956 0.4196093333 0.6017270850 0.5565628026 -0.389987652768 +1403637258638319104.0000000000 4.6014973033 -1.3291026968 0.9137104883 0.4195813381 0.6002786677 0.5566178308 -0.392165287 +1403637258688318976.0000000000 4.5949738693 -1.3556759154 0.9044452517 0.4211037448 0.5983064804 0.5562961030 -0.393999539797 +1403637258738319104.0000000000 4.5885660568 -1.3816545356 0.8946211198 0.4216420747 0.5970952157 0.5559115412 -0.395799977982 +1403637258788318976.0000000000 4.5822468057 -1.4065712931 0.8841747763 0.4231328433 0.5958908516 0.5555976253 -0.396464334741 +1403637258838319104.0000000000 4.5765498056 -1.4309221988 0.8735434268 0.4239913770 0.5951277205 0.5548806555 -0.397695570391 +1403637258888318976.0000000000 4.5715227842 -1.4548290006 0.8633109685 0.4245736987 0.5947722207 0.5537385516 -0.399195185684 +1403637258938319104.0000000000 4.5667384005 -1.4781244255 0.8546669200 0.4238925915 0.5955973954 0.5526142169 -0.400245350752 +1403637258988318976.0000000000 4.5619338487 -1.5004877776 0.8486913846 0.4235353691 0.5962028997 0.5520504832 -0.400499884538 +1403637259038319104.0000000000 4.5573804563 -1.5221978208 0.8452504044 0.4223633933 0.5976146693 0.5507042740 -0.401485583295 +1403637259088318976.0000000000 4.5523319116 -1.5429103559 0.8434573409 0.4233575911 0.5977279960 0.5508350035 -0.400087980044 +1403637259138319104.0000000000 4.5473954258 -1.5629642617 0.8460540153 0.4239944396 0.5975083686 0.5504381957 -0.400287718236 +1403637259188318976.0000000000 4.5434811599 -1.5822296854 0.8512640829 0.4235568882 0.5983071741 0.5495507395 -0.400776836381 +1403637259238319104.0000000000 4.5396643485 -1.6005043605 0.8587326064 0.4243588430 0.5984560933 0.5486998530 -0.400871984568 +1403637259288318976.0000000000 4.5361426847 -1.6181726666 0.8670093702 0.4243654759 0.5988968674 0.5476988492 -0.401574968863 +1403637259338319104.0000000000 4.5329731492 -1.6350210160 0.8745011206 0.4240066978 0.5998748843 0.5470511762 -0.401376947554 +1403637259388318976.0000000000 4.5300248799 -1.6512242087 0.8811465207 0.4236304268 0.6006510929 0.5461941105 -0.401780437206 +1403637259438319104.0000000000 4.5285018165 -1.6669708171 0.8885012204 0.4223853585 0.6020970478 0.5436481579 -0.404371653658 +1403637259488318976.0000000000 4.5268264863 -1.6816743443 0.8942176241 0.4200595201 0.6040132339 0.5405778066 -0.408036331611 +1403637259538319104.0000000000 4.5257427940 -1.6948732023 0.8987434012 0.4186943192 0.6052384742 0.5386858815 -0.410120686435 +1403637259588318976.0000000000 4.5253043608 -1.7064134598 0.9021817687 0.4179708022 0.6059019599 0.5376810929 -0.411196140313 +1403637259638319104.0000000000 4.5252344190 -1.7162976529 0.9048478882 0.4189709520 0.6056062441 0.5374030935 -0.410977290713 +1403637259688318976.0000000000 4.5255185679 -1.7246900931 0.9062665254 0.4203003292 0.6050537104 0.5389118175 -0.408450356563 +1403637259738319104.0000000000 4.5263152751 -1.7317555011 0.9065050971 0.4204591552 0.6052011714 0.5414079699 -0.404750603584 +1403637259788318976.0000000000 4.5277372355 -1.7377276203 0.9058539203 0.4206917558 0.6052509806 0.5442279388 -0.400631561137 +1403637259838319104.0000000000 4.5292752860 -1.7427924514 0.9047294741 0.4214445813 0.6048666057 0.5462058147 -0.397718571564 +1403637259888318976.0000000000 4.5305683666 -1.7474266758 0.9036391712 0.4212388010 0.6051206337 0.5448663641 -0.399383946029 +1403637259938319104.0000000000 4.5320291676 -1.7513150711 0.9017956533 0.4208349826 0.6054467965 0.5423197862 -0.402767108416 +1403637259988318976.0000000000 4.5338848187 -1.7540110623 0.8983675678 0.4215098750 0.6048740896 0.5415333448 -0.403978214062 +1403637260038319104.0000000000 4.5360226446 -1.7554971308 0.8936425582 0.4238662007 0.6032042531 0.5419523165 -0.403447344248 +1403637260088318976.0000000000 4.5387088254 -1.7561470731 0.8877597071 0.4260998003 0.6015245868 0.5428768720 -0.402357842641 +1403637260138319104.0000000000 4.5419433808 -1.7558660301 0.8804578989 0.4276172422 0.6003578474 0.5448096682 -0.399870447452 +1403637260188318976.0000000000 4.5456325078 -1.7550486036 0.8721219606 0.4288613685 0.5993845404 0.5470002742 -0.396997228408 +1403637260238319104.0000000000 4.5497635654 -1.7539752063 0.8627086547 0.4302418900 0.5981079326 0.5500715992 -0.393166698404 +1403637260288318976.0000000000 4.5540801045 -1.7528175313 0.8531221395 0.4323268475 0.5964538271 0.5522205365 -0.390370091234 +1403637260338319104.0000000000 4.5588836443 -1.7514748222 0.8430985745 0.4348772448 0.5943379850 0.5546871865 -0.38725478274 +1403637260388318976.0000000000 4.5639110986 -1.7502247356 0.8327619675 0.4388398606 0.5912340695 0.5573328790 -0.383721140751 +1403637260438319104.0000000000 4.5689590973 -1.7494330202 0.8221229773 0.4421425786 0.5885123878 0.5594725930 -0.380990193171 +1403637260488318976.0000000000 4.5741427767 -1.7497504592 0.8111586209 0.4409107790 0.5890121102 0.5612379671 -0.379044012383 +1403637260538319104.0000000000 4.5793624959 -1.7508602039 0.7997314454 0.4377117667 0.5911588118 0.5634692255 -0.376087889162 +1403637260588318976.0000000000 4.5843941145 -1.7529016429 0.7882442179 0.4331063120 0.5942093120 0.5654065190 -0.373697316478 +1403637260638319104.0000000000 4.5886513623 -1.7558698837 0.7768478704 0.4286841152 0.5972538414 0.5665075588 -0.372272701319 +1403637260688318976.0000000000 4.5918621553 -1.7594268056 0.7655331541 0.4268386130 0.5986887418 0.5667645232 -0.371696871304 +1403637260738319104.0000000000 4.5942593653 -1.7637960661 0.7547572442 0.4261255028 0.5991209778 0.5650572493 -0.374408085901 +1403637260788318976.0000000000 4.5958986185 -1.7684015982 0.7438693133 0.4281990858 0.5975193313 0.5639465859 -0.376271763289 +1403637260838319104.0000000000 4.5970579850 -1.7736137912 0.7332267336 0.4304908858 0.5955459292 0.5617536067 -0.380046745573 +1403637260888318976.0000000000 4.5979403094 -1.7791745900 0.7222442083 0.4319510080 0.5941515959 0.5601625691 -0.382910046677 +1403637260938319104.0000000000 4.5987120038 -1.7850504810 0.7115285172 0.4340841611 0.5924418722 0.5581425194 -0.386083536567 +1403637260988318976.0000000000 4.5995081584 -1.7910570521 0.7002799300 0.4364755479 0.5904907655 0.5572580356 -0.387650917139 +1403637261038319104.0000000000 4.6006768043 -1.7974437409 0.6888969912 0.4364444607 0.5903778931 0.5568992942 -0.388372697493 +1403637261088318976.0000000000 4.6024678896 -1.8041265547 0.6772291802 0.4338978472 0.5920334996 0.5579484725 -0.387198263893 +1403637261138319104.0000000000 4.6042474584 -1.8110419454 0.6654426416 0.4300932672 0.5947550958 0.5599354547 -0.384393605778 +1403637261188318976.0000000000 4.6060966949 -1.8181517097 0.6539553300 0.4265716941 0.5971550992 0.5627642715 -0.380445465227 +1403637261238319104.0000000000 4.6076253975 -1.8256527123 0.6432642979 0.4226856249 0.5997455589 0.5651900565 -0.37709723817 +1403637261288318976.0000000000 4.6083638069 -1.8332201906 0.6339796979 0.4208352601 0.6010529775 0.5668674948 -0.374558734264 +1403637261338319104.0000000000 4.6078581633 -1.8408752015 0.6268863910 0.4220228475 0.6002978699 0.5663197311 -0.375261436466 +1403637261388318976.0000000000 4.6063516155 -1.8489734037 0.6217379650 0.4244296027 0.5987734873 0.5637856321 -0.378781710627 +1403637261438319104.0000000000 4.6043194393 -1.8573181024 0.6178435327 0.4256841132 0.5980931737 0.5602319807 -0.383689612919 +1403637261488318976.0000000000 4.6021872596 -1.8654619080 0.6147637826 0.4260631368 0.5977678218 0.5575583489 -0.387649999658 +1403637261538319104.0000000000 4.6003873806 -1.8731016976 0.6112353259 0.4238917713 0.5994872226 0.5578049293 -0.38702002144 +1403637261588318976.0000000000 4.5986588949 -1.8804212083 0.6076540409 0.4203394760 0.6020121457 0.5602293320 -0.383456903552 +1403637261638319104.0000000000 4.5964670093 -1.8873371554 0.6049856553 0.4171806692 0.6041747527 0.5633290714 -0.378937349322 +1403637261688318976.0000000000 4.5930277583 -1.8940984913 0.6042672015 0.4151866135 0.6056602843 0.5653018976 -0.375805083344 +1403637261738319104.0000000000 4.5881586506 -1.9004567026 0.6051784548 0.4158228471 0.6054344077 0.5661761912 -0.374145771547 +1403637261788318976.0000000000 4.5817342120 -1.9068127567 0.6083915825 0.4188511486 0.6033905062 0.5645836226 -0.376469049856 +1403637261838319104.0000000000 4.5739944783 -1.9130341752 0.6125142104 0.4237465046 0.6003351451 0.5620624099 -0.379634641048 +1403637261888318976.0000000000 4.5655986360 -1.9193668916 0.6161992641 0.4270698531 0.5982356301 0.5593059433 -0.383278401756 +1403637261938319104.0000000000 4.5574883368 -1.9256384350 0.6182516942 0.4301163747 0.5964401895 0.5570000268 -0.386018101521 +1403637261988318976.0000000000 4.5497907889 -1.9317143976 0.6177723467 0.4326187434 0.5952255710 0.5552498050 -0.387614752705 +1403637262038319104.0000000000 4.5419421446 -1.9380306282 0.6151638084 0.4333471016 0.5951931653 0.5527779048 -0.390374145621 +1403637262088318976.0000000000 4.5346057947 -1.9440446178 0.6103401900 0.4344841919 0.5948391422 0.5506695780 -0.392623098757 +1403637262138319104.0000000000 4.5278712155 -1.9501969470 0.6034598466 0.4332904988 0.5961870590 0.5490786408 -0.394123052613 +1403637262188318976.0000000000 4.5214424586 -1.9562265114 0.5948234677 0.4327496787 0.5969249777 0.5474156599 -0.395909562744 +1403637262238319104.0000000000 4.5156541842 -1.9618562360 0.5846148747 0.4322945066 0.5976887707 0.5460791108 -0.397098473565 +1403637262288318976.0000000000 4.5108240686 -1.9667176447 0.5726824782 0.4311171881 0.5991567262 0.5446093092 -0.398183234072 +1403637262338319104.0000000000 4.5127971884 -1.9672887373 0.5761294645 0.4283355784 0.5997133208 0.5194146259 -0.432528625142 +1403637262388318976.0000000000 4.5168987334 -1.9642046189 0.5725722445 0.4455642220 0.5884996087 0.5363933977 -0.409173383179 +1403637262438319104.0000000000 4.5183509225 -1.9604750192 0.5712207207 0.4446337208 0.6032209358 0.5306013653 -0.396090328148 +1403637262488318976.0000000000 4.5204113651 -1.9581259696 0.5669351403 0.4408841838 0.6179557945 0.5185598139 -0.393506660501 +1403637262538319104.0000000000 4.5238495082 -1.9590589364 0.5685795759 0.4456251779 0.6142812581 0.5047793112 -0.411429925678 +1403637262588318976.0000000000 4.5268725499 -1.9578512943 0.5710118457 0.4552182945 0.6086061983 0.5010941937 -0.41385916532 +1403637262638319104.0000000000 4.5267222813 -1.9561532050 0.5710752576 0.4572353954 0.6091241820 0.4989612224 -0.413450387239 +1403637262688318976.0000000000 4.5249731489 -1.9565211379 0.5654588691 0.4460361428 0.6164796051 0.5080285639 -0.403623133785 +1403637262738319104.0000000000 4.5234887370 -1.9565050092 0.5654304832 0.4452771449 0.6186268128 0.5086425114 -0.400389717977 +1403637262788318976.0000000000 4.5251733281 -1.9558522220 0.5663870807 0.4479397885 0.6160760031 0.5048981408 -0.406051932275 +1403637262838319104.0000000000 4.5251185135 -1.9558094221 0.5664790089 0.4483566465 0.6155124290 0.5055702860 -0.405609976741 +1403637262888318976.0000000000 4.5237962115 -1.9567194699 0.5663397171 0.4461348682 0.6165077980 0.5062457011 -0.405705687123 +1403637262938319104.0000000000 4.5244595522 -1.9555807923 0.5664653478 0.4482844985 0.6155272739 0.5060646191 -0.405050348486 +1403637262988318976.0000000000 4.5239742126 -1.9561096420 0.5665935745 0.4467191060 0.6162344645 0.5059323442 -0.405868929779 +1403637263038319104.0000000000 4.5240620515 -1.9557084824 0.5666220420 0.4474612420 0.6158989289 0.5062307586 -0.405188061685 +1403637263088318976.0000000000 4.5237404994 -1.9557909119 0.5666773108 0.4471147505 0.6160879021 0.5061513094 -0.405382472244 +1403637263138319104.0000000000 4.5237948681 -1.9558219024 0.5668495496 0.4469956473 0.6161613851 0.5060178205 -0.405568741632 +1403637263188318976.0000000000 4.5237149416 -1.9554945177 0.5668566597 0.4475081450 0.6159090577 0.5062141287 -0.40514164033 +1403637263238319104.0000000000 4.5236227186 -1.9558630116 0.5669063955 0.4467118390 0.6163193555 0.5060525420 -0.405598088929 +1403637263288318976.0000000000 4.5236430236 -1.9556039245 0.5669190861 0.4471395456 0.6161509412 0.5062210479 -0.40517217949 +1403637263338319104.0000000000 4.5236874611 -1.9556016460 0.5670194188 0.4470791337 0.6161538459 0.5061482203 -0.405325382162 +1403637263388318976.0000000000 4.5234876471 -1.9557595412 0.5670241295 0.4469537891 0.6162105629 0.5061523095 -0.405372288412 +1403637263438319104.0000000000 4.5235770445 -1.9558072913 0.5669772995 0.4467998427 0.6163191052 0.5061268120 -0.405408819951 +1403637263488318976.0000000000 4.5236033279 -1.9556869591 0.5669413568 0.4471118298 0.6161591887 0.5062600390 -0.405141504606 +1403637263538319104.0000000000 4.5237363454 -1.9559182865 0.5669337257 0.4467087913 0.6163589208 0.5060594881 -0.405532651008 +1403637263588318976.0000000000 4.5236729843 -1.9558193441 0.5668253872 0.4469449110 0.6162572218 0.5061740393 -0.405284005467 +1403637263638319104.0000000000 4.5237562545 -1.9559038515 0.5668505879 0.4467474108 0.6163678028 0.5060981433 -0.405428356112 +1403637263688318976.0000000000 4.5237412344 -1.9558308329 0.5668005261 0.4467878985 0.6163211566 0.5061841473 -0.405347276616 +1403637263738319104.0000000000 4.5236422264 -1.9558540654 0.5668400383 0.4468603596 0.6162907008 0.5061625048 -0.405340732997 +1403637263788318976.0000000000 4.5236156041 -1.9560019994 0.5669299967 0.4465866025 0.6164809507 0.5059366268 -0.405635025028 +1403637263838319104.0000000000 4.5237339180 -1.9557633463 0.5668818709 0.4469987480 0.6162443479 0.5062768870 -0.405115707673 +1403637263888318976.0000000000 4.5236265101 -1.9560614226 0.5669964853 0.4465263387 0.6165153579 0.5059146587 -0.405676472581 +1403637263938319104.0000000000 4.5236519531 -1.9559339938 0.5669204220 0.4467242522 0.6164334365 0.5061151927 -0.405332792397 +1403637263988318976.0000000000 4.5237056571 -1.9559393972 0.5669529855 0.4466170721 0.6164875201 0.5060497609 -0.405450327368 +1403637264038319104.0000000000 4.5237338087 -1.9560010819 0.5669490542 0.4465247209 0.6165228036 0.5060241278 -0.405530379085 +1403637264088318976.0000000000 4.5237625205 -1.9559304897 0.5668855010 0.4465511513 0.6165128988 0.5061096197 -0.405409629599 +1403637264138319104.0000000000 4.5238485948 -1.9560311731 0.5669615466 0.4463974278 0.6166042773 0.5059716496 -0.405612119469 +1403637264188318976.0000000000 4.5238589103 -1.9559051464 0.5669549575 0.4466009277 0.6165085070 0.5060616636 -0.405421342333 +1403637264238319104.0000000000 4.5238123500 -1.9559886095 0.5669541856 0.4462959299 0.6166730190 0.5059842153 -0.40560362966 +1403637264288318976.0000000000 4.5237410605 -1.9558664210 0.5669498817 0.4463918614 0.6166114942 0.5060199242 -0.405547047281 +1403637264338319104.0000000000 4.5237244845 -1.9556858436 0.5669014235 0.4464062094 0.6166010363 0.5060742828 -0.405479319619 +1403637264388318976.0000000000 4.5236701917 -1.9555772678 0.5667892589 0.4462904014 0.6166278820 0.5061063656 -0.405525929372 diff --git a/data/euroc_groundtruth/MH_04_difficult.txt b/data/euroc_groundtruth/MH_04_difficult.txt new file mode 100755 index 00000000..b29e4c02 --- /dev/null +++ b/data/euroc_groundtruth/MH_04_difficult.txt @@ -0,0 +1,1977 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403638128945096960.0000000000 4.6265387629 -1.7083496317 0.5461395743 0.5103444218 0.7886542665 -0.2868608379 0.187840034894 +1403638128995097088.0000000000 4.6264667325 -1.7086660172 0.5459771241 0.5103545302 0.7886576935 -0.2868694803 0.187784975855 +1403638129045096960.0000000000 4.6265826468 -1.7086672982 0.5459224344 0.5105650855 0.7887041375 -0.2861953050 0.188046069704 +1403638129095097088.0000000000 4.6266594564 -1.7086902883 0.5461518903 0.5095481369 0.7896265709 -0.2838013806 0.190544879462 +1403638129145096960.0000000000 4.6265764041 -1.7085134380 0.5469755807 0.5093628176 0.7896618557 -0.2826272271 0.192627942413 +1403638129195097088.0000000000 4.6267783987 -1.7082456054 0.5488787730 0.5113749782 0.7883076370 -0.2827621014 0.192645516975 +1403638129245096960.0000000000 4.6272339803 -1.7077847482 0.5529592999 0.5180352556 0.7837527253 -0.2869508712 0.187163931189 +1403638129295097088.0000000000 4.6284473929 -1.7074542724 0.5599171069 0.5297565726 0.7745431633 -0.2957947689 0.178735325688 +1403638129345096960.0000000000 4.6302831126 -1.7077073301 0.5682943014 0.5432033052 0.7627725207 -0.3068792631 0.170098114669 +1403638129395097088.0000000000 4.6313335338 -1.7080333601 0.5758898882 0.5528686513 0.7537294017 -0.3167727016 0.160882872985 +1403638129445096960.0000000000 4.6320791899 -1.7088266421 0.5805192415 0.5528399619 0.7527759908 -0.3212247354 0.156559744282 +1403638129495097088.0000000000 4.6318611996 -1.7093173713 0.5825376902 0.5449275584 0.7596984092 -0.3184428401 0.156545331229 +1403638129545096960.0000000000 4.6309573253 -1.7095449163 0.5833191401 0.5337461913 0.7701087610 -0.3104013885 0.160307446978 +1403638129595097088.0000000000 4.6302519116 -1.7095513040 0.5849344727 0.5238058714 0.7795870088 -0.3001647552 0.166651206006 +1403638129645096960.0000000000 4.6300114780 -1.7093429283 0.5881647634 0.5178649796 0.7853048374 -0.2920117115 0.172746448889 +1403638129695097088.0000000000 4.6304285300 -1.7089230865 0.5934252807 0.5177596401 0.7857565457 -0.2884046889 0.177015087998 +1403638129745096960.0000000000 4.6306944381 -1.7081088690 0.6003197164 0.5214061138 0.7832112676 -0.2884830113 0.17746359357 +1403638129795097088.0000000000 4.6304825665 -1.7072738470 0.6079204169 0.5218352639 0.7830865853 -0.2890553360 0.175813452065 +1403638129845096960.0000000000 4.6297027466 -1.7064570789 0.6162028514 0.5172684881 0.7869778469 -0.2876369059 0.174253235359 +1403638129895097088.0000000000 4.6286399232 -1.7052582262 0.6264462279 0.5119891586 0.7915682497 -0.2851021437 0.173215401285 +1403638129945096960.0000000000 4.6279600712 -1.7038640313 0.6396164262 0.5094834911 0.7941344912 -0.2821404544 0.17370591852 +1403638129995097088.0000000000 4.6277633240 -1.7016933612 0.6561908476 0.5132090996 0.7920005591 -0.2817173545 0.173167163686 +1403638130045096960.0000000000 4.6281045230 -1.6994771070 0.6754077944 0.5213725722 0.7861464668 -0.2841499289 0.171473588627 +1403638130095097088.0000000000 4.6284529895 -1.6975694487 0.6956640076 0.5291457539 0.7806242435 -0.2865233267 0.168922896323 +1403638130145096960.0000000000 4.6282415200 -1.6959079523 0.7156849888 0.5334093264 0.7782817449 -0.2865478486 0.166259876663 +1403638130195097088.0000000000 4.6276764732 -1.6944425933 0.7352616017 0.5339174741 0.7792888961 -0.2836119682 0.164939985299 +1403638130245096960.0000000000 4.6271123313 -1.6930132430 0.7553323343 0.5343280568 0.7803863731 -0.2804693764 0.163791224804 +1403638130295097088.0000000000 4.6268829640 -1.6914049418 0.7769824585 0.5389111541 0.7777442633 -0.2804610415 0.161338876625 +1403638130345096960.0000000000 4.6270492809 -1.6897567594 0.7997074930 0.5457727377 0.7724039834 -0.2843000674 0.157154945355 +1403638130395097088.0000000000 4.6270277814 -1.6884224261 0.8221989396 0.5512874298 0.7682855539 -0.2871549260 0.15284477677 +1403638130445096960.0000000000 4.6262848221 -1.6871553033 0.8433924477 0.5535940737 0.7674663642 -0.2867644429 0.149315557294 +1403638130495097088.0000000000 4.6252078508 -1.6863522327 0.8631529546 0.5523071851 0.7700608784 -0.2820480095 0.149706169127 +1403638130545096960.0000000000 4.6241106227 -1.6857190502 0.8822442057 0.5489587499 0.7738667490 -0.2764449131 0.152816084847 +1403638130595097088.0000000000 4.6231970315 -1.6847369692 0.9018205256 0.5484397328 0.7746894934 -0.2737877688 0.155274936799 +1403638130645096960.0000000000 4.6228185538 -1.6839091400 0.9222932971 0.5523096620 0.7717372031 -0.2734342589 0.156873938856 +1403638130695097088.0000000000 4.6228592120 -1.6832799780 0.9435722070 0.5583280042 0.7666182068 -0.2766076355 0.155095392321 +1403638130745096960.0000000000 4.6226685485 -1.6824648947 0.9648519304 0.5661972694 0.7598849863 -0.2827591196 0.14846797625 +1403638130795097088.0000000000 4.6222318663 -1.6820673547 0.9843140109 0.5714577872 0.7555529981 -0.2874641521 0.141209156269 +1403638130845096960.0000000000 4.6219608266 -1.6825674650 1.0009325774 0.5732478263 0.7546098320 -0.2879027113 0.138068678372 +1403638130895097088.0000000000 4.6216363237 -1.6838736069 1.0140858267 0.5753420494 0.7534734684 -0.2877914510 0.135776799607 +1403638130945096960.0000000000 4.6224393857 -1.6857148998 1.0238896651 0.5800781962 0.7489702707 -0.2891081895 0.137728989894 +1403638130995097088.0000000000 4.6239067658 -1.6876855203 1.0296513732 0.5872912705 0.7417812693 -0.2911186248 0.141772558409 +1403638131045096960.0000000000 4.6250379999 -1.6889138555 1.0309189735 0.5934216524 0.7356904133 -0.2929760533 0.144136707762 +1403638131095097088.0000000000 4.6261631464 -1.6898518843 1.0267175475 0.5946903291 0.7341500336 -0.2927309603 0.147226782528 +1403638131145096960.0000000000 4.6263353024 -1.6902465238 1.0177860170 0.5907938818 0.7377397587 -0.2906631704 0.149055556781 +1403638131195097088.0000000000 4.6260877092 -1.6904104021 1.0052499983 0.5828187121 0.7452246769 -0.2859987011 0.152207991622 +1403638131245096960.0000000000 4.6258634630 -1.6907393971 0.9907177497 0.5730681062 0.7539968036 -0.2804380926 0.156320958685 +1403638131295097088.0000000000 4.6256303404 -1.6912456137 0.9757983129 0.5661029333 0.7603392537 -0.2764236526 0.158119108413 +1403638131345096960.0000000000 4.6258529103 -1.6922238522 0.9610684348 0.5626385386 0.7633223390 -0.2747855063 0.158964798466 +1403638131395097088.0000000000 4.6266504827 -1.6924519128 0.9437289418 0.5622804542 0.7630541384 -0.2760169853 0.159385371222 +1403638131445096960.0000000000 4.6269506490 -1.6939525026 0.9273699944 0.5629587519 0.7621149884 -0.2766885090 0.160317363547 +1403638131495097088.0000000000 4.6275920018 -1.6962274327 0.9090225914 0.5610188719 0.7631722782 -0.2747020949 0.165422665626 +1403638131545096960.0000000000 4.6272695152 -1.6982202325 0.8894975622 0.5584607715 0.7649807905 -0.2745011829 0.166057392319 +1403638131595097088.0000000000 4.6270446843 -1.7004386581 0.8688359884 0.5554514150 0.7672561878 -0.2741593543 0.166217677335 +1403638131645096960.0000000000 4.6270178675 -1.7026453032 0.8476821211 0.5533788535 0.7692642716 -0.2723517669 0.166819782796 +1403638131695097088.0000000000 4.6274675815 -1.7048614764 0.8254363502 0.5528120529 0.7697252283 -0.2709598326 0.168827356316 +1403638131745096960.0000000000 4.6276457809 -1.7070794275 0.8024277599 0.5522239519 0.7702022022 -0.2697380883 0.170524597746 +1403638131795097088.0000000000 4.6279815591 -1.7097851883 0.7787088536 0.5502246740 0.7715223488 -0.2668746583 0.175453669788 +1403638131845096960.0000000000 4.6282495263 -1.7126820576 0.7549320698 0.5470964149 0.7734009204 -0.2647347197 0.180144545321 +1403638131895097088.0000000000 4.6283044197 -1.7153954919 0.7324220877 0.5452953492 0.7741957028 -0.2638439878 0.183467561203 +1403638131945096960.0000000000 4.6282777896 -1.7177524606 0.7122689216 0.5441976417 0.7748712879 -0.2626418747 0.185587336954 +1403638131995097088.0000000000 4.6281892316 -1.7200748454 0.6952719558 0.5406572504 0.7780157531 -0.2583905435 0.188720832163 +1403638132045096960.0000000000 4.6275917333 -1.7217579045 0.6828220843 0.5357255419 0.7829294410 -0.2515579530 0.191672195455 +1403638132095097088.0000000000 4.6269947029 -1.7229936794 0.6761824548 0.5292850707 0.7887381769 -0.2451159018 0.194081418471 +1403638132145096960.0000000000 4.6262944218 -1.7231555251 0.6777960149 0.5262753314 0.7920382082 -0.2403833067 0.194745008057 +1403638132195097088.0000000000 4.6260844075 -1.7229057799 0.6881356840 0.5279155568 0.7915464824 -0.2391041173 0.193877673236 +1403638132245096960.0000000000 4.6259411212 -1.7221421351 0.7063153133 0.5350741592 0.7869203919 -0.2411009451 0.190584037212 +1403638132295097088.0000000000 4.6253899022 -1.7212390838 0.7295830399 0.5435152615 0.7813265684 -0.2438213185 0.186201822524 +1403638132345096960.0000000000 4.6249469043 -1.7205212828 0.7557942193 0.5491270062 0.7775776360 -0.2449090727 0.183989394191 +1403638132395097088.0000000000 4.6233217658 -1.7193359971 0.7835977071 0.5536942567 0.7753018415 -0.2474999889 0.176276714789 +1403638132445096960.0000000000 4.6224205262 -1.7184494731 0.8125742317 0.5602306109 0.7711851658 -0.2502111710 0.169733533833 +1403638132495097088.0000000000 4.6214893839 -1.7174250006 0.8423385441 0.5704548131 0.7637527803 -0.2552793090 0.161540927588 +1403638132545096960.0000000000 4.6210973439 -1.7165563482 0.8713397522 0.5825425352 0.7541972659 -0.2603079612 0.155146525057 +1403638132595097088.0000000000 4.6201792826 -1.7149820626 0.8980750145 0.5930339173 0.7456055039 -0.2644031228 0.149913955779 +1403638132645096960.0000000000 4.6199213138 -1.7127061589 0.9286692364 0.5975740938 0.7418814894 -0.2667080356 0.146232287559 +1403638132695097088.0000000000 4.6172603994 -1.7100562175 0.9478057892 0.5945963807 0.7444325000 -0.2678874872 0.143219032376 +1403638132745096960.0000000000 4.6136917601 -1.7064963560 0.9636961344 0.5901762297 0.7481711215 -0.2689187021 0.140052570101 +1403638132795097088.0000000000 4.6100469571 -1.7031121108 0.9763977642 0.5882991122 0.7491826898 -0.2709912186 0.138539565796 +1403638132845096960.0000000000 4.6063478065 -1.7006797564 0.9859776333 0.5922502896 0.7456132364 -0.2727543475 0.137497498537 +1403638132895097088.0000000000 4.6037842286 -1.6989095637 0.9917371694 0.5987520076 0.7392521202 -0.2765911882 0.136013421344 +1403638132945096960.0000000000 4.6022199728 -1.6982592159 0.9932430903 0.6049045087 0.7342216485 -0.2776671270 0.133828520141 +1403638132995097088.0000000000 4.6022668619 -1.6985964076 0.9901724288 0.6081623453 0.7327583425 -0.2751409474 0.132292222734 +1403638133045096960.0000000000 4.6044666201 -1.7005054613 0.9828690849 0.6057439350 0.7366033101 -0.2689989025 0.134645605593 +1403638133095097088.0000000000 4.6092834076 -1.7038210633 0.9728129140 0.6004652698 0.7421652719 -0.2630020660 0.139506566757 +1403638133145096960.0000000000 4.6158261408 -1.7073740388 0.9611870459 0.5958850250 0.7458801128 -0.2612102871 0.142664221631 +1403638133195097088.0000000000 4.6255609811 -1.7128249856 0.9497310312 0.5925462750 0.7468552717 -0.2626459939 0.148705066932 +1403638133245096960.0000000000 4.6371139319 -1.7197601498 0.9384764458 0.5904497298 0.7457426242 -0.2673588855 0.154130728345 +1403638133295097088.0000000000 4.6503831594 -1.7284801245 0.9256415764 0.5865820878 0.7450690115 -0.2724802329 0.162936015263 +1403638133345096960.0000000000 4.6647976028 -1.7396428312 0.9121574571 0.5803815956 0.7467351254 -0.2767875304 0.170095616848 +1403638133395097088.0000000000 4.6801298348 -1.7523343193 0.8989072282 0.5739165575 0.7484813193 -0.2811455313 0.177066907916 +1403638133445096960.0000000000 4.6963720143 -1.7671302728 0.8865358406 0.5673204152 0.7490185334 -0.2869625859 0.186470526808 +1403638133495097088.0000000000 4.7124818478 -1.7829605239 0.8759001653 0.5633160511 0.7469172476 -0.2952696078 0.193921403022 +1403638133545096960.0000000000 4.7288236116 -1.8001835225 0.8661200779 0.5603854688 0.7433394114 -0.3061344004 0.199239490835 +1403638133595097088.0000000000 4.7432917271 -1.8184161659 0.8567485606 0.5573105874 0.7410279049 -0.3167002359 0.199958780528 +1403638133645096960.0000000000 4.7562432703 -1.8366701772 0.8475578064 0.5543075331 0.7395596215 -0.3261571946 0.198535159058 +1403638133695097088.0000000000 4.7680474795 -1.8550558577 0.8382227977 0.5506144450 0.7385396531 -0.3343127289 0.199042490659 +1403638133745096960.0000000000 4.7794263974 -1.8732408968 0.8283982368 0.5458678316 0.7373892095 -0.3418357717 0.203552866377 +1403638133795097088.0000000000 4.7907204064 -1.8895299829 0.8184219055 0.5416451088 0.7357245956 -0.3478397462 0.210564494835 +1403638133845096960.0000000000 4.8016322438 -1.9036692032 0.8080932589 0.5360109939 0.7354689260 -0.3519343716 0.218906079031 +1403638133895097088.0000000000 4.8112889194 -1.9136637937 0.7987492405 0.5313512226 0.7354523542 -0.3558141644 0.223991056496 +1403638133945096960.0000000000 4.8193634801 -1.9184623688 0.7914168730 0.5291259435 0.7341708065 -0.3592767065 0.22790175752 +1403638133995097088.0000000000 4.8255064411 -1.9170026172 0.7864689290 0.5289902818 0.7326414346 -0.3608814217 0.230587097667 +1403638134045096960.0000000000 4.8293934309 -1.9101766575 0.7829605062 0.5279531968 0.7333659179 -0.3601126107 0.231859354145 +1403638134095097088.0000000000 4.8312268464 -1.8990061725 0.7801021534 0.5247906514 0.7371118465 -0.3568281995 0.232238097639 +1403638134145096960.0000000000 4.8322595155 -1.8840627143 0.7784661474 0.5219099832 0.7408501903 -0.3527350946 0.233085645224 +1403638134195097088.0000000000 4.8331102648 -1.8658486640 0.7790182594 0.5227607292 0.7404722676 -0.3512909408 0.234556423467 +1403638134245096960.0000000000 4.8336989478 -1.8444977933 0.7817889060 0.5296067202 0.7344425039 -0.3532515946 0.23521105684 +1403638134295097088.0000000000 4.8332406090 -1.8209756890 0.7847778222 0.5352581630 0.7291657057 -0.3558665662 0.234893719912 +1403638134345096960.0000000000 4.8307455475 -1.7958187967 0.7866835011 0.5364975653 0.7281008375 -0.3586980138 0.231030880501 +1403638134395097088.0000000000 4.8268157905 -1.7697186596 0.7878224099 0.5361035104 0.7289611508 -0.3608840878 0.225768336862 +1403638134445096960.0000000000 4.8216580003 -1.7438990613 0.7887996413 0.5352207203 0.7299572235 -0.3628377054 0.221472417999 +1403638134495097088.0000000000 4.8155888714 -1.7184814157 0.7904119529 0.5366427125 0.7288458574 -0.3648745725 0.218322837851 +1403638134545096960.0000000000 4.8081312527 -1.6942808607 0.7922865024 0.5387133276 0.7269852524 -0.3678096446 0.214467850338 +1403638134595097088.0000000000 4.7984142496 -1.6705922901 0.7943925979 0.5417189726 0.7254826249 -0.3692792917 0.209399905504 +1403638134645096960.0000000000 4.7869742887 -1.6485392019 0.7962969434 0.5412393307 0.7264213118 -0.3700161106 0.206058590159 +1403638134695097088.0000000000 4.7737865772 -1.6276258214 0.7982883372 0.5389709824 0.7291290340 -0.3694478163 0.203443955374 +1403638134745096960.0000000000 4.7592729175 -1.6074706669 0.8003974724 0.5357334761 0.7330332806 -0.3684046604 0.199824568955 +1403638134795097088.0000000000 4.7447896335 -1.5880392613 0.8033577355 0.5310748624 0.7377389956 -0.3665225096 0.198398373954 +1403638134845096960.0000000000 4.7306088675 -1.5695280801 0.8078785665 0.5279917178 0.7407419921 -0.3645915629 0.198995073571 +1403638134895097088.0000000000 4.7167151512 -1.5525650517 0.8132751344 0.5279047725 0.7409773354 -0.3634989506 0.200343835646 +1403638134945096960.0000000000 4.7036497478 -1.5369462696 0.8183990784 0.5309824186 0.7386530298 -0.3630686289 0.201570194771 +1403638134995097088.0000000000 4.6911125531 -1.5228223449 0.8217086385 0.5333031988 0.7368063129 -0.3630747606 0.202190191632 +1403638135045096960.0000000000 4.6790258405 -1.5105416337 0.8225212228 0.5316115172 0.7388381720 -0.3606110175 0.203634585552 +1403638135095097088.0000000000 4.6679670202 -1.5000214941 0.8214808543 0.5279189557 0.7429626905 -0.3572223345 0.204206318471 +1403638135145096960.0000000000 4.6579704581 -1.4918935358 0.8188538369 0.5250493275 0.7467330972 -0.3538046624 0.203801732192 +1403638135195097088.0000000000 4.6502179359 -1.4868548124 0.8151440900 0.5224296268 0.7494466051 -0.3517565430 0.204118606738 +1403638135245096960.0000000000 4.6447042341 -1.4854487124 0.8106206962 0.5195500906 0.7518597425 -0.3507315836 0.204357498645 +1403638135295097088.0000000000 4.6423921225 -1.4872189393 0.8057541917 0.5194804542 0.7518849510 -0.3498230933 0.205992430667 +1403638135345096960.0000000000 4.6420029251 -1.4917855504 0.8002272581 0.5211982118 0.7499399668 -0.3504173500 0.20772614433 +1403638135395097088.0000000000 4.6429693567 -1.4989186346 0.7944990579 0.5216107930 0.7485318447 -0.3511951619 0.210438153263 +1403638135445096960.0000000000 4.6456886739 -1.5087776615 0.7883335564 0.5186919358 0.7491771802 -0.3513587843 0.215033097684 +1403638135495097088.0000000000 4.6498477915 -1.5201713563 0.7824810008 0.5149997641 0.7507999178 -0.3513343356 0.218263398206 +1403638135545096960.0000000000 4.6555762074 -1.5327283945 0.7780485867 0.5102738860 0.7532136545 -0.3525543159 0.219078082442 +1403638135595097088.0000000000 4.6641199881 -1.5471863383 0.7760242000 0.5054122220 0.7550307592 -0.3529811420 0.223363721059 +1403638135645096960.0000000000 4.6747522840 -1.5628321079 0.7757214269 0.5052189058 0.7529231358 -0.3551616846 0.227422045193 +1403638135695097088.0000000000 4.6859571492 -1.5797192436 0.7754918289 0.5079801825 0.7475766373 -0.3608938824 0.229871509951 +1403638135745096960.0000000000 4.6959763848 -1.5970374537 0.7746977325 0.5114149801 0.7421008811 -0.3673735041 0.229733995892 +1403638135795097088.0000000000 4.7040060352 -1.6151182226 0.7724072723 0.5115340734 0.7400591438 -0.3721256820 0.228402785028 +1403638135845096960.0000000000 4.7107718952 -1.6335437983 0.7699010294 0.5083396883 0.7416583727 -0.3719776813 0.230578021498 +1403638135895097088.0000000000 4.7163911810 -1.6528555647 0.7678974681 0.5007895967 0.7463668112 -0.3696879471 0.235535952113 +1403638135945096960.0000000000 4.7211152808 -1.6720538080 0.7686894945 0.4933323299 0.7511693301 -0.3677004603 0.239090403928 +1403638135995097088.0000000000 4.7269690012 -1.6914970301 0.7732565549 0.4889410170 0.7527399431 -0.3673196398 0.243712006468 +1403638136045096960.0000000000 4.7350150743 -1.7112545980 0.7814821768 0.4892754135 0.7501874675 -0.3677907789 0.250116525436 +1403638136095097088.0000000000 4.7451708146 -1.7318407631 0.7914588141 0.4942756047 0.7437260667 -0.3705767860 0.255413409946 +1403638136145096960.0000000000 4.7557770310 -1.7537349066 0.8010496438 0.5008446956 0.7360528596 -0.3757355154 0.257300604811 +1403638136195097088.0000000000 4.7659528142 -1.7767003870 0.8079267910 0.5072944335 0.7291880866 -0.3801638950 0.257706237891 +1403638136245096960.0000000000 4.7757332551 -1.8004342790 0.8104964752 0.5084976749 0.7261451091 -0.3833017415 0.25927431442 +1403638136295097088.0000000000 4.7851921755 -1.8237411396 0.8094459400 0.5068880328 0.7249446663 -0.3842190927 0.264377460834 +1403638136345096960.0000000000 4.7935980015 -1.8458633241 0.8056147109 0.5031490749 0.7252635112 -0.3849394514 0.269546780057 +1403638136395097088.0000000000 4.8000707325 -1.8649556354 0.8005763326 0.4998163549 0.7262497606 -0.3857112416 0.271977452463 +1403638136445096960.0000000000 4.8050353899 -1.8811854619 0.7959202703 0.4957881627 0.7276677326 -0.3861940904 0.274859770186 +1403638136495097088.0000000000 4.8080051058 -1.8924920772 0.7936248089 0.4933026901 0.7276730456 -0.3885852509 0.275945460981 +1403638136545096960.0000000000 4.8085460239 -1.8982150862 0.7945601890 0.4918011391 0.7264577436 -0.3944444524 0.273503858063 +1403638136595097088.0000000000 4.8067412306 -1.8989390822 0.7984368387 0.4931810528 0.7244346122 -0.3988852269 0.269921317566 +1403638136645096960.0000000000 4.8023960092 -1.8950494681 0.8043211595 0.4969539190 0.7229113952 -0.4005838939 0.264515521251 +1403638136695097088.0000000000 4.7956631443 -1.8876727168 0.8112784211 0.5007143827 0.7225716079 -0.4003793750 0.258595697121 +1403638136745096960.0000000000 4.7869641793 -1.8774761100 0.8190805730 0.5038597466 0.7235178039 -0.3988286554 0.252156790193 +1403638136795097088.0000000000 4.7765344833 -1.8641871392 0.8276364015 0.5094302591 0.7236360993 -0.3966819178 0.243875097389 +1403638136845096960.0000000000 4.7650781550 -1.8482168715 0.8357196120 0.5178720790 0.7213371856 -0.3956519870 0.234394282631 +1403638136895097088.0000000000 4.7528246489 -1.8306377932 0.8413978496 0.5287457430 0.7162296561 -0.3960962098 0.224835076341 +1403638136945096960.0000000000 4.7404264125 -1.8121652918 0.8434918548 0.5399731066 0.7099479088 -0.3964258912 0.217369555878 +1403638136995097088.0000000000 4.7279936772 -1.7938656929 0.8406734805 0.5477797790 0.7057243911 -0.3960939909 0.212131911764 +1403638137045096960.0000000000 4.7151608502 -1.7762671209 0.8326184449 0.5517824606 0.7049644318 -0.3944045119 0.207379717227 +1403638137095097088.0000000000 4.7029796785 -1.7606023093 0.8199336670 0.5506672689 0.7080825954 -0.3910420719 0.20608419402 +1403638137145096960.0000000000 4.6913331677 -1.7467058891 0.8038860080 0.5469143312 0.7133704196 -0.3864161082 0.206567059525 +1403638137195097088.0000000000 4.6798889525 -1.7344219684 0.7856820806 0.5417117481 0.7202581409 -0.3812089797 0.206049281006 +1403638137245096960.0000000000 4.6678907751 -1.7214242431 0.7652443220 0.5354038318 0.7277911816 -0.3757022154 0.206180935483 +1403638137295097088.0000000000 4.6579512830 -1.7120455521 0.7453778344 0.5311097539 0.7333674686 -0.3709522628 0.206128610596 +1403638137345096960.0000000000 4.6487678900 -1.7040398703 0.7250403799 0.5281390893 0.7372453145 -0.3684044292 0.204491137123 +1403638137395097088.0000000000 4.6411350573 -1.6977074157 0.7047220045 0.5240470256 0.7409081920 -0.3659361632 0.206204971994 +1403638137445096960.0000000000 4.6344672403 -1.6924523266 0.6845639679 0.5178919055 0.7455805025 -0.3637531961 0.208761349206 +1403638137495097088.0000000000 4.6288463086 -1.6881143599 0.6651111126 0.5104869670 0.7512313424 -0.3605160997 0.212326796538 +1403638137545096960.0000000000 4.6240835586 -1.6845687730 0.6465479127 0.5018248703 0.7577475789 -0.3568438524 0.215992757428 +1403638137595097088.0000000000 4.6210427103 -1.6820432699 0.6298461919 0.4938758448 0.7630733883 -0.3528403165 0.222057121023 +1403638137645096960.0000000000 4.6183062798 -1.6792776522 0.6157631983 0.4905224798 0.7646852286 -0.3518994215 0.225412943484 +1403638137695097088.0000000000 4.6164551823 -1.6774320483 0.6037472911 0.4895451531 0.7636006914 -0.3531227580 0.229268063621 +1403638137745096960.0000000000 4.6148736982 -1.6762033134 0.5934907577 0.4901653155 0.7614096878 -0.3552200584 0.231974052073 +1403638137795097088.0000000000 4.6130439304 -1.6755546116 0.5841378734 0.4889413932 0.7609203927 -0.3580052594 0.231880797621 +1403638137845096960.0000000000 4.6113487001 -1.6755166203 0.5755994504 0.4851356912 0.7628708654 -0.3581157060 0.233290687743 +1403638137895097088.0000000000 4.6095737772 -1.6756082023 0.5677369316 0.4782572899 0.7674333318 -0.3566059088 0.234836691554 +1403638137945096960.0000000000 4.6079255779 -1.6759766594 0.5608743868 0.4697369449 0.7733027772 -0.3544230422 0.236081182022 +1403638137995097088.0000000000 4.6061883172 -1.6757315001 0.5555769801 0.4634921210 0.7782017782 -0.3522061620 0.235643513901 +1403638138045096960.0000000000 4.6053573660 -1.6754034781 0.5518336407 0.4611786045 0.7803065880 -0.3500134123 0.236487916654 +1403638138095097088.0000000000 4.6050197751 -1.6747687547 0.5492825084 0.4625988050 0.7796298652 -0.3491080658 0.237282905709 +1403638138145096960.0000000000 4.6056705633 -1.6745393517 0.5493813161 0.4700911217 0.7736147894 -0.3517817973 0.238294066381 +1403638138195097088.0000000000 4.6060761190 -1.6744248832 0.5484896104 0.4749450041 0.7693661049 -0.3542869507 0.238712790308 +1403638138245096960.0000000000 4.6062973748 -1.6744210628 0.5469850794 0.4781845262 0.7669694497 -0.3555357317 0.238100326818 +1403638138295097088.0000000000 4.6063730983 -1.6744387990 0.5465496232 0.4810345360 0.7647158483 -0.3559443986 0.238995882195 +1403638138345096960.0000000000 4.6059430229 -1.6746308408 0.5466604100 0.4834802103 0.7628860012 -0.3553943435 0.240721199911 +1403638138395097088.0000000000 4.6056136232 -1.6748900964 0.5465833447 0.4873754179 0.7600602905 -0.3552579407 0.242002794167 +1403638138445096960.0000000000 4.6052267438 -1.6754606781 0.5462141207 0.4874320337 0.7601416148 -0.3545211392 0.242712792827 +1403638138495097088.0000000000 4.6054494284 -1.6756819733 0.5460917338 0.4875047213 0.7601225992 -0.3542870683 0.242968010404 +1403638138545096960.0000000000 4.6053683746 -1.6756293713 0.5461135096 0.4878331226 0.7599034070 -0.3545425324 0.24262161767 +1403638138595097088.0000000000 4.6053035172 -1.6758637677 0.5459662600 0.4877193268 0.7599970310 -0.3544141389 0.242744699768 +1403638138645096960.0000000000 4.6051461213 -1.6757982787 0.5459240834 0.4879132958 0.7598253014 -0.3547866206 0.242348057501 +1403638138695097088.0000000000 4.6051217295 -1.6757195445 0.5458864985 0.4880198676 0.7597195893 -0.3550310641 0.242106790368 +1403638138745096960.0000000000 4.6051781284 -1.6757918424 0.5458674285 0.4879748203 0.7598222196 -0.3547875649 0.242232436245 +1403638138795097088.0000000000 4.6050346127 -1.6759404371 0.5457991445 0.4878923843 0.7599589717 -0.3546412481 0.242183748053 +1403638138845096960.0000000000 4.6050657191 -1.6759685581 0.5457643705 0.4878711943 0.7600694086 -0.3543221190 0.242346916301 +1403638138895097088.0000000000 4.6048235713 -1.6754075545 0.5460378961 0.4885331431 0.7594282880 -0.3556308864 0.241103123446 +1403638138945096960.0000000000 4.6050399900 -1.6758493422 0.5458948906 0.4878134567 0.7599883466 -0.3547741172 0.242055923701 +1403638138995097088.0000000000 4.6047581008 -1.6755406405 0.5459707361 0.4883158438 0.7596405044 -0.3553226268 0.241329176894 +1403638139045096960.0000000000 4.6049064468 -1.6755983848 0.5459766858 0.4881076841 0.7598114158 -0.3549493510 0.24176116167 +1403638139095097088.0000000000 4.6048611130 -1.6755393365 0.5460199616 0.4881072906 0.7598086687 -0.3550932861 0.241559139642 +1403638139145096960.0000000000 4.6047863232 -1.6754615731 0.5460403938 0.4882251260 0.7597224942 -0.3551594194 0.241494813537 +1403638139195097088.0000000000 4.6049225401 -1.6755444435 0.5460552180 0.4880743204 0.7598219321 -0.3549289573 0.241825400861 +1403638139245096960.0000000000 4.6047844919 -1.6753451992 0.5461084377 0.4882925523 0.7596244295 -0.3553890865 0.241329042337 +1403638139295097088.0000000000 4.6049452905 -1.6755410355 0.5460296713 0.4880714383 0.7597975320 -0.3549338407 0.241900703239 +1403638139345096960.0000000000 4.6047923315 -1.6753755064 0.5461292950 0.4882313896 0.7596554463 -0.3553800463 0.241368464837 +1403638139395097088.0000000000 4.6049287252 -1.6753967158 0.5461603426 0.4881017124 0.7597569344 -0.3551138999 0.24170278666 +1403638139445096960.0000000000 4.6049335202 -1.6754850316 0.5461260828 0.4882027746 0.7596820040 -0.3552766443 0.241494947554 +1403638139495097088.0000000000 4.6049208068 -1.6755173672 0.5461391008 0.4881539684 0.7597068766 -0.3552573861 0.241543690442 +1403638139545096960.0000000000 4.6049603434 -1.6755541695 0.5460994578 0.4881624410 0.7597048660 -0.3552375821 0.241562016992 +1403638139595097088.0000000000 4.6049242230 -1.6755123061 0.5460950368 0.4881825791 0.7596767487 -0.3553118517 0.241500507386 +1403638139645096960.0000000000 4.6049203523 -1.6755447490 0.5460656703 0.4881163361 0.7597232101 -0.3552439461 0.241588131611 +1403638139695097088.0000000000 4.6048785211 -1.6754878974 0.5460624875 0.4881677868 0.7596624221 -0.3553648416 0.241497506744 +1403638139745096960.0000000000 4.6049477275 -1.6754988418 0.5460599233 0.4880976622 0.7597121098 -0.3552914290 0.24159094133 +1403638139795097088.0000000000 4.6048611400 -1.6754501569 0.5460562759 0.4881546693 0.7596652186 -0.3554326078 0.241415483737 +1403638139845096960.0000000000 4.6048950374 -1.6755308447 0.5460000382 0.4880656098 0.7597151730 -0.3553252990 0.241596250764 +1403638139895097088.0000000000 4.6048877020 -1.6754748149 0.5460455825 0.4881063875 0.7596556881 -0.3554460572 0.241523271091 +1403638139945096960.0000000000 4.6048769526 -1.6755081082 0.5460458550 0.4880587876 0.7596717864 -0.3554765453 0.241523958667 +1403638139995097088.0000000000 4.6048515228 -1.6755454405 0.5460564652 0.4880525149 0.7596801041 -0.3554899050 0.241490806461 +1403638140045096960.0000000000 4.6048482421 -1.6755328503 0.5461039807 0.4880116607 0.7596934733 -0.3555649952 0.241420752589 +1403638140095097088.0000000000 4.6048679012 -1.6755215355 0.5461290410 0.4879868030 0.7596998602 -0.3555475974 0.241476517366 +1403638140145096960.0000000000 4.6048460289 -1.6755374202 0.5461382810 0.4879827431 0.7596943337 -0.3555799724 0.241454436728 +1403638140195097088.0000000000 4.6048863284 -1.6755443597 0.5461704381 0.4879837351 0.7596812912 -0.3556161503 0.241440186776 +1403638140245096960.0000000000 4.6049140491 -1.6755195211 0.5461928299 0.4880061663 0.7596503457 -0.3556572329 0.241431701828 +1403638140295097088.0000000000 4.6049121133 -1.6755249133 0.5461838871 0.4879877197 0.7596595800 -0.3556618684 0.241433103039 +1403638140345096960.0000000000 4.6049148536 -1.6755052071 0.5461877424 0.4879863942 0.7596412345 -0.3557207218 0.241406797752 +1403638140395097088.0000000000 4.6049358040 -1.6754750467 0.5461710690 0.4879729850 0.7596344347 -0.3557422992 0.241423503542 +1403638140445096960.0000000000 4.6049375151 -1.6754635432 0.5461156572 0.4879472966 0.7596337809 -0.3557569058 0.241455955958 +1403638140495097088.0000000000 4.6049029274 -1.6754757019 0.5460848213 0.4879563039 0.7596180987 -0.3558111101 0.241407215158 +1403638140545096960.0000000000 4.6048724192 -1.6754533516 0.5461113513 0.4879576516 0.7596206171 -0.3558039178 0.241407167299 +1403638140595097088.0000000000 4.6048475411 -1.6754516339 0.5461190055 0.4879625319 0.7595951395 -0.3558450789 0.241416799949 +1403638140645096960.0000000000 4.6048057671 -1.6754380949 0.5460888591 0.4879631864 0.7595892936 -0.3558657560 0.241403391529 +1403638140695097088.0000000000 4.6048290688 -1.6754607779 0.5460811023 0.4879645076 0.7595886068 -0.3558472443 0.241430168936 +1403638140745096960.0000000000 4.6048539527 -1.6754494159 0.5460736521 0.4879894699 0.7595600085 -0.3559115173 0.241374942056 +1403638140795097088.0000000000 4.6048567174 -1.6754727278 0.5460428564 0.4879782358 0.7595627048 -0.3559029327 0.241401825437 +1403638140845096960.0000000000 4.6048465390 -1.6754919407 0.5460258569 0.4879685541 0.7595490709 -0.3559468226 0.241399582909 +1403638140895097088.0000000000 4.6048484732 -1.6754994939 0.5460592589 0.4879474153 0.7595517282 -0.3559745949 0.241392998734 +1403638140945096960.0000000000 4.6048345322 -1.6755098232 0.5460917783 0.4879013268 0.7595831768 -0.3559790947 0.241380564793 +1403638140995097088.0000000000 4.6048370305 -1.6754991203 0.5461107389 0.4879024103 0.7595587022 -0.3560200239 0.241395026027 +1403638141045096960.0000000000 4.6048811570 -1.6754698682 0.5461411728 0.4878863220 0.7595505933 -0.3560374572 0.241427343343 +1403638141095097088.0000000000 4.6049179009 -1.6754506301 0.5461556117 0.4879094629 0.7595160931 -0.3560779059 0.241429462238 +1403638141145096960.0000000000 4.6049252935 -1.6754585176 0.5461531522 0.4879347032 0.7595039939 -0.3560625127 0.241439217398 +1403638141195097088.0000000000 4.6049334274 -1.6754503812 0.5461661092 0.4879421407 0.7594936867 -0.3561150686 0.241379090158 +1403638141245096960.0000000000 4.6049489761 -1.6754396090 0.5461533211 0.4879177823 0.7594985409 -0.3561046559 0.241428412015 +1403638141295097088.0000000000 4.6049302617 -1.6753771112 0.5461565393 0.4879133786 0.7594985995 -0.3561393124 0.241386002993 +1403638141345096960.0000000000 4.6049307378 -1.6753849548 0.5461068247 0.4879295419 0.7594764361 -0.3561610787 0.241390950894 +1403638141395097088.0000000000 4.6049398017 -1.6753958809 0.5460993274 0.4879398455 0.7594630454 -0.3561789391 0.241385900877 +1403638141445096960.0000000000 4.6049449230 -1.6754240435 0.5461034413 0.4879363231 0.7594652293 -0.3562044525 0.241348499293 +1403638141495097088.0000000000 4.6049245778 -1.6754002906 0.5461234281 0.4879349011 0.7594657997 -0.3562243134 0.241320264251 +1403638141545096960.0000000000 4.6049039099 -1.6754406789 0.5461125728 0.4879320616 0.7594607221 -0.3562208383 0.241347113475 +1403638141595097088.0000000000 4.6048916045 -1.6754788921 0.5461149169 0.4879162128 0.7594514870 -0.3562486088 0.241367224016 +1403638141645096960.0000000000 4.6048390710 -1.6755106989 0.5460989507 0.4879099736 0.7594548641 -0.3562848168 0.241315760584 +1403638141695097088.0000000000 4.6048049107 -1.6755473829 0.5460659133 0.4878856461 0.7594540027 -0.3562951356 0.24135241964 +1403638141745096960.0000000000 4.6047582657 -1.6755394171 0.5460640325 0.4879054941 0.7594262246 -0.3563478788 0.241321833884 +1403638141795097088.0000000000 4.6047616536 -1.6755759264 0.5460676799 0.4878556126 0.7594608454 -0.3563293803 0.241341041341 +1403638141845096960.0000000000 4.6047578845 -1.6755701308 0.5460756332 0.4878674347 0.7594529274 -0.3563592910 0.241297892395 +1403638141895097088.0000000000 4.6047711492 -1.6755554470 0.5460937136 0.4878433776 0.7594621466 -0.3563610864 0.241314862411 +1403638141945096960.0000000000 4.6048047701 -1.6755198826 0.5461202037 0.4878138271 0.7594356690 -0.3564428993 0.241337096489 +1403638141995097088.0000000000 4.6048071432 -1.6754979460 0.5461463388 0.4878474492 0.7594623819 -0.3563780184 0.241280883645 +1403638142045096960.0000000000 4.6047690212 -1.6755000707 0.5461358594 0.4878312794 0.7594737357 -0.3563983785 0.241247763645 +1403638142095097088.0000000000 4.6047717998 -1.6755326565 0.5461024217 0.4878305311 0.7594883252 -0.3563538192 0.241269170041 +1403638142145096960.0000000000 4.6047701127 -1.6755618198 0.5460941212 0.4878676351 0.7594660652 -0.3564103136 0.241180751264 +1403638142195097088.0000000000 4.6048994364 -1.6756467806 0.5460943215 0.4878011835 0.7593446643 -0.3566230210 0.241382905434 +1403638142245096960.0000000000 4.6049696827 -1.6756334662 0.5460806914 0.4875948454 0.7593107357 -0.3568583156 0.241558721467 +1403638142295097088.0000000000 4.6049264426 -1.6754630883 0.5461048246 0.4875861672 0.7592194835 -0.3569722126 0.241694734746 +1403638142345096960.0000000000 4.6049024782 -1.6753621700 0.5461379677 0.4875551269 0.7592992546 -0.3568974779 0.241617115461 +1403638142395097088.0000000000 4.6050115836 -1.6754082791 0.5461534930 0.4874762184 0.7592288035 -0.3570338215 0.241796217357 +1403638142445096960.0000000000 4.6050766978 -1.6754557277 0.5461838433 0.4874989811 0.7593273247 -0.3569532022 0.241559866035 +1403638142495097088.0000000000 4.6051478428 -1.6754713389 0.5462261857 0.4875220206 0.7592800087 -0.3570579317 0.241507311119 +1403638142545096960.0000000000 4.6051841930 -1.6754075830 0.5462680772 0.4875821137 0.7593466698 -0.3569361745 0.241356344091 +1403638142595097088.0000000000 4.6050242756 -1.6752229079 0.5463082648 0.4878289293 0.7594982183 -0.3565317405 0.24097823604 +1403638142645096960.0000000000 4.6049342105 -1.6751576493 0.5462589502 0.4877658763 0.7594880051 -0.3565794599 0.241067436194 +1403638142695097088.0000000000 4.6048021683 -1.6751537927 0.5462051313 0.4876902232 0.7595334144 -0.3565838038 0.24107100503 +1403638142745096960.0000000000 4.6047455476 -1.6752262984 0.5461399656 0.4876924235 0.7594519453 -0.3566897628 0.241166448608 +1403638142795097088.0000000000 4.6047895825 -1.6753555921 0.5460424927 0.4874726468 0.7594171248 -0.3568951644 0.241416426065 +1403638142845096960.0000000000 4.6046388878 -1.6754517476 0.5460307708 0.4875423002 0.7594326459 -0.3568468420 0.241298348839 +1403638142895097088.0000000000 4.6046238620 -1.6754983400 0.5460062889 0.4874920738 0.7594681189 -0.3568032165 0.241352686157 +1403638142945096960.0000000000 4.6046029848 -1.6754076991 0.5459771864 0.4875677689 0.7595149902 -0.3567039691 0.241198940261 +1403638142995097088.0000000000 4.6047002087 -1.6753685629 0.5459726665 0.4875972184 0.7595907177 -0.3564942866 0.241210940539 +1403638143045096960.0000000000 4.6048112864 -1.6753972923 0.5460057719 0.4875636895 0.7595777494 -0.3566605404 0.241073744525 +1403638143095097088.0000000000 4.6049128206 -1.6755077217 0.5461039512 0.4875335390 0.7596025986 -0.3565776615 0.241179003754 +1403638143145096960.0000000000 4.6049440772 -1.6755765028 0.5462111554 0.4876088809 0.7595506289 -0.3566556034 0.241075095944 +1403638143195097088.0000000000 4.6049453430 -1.6755991414 0.5462450797 0.4875171596 0.7596096119 -0.3566781916 0.241041333206 +1403638143245096960.0000000000 4.6048777863 -1.6755555764 0.5462076133 0.4875713888 0.7595799437 -0.3566668654 0.241041899033 +1403638143295097088.0000000000 4.6047430426 -1.6755147668 0.5461493444 0.4876026255 0.7595653030 -0.3566915759 0.240988277291 +1403638143345096960.0000000000 4.6046631969 -1.6754930351 0.5460590746 0.4875459524 0.7596104053 -0.3566055639 0.241088050948 +1403638143395097088.0000000000 4.6046532553 -1.6754218937 0.5460211607 0.4875836358 0.7595543726 -0.3567132567 0.241029055486 +1403638143445096960.0000000000 4.6046381464 -1.6754711363 0.5459717171 0.4875526745 0.7595508338 -0.3566949851 0.24112985734 +1403638143495097088.0000000000 4.6046481438 -1.6755384259 0.5459752889 0.4875542726 0.7595273130 -0.3567653925 0.241096550614 +1403638143545096960.0000000000 4.6046806021 -1.6755834817 0.5459797287 0.4875598117 0.7595034857 -0.3567929961 0.241119561986 +1403638143595097088.0000000000 4.6047651021 -1.6756285385 0.5459868891 0.4874388026 0.7594668372 -0.3569790821 0.24120421184 +1403638143645096960.0000000000 4.6047679479 -1.6755621790 0.5460043537 0.4874801181 0.7594870590 -0.3569867626 0.24104562414 +1403638143695097088.0000000000 4.6047951142 -1.6755470175 0.5460131829 0.4874813655 0.7594768082 -0.3569840104 0.241079473355 +1403638143745096960.0000000000 4.6047859415 -1.6755337159 0.5460185684 0.4874956735 0.7594769121 -0.3569785316 0.241058325425 +1403638143795097088.0000000000 4.6047925664 -1.6755217357 0.5460196907 0.4874931817 0.7595135715 -0.3569423308 0.241001462783 +1403638143845096960.0000000000 4.6047984395 -1.6754965681 0.5460365261 0.4874941867 0.7595060855 -0.3569741462 0.24097589708 +1403638143895097088.0000000000 4.6047627721 -1.6754954560 0.5460672426 0.4874815519 0.7594901330 -0.3570421202 0.240951030135 +1403638143945096960.0000000000 4.6047564130 -1.6755153474 0.5460681101 0.4874682350 0.7594748385 -0.3570348138 0.241036991495 +1403638143995097088.0000000000 4.6047281991 -1.6755059926 0.5460924100 0.4874663596 0.7594666062 -0.3570921579 0.24098176923 +1403638144045096960.0000000000 4.6047166595 -1.6755002957 0.5461068588 0.4874345599 0.7594897785 -0.3571334264 0.240911896463 +1403638144095097088.0000000000 4.6047589350 -1.6754506392 0.5461362029 0.4874090754 0.7595051803 -0.3571535478 0.240885071467 +1403638144145096960.0000000000 4.6047070214 -1.6755936125 0.5460667532 0.4873773590 0.7595025443 -0.3571444517 0.240971026985 +1403638144195097088.0000000000 4.6047205302 -1.6756084309 0.5460678343 0.4873894992 0.7594838035 -0.3571748095 0.240960543939 +1403638144245096960.0000000000 4.6047115410 -1.6755938117 0.5460744418 0.4873915457 0.7594912002 -0.3571653879 0.240947055705 +1403638144295097088.0000000000 4.6046747575 -1.6755765749 0.5460963066 0.4874105691 0.7594991445 -0.3571366892 0.240926071363 +1403638144345096960.0000000000 4.6046235304 -1.6755640334 0.5460924727 0.4874169946 0.7594937132 -0.3571894341 0.240851990114 +1403638144395097088.0000000000 4.6046394109 -1.6755362009 0.5460965452 0.4874338953 0.7594853110 -0.3571718938 0.24087029369 +1403638144445096960.0000000000 4.6045958955 -1.6755350369 0.5460540729 0.4874114612 0.7594887376 -0.3572196137 0.240834118262 +1403638144495097088.0000000000 4.6046558438 -1.6754653049 0.5460224093 0.4873833132 0.7594775434 -0.3572547664 0.240874239118 +1403638144545096960.0000000000 4.6046582358 -1.6753820547 0.5460050188 0.4873622864 0.7594542539 -0.3573465319 0.240854093097 +1403638144595097088.0000000000 4.6047088923 -1.6753008062 0.5460432525 0.4873354454 0.7594779443 -0.3573565812 0.240818789959 +1403638144645096960.0000000000 4.6047360113 -1.6752688264 0.5461356590 0.4873974374 0.7594667071 -0.3573203872 0.240782474008 +1403638144695097088.0000000000 4.6047196571 -1.6752862825 0.5462381044 0.4874415249 0.7594515370 -0.3572962691 0.240776865391 +1403638144745096960.0000000000 4.6046781485 -1.6753501100 0.5462579324 0.4873888450 0.7594570994 -0.3573256155 0.240822408562 +1403638144795097088.0000000000 4.6046841576 -1.6753756367 0.5462767262 0.4874452420 0.7594214342 -0.3573968373 0.240715022305 +1403638144845096960.0000000000 4.6046953138 -1.6754214522 0.5462221364 0.4874199285 0.7594312530 -0.3573866554 0.240750418202 +1403638144895097088.0000000000 4.6046624074 -1.6754706100 0.5461630305 0.4873814252 0.7594382617 -0.3574499758 0.24071225093 +1403638144945096960.0000000000 4.6046458908 -1.6755325150 0.5460848006 0.4872975081 0.7595026153 -0.3574128653 0.240734209572 +1403638144995097088.0000000000 4.6046360163 -1.6755373763 0.5460245634 0.4873903919 0.7594184111 -0.3574497442 0.240757062513 +1403638145045096960.0000000000 4.6046030539 -1.6755536896 0.5459310153 0.4873080035 0.7594796797 -0.3574703100 0.240700027726 +1403638145095097088.0000000000 4.6046332023 -1.6755849937 0.5459181538 0.4873753639 0.7594135017 -0.3575334240 0.240678704411 +1403638145145096960.0000000000 4.6046400432 -1.6755967496 0.5458582811 0.4872465954 0.7594751359 -0.3575301674 0.240749772 +1403638145195097088.0000000000 4.6046982386 -1.6755443862 0.5458887211 0.4873244172 0.7594176721 -0.3575708526 0.24071310122 +1403638145245096960.0000000000 4.6047279004 -1.6754991293 0.5459171248 0.4872572064 0.7594619582 -0.3575631631 0.240720861795 +1403638145295097088.0000000000 4.6046952378 -1.6754383379 0.5458810939 0.4872772405 0.7594312888 -0.3576281722 0.240680491339 +1403638145345096960.0000000000 4.6047079517 -1.6753866867 0.5458674218 0.4872855435 0.7594223508 -0.3576225836 0.240700186668 +1403638145395097088.0000000000 4.6047255956 -1.6753837899 0.5458742656 0.4872316704 0.7593997024 -0.3577053922 0.240757645153 +1403638145445096960.0000000000 4.6047754514 -1.6754201765 0.5459437845 0.4872029357 0.7593718752 -0.3577596167 0.240822987564 +1403638145495097088.0000000000 4.6047003752 -1.6754399001 0.5459898727 0.4872502656 0.7593666819 -0.3577640265 0.240737039865 +1403638145545096960.0000000000 4.6047175196 -1.6755022858 0.5460581911 0.4872887755 0.7593301722 -0.3577696762 0.240765856581 +1403638145595097088.0000000000 4.6046381349 -1.6755849468 0.5460620915 0.4872528621 0.7593908853 -0.3577674621 0.240650316265 +1403638145645096960.0000000000 4.6046070305 -1.6756248570 0.5461238324 0.4872258583 0.7594079946 -0.3578030868 0.240598029523 +1403638145695097088.0000000000 4.6045942286 -1.6756096239 0.5461256740 0.4872676615 0.7593782707 -0.3577983009 0.240614305495 +1403638145745096960.0000000000 4.6045342147 -1.6755679519 0.5460942877 0.4872281125 0.7594005289 -0.3578551892 0.240539532332 +1403638145795097088.0000000000 4.6045558387 -1.6755711790 0.5461273511 0.4871727810 0.7594358792 -0.3578156845 0.240598758861 +1403638145845096960.0000000000 4.6045206676 -1.6754372043 0.5461661230 0.4872299151 0.7593807964 -0.3578882217 0.240549031644 +1403638145895097088.0000000000 4.6045495909 -1.6753870541 0.5461394281 0.4871950958 0.7593882651 -0.3578870351 0.240597738017 +1403638145945096960.0000000000 4.6045547768 -1.6753108362 0.5461476505 0.4871599874 0.7593647734 -0.3580171196 0.240549432723 +1403638145995097088.0000000000 4.6045590344 -1.6752842315 0.5461385713 0.4872150566 0.7593505497 -0.3579812466 0.240536189217 +1403638146045096960.0000000000 4.6045574811 -1.6752706441 0.5461357658 0.4872556993 0.7593410230 -0.3579996757 0.240456496199 +1403638146095097088.0000000000 4.6045370170 -1.6753399997 0.5461557381 0.4871912404 0.7594023007 -0.3579828920 0.240418572408 +1403638146145096960.0000000000 4.6044748651 -1.6754577418 0.5462113804 0.4872439962 0.7593478331 -0.3580354068 0.24040549914 +1403638146195097088.0000000000 4.6044408242 -1.6753894374 0.5462448744 0.4872735344 0.7593251877 -0.3580195777 0.240440728441 +1403638146245096960.0000000000 4.6044572805 -1.6754189374 0.5462011474 0.4872137652 0.7593658147 -0.3580122748 0.240444416794 +1403638146295097088.0000000000 4.6045695890 -1.6754966076 0.5461375626 0.4872421996 0.7593278588 -0.3580745744 0.240413895197 +1403638146345096960.0000000000 4.6045685531 -1.6755533873 0.5461219799 0.4872226360 0.7593497339 -0.3580841401 0.24037020036 +1403638146395097088.0000000000 4.6045058855 -1.6755845822 0.5461125451 0.4872113585 0.7593648264 -0.3580418999 0.240408299394 +1403638146445096960.0000000000 4.6045040659 -1.6755452572 0.5461451438 0.4872910387 0.7592769993 -0.3581123186 0.240419319651 +1403638146495097088.0000000000 4.6045803994 -1.6755015671 0.5462635715 0.4871285963 0.7593811027 -0.3581541874 0.240357337152 +1403638146545096960.0000000000 4.6047022215 -1.6753938641 0.5463161464 0.4871662565 0.7593366647 -0.3581868609 0.240372712363 +1403638146595097088.0000000000 4.6047902129 -1.6752726498 0.5463868093 0.4871485266 0.7593311729 -0.3581848945 0.240428917118 +1403638146645096960.0000000000 4.6046954230 -1.6753246633 0.5463814043 0.4870591434 0.7593696822 -0.3582352417 0.240413369592 +1403638146695097088.0000000000 4.6047791847 -1.6753042113 0.5465367107 0.4871101693 0.7593341846 -0.3582249652 0.240437421026 +1403638146745096960.0000000000 4.6048803561 -1.6753081486 0.5465751342 0.4871199604 0.7593502166 -0.3581846603 0.240426998991 +1403638146795097088.0000000000 4.6048915746 -1.6752817306 0.5464202587 0.4872899820 0.7592453557 -0.3581753762 0.240427459205 +1403638146845096960.0000000000 4.6047499818 -1.6753125717 0.5461586350 0.4871078067 0.7593815301 -0.3581119474 0.240461035395 +1403638146895097088.0000000000 4.6044746428 -1.6754169499 0.5459852734 0.4872383380 0.7593129000 -0.3580646685 0.24048371039 +1403638146945096960.0000000000 4.6043231145 -1.6754606914 0.5457997419 0.4871469489 0.7593789978 -0.3581081482 0.240395387106 +1403638146995097088.0000000000 4.6043379386 -1.6754387975 0.5457201589 0.4869925010 0.7594309196 -0.3581963825 0.240412840512 +1403638147045096960.0000000000 4.6043229767 -1.6753794904 0.5458139280 0.4869599261 0.7594749039 -0.3581411160 0.240422215546 +1403638147095097088.0000000000 4.6042750929 -1.6751990436 0.5459534391 0.4869248146 0.7595534682 -0.3581497948 0.240232134142 +1403638147145096960.0000000000 4.6044718994 -1.6749174326 0.5459955052 0.4868204994 0.7596565947 -0.3581848276 0.240065176139 +1403638147195097088.0000000000 4.6047828925 -1.6748032830 0.5460316472 0.4867368223 0.7597243789 -0.3580831983 0.240171932019 +1403638147245096960.0000000000 4.6048537731 -1.6747876617 0.5461685785 0.4868579471 0.7596623871 -0.3581527572 0.240018748013 +1403638147295097088.0000000000 4.6048325683 -1.6749878579 0.5462343740 0.4868931855 0.7596080932 -0.3581790074 0.240079922642 +1403638147345096960.0000000000 4.6048283732 -1.6752429175 0.5462454153 0.4870136237 0.7595121281 -0.3580924963 0.240268228744 +1403638147395097088.0000000000 4.6046662345 -1.6755915023 0.5461496073 0.4871212490 0.7594855284 -0.3580559243 0.240188625763 +1403638147445096960.0000000000 4.6044732589 -1.6760118649 0.5460960410 0.4871500044 0.7594567917 -0.3580536502 0.240224558169 +1403638147495097088.0000000000 4.6042659015 -1.6761855812 0.5463894355 0.4878252105 0.7591592224 -0.3576832295 0.240346721101 +1403638147545096960.0000000000 4.6041186996 -1.6763077113 0.5464124065 0.4878880593 0.7590018557 -0.3579624707 0.240300424908 +1403638147595097088.0000000000 4.6039828750 -1.6762524572 0.5465378880 0.4885680002 0.7587612457 -0.3576841352 0.240093191681 +1403638147645096960.0000000000 4.6042064645 -1.6760815124 0.5462252140 0.4881096435 0.7592635762 -0.3572440353 0.240092684375 +1403638147695097088.0000000000 4.6042118541 -1.6756723479 0.5461428781 0.4885101436 0.7592766693 -0.3569704227 0.23964326891 +1403638147745096960.0000000000 4.6045303839 -1.6751803869 0.5460641487 0.4892944309 0.7588695259 -0.3567162357 0.239711346791 +1403638147795097088.0000000000 4.6055150553 -1.6743163945 0.5460364391 0.4913981670 0.7569923526 -0.3566991791 0.241363036356 +1403638147845096960.0000000000 4.6076712081 -1.6728744774 0.5465281457 0.4944048257 0.7538416639 -0.3574218300 0.244000511186 +1403638147895097088.0000000000 4.6108118176 -1.6706216286 0.5486287336 0.4998962315 0.7492139102 -0.3571335617 0.247462913418 +1403638147945096960.0000000000 4.6145335351 -1.6675992497 0.5524424054 0.5044459422 0.7453251426 -0.3568944775 0.250301928006 +1403638147995097088.0000000000 4.6185273094 -1.6639909968 0.5579577514 0.5084285312 0.7421952944 -0.3569389598 0.251477936494 +1403638148045096960.0000000000 4.6227661188 -1.6605658084 0.5650159039 0.5117099694 0.7397924105 -0.3553719425 0.254108006464 +1403638148095097088.0000000000 4.6271774494 -1.6568128933 0.5742466083 0.5150181184 0.7376032784 -0.3546564085 0.254787309947 +1403638148145096960.0000000000 4.6319242921 -1.6530333460 0.5854744645 0.5169513552 0.7367099696 -0.3524641630 0.256493140022 +1403638148195097088.0000000000 4.6366298358 -1.6492710243 0.6001796866 0.5188033101 0.7360489545 -0.3508267424 0.256896202551 +1403638148245096960.0000000000 4.6410431079 -1.6456394289 0.6190735263 0.5198389400 0.7361271975 -0.3497476821 0.256048402659 +1403638148295097088.0000000000 4.6449529103 -1.6425138403 0.6423922119 0.5201737225 0.7367974607 -0.3481715736 0.255588254081 +1403638148345096960.0000000000 4.6489064386 -1.6391567814 0.6690364483 0.5216287264 0.7366477660 -0.3466891601 0.255068945654 +1403638148395097088.0000000000 4.6523920732 -1.6360765537 0.6948042070 0.5215073433 0.7376314322 -0.3453388055 0.254305073694 +1403638148445096960.0000000000 4.6556559393 -1.6332180271 0.7171589864 0.5206340409 0.7389739488 -0.3443020283 0.253601679332 +1403638148495097088.0000000000 4.6584650311 -1.6305840926 0.7330078486 0.5167493936 0.7423732341 -0.3437784311 0.252326050653 +1403638148545096960.0000000000 4.6613773574 -1.6278187665 0.7430894491 0.5141376969 0.7446726431 -0.3430519880 0.251873811156 +1403638148595097088.0000000000 4.6640820511 -1.6248653444 0.7471781072 0.5115762848 0.7470601323 -0.3428544134 0.250283269037 +1403638148645096960.0000000000 4.6668087283 -1.6214830484 0.7465841303 0.5089863562 0.7494829022 -0.3422855820 0.249096063622 +1403638148695097088.0000000000 4.6699950951 -1.6171289091 0.7438950232 0.5070906008 0.7513232027 -0.3420845860 0.247690742035 +1403638148745096960.0000000000 4.6733671495 -1.6121858972 0.7411441978 0.5058040133 0.7528543651 -0.3419774050 0.245813058187 +1403638148795097088.0000000000 4.6772292671 -1.6064269190 0.7402414589 0.5046154340 0.7541365399 -0.3418109420 0.244553926233 +1403638148845096960.0000000000 4.6811292596 -1.6000172614 0.7419039629 0.5045175207 0.7548047893 -0.3414274134 0.243226484575 +1403638148895097088.0000000000 4.6856069680 -1.5929987186 0.7456700244 0.5043489211 0.7553876162 -0.3407054448 0.242778736798 +1403638148945096960.0000000000 4.6905664550 -1.5848194890 0.7524211165 0.5057134536 0.7548521794 -0.3400587399 0.242512151287 +1403638148995097088.0000000000 4.6956705961 -1.5762303546 0.7622164657 0.5075009356 0.7541656601 -0.3388857898 0.242555929494 +1403638149045096960.0000000000 4.7011799948 -1.5669493577 0.7762147560 0.5104486327 0.7525578537 -0.3375073651 0.24328511803 +1403638149095097088.0000000000 4.7070666422 -1.5569303275 0.7931892650 0.5128153101 0.7512577530 -0.3361491077 0.244204880445 +1403638149145096960.0000000000 4.7134150224 -1.5460800614 0.8120043615 0.5148522463 0.7501161262 -0.3351329610 0.244824141175 +1403638149195097088.0000000000 4.7198916853 -1.5345045844 0.8310458041 0.5160863059 0.7493431430 -0.3348071993 0.245038605408 +1403638149245096960.0000000000 4.7262062081 -1.5226766730 0.8493920262 0.5174545162 0.7485378587 -0.3346522828 0.244825953009 +1403638149295097088.0000000000 4.7322854050 -1.5106630362 0.8669810189 0.5184955567 0.7477588784 -0.3355857775 0.243723621018 +1403638149345096960.0000000000 4.7383184717 -1.4983299410 0.8842726603 0.5198277758 0.7469606386 -0.3356821842 0.243200244799 +1403638149395097088.0000000000 4.7441226658 -1.4861838828 0.9003806367 0.5205663665 0.7465162984 -0.3352138256 0.243630386896 +1403638149445096960.0000000000 4.7498117778 -1.4739786541 0.9152850512 0.5211214656 0.7461714413 -0.3351594486 0.243574921105 +1403638149495097088.0000000000 4.7554799069 -1.4618934146 0.9287165874 0.5214478678 0.7459836284 -0.3344285630 0.244454665509 +1403638149545096960.0000000000 4.7608438954 -1.4499087528 0.9407513663 0.5214712816 0.7460373372 -0.3339310282 0.244920522666 +1403638149595097088.0000000000 4.7659397648 -1.4378835204 0.9510641718 0.5214256908 0.7464314695 -0.3329191677 0.245194082293 +1403638149645096960.0000000000 4.7704488390 -1.4256907749 0.9597388358 0.5215875969 0.7473757068 -0.3311679238 0.244343483348 +1403638149695097088.0000000000 4.7745817849 -1.4134430252 0.9672791227 0.5226435133 0.7483364709 -0.3285728160 0.242644160967 +1403638149745096960.0000000000 4.7785980605 -1.4011957985 0.9733443786 0.5233355238 0.7494680060 -0.3256888460 0.241545882079 +1403638149795097088.0000000000 4.7824537778 -1.3887812829 0.9781037244 0.5239562271 0.7505242395 -0.3236700912 0.239626605633 +1403638149845096960.0000000000 4.7860844113 -1.3766043079 0.9817092489 0.5242421985 0.7517147855 -0.3215358778 0.23813793865 +1403638149895097088.0000000000 4.7897447816 -1.3642969454 0.9845777592 0.5253487432 0.7519611217 -0.3200437045 0.236928673983 +1403638149945096960.0000000000 4.7930432907 -1.3523224637 0.9858777204 0.5252642421 0.7529570413 -0.3184207608 0.236138495517 +1403638149995097088.0000000000 4.7961567902 -1.3404249189 0.9857941579 0.5251252143 0.7538791354 -0.3164354534 0.236174432013 +1403638150045096960.0000000000 4.7993161440 -1.3285169180 0.9839985771 0.5242989418 0.7549096245 -0.3133346539 0.238837754843 +1403638150095097088.0000000000 4.8020325558 -1.3165166400 0.9804459221 0.5229621491 0.7562834795 -0.3101806850 0.241523977921 +1403638150145096960.0000000000 4.8042050173 -1.3041687767 0.9751325950 0.5214165489 0.7576715575 -0.3067867344 0.24482747616 +1403638150195097088.0000000000 4.8056775476 -1.2912844390 0.9685787075 0.5201478237 0.7587020190 -0.3041116289 0.247656223294 +1403638150245096960.0000000000 4.8063287572 -1.2777120223 0.9609103543 0.5191775790 0.7593685010 -0.3015472143 0.250765624884 +1403638150295097088.0000000000 4.8055746789 -1.2632437307 0.9518880423 0.5175416178 0.7606658196 -0.3018548801 0.249843583174 +1403638150345096960.0000000000 4.8039139940 -1.2478425522 0.9418359090 0.5153301478 0.7622811648 -0.3024102721 0.24881778866 +1403638150395097088.0000000000 4.8006175952 -1.2315765433 0.9315985493 0.5132826453 0.7644846410 -0.3038001355 0.244560089478 +1403638150445096960.0000000000 4.7962657537 -1.2138876618 0.9225125373 0.5107973255 0.7676588360 -0.3055970317 0.23747938447 +1403638150495097088.0000000000 4.7910782278 -1.1951000986 0.9159483852 0.5102391118 0.7699952325 -0.3056851549 0.230911188218 +1403638150545096960.0000000000 4.7857216671 -1.1754733243 0.9106956719 0.5088281777 0.7730279828 -0.3042735359 0.225697227901 +1403638150595097088.0000000000 4.7808633665 -1.1544045216 0.9082698351 0.5085173787 0.7751197745 -0.3027272610 0.221259160808 +1403638150645096960.0000000000 4.7762564816 -1.1322130713 0.9086266452 0.5091477928 0.7764796895 -0.3008878591 0.217518535159 +1403638150695097088.0000000000 4.7722967754 -1.1091386772 0.9110112606 0.5107331587 0.7768538150 -0.2988285350 0.215293514391 +1403638150745096960.0000000000 4.7690188177 -1.0848453852 0.9148742797 0.5121147214 0.7775534625 -0.2958848231 0.213544600695 +1403638150795097088.0000000000 4.7666924772 -1.0589683208 0.9208478969 0.5138903179 0.7781590241 -0.2920363240 0.21236774682 +1403638150845096960.0000000000 4.7643406319 -1.0321959465 0.9283473701 0.5163582144 0.7787664410 -0.2871505507 0.210811731172 +1403638150895097088.0000000000 4.7622453826 -1.0046507513 0.9355334752 0.5191437407 0.7790131227 -0.2822407120 0.209686698737 +1403638150945096960.0000000000 4.7602879454 -0.9764174408 0.9417865688 0.5220899571 0.7787815876 -0.2778742999 0.20906264368 +1403638150995097088.0000000000 4.7580632268 -0.9472421546 0.9471883343 0.5265046369 0.7778063399 -0.2730347246 0.207995682966 +1403638151045096960.0000000000 4.7551701562 -0.9179417933 0.9504094224 0.5281929707 0.7791114300 -0.2677272785 0.205717451115 +1403638151095097088.0000000000 4.7516608524 -0.8879697122 0.9528632186 0.5313305348 0.7799545851 -0.2606930489 0.203464597297 +1403638151145096960.0000000000 4.7475186758 -0.8575342126 0.9539384689 0.5344994465 0.7813474803 -0.2521453369 0.200572145891 +1403638151195097088.0000000000 4.7425039282 -0.8266801780 0.9528607111 0.5368885637 0.7837535906 -0.2435152088 0.195400415835 +1403638151245096960.0000000000 4.7366019743 -0.7952866611 0.9502606939 0.5386269027 0.7869820663 -0.2347060127 0.188290665023 +1403638151295097088.0000000000 4.7301322394 -0.7635150767 0.9465474001 0.5404222096 0.7900327592 -0.2256102118 0.181361812325 +1403638151345096960.0000000000 4.7231494181 -0.7314192897 0.9422459986 0.5420181691 0.7932764900 -0.2158027579 0.174235141393 +1403638151395097088.0000000000 4.7152131674 -0.6989859750 0.9387111532 0.5445511153 0.7958425190 -0.2060856307 0.166215163559 +1403638151445096960.0000000000 4.7068632442 -0.6660050614 0.9366637921 0.5470501248 0.7981492786 -0.1970587183 0.157676096903 +1403638151495097088.0000000000 4.6979829695 -0.6332371622 0.9356913698 0.5491980290 0.8004318502 -0.1870470272 0.150677761118 +1403638151545096960.0000000000 4.6889230560 -0.6001393623 0.9362818747 0.5513338261 0.8021836449 -0.1784955354 0.143776757276 +1403638151595097088.0000000000 4.6799328301 -0.5667993778 0.9380065599 0.5524296468 0.8041199996 -0.1706657481 0.138151054698 +1403638151645096960.0000000000 4.6707149494 -0.5332735781 0.9411518325 0.5542537471 0.8050862659 -0.1639628137 0.133248204678 +1403638151695097088.0000000000 4.6614681670 -0.4993698382 0.9458145655 0.5553393314 0.8061316940 -0.1580870687 0.129454229735 +1403638151745096960.0000000000 4.6520260168 -0.4653407050 0.9527406661 0.5558040041 0.8071928967 -0.1533994136 0.126452190296 +1403638151795097088.0000000000 4.6421544979 -0.4312511223 0.9617205911 0.5556034866 0.8084373936 -0.1496143116 0.123892307961 +1403638151845096960.0000000000 4.6320327432 -0.3970796695 0.9729504026 0.5558290937 0.8091427041 -0.1467883341 0.121635882234 +1403638151895097088.0000000000 4.6218322162 -0.3626428841 0.9858438535 0.5557885160 0.8097308448 -0.1447791228 0.12030831285 +1403638151945096960.0000000000 4.6116086741 -0.3275406612 0.9998538315 0.5551821022 0.8105378923 -0.1424907194 0.1204057865 +1403638151995097088.0000000000 4.6008689238 -0.2920330714 1.0143768938 0.5548294613 0.8110644373 -0.1412165551 0.119985966182 +1403638152045096960.0000000000 4.5899282502 -0.2558938935 1.0281455656 0.5545123842 0.8114157827 -0.1409897251 0.119341278128 +1403638152095097088.0000000000 4.5784993792 -0.2198965383 1.0408769125 0.5541252217 0.8117279634 -0.1405131646 0.119578437389 +1403638152145096960.0000000000 4.5666939836 -0.1835953269 1.0524388344 0.5541646338 0.8117249740 -0.1398214903 0.120225105856 +1403638152195097088.0000000000 4.5545805462 -0.1469766966 1.0624741096 0.5539513709 0.8118287547 -0.1401441740 0.120131436776 +1403638152245096960.0000000000 4.5423250891 -0.1101391164 1.0706004242 0.5538559143 0.8118153475 -0.1393672661 0.1215575291 +1403638152295097088.0000000000 4.5296606616 -0.0729905244 1.0769485816 0.5535714345 0.8118901807 -0.1388773432 0.122906814025 +1403638152345096960.0000000000 4.5166439277 -0.0353265004 1.0815548657 0.5535178190 0.8116908661 -0.1383484199 0.125042699581 +1403638152395097088.0000000000 4.5028425897 0.0026091603 1.0840195127 0.5526380109 0.8120990048 -0.1379772695 0.126683496909 +1403638152445096960.0000000000 4.4883837964 0.0410472334 1.0844466507 0.5520245028 0.8122729363 -0.1380379370 0.12816845637 +1403638152495097088.0000000000 4.4732524488 0.0800492162 1.0832277103 0.5509342653 0.8127588992 -0.1376656107 0.130163691663 +1403638152545096960.0000000000 4.4571375902 0.1195591356 1.0814245261 0.5512805815 0.8124477893 -0.1376976582 0.130604996246 +1403638152595097088.0000000000 4.4402073826 0.1594112811 1.0783977548 0.5508976812 0.8125845470 -0.1385619007 0.130455734162 +1403638152645096960.0000000000 4.4220038274 0.1995405498 1.0745238784 0.5500935688 0.8132314423 -0.1402502284 0.127990469183 +1403638152695097088.0000000000 4.4028681600 0.2402788429 1.0714668121 0.5500061993 0.8136858919 -0.1409914012 0.124618918276 +1403638152745096960.0000000000 4.3832062921 0.2818425752 1.0700796454 0.5506320624 0.8139291468 -0.1393335813 0.12210581067 +1403638152795097088.0000000000 4.3628713990 0.3245662058 1.0714264902 0.5528613434 0.8133542715 -0.1376403037 0.117704336215 +1403638152845096960.0000000000 4.3420544618 0.3680076727 1.0747572903 0.5549336430 0.8130670318 -0.1347646418 0.113177492843 +1403638152895097088.0000000000 4.3210125080 0.4117887099 1.0804961928 0.5588304389 0.8116829583 -0.1309459790 0.108316510007 +1403638152945096960.0000000000 4.2997100130 0.4550728434 1.0874121294 0.5619669039 0.8109747354 -0.1253626527 0.103910455126 +1403638152995097088.0000000000 4.2781703576 0.4980227454 1.0956136630 0.5629401803 0.8118304482 -0.1193902629 0.0988718460262 +1403638153045096960.0000000000 4.2563526038 0.5407392888 1.1056258223 0.5620297305 0.8139038385 -0.1134793884 0.0938379038967 +1403638153095097088.0000000000 4.2344754630 0.5833840409 1.1169435617 0.5601481504 0.8164228161 -0.1084048769 0.0890854508971 +1403638153145096960.0000000000 4.2126507949 0.6262337134 1.1283626729 0.5581970228 0.8187684076 -0.1037576079 0.0852568894403 +1403638153195097088.0000000000 4.1911576622 0.6696558013 1.1392264468 0.5569585860 0.8203937643 -0.0997152712 0.0825110274666 +1403638153245096960.0000000000 4.1701434445 0.7135418037 1.1487754565 0.5560937749 0.8216156335 -0.0962050980 0.0803246127145 +1403638153295097088.0000000000 4.1492014980 0.7581202862 1.1572017722 0.5556207179 0.8226233400 -0.0915903655 0.0786617012959 +1403638153345096960.0000000000 4.1280195633 0.8027021214 1.1642561735 0.5551697115 0.8237275121 -0.0871460743 0.0752671177221 +1403638153395097088.0000000000 4.1067038404 0.8475835882 1.1703874011 0.5551898073 0.8245929288 -0.0813889780 0.0720181498922 +1403638153445096960.0000000000 4.0855062734 0.8928854187 1.1758748292 0.5548718729 0.8256942644 -0.0740215771 0.0697638333233 +1403638153495097088.0000000000 4.0644184448 0.9385648958 1.1818525221 0.5541516137 0.8269888026 -0.0648185199 0.0693113911604 +1403638153545096960.0000000000 4.0429591662 0.9852178231 1.1896601638 0.5531961027 0.8283947444 -0.0550168141 0.0686248462347 +1403638153595097088.0000000000 4.0205795084 1.0327998215 1.1994454549 0.5527160595 0.8294985120 -0.0459552990 0.0657669118825 +1403638153645096960.0000000000 3.9973165342 1.0812541580 1.2108450394 0.5529834764 0.8300273390 -0.0364795747 0.0627146865351 +1403638153695097088.0000000000 3.9728086538 1.1306830928 1.2231113163 0.5539440117 0.8301286400 -0.0282399621 0.0568768629647 +1403638153745096960.0000000000 3.9474172451 1.1811689762 1.2351230678 0.5563775005 0.8291822029 -0.0212606756 0.0494867156176 +1403638153795097088.0000000000 3.9217403788 1.2324430513 1.2454277487 0.5577534584 0.8287004359 -0.0140724277 0.0443692901382 +1403638153845096960.0000000000 3.8954087253 1.2843263818 1.2544638530 0.5595372408 0.8278481428 -0.0081246407 0.0389810069005 +1403638153895097088.0000000000 3.8685397506 1.3368409848 1.2623406936 0.5618969601 0.8264750083 -0.0033869117 0.0346322932061 +1403638153945096960.0000000000 3.8410949303 1.3902205078 1.2691412194 0.5653565629 0.8242957679 -0.0001419994 0.0301400666279 +1403638153995097088.0000000000 3.8133221846 1.4435019158 1.2737429739 0.5670238004 0.8232780280 0.0021749100 0.0263166885302 +1403638154045096960.0000000000 3.7852619395 1.4967913545 1.2767115295 0.5688481960 0.8221104711 0.0037133161 0.0230719421922 +1403638154095097088.0000000000 3.7569756203 1.5500762054 1.2782111995 0.5709306846 0.8206881965 0.0058380796 0.02179344689 +1403638154145096960.0000000000 3.7282624122 1.6033643088 1.2785339481 0.5738522135 0.8186482944 0.0075959547 0.0212346072042 +1403638154195097088.0000000000 3.6991683565 1.6565591529 1.2777510128 0.5768313888 0.8165298917 0.0090083648 0.0215251998462 +1403638154245096960.0000000000 3.6695058325 1.7093252528 1.2757983238 0.5795588737 0.8145520010 0.0106214829 0.0224440134866 +1403638154295097088.0000000000 3.6393334123 1.7614534382 1.2727581355 0.5816347834 0.8130456260 0.0112643067 0.0230413602304 +1403638154345096960.0000000000 3.6083311273 1.8130263221 1.2691932198 0.5850172990 0.8106357186 0.0107266134 0.0225705870607 +1403638154395097088.0000000000 3.5769968752 1.8638312816 1.2648181680 0.5896502588 0.8072575001 0.0106817120 0.023104154223 +1403638154445096960.0000000000 3.5450064133 1.9132402220 1.2589840894 0.5929979415 0.8048268866 0.0097765491 0.0226173181239 +1403638154495097088.0000000000 3.5124515369 1.9614155573 1.2522075674 0.5953283805 0.8031088927 0.0090819705 0.022753979208 +1403638154545096960.0000000000 3.4791401758 2.0080976291 1.2459009488 0.5951199436 0.8032918570 0.0082819600 0.0220421063584 +1403638154595097088.0000000000 3.4448295696 2.0521761459 1.2410478688 0.5940576176 0.8041254226 0.0083851781 0.0201876335573 +1403638154645096960.0000000000 3.4098400895 2.0943203403 1.2379420467 0.5918842136 0.8057673557 0.0095693727 0.017901769458 +1403638154695097088.0000000000 3.3742555885 2.1350310078 1.2365143342 0.5886237217 0.8081837890 0.0117323635 0.0149475408197 +1403638154745096960.0000000000 3.3383771553 2.1743997026 1.2361510751 0.5851454876 0.8106557428 0.0160776794 0.0135474403442 +1403638154795097088.0000000000 3.3022122878 2.2128179717 1.2377716335 0.5822514805 0.8126429941 0.0206517734 0.0129646353246 +1403638154845096960.0000000000 3.2656336620 2.2502075358 1.2406876780 0.5802908792 0.8139074618 0.0254586108 0.0129999371144 +1403638154895097088.0000000000 3.2284090276 2.2877580846 1.2456437419 0.5791292945 0.8145946311 0.0297888078 0.0125488706789 +1403638154945096960.0000000000 3.1903559633 2.3244082239 1.2528909495 0.5782544031 0.8150080342 0.0350636772 0.0124212717975 +1403638154995097088.0000000000 3.1511087625 2.3598349309 1.2623527894 0.5785470364 0.8146081046 0.0398196755 0.0105525325688 +1403638155045096960.0000000000 3.1105429877 2.3948680414 1.2737870812 0.5794379824 0.8137215585 0.0452778578 0.0076658545026 +1403638155095097088.0000000000 3.0689091702 2.4285482307 1.2864272089 0.5797872126 0.8131589380 0.0509965785 0.00432187447544 +1403638155145096960.0000000000 3.0264382023 2.4618263832 1.2990164511 0.5813398334 0.8117348176 0.0559495491 0.000481621016533 +1403638155195097088.0000000000 2.9832951106 2.4945294363 1.3106698792 0.5821964153 0.8108516118 0.0596074539 -0.00373483357918 +1403638155245096960.0000000000 2.9395131972 2.5267757684 1.3210247531 0.5847359567 0.8087392130 0.0630221998 -0.00727657800644 +1403638155295097088.0000000000 2.8951729123 2.5581288011 1.3296609702 0.5870096247 0.8068036711 0.0662989787 -0.00959073215819 +1403638155345096960.0000000000 2.8499861399 2.5885775052 1.3367500870 0.5893020635 0.8047599298 0.0704243115 -0.0111780880477 +1403638155395097088.0000000000 2.8039396359 2.6176369821 1.3422874820 0.5915382829 0.8026449616 0.0752003831 -0.0137269052789 +1403638155445096960.0000000000 2.7572338362 2.6456389660 1.3460210321 0.5932498345 0.8008002047 0.0808829809 -0.0152187181909 +1403638155495097088.0000000000 2.7095071121 2.6720766288 1.3480278300 0.5936310486 0.7998687874 0.0865080137 -0.0181235939031 +1403638155545096960.0000000000 2.6604118567 2.6969278752 1.3490629713 0.5944660693 0.7986110895 0.0904910884 -0.0253334398931 +1403638155595097088.0000000000 2.6107397162 2.7200872172 1.3485538100 0.5949771378 0.7974564364 0.0948189479 -0.0327842148326 +1403638155645096960.0000000000 2.5603113307 2.7415556999 1.3474013014 0.5967027319 0.7951790767 0.0992274913 -0.0423082799357 +1403638155695097088.0000000000 2.5096220724 2.7612628924 1.3449534315 0.5985100989 0.7925140897 0.1052505388 -0.0512777077104 +1403638155745096960.0000000000 2.4589054613 2.7792335038 1.3409451784 0.5987457127 0.7908167472 0.1118828874 -0.0599555112104 +1403638155795097088.0000000000 2.4083657666 2.7952902791 1.3354239677 0.5978408837 0.7896846102 0.1200027392 -0.067704037471 +1403638155845096960.0000000000 2.3577977555 2.8093585079 1.3290258338 0.5960812559 0.7889731417 0.1279006581 -0.0764848990288 +1403638155895097088.0000000000 2.3075555570 2.8212164367 1.3214951146 0.5919645188 0.7896729087 0.1373948328 -0.0843644809916 +1403638155945096960.0000000000 2.2577165246 2.8309669668 1.3145253059 0.5860072627 0.7913718243 0.1475447868 -0.0925022139879 +1403638155995097088.0000000000 2.2084066481 2.8389148319 1.3084656488 0.5791185645 0.7933104245 0.1587976877 -0.100317262326 +1403638156045096960.0000000000 2.1596261480 2.8461690875 1.3045551526 0.5720388168 0.7950638481 0.1704115138 -0.107726438532 +1403638156095097088.0000000000 2.1109898989 2.8527429204 1.3030215337 0.5651839240 0.7963488322 0.1817636138 -0.115575335987 +1403638156145096960.0000000000 2.0630665442 2.8587317908 1.3036913030 0.5609791116 0.7958771151 0.1915098941 -0.123312669623 +1403638156195097088.0000000000 2.0152033100 2.8650079804 1.3070604409 0.5573377608 0.7951418130 0.1995036919 -0.131614568236 +1403638156245096960.0000000000 1.9676688439 2.8717389761 1.3117841695 0.5537137719 0.7942760405 0.2085707326 -0.137930706402 +1403638156295097088.0000000000 1.9204822734 2.8788940220 1.3173750236 0.5486124130 0.7944950878 0.2171092141 -0.143755225751 +1403638156345096960.0000000000 1.8738853655 2.8865532541 1.3230675428 0.5443953146 0.7944398952 0.2245229813 -0.148621752179 +1403638156395097088.0000000000 1.8277049768 2.8947920683 1.3276866974 0.5410468764 0.7942746421 0.2298229947 -0.153549541281 +1403638156445096960.0000000000 1.7819372618 2.9037007297 1.3308802486 0.5378881675 0.7943414824 0.2346508406 -0.156961497196 +1403638156495097088.0000000000 1.7364066632 2.9137848439 1.3324709198 0.5354502545 0.7943904556 0.2380421620 -0.159914846147 +1403638156545096960.0000000000 1.6911208785 2.9249091066 1.3327768099 0.5344896665 0.7937483189 0.2408813861 -0.162051104713 +1403638156595097088.0000000000 1.6459420887 2.9370427827 1.3316188465 0.5338401409 0.7932156428 0.2428340944 -0.163875716746 +1403638156645096960.0000000000 1.6008354383 2.9504180027 1.3287161431 0.5333103392 0.7930122971 0.2442247005 -0.164517094512 +1403638156695097088.0000000000 1.5558854013 2.9646020111 1.3244675484 0.5324866152 0.7932173340 0.2449208858 -0.165160604783 +1403638156745096960.0000000000 1.5105629769 2.9803299601 1.3192023416 0.5328360816 0.7927345579 0.2457253196 -0.165156586868 +1403638156795097088.0000000000 1.4653199725 2.9971971558 1.3126717764 0.5325154800 0.7929784971 0.2457756281 -0.164944558279 +1403638156845096960.0000000000 1.4199846300 3.0154107838 1.3051931860 0.5322854558 0.7933383647 0.2455462656 -0.164296878035 +1403638156895097088.0000000000 1.3750088184 3.0341105390 1.2974326520 0.5323974895 0.7934939248 0.2452334456 -0.163648592076 +1403638156945096960.0000000000 1.3308234944 3.0531193671 1.2898861370 0.5320725090 0.7941458684 0.2446407496 -0.162425639768 +1403638156995097088.0000000000 1.2863309145 3.0733391769 1.2839547502 0.5322714025 0.7945241395 0.2435154339 -0.161613053957 +1403638157045096960.0000000000 1.2412531441 3.0955006611 1.2799175431 0.5311069126 0.7958140473 0.2424619560 -0.160678715089 +1403638157095097088.0000000000 1.1960864655 3.1193257025 1.2778515575 0.5298921971 0.7970557093 0.2416252803 -0.159792614552 +1403638157145096960.0000000000 1.1510413562 3.1443252809 1.2772357064 0.5281237756 0.7987506101 0.2408283025 -0.158380773181 +1403638157195097088.0000000000 1.1059105167 3.1707438740 1.2777797847 0.5265460505 0.8003080428 0.2404272308 -0.156368283661 +1403638157245096960.0000000000 1.0605550451 3.1980341061 1.2801109904 0.5261615494 0.8009126890 0.2389378079 -0.156849011469 +1403638157295097088.0000000000 1.0152026541 3.2262234915 1.2844338080 0.5271062913 0.8000970622 0.2393920085 -0.157146794255 +1403638157345096960.0000000000 0.9691177254 3.2557784552 1.2903519087 0.5284240610 0.7987964052 0.2412782427 -0.156451667866 +1403638157395097088.0000000000 0.9228802717 3.2870242163 1.2959969993 0.5299158105 0.7973741140 0.2435252401 -0.155174783484 +1403638157445096960.0000000000 0.8762341159 3.3190940656 1.3005242077 0.5323433788 0.7952765845 0.2458186322 -0.154009354657 +1403638157495097088.0000000000 0.8287792438 3.3515956832 1.3039582188 0.5344322598 0.7929760310 0.2480275218 -0.155091979988 +1403638157545096960.0000000000 0.7808747228 3.3844262540 1.3061765478 0.5366015822 0.7901313442 0.2511463541 -0.157088222655 +1403638157595097088.0000000000 0.7324193540 3.4174958242 1.3072189076 0.5389500576 0.7865712266 0.2554906023 -0.159884624187 +1403638157645096960.0000000000 0.6833552803 3.4506846273 1.3071087716 0.5419035961 0.7820836221 0.2611387185 -0.162764462386 +1403638157695097088.0000000000 0.6343930687 3.4832713930 1.3067650871 0.5444713015 0.7771434402 0.2685044723 -0.165844576313 +1403638157745096960.0000000000 0.5851668709 3.5154792254 1.3074438753 0.5457992032 0.7724961490 0.2770171784 -0.169157951426 +1403638157795097088.0000000000 0.5353446294 3.5471324012 1.3097632976 0.5454770327 0.7685247406 0.2854793539 -0.174143815291 +1403638157845096960.0000000000 0.4849841271 3.5780835697 1.3145074143 0.5441697386 0.7646737612 0.2938288816 -0.181157177004 +1403638157895097088.0000000000 0.4341690549 3.6084315890 1.3215168991 0.5425720152 0.7609138557 0.3015680662 -0.188897893022 +1403638157945096960.0000000000 0.3832262221 3.6380881470 1.3304653658 0.5401143790 0.7576882386 0.3093729991 -0.196146216172 +1403638157995097088.0000000000 0.3323665253 3.6676759966 1.3401909437 0.5384937737 0.7544422249 0.3165611190 -0.201569945339 +1403638158045096960.0000000000 0.2817219822 3.6965296473 1.3489454526 0.5334874658 0.7538381419 0.3221696923 -0.208148670566 +1403638158095097088.0000000000 0.2310101817 3.7252566684 1.3570789610 0.5299414572 0.7527161284 0.3260448432 -0.215116810636 +1403638158145096960.0000000000 0.1806232572 3.7542913474 1.3638320819 0.5272170772 0.7516029619 0.3290876364 -0.220989748106 +1403638158195097088.0000000000 0.1305006664 3.7835223576 1.3691331816 0.5243455963 0.7510372710 0.3309913704 -0.226824659062 +1403638158245096960.0000000000 0.0809980207 3.8134598640 1.3727362833 0.5232313929 0.7497786556 0.3336234627 -0.229687313946 +1403638158295097088.0000000000 0.0317608149 3.8439215091 1.3750305404 0.5231547686 0.7482068267 0.3362376049 -0.231170728205 +1403638158345096960.0000000000 -0.0170063790 3.8748823847 1.3759546321 0.5227836621 0.7472382284 0.3396137127 -0.230205992099 +1403638158395097088.0000000000 -0.0654189307 3.9059717394 1.3762756707 0.5229931425 0.7463285191 0.3413250111 -0.230150279702 +1403638158445096960.0000000000 -0.1132801346 3.9371460555 1.3753480499 0.5245923041 0.7446051946 0.3440707589 -0.227994148037 +1403638158495097088.0000000000 -0.1605715000 3.9679823279 1.3734086549 0.5260612805 0.7431880568 0.3458673940 -0.226510015539 +1403638158545096960.0000000000 -0.2078823364 3.9985929607 1.3704239675 0.5279585677 0.7416967484 0.3472573712 -0.224851067191 +1403638158595097088.0000000000 -0.2552208627 4.0288916270 1.3667357825 0.5289302719 0.7411151736 0.3479605962 -0.223393129939 +1403638158645096960.0000000000 -0.3028029139 4.0586808451 1.3630234790 0.5302676403 0.7404057252 0.3476992510 -0.222981664315 +1403638158695097088.0000000000 -0.3506429768 4.0875491284 1.3594206249 0.5300972534 0.7408999255 0.3461900157 -0.224090774926 +1403638158745096960.0000000000 -0.3986772613 4.1156306383 1.3560733911 0.5290398610 0.7419988619 0.3445372574 -0.225496325195 +1403638158795097088.0000000000 -0.4463557562 4.1429496988 1.3529033214 0.5260019745 0.7445146670 0.3428999183 -0.226802732461 +1403638158845096960.0000000000 -0.4938995664 4.1701126348 1.3514825386 0.5229223051 0.7472530529 0.3409123965 -0.227911991135 +1403638158895097088.0000000000 -0.5412575057 4.1972330380 1.3515848612 0.5196423408 0.7500182574 0.3397195291 -0.228112017903 +1403638158945096960.0000000000 -0.5890109808 4.2249002707 1.3543070514 0.5172463207 0.7520453510 0.3381297861 -0.22924284395 +1403638158995097088.0000000000 -0.6362240356 4.2527984587 1.3586861865 0.5142110380 0.7546010512 0.3378912394 -0.228021429409 +1403638159045096960.0000000000 -0.6830564069 4.2807258878 1.3649759861 0.5096456099 0.7579809600 0.3380749907 -0.226785178347 +1403638159095097088.0000000000 -0.7303882712 4.3095033289 1.3729524133 0.5050023854 0.7614644858 0.3389154892 -0.224233625628 +1403638159145096960.0000000000 -0.7779746794 4.3386397819 1.3807471457 0.4985297154 0.7660978083 0.3394271603 -0.222151916063 +1403638159195097088.0000000000 -0.8262123955 4.3688744370 1.3870920719 0.4931054310 0.7698839273 0.3410421500 -0.218668754897 +1403638159245096960.0000000000 -0.8757085588 4.4006639539 1.3926587048 0.4914969064 0.7712513931 0.3413585567 -0.21697100138 +1403638159295097088.0000000000 -0.9267031077 4.4344995018 1.3980008201 0.4950715197 0.7693996502 0.3392322783 -0.218746039933 +1403638159345096960.0000000000 -0.9788443065 4.4698562037 1.4027320163 0.5017113508 0.7654516789 0.3354541217 -0.223248695323 +1403638159395097088.0000000000 -1.0315972726 4.5065706452 1.4063619897 0.5103260826 0.7600125498 0.3317642920 -0.227773282172 +1403638159445096960.0000000000 -1.0842347111 4.5441886167 1.4101079141 0.5201832778 0.7536177077 0.3271860082 -0.233278855005 +1403638159495097088.0000000000 -1.1364817967 4.5821302149 1.4152444661 0.5287202069 0.7477950089 0.3219268085 -0.240043115911 +1403638159545096960.0000000000 -1.1877305730 4.6196756200 1.4215959048 0.5353779193 0.7429480021 0.3156707977 -0.248496875631 +1403638159595097088.0000000000 -1.2365507023 4.6567525064 1.4298551731 0.5387124385 0.7401988347 0.3090095274 -0.257696926076 +1403638159645096960.0000000000 -1.2831047768 4.6941240641 1.4398007294 0.5409136028 0.7381429775 0.3037416082 -0.265138557185 +1403638159695097088.0000000000 -1.3273645119 4.7324704380 1.4513944750 0.5424567761 0.7365781487 0.2994271879 -0.271176393057 +1403638159745096960.0000000000 -1.3685009212 4.7713061466 1.4641418320 0.5415237846 0.7367958649 0.2971004248 -0.274982148184 +1403638159795097088.0000000000 -1.4056218076 4.8105826589 1.4784389507 0.5444161371 0.7347257472 0.2981116187 -0.273712639204 +1403638159845096960.0000000000 -1.4391409901 4.8499770003 1.4942573679 0.5470025440 0.7329570769 0.3002637641 -0.270931379354 +1403638159895097088.0000000000 -1.4693116372 4.8897129538 1.5115303818 0.5497711253 0.7311856780 0.3057007462 -0.263943683174 +1403638159945096960.0000000000 -1.4959114882 4.9284679437 1.5305935859 0.5521683378 0.7298109048 0.3108216870 -0.256663298535 +1403638159995097088.0000000000 -1.5196855224 4.9660157189 1.5529405957 0.5534862763 0.7287163654 0.3150075754 -0.251784884838 +1403638160045096960.0000000000 -1.5403102535 5.0018260498 1.5771437170 0.5539736447 0.7282310927 0.3185155540 -0.247670180645 +1403638160095097088.0000000000 -1.5587655208 5.0363439054 1.6026904212 0.5520210331 0.7295051486 0.3211242425 -0.244896382312 +1403638160145096960.0000000000 -1.5754401005 5.0699184204 1.6301799922 0.5489297399 0.7315476634 0.3241593100 -0.241733114382 +1403638160195097088.0000000000 -1.5912346435 5.1028498691 1.6600491983 0.5421338050 0.7362210746 0.3277230975 -0.238048394485 +1403638160245096960.0000000000 -1.6057775037 5.1348615988 1.6924774779 0.5346665795 0.7413099433 0.3314280155 -0.233980100189 +1403638160295097088.0000000000 -1.6191039035 5.1662296792 1.7267279463 0.5278359140 0.7458215928 0.3341162777 -0.231313018564 +1403638160345096960.0000000000 -1.6321861203 5.1976252655 1.7628591362 0.5226762773 0.7491716002 0.3370410005 -0.227935926406 +1403638160395097088.0000000000 -1.6453065065 5.2290824777 1.8001046299 0.5188327166 0.7516430173 0.3390379194 -0.225607349051 +1403638160445096960.0000000000 -1.6585084563 5.2609257653 1.8369861395 0.5166543728 0.7530584278 0.3395426295 -0.225126778033 +1403638160495097088.0000000000 -1.6719029511 5.2930857274 1.8726665754 0.5153478750 0.7539780949 0.3398793992 -0.224534171575 +1403638160545096960.0000000000 -1.6858260932 5.3255602472 1.9071317802 0.5143746466 0.7546960287 0.3402232342 -0.223832031034 +1403638160595097088.0000000000 -1.7004722729 5.3583724399 1.9405719029 0.5139829201 0.7549508032 0.3402832310 -0.223781512612 +1403638160645096960.0000000000 -1.7159280372 5.3915253350 1.9727394216 0.5126907601 0.7559559417 0.3398680151 -0.223983327527 +1403638160695097088.0000000000 -1.7321922899 5.4254246306 2.0040938738 0.5140581132 0.7551104927 0.3397434484 -0.223890127974 +1403638160745096960.0000000000 -1.7491383560 5.4596218399 2.0350101151 0.5154281184 0.7542015668 0.3374735574 -0.227212344295 +1403638160795097088.0000000000 -1.7664759011 5.4947687108 2.0652808666 0.5182137675 0.7529326052 0.3332523026 -0.231278805956 +1403638160845096960.0000000000 -1.7837617266 5.5308382213 2.0952496842 0.5234489418 0.7507715557 0.3270372340 -0.235350640635 +1403638160895097088.0000000000 -1.8007498950 5.5674806495 2.1246435422 0.5290838097 0.7491743838 0.3190996889 -0.238712072281 +1403638160945096960.0000000000 -1.8161381444 5.6044090175 2.1526030257 0.5355145626 0.7477976204 0.3110934128 -0.239256683608 +1403638160995097088.0000000000 -1.8300860449 5.6417348053 2.1790528250 0.5406800338 0.7477799198 0.3037045346 -0.237178937269 +1403638161045096960.0000000000 -1.8429212682 5.6797374233 2.2050461986 0.5450590990 0.7487903318 0.2959527623 -0.233742550803 +1403638161095097088.0000000000 -1.8537941775 5.7171642521 2.2302172783 0.5480435455 0.7510624390 0.2880755885 -0.22927263293 +1403638161145096960.0000000000 -1.8624132606 5.7541049595 2.2540473555 0.5505533582 0.7540507193 0.2812013753 -0.22186549778 +1403638161195097088.0000000000 -1.8694752635 5.7907637027 2.2764685681 0.5520583149 0.7582511662 0.2732732849 -0.213561460835 +1403638161245096960.0000000000 -1.8755816028 5.8277904188 2.2986402890 0.5529011618 0.7631859854 0.2647468861 -0.204344178194 +1403638161295097088.0000000000 -1.8809056732 5.8651381816 2.3205872999 0.5543058017 0.7677883150 0.2548991864 -0.19563380641 +1403638161345096960.0000000000 -1.8848988095 5.9014965473 2.3426999316 0.5546993514 0.7728532739 0.2454847238 -0.186396611909 +1403638161395097088.0000000000 -1.8876711492 5.9364837266 2.3637919967 0.5528728821 0.7785401155 0.2377258546 -0.178026073374 +1403638161445096960.0000000000 -1.8895287091 5.9707197553 2.3842469044 0.5502783029 0.7841013396 0.2313286453 -0.169899783301 +1403638161495097088.0000000000 -1.8910030979 6.0048804541 2.4038298780 0.5475801311 0.7889405652 0.2266308272 -0.162379964111 +1403638161545096960.0000000000 -1.8922192571 6.0386315809 2.4223955855 0.5456975534 0.7926479465 0.2221288548 -0.156787068745 +1403638161595097088.0000000000 -1.8933414090 6.0727386317 2.4397009446 0.5446428457 0.7954492834 0.2174366774 -0.15279364983 +1403638161645096960.0000000000 -1.8943531240 6.1069844368 2.4554898785 0.5435011822 0.7979052803 0.2130584002 -0.150199023641 +1403638161695097088.0000000000 -1.8953183880 6.1416164787 2.4700674026 0.5428143046 0.7996850941 0.2084140730 -0.149732946358 +1403638161745096960.0000000000 -1.8961241452 6.1769467663 2.4834614304 0.5435937200 0.8001683024 0.2042657710 -0.150040162222 +1403638161795097088.0000000000 -1.8964842202 6.2131749216 2.4955770276 0.5452326061 0.8001618301 0.2001810016 -0.149632942246 +1403638161845096960.0000000000 -1.8963535143 6.2505562001 2.5065837849 0.5484736169 0.7991823992 0.1965892868 -0.147772922484 +1403638161895097088.0000000000 -1.8957402091 6.2885128456 2.5165732488 0.5519774525 0.7982212405 0.1918826923 -0.146098513414 +1403638161945096960.0000000000 -1.8943005315 6.3267890062 2.5247177863 0.5543696492 0.7981691567 0.1875050556 -0.142976024042 +1403638161995097088.0000000000 -1.8922232519 6.3650451290 2.5324893808 0.5556216362 0.7986992940 0.1835123589 -0.140311258121 +1403638162045096960.0000000000 -1.8896841209 6.4035986564 2.5413293296 0.5565918806 0.7991627814 0.1800187263 -0.138338661953 +1403638162095097088.0000000000 -1.8867908861 6.4431015450 2.5518529863 0.5568209603 0.7999147892 0.1773354836 -0.136524263364 +1403638162145096960.0000000000 -1.8830728692 6.4822931317 2.5642545191 0.5554195210 0.8016082401 0.1746854820 -0.135714286144 +1403638162195097088.0000000000 -1.8787513964 6.5215481554 2.5783831756 0.5533879037 0.8035719718 0.1718616177 -0.136005508922 +1403638162245096960.0000000000 -1.8735674782 6.5608861243 2.5929389068 0.5516580013 0.8052514597 0.1698476850 -0.135629274727 +1403638162295097088.0000000000 -1.8676930871 6.6009750236 2.6068590395 0.5501951995 0.8066490684 0.1679149809 -0.135672702342 +1403638162345096960.0000000000 -1.8610178915 6.6417764980 2.6196493374 0.5492975694 0.8074925169 0.1654758957 -0.137279799647 +1403638162395097088.0000000000 -1.8534045326 6.6837941977 2.6313322442 0.5498422985 0.8072836080 0.1634836912 -0.138707266437 +1403638162445096960.0000000000 -1.8448704411 6.7267206210 2.6419003114 0.5511696656 0.8064915679 0.1623270904 -0.139403251015 +1403638162495097088.0000000000 -1.8350247131 6.7702211562 2.6512616791 0.5527090494 0.8055771489 0.1622970372 -0.138628408426 +1403638162545096960.0000000000 -1.8241618067 6.8140589767 2.6605561191 0.5537495446 0.8048932425 0.1634313402 -0.137107648087 +1403638162595097088.0000000000 -1.8121743358 6.8586478898 2.6706753792 0.5539032552 0.8047968940 0.1655682908 -0.134462947755 +1403638162645096960.0000000000 -1.7993095782 6.9034630955 2.6825874420 0.5547912637 0.8041251104 0.1676423051 -0.132232817838 +1403638162695097088.0000000000 -1.7858244696 6.9488533771 2.6961985946 0.5546187537 0.8041194606 0.1702173601 -0.129676449282 +1403638162745096960.0000000000 -1.7717498730 6.9944184407 2.7119817348 0.5539579680 0.8044473351 0.1722198841 -0.12780988328 +1403638162795097088.0000000000 -1.7574020159 7.0405803628 2.7300377325 0.5523589316 0.8057443081 0.1706090982 -0.128717739079 +1403638162845096960.0000000000 -1.7422579224 7.0874044514 2.7499957068 0.5516870395 0.8067563364 0.1683328910 -0.128256235483 +1403638162895097088.0000000000 -1.7266705775 7.1350049887 2.7725018436 0.5528210384 0.8066842974 0.1637349138 -0.129769880248 +1403638162945096960.0000000000 -1.7100763438 7.1826271580 2.7967417666 0.5548941406 0.8058491094 0.1587162986 -0.132320981574 +1403638162995097088.0000000000 -1.6925727890 7.2315173686 2.8219709494 0.5601454814 0.8028751409 0.1551134739 -0.132545682823 +1403638163045096960.0000000000 -1.6741080791 7.2807851688 2.8462614408 0.5651655530 0.7999831125 0.1513368206 -0.133086754011 +1403638163095097088.0000000000 -1.6543106957 7.3299261858 2.8666912796 0.5691153409 0.7980034271 0.1467664128 -0.133258692317 +1403638163145096960.0000000000 -1.6331528951 7.3792607986 2.8822436360 0.5706020336 0.7980646664 0.1430002479 -0.130602589988 +1403638163195097088.0000000000 -1.6104473774 7.4280304387 2.8926735216 0.5709831219 0.7991453628 0.1396408424 -0.125878507972 +1403638163245096960.0000000000 -1.5863576066 7.4767678606 2.8990938986 0.5712790744 0.8005039015 0.1364156815 -0.119266444288 +1403638163295097088.0000000000 -1.5613260175 7.5257557752 2.9032348813 0.5715744130 0.8019741968 0.1324733333 -0.112209153301 +1403638163345096960.0000000000 -1.5351725187 7.5744020293 2.9058081115 0.5727552383 0.8029214979 0.1276984153 -0.104697755182 +1403638163395097088.0000000000 -1.5081586832 7.6228349695 2.9075754849 0.5740230820 0.8038124829 0.1223627283 -0.09700699101 +1403638163445096960.0000000000 -1.4804792982 7.6705603776 2.9081746109 0.5754453334 0.8045267870 0.1157834175 -0.0905180504676 +1403638163495097088.0000000000 -1.4523819501 7.7173697378 2.9087704336 0.5753107634 0.8060172568 0.1100131837 -0.085151668414 +1403638163545096960.0000000000 -1.4237594074 7.7628609714 2.9112081336 0.5766232337 0.8062486269 0.1045963677 -0.0807985016293 +1403638163595097088.0000000000 -1.3946877325 7.8069193273 2.9146671261 0.5756134976 0.8078193732 0.1002056329 -0.0778189753692 +1403638163645096960.0000000000 -1.3653398470 7.8507864222 2.9203555355 0.5759963798 0.8082137643 0.0973199716 -0.0744815738097 +1403638163695097088.0000000000 -1.3355191368 7.8937610140 2.9281127366 0.5765869447 0.8083549500 0.0948172050 -0.0715504553352 +1403638163745096960.0000000000 -1.3056777662 7.9362024203 2.9381427131 0.5764350977 0.8088481837 0.0927406111 -0.0699025956025 +1403638163795097088.0000000000 -1.2756266135 7.9781685111 2.9505183148 0.5776571072 0.8082572779 0.0916753846 -0.068029868318 +1403638163845096960.0000000000 -1.2453972532 8.0188045364 2.9648761678 0.5779926049 0.8082107245 0.0894630219 -0.0686756233573 +1403638163895097088.0000000000 -1.2148879493 8.0588734827 2.9810173532 0.5785058216 0.8079591325 0.0878924669 -0.0693395180432 +1403638163945096960.0000000000 -1.1840015087 8.0979648453 2.9984975998 0.5771109426 0.8089877892 0.0868271168 -0.0703048258021 +1403638163995097088.0000000000 -1.1528878308 8.1368370581 3.0179792303 0.5762260086 0.8095793007 0.0843489900 -0.0736898288209 +1403638164045096960.0000000000 -1.1211838661 8.1754704074 3.0387775538 0.5748083105 0.8104954132 0.0833601594 -0.0757870388174 +1403638164095097088.0000000000 -1.0888581149 8.2140616904 3.0617861524 0.5744824231 0.8105731935 0.0823886823 -0.0784420073712 +1403638164145096960.0000000000 -1.0556292285 8.2525422474 3.0863203669 0.5748075472 0.8102029733 0.0816355825 -0.0806415369794 +1403638164195097088.0000000000 -1.0214794562 8.2906704564 3.1111498434 0.5751605629 0.8097626797 0.0804846261 -0.0836478000214 +1403638164245096960.0000000000 -0.9861468915 8.3285278876 3.1349771382 0.5764929581 0.8086715826 0.0808980039 -0.0846265540432 +1403638164295097088.0000000000 -0.9500843573 8.3662945494 3.1576338588 0.5775457483 0.8077232410 0.0803614509 -0.0869833993959 +1403638164345096960.0000000000 -0.9127227724 8.4036144757 3.1787185576 0.5785737903 0.8068331480 0.0804357539 -0.0883330630012 +1403638164395097088.0000000000 -0.8742290958 8.4403782958 3.1982830169 0.5791285590 0.8062930103 0.0808045968 -0.0892877975491 +1403638164445096960.0000000000 -0.8345405214 8.4765922877 3.2162962520 0.5797125491 0.8057159647 0.0818611760 -0.0897434809932 +1403638164495097088.0000000000 -0.7937245810 8.5124473996 3.2331173813 0.5788336664 0.8061880215 0.0813773299 -0.0915979848102 +1403638164545096960.0000000000 -0.7516757563 8.5479648012 3.2492522610 0.5789956046 0.8059237658 0.0806877473 -0.0934904327646 +1403638164595097088.0000000000 -0.7082453517 8.5829048120 3.2639885219 0.5784216253 0.8062404418 0.0797453185 -0.0951076106005 +1403638164645096960.0000000000 -0.6631048086 8.6176174242 3.2775048269 0.5781670608 0.8065928911 0.0777353306 -0.0953308774039 +1403638164695097088.0000000000 -0.6158095810 8.6520073784 3.2893297704 0.5782948004 0.8070139593 0.0760290910 -0.092321019547 +1403638164745096960.0000000000 -0.5669326233 8.6861867643 3.2999378542 0.5801497163 0.8063027965 0.0746735915 -0.0878974501794 +1403638164795097088.0000000000 -0.5164179995 8.7198499932 3.3092301896 0.5831999425 0.8047794906 0.0764249323 -0.0797936605922 +1403638164845096960.0000000000 -0.4646858965 8.7527536236 3.3177674369 0.5868915860 0.8026997091 0.0790478831 -0.070589485776 +1403638164895097088.0000000000 -0.4124604231 8.7848567241 3.3255075958 0.5902897494 0.8006796919 0.0812070375 -0.0622531912083 +1403638164945096960.0000000000 -0.3603193229 8.8156039314 3.3323432745 0.5924239414 0.7994413791 0.0818564371 -0.0568056221116 +1403638164995097088.0000000000 -0.3086615418 8.8452044925 3.3390283517 0.5955487031 0.7974325124 0.0789583073 -0.0564687175574 +1403638165045096960.0000000000 -0.2572678166 8.8733563900 3.3447786740 0.5986837690 0.7954734161 0.0727167797 -0.0592626268147 +1403638165095097088.0000000000 -0.2055931947 8.9000118425 3.3488401958 0.5996082235 0.7952124760 0.0655528382 -0.0617245634604 +1403638165145096960.0000000000 -0.1533844307 8.9250688700 3.3511137042 0.5980125585 0.7967841088 0.0597678087 -0.0628002612265 +1403638165195097088.0000000000 -0.1002274111 8.9485453153 3.3515977852 0.5942344894 0.7999724333 0.0564461252 -0.0611826162073 +1403638165245096960.0000000000 -0.0463724703 8.9706876933 3.3504218019 0.5880150700 0.8048940232 0.0540655283 -0.0588286285508 +1403638165295097088.0000000000 0.0078551970 8.9917217447 3.3480793216 0.5809040455 0.8102798521 0.0510408298 -0.058239890521 +1403638165345096960.0000000000 0.0626742637 9.0124805364 3.3452409423 0.5769097754 0.8133440229 0.0470792641 -0.058567519253 +1403638165395097088.0000000000 0.1180524406 9.0332729833 3.3417073753 0.5751386538 0.8147306641 0.0432192358 -0.0596789034413 +1403638165445096960.0000000000 0.1744887609 9.0546774251 3.3368984307 0.5757183919 0.8145068830 0.0416713528 -0.0582268761393 +1403638165495097088.0000000000 0.2320743895 9.0761696811 3.3318857388 0.5806206190 0.8112284051 0.0404980777 -0.0561077290282 +1403638165545096960.0000000000 0.2906606884 9.0974607863 3.3256337024 0.5863059874 0.8073503079 0.0402713763 -0.0529998656594 +1403638165595097088.0000000000 0.3499182316 9.1180756608 3.3185549645 0.5931227920 0.8025193313 0.0398520567 -0.0507926180331 +1403638165645096960.0000000000 0.4100230767 9.1376115704 3.3099947995 0.6001231516 0.7974889888 0.0415721319 -0.0462090192852 +1403638165695097088.0000000000 0.4704114763 9.1554602525 3.3001580967 0.6057716059 0.7933119988 0.0418634907 -0.0440940148727 +1403638165745096960.0000000000 0.5314884971 9.1711605639 3.2885038845 0.6096199561 0.7904734761 0.0435329017 -0.0402502057874 +1403638165795097088.0000000000 0.5926751880 9.1844260286 3.2749207577 0.6091872484 0.7908443571 0.0446661757 -0.0382234480523 +1403638165845096960.0000000000 0.6540217527 9.1952622302 3.2608098727 0.6052598416 0.7938688444 0.0459253831 -0.0363818798824 +1403638165895097088.0000000000 0.7154053816 9.2039298203 3.2478702623 0.6002555976 0.7976441121 0.0466357955 -0.0358076893157 +1403638165945096960.0000000000 0.7769224236 9.2109209953 3.2363627824 0.5957051921 0.8010382333 0.0478858775 -0.0343513543545 +1403638165995097088.0000000000 0.8382671094 9.2164779445 3.2269543942 0.5902528673 0.8050237119 0.0487196082 -0.0341288120591 +1403638166045096960.0000000000 0.8994441784 9.2213454233 3.2197852637 0.5845362926 0.8091498435 0.0491077746 -0.0343842973778 +1403638166095097088.0000000000 0.9606630513 9.2260284216 3.2154022441 0.5806052748 0.8119224517 0.0518175240 -0.031533973522 +1403638166145096960.0000000000 1.0215050093 9.2299808623 3.2134354174 0.5777988928 0.8138366285 0.0544459337 -0.0292236512395 +1403638166195097088.0000000000 1.0814815754 9.2343475682 3.2162322522 0.5758953583 0.8150742646 0.0563867990 -0.0286183236859 +1403638166245096960.0000000000 1.1405976152 9.2391499230 3.2243586961 0.5748638187 0.8156836746 0.0583256356 -0.0281043280715 +1403638166295097088.0000000000 1.1989543589 9.2438102147 3.2377124175 0.5748921088 0.8155462166 0.0602370273 -0.0274760333875 +1403638166345096960.0000000000 1.2564949966 9.2483192455 3.2558938567 0.5741162152 0.8159594531 0.0624087887 -0.02656850457 +1403638166395097088.0000000000 1.3131911349 9.2523545681 3.2784238180 0.5741969284 0.8157996186 0.0640557894 -0.0258016564835 +1403638166445096960.0000000000 1.3688241553 9.2548002522 3.3036523203 0.5730038209 0.8165555097 0.0652145815 -0.0255103747422 +1403638166495097088.0000000000 1.4235315986 9.2573614449 3.3283111852 0.5731556370 0.8163580622 0.0663746375 -0.0254271022452 +1403638166545096960.0000000000 1.4771727448 9.2598029108 3.3516687076 0.5731192296 0.8163291679 0.0663615545 -0.0271511021671 +1403638166595097088.0000000000 1.5295640203 9.2609104744 3.3739804823 0.5738064095 0.8157770895 0.0671403455 -0.0273151724068 +1403638166645096960.0000000000 1.5814510754 9.2624291080 3.3940002295 0.5732689037 0.8161100813 0.0670661838 -0.0287962897654 +1403638166695097088.0000000000 1.6322272848 9.2639470160 3.4123144244 0.5730630422 0.8162589884 0.0659180823 -0.0312221075165 +1403638166745096960.0000000000 1.6821008693 9.2655804971 3.4286458376 0.5720051185 0.8169871002 0.0642298441 -0.034881938045 +1403638166795097088.0000000000 1.7311078941 9.2671485247 3.4430108370 0.5686925059 0.8192773316 0.0606337114 -0.0411951536465 +1403638166845096960.0000000000 1.7798344865 9.2690929267 3.4548909871 0.5632720115 0.8229576102 0.0570342546 -0.0470372897974 +1403638166895097088.0000000000 1.8287190021 9.2714028127 3.4642683588 0.5554469243 0.8281391419 0.0537205763 -0.0527102987553 +1403638166945096960.0000000000 1.8781672781 9.2748271239 3.4718631105 0.5487574259 0.8324988956 0.0519718907 -0.0557655708311 +1403638166995097088.0000000000 1.9282593699 9.2798044750 3.4778135451 0.5428862169 0.8363230903 0.0517994146 -0.0561699626399 +1403638167045096960.0000000000 1.9789985138 9.2868491758 3.4835154814 0.5391285389 0.8387815647 0.0530759176 -0.0544871756147 +1403638167095097088.0000000000 2.0302802000 9.2961208583 3.4904271856 0.5368042061 0.8402936387 0.0544699123 -0.0527339899919 +1403638167145096960.0000000000 2.0821218317 9.3079535317 3.4987993857 0.5364738706 0.8405451070 0.0572250946 -0.0490407769887 +1403638167195097088.0000000000 2.1337424073 9.3224911055 3.5097038104 0.5372799292 0.8400483505 0.0590093515 -0.046550434757 +1403638167245096960.0000000000 2.1851320903 9.3396662967 3.5223453072 0.5381033554 0.8395210539 0.0617743555 -0.0428148101704 +1403638167295097088.0000000000 2.2360811419 9.3589650180 3.5369791639 0.5399170079 0.8383634062 0.0630241856 -0.0407967615558 +1403638167345096960.0000000000 2.2863516598 9.3807698970 3.5532951935 0.5413289741 0.8374480356 0.0639474584 -0.0394265392408 +1403638167395097088.0000000000 2.3360198864 9.4043433282 3.5705592832 0.5421764810 0.8369382774 0.0637257304 -0.03896170573 +1403638167445096960.0000000000 2.3849435260 9.4297105053 3.5875796409 0.5442146034 0.8356503179 0.0629627233 -0.0394297753755 +1403638167495097088.0000000000 2.4335539960 9.4566721303 3.6034178470 0.5468208786 0.8339918909 0.0617621298 -0.0403719206037 +1403638167545096960.0000000000 2.4819449563 9.4851435087 3.6178483285 0.5504036369 0.8316718588 0.0605277201 -0.0414023054092 +1403638167595097088.0000000000 2.5298373602 9.5148428927 3.6309005581 0.5540401708 0.8293149970 0.0574269296 -0.0444777774644 +1403638167645096960.0000000000 2.5777194507 9.5451540310 3.6423455959 0.5569775402 0.8274484303 0.0523509559 -0.0486260454739 +1403638167695097088.0000000000 2.6260936499 9.5765927936 3.6518567626 0.5591929971 0.8261447725 0.0471398691 -0.0506541169148 +1403638167745096960.0000000000 2.6751803994 9.6089882746 3.6597835631 0.5613195485 0.8249792402 0.0407746317 -0.0516434618687 +1403638167795097088.0000000000 2.7250707460 9.6423051220 3.6664852413 0.5625735738 0.8243948641 0.0333173588 -0.0526691150961 +1403638167845096960.0000000000 2.7763177165 9.6766336836 3.6719475410 0.5628770483 0.8244949720 0.0254191869 -0.0522621713109 +1403638167895097088.0000000000 2.8289534554 9.7118517185 3.6764764033 0.5640458052 0.8240555524 0.0179643488 -0.0496191322975 +1403638167945096960.0000000000 2.8828723901 9.7475930873 3.6800883168 0.5652380004 0.8235396387 0.0103776928 -0.0466987151362 +1403638167995097088.0000000000 2.9383333676 9.7837974613 3.6824781787 0.5657158399 0.8235389310 0.0033088979 -0.0416925509231 +1403638168045096960.0000000000 2.9949660588 9.8206844493 3.6860886542 0.5667861705 0.8229953991 -0.0032338707 -0.0377034761393 +1403638168095097088.0000000000 3.0527839142 9.8584600920 3.6916973975 0.5676777558 0.8224547178 -0.0096691866 -0.0348813639501 +1403638168145096960.0000000000 3.1111648452 9.8972664852 3.6959805635 0.5679310145 0.8224200978 -0.0143291264 -0.0295672396408 +1403638168195097088.0000000000 3.1721744272 9.9346699855 3.7047217560 0.5689962824 0.8217039885 -0.0203067263 -0.0251678904321 +1403638168245096960.0000000000 3.2351640869 9.9719957271 3.7148789248 0.5685289997 0.8221169493 -0.0245314204 -0.0172252030797 +1403638168295097088.0000000000 3.2995406073 10.0089546078 3.7264884364 0.5683037239 0.8222061421 -0.0300000283 -0.0103892069286 +1403638168345096960.0000000000 3.3651526244 10.0461753911 3.7399035675 0.5688203003 0.8216824997 -0.0356738869 -0.00295118267311 +1403638168395097088.0000000000 3.4316732411 10.0839045104 3.7555344066 0.5699759277 0.8205691048 -0.0422081382 0.00350129764488 +1403638168445096960.0000000000 3.4991237254 10.1213980881 3.7719079422 0.5694812813 0.8206194457 -0.0461454135 0.0120580396306 +1403638168495097088.0000000000 3.5671695235 10.1589768557 3.7871538108 0.5664750197 0.8223965068 -0.0484940609 0.0204539427051 +1403638168545096960.0000000000 3.6353506193 10.1968285606 3.8006987804 0.5629217139 0.8245236207 -0.0491059982 0.0294710695755 +1403638168595097088.0000000000 3.7036904223 10.2352563750 3.8125064460 0.5578314536 0.8276453507 -0.0493385616 0.037322233585 +1403638168645096960.0000000000 3.7714596148 10.2742098718 3.8225648320 0.5542072921 0.8297241465 -0.0490990539 0.0447370203815 +1403638168695097088.0000000000 3.8384975820 10.3138688365 3.8307123282 0.5509078812 0.8315967788 -0.0488592271 0.0505972314209 +1403638168745096960.0000000000 3.9043441608 10.3542464934 3.8375464471 0.5488190936 0.8327364854 -0.0488247339 0.0544398169533 +1403638168795097088.0000000000 3.9688336018 10.3951246107 3.8430276540 0.5474554925 0.8334847117 -0.0492377632 0.0563148455149 +1403638168845096960.0000000000 4.0321850890 10.4368784282 3.8468700102 0.5455418647 0.8346193251 -0.0493243589 0.057980718427 +1403638168895097088.0000000000 4.0944982342 10.4801869954 3.8496006245 0.5446545801 0.8351200281 -0.0487296665 0.059593176002 +1403638168945096960.0000000000 4.1552661375 10.5248735813 3.8510329957 0.5436716291 0.8357749864 -0.0489200387 0.0592297359341 +1403638168995097088.0000000000 4.2147512260 10.5711781274 3.8513929014 0.5444281177 0.8353365393 -0.0478126000 0.0593704131678 +1403638169045096960.0000000000 4.2731336239 10.6191028672 3.8508516339 0.5478068856 0.8332182919 -0.0464005835 0.059176683896 +1403638169095097088.0000000000 4.3300380159 10.6683579461 3.8496790474 0.5535420750 0.8296062534 -0.0469933670 0.0560023114355 +1403638169145096960.0000000000 4.3851536106 10.7164430601 3.8467732043 0.5577797594 0.8269766030 -0.0475588756 0.0522454914146 +1403638169195097088.0000000000 4.4397831254 10.7666282947 3.8421045382 0.5610880959 0.8249501491 -0.0490649388 0.0472232132964 +1403638169245096960.0000000000 4.4937550901 10.8173865888 3.8364523121 0.5647664168 0.8225458912 -0.0526500820 0.0410502164715 +1403638169295097088.0000000000 4.5474404770 10.8685016892 3.8294399608 0.5688282361 0.8196357430 -0.0581694030 0.0353271449723 +1403638169345096960.0000000000 4.6011595444 10.9197883020 3.8215338127 0.5744668027 0.8153134801 -0.0668435493 0.0279957438225 +1403638169395097088.0000000000 4.6557833618 10.9708430071 3.8122840923 0.5794533483 0.8111427063 -0.0757603884 0.0232742521053 +1403638169445096960.0000000000 4.7115419140 11.0206547103 3.8019709764 0.5842933135 0.8068575386 -0.0844888776 0.0210681249754 +1403638169495097088.0000000000 4.7691369566 11.0693286356 3.7918590754 0.5874159295 0.8036245442 -0.0929499249 0.022145636969 +1403638169545096960.0000000000 4.8284662375 11.1168848515 3.7828705734 0.5902347676 0.8005820814 -0.1002509560 0.0253178982557 +1403638169595097088.0000000000 4.8901654932 11.1622585179 3.7754037025 0.5911463714 0.7987614066 -0.1074637470 0.0312686114554 +1403638169645096960.0000000000 4.9536006032 11.2054546393 3.7688826061 0.5907722642 0.7977867014 -0.1137994310 0.0396761956851 +1403638169695097088.0000000000 5.0188841200 11.2476852692 3.7627977146 0.5883612361 0.7981771675 -0.1191484176 0.0504769222763 +1403638169745096960.0000000000 5.0853492976 11.2882485418 3.7590418061 0.5865363257 0.7977941003 -0.1257813506 0.0606528155648 +1403638169795097088.0000000000 5.1531887621 11.3266785233 3.7569957666 0.5841593269 0.7975889611 -0.1304434705 0.0747945919112 +1403638169845096960.0000000000 5.2215521331 11.3637005791 3.7571570296 0.5810816988 0.7975201520 -0.1352584496 0.0895031746681 +1403638169895097088.0000000000 5.2898818503 11.3998189825 3.7598648509 0.5787936606 0.7965009594 -0.1409427446 0.103533873064 +1403638169945096960.0000000000 5.3576939397 11.4348781191 3.7644251537 0.5792151143 0.7931843646 -0.1459194094 0.118642071264 +1403638169995097088.0000000000 5.4241778162 11.4692024217 3.7716292237 0.5812890546 0.7884324281 -0.1526698444 0.131031522409 +1403638170045096960.0000000000 5.4890033984 11.5023117101 3.7799536393 0.5839697847 0.7830662271 -0.1616146826 0.140240040363 +1403638170095097088.0000000000 5.5522466332 11.5341569813 3.7881762825 0.5855182775 0.7783931238 -0.1716688321 0.147656031489 +1403638170145096960.0000000000 5.6137615702 11.5643149978 3.7947224201 0.5852288149 0.7748877328 -0.1836892186 0.152690885893 +1403638170195097088.0000000000 5.6737744820 11.5925514584 3.7995715696 0.5844433466 0.7715305712 -0.1961376636 0.157151421051 +1403638170245096960.0000000000 5.7322205547 11.6188283859 3.8024472257 0.5829061905 0.7685551223 -0.2086967959 0.161211179821 +1403638170295097088.0000000000 5.7893291632 11.6433718614 3.8040662072 0.5812838785 0.7654528002 -0.2219670247 0.164078344777 +1403638170345096960.0000000000 5.8456130971 11.6659536062 3.8034418921 0.5781139376 0.7633018393 -0.2344569087 0.167882504372 +1403638170395097088.0000000000 5.9011435817 11.6866564864 3.8012395205 0.5739834080 0.7616104224 -0.2468716688 0.171892382085 +1403638170445096960.0000000000 5.9558793810 11.7052859043 3.7977249532 0.5699369357 0.7597456767 -0.2582924536 0.176758039235 +1403638170495097088.0000000000 6.0099878752 11.7224606854 3.7941319917 0.5673208880 0.7567794306 -0.2707742632 0.179201567484 +1403638170545096960.0000000000 6.0638906487 11.7380686776 3.7921802376 0.5672685250 0.7519035278 -0.2830620881 0.180895991649 +1403638170595097088.0000000000 6.1183372900 11.7521339772 3.7918699522 0.5674491474 0.7466838011 -0.2942817553 0.184019061039 +1403638170645096960.0000000000 6.1734944318 11.7642445006 3.7940466188 0.5682994960 0.7407919980 -0.3040030671 0.189327847286 +1403638170695097088.0000000000 6.2281264921 11.7733514192 3.7980084065 0.5685645476 0.7352871511 -0.3133213497 0.194722603875 +1403638170745096960.0000000000 6.2822921311 11.7793627215 3.8033045916 0.5665310325 0.7316489273 -0.3219013218 0.200279742855 +1403638170795097088.0000000000 6.3364487243 11.7830529087 3.8103296819 0.5650588483 0.7273783533 -0.3301480478 0.206473958543 +1403638170845096960.0000000000 6.3904819416 11.7840752701 3.8177739009 0.5623101826 0.7240851824 -0.3382171261 0.212407821994 +1403638170895097088.0000000000 6.4442193978 11.7825387194 3.8240977740 0.5591446866 0.7209458214 -0.3455098770 0.219584305049 +1403638170945096960.0000000000 6.4976155075 11.7783177941 3.8286999520 0.5556296029 0.7178699630 -0.3533678994 0.225985814196 +1403638170995097088.0000000000 6.5508132576 11.7716682456 3.8319331294 0.5530344322 0.7139514140 -0.3608083204 0.23290266455 +1403638171045096960.0000000000 6.6036244972 11.7630373203 3.8340025259 0.5514217616 0.7094644550 -0.3680822399 0.238976343046 +1403638171095097088.0000000000 6.6548094081 11.7518498874 3.8354715121 0.5498328356 0.7055561663 -0.3747112011 0.243856238113 +1403638171145096960.0000000000 6.7059040252 11.7388260627 3.8358908995 0.5487105197 0.7019605951 -0.3801253162 0.248340154689 +1403638171195097088.0000000000 6.7560478509 11.7236236998 3.8356587436 0.5481512654 0.6985226202 -0.3854964219 0.250975791508 +1403638171245096960.0000000000 6.8055091100 11.7062031788 3.8349684355 0.5477855703 0.6955568980 -0.3898164824 0.253327220574 +1403638171295097088.0000000000 6.8542116313 11.6863444011 3.8336550117 0.5471889429 0.6933667157 -0.3928127017 0.255978592182 +1403638171345096960.0000000000 6.9018316581 11.6641953352 3.8319615378 0.5470677036 0.6913930747 -0.3955923775 0.257292080804 +1403638171395097088.0000000000 6.9488192329 11.6394543145 3.8298484440 0.5476263074 0.6889811905 -0.3978511881 0.259084501242 +1403638171445096960.0000000000 6.9952706915 11.6121090729 3.8270864998 0.5471854519 0.6867527143 -0.4009363939 0.261168142648 +1403638171495097088.0000000000 7.0408980479 11.5824178461 3.8241006191 0.5478147542 0.6841750875 -0.4036136415 0.262487091328 +1403638171545096960.0000000000 7.0856287756 11.5502958758 3.8207446711 0.5490748130 0.6812345808 -0.4067637820 0.262639527413 +1403638171595097088.0000000000 7.1300914957 11.5152078602 3.8166700574 0.5492560688 0.6787309280 -0.4091895953 0.264964098141 +1403638171645096960.0000000000 7.1736310601 11.4774316844 3.8123323235 0.5500936346 0.6754515560 -0.4129390230 0.265788547415 +1403638171695097088.0000000000 7.2163941083 11.4365961527 3.8075507456 0.5505756492 0.6718948385 -0.4174782080 0.266712816256 +1403638171745096960.0000000000 7.2585616433 11.3927845949 3.8021641041 0.5504641533 0.6683193240 -0.4220154800 0.268777662304 +1403638171795097088.0000000000 7.2995975885 11.3456923281 3.7969965499 0.5498485575 0.6654345148 -0.4263893304 0.270288011762 +1403638171845096960.0000000000 7.3396201967 11.2953517243 3.7935171172 0.5510999837 0.6612674581 -0.4303409775 0.271699834341 +1403638171895097088.0000000000 7.3787758203 11.2413747077 3.7912203910 0.5523663344 0.6571842120 -0.4340955496 0.273059330621 +1403638171945096960.0000000000 7.4169851883 11.1833827720 3.7905856891 0.5534690102 0.6536205504 -0.4351405761 0.277677708443 +1403638171995097088.0000000000 7.4540251082 11.1216222668 3.7910202405 0.5519446344 0.6524728761 -0.4359505204 0.282105317772 +1403638172045096960.0000000000 7.4897031174 11.0563990653 3.7931071824 0.5510688058 0.6510233862 -0.4368860487 0.285696171453 +1403638172095097088.0000000000 7.5235056582 10.9875846737 3.7959249445 0.5490228270 0.6509520968 -0.4371790789 0.289326383306 +1403638172145096960.0000000000 7.5557774060 10.9159295929 3.7986664716 0.5479371420 0.6505842367 -0.4376743824 0.291455269929 +1403638172195097088.0000000000 7.5864284413 10.8415986977 3.7995670169 0.5463895237 0.6508344608 -0.4387361420 0.292204706919 +1403638172245096960.0000000000 7.6154779449 10.7648204449 3.7978539378 0.5450088773 0.6512081076 -0.4387901658 0.293864789752 +1403638172295097088.0000000000 7.6448276521 10.6867945733 3.7989727252 0.5438039262 0.6517743481 -0.4386803649 0.295003434643 +1403638172345096960.0000000000 7.6712473765 10.6058445981 3.7939966118 0.5434723002 0.6517654695 -0.4383876396 0.29606740632 +1403638172395097088.0000000000 7.6963750736 10.5230034593 3.7866103309 0.5436499143 0.6517469328 -0.4381868982 0.296079294318 +1403638172445096960.0000000000 7.7210088250 10.4384839734 3.7768651537 0.5448125252 0.6510556365 -0.4375904679 0.296345158457 +1403638172495097088.0000000000 7.7444013650 10.3521657272 3.7646059038 0.5468462547 0.6498118089 -0.4373854850 0.295631061049 +1403638172545096960.0000000000 7.7668977321 10.2640150362 3.7502648096 0.5487241155 0.6487839067 -0.4370357045 0.294925550788 +1403638172595097088.0000000000 7.7881267048 10.1733005735 3.7338612882 0.5503615634 0.6481777676 -0.4361191240 0.294563814434 +1403638172645096960.0000000000 7.8072371189 10.0797623151 3.7154755929 0.5524840129 0.6473326015 -0.4363179108 0.292144825699 +1403638172695097088.0000000000 7.8248871077 9.9833801250 3.6951538767 0.5529171634 0.6478591339 -0.4358823177 0.290805361359 +1403638172745096960.0000000000 7.8411037210 9.8842216747 3.6738320937 0.5533930049 0.6483747242 -0.4354416455 0.289407968947 +1403638172795097088.0000000000 7.8560837921 9.7821429672 3.6513973438 0.5539318846 0.6488323653 -0.4346499728 0.288540170711 +1403638172845096960.0000000000 7.8696675219 9.6774364305 3.6283010790 0.5558726688 0.6483250290 -0.4350069434 0.285393048584 +1403638172895097088.0000000000 7.8820490705 9.5695485407 3.6037821845 0.5558461710 0.6492838805 -0.4339091887 0.284935593833 +1403638172945096960.0000000000 7.8927906288 9.4590386956 3.5784591140 0.5559595804 0.6505007566 -0.4348496861 0.280470071557 +1403638172995097088.0000000000 7.9025196751 9.3455512222 3.5521697472 0.5559440079 0.6516081733 -0.4356481880 0.276665329948 +1403638173045096960.0000000000 7.9112525354 9.2291754960 3.5239581740 0.5541447821 0.6542585389 -0.4360936126 0.273297796871 +1403638173095097088.0000000000 7.9193050347 9.1103319160 3.4942922713 0.5531163196 0.6562975466 -0.4377240213 0.267831194057 +1403638173145096960.0000000000 7.9276202011 8.9887301510 3.4626525233 0.5504897204 0.6592431026 -0.4378061225 0.265867257455 +1403638173195097088.0000000000 7.9358751729 8.8644388472 3.4289771268 0.5481315791 0.6618864508 -0.4374739501 0.264716152011 +1403638173245096960.0000000000 7.9440679127 8.7372474622 3.3936705765 0.5453126318 0.6649294430 -0.4351846620 0.26667823208 +1403638173295097088.0000000000 7.9524244080 8.6078627554 3.3572881452 0.5425348149 0.6675903316 -0.4332197316 0.268886198827 +1403638173345096960.0000000000 7.9608022954 8.4765891747 3.3188814349 0.5383504206 0.6713875239 -0.4310698463 0.271286573402 +1403638173395097088.0000000000 7.9697865101 8.3436613098 3.2791484976 0.5349647575 0.6740677051 -0.4263987114 0.278620846636 +1403638173445096960.0000000000 7.9783710749 8.2094931749 3.2359586623 0.5302886939 0.6776669671 -0.4222673774 0.285046741419 +1403638173495097088.0000000000 7.9869095182 8.0749739890 3.1897346630 0.5253289325 0.6814313927 -0.4194342597 0.289405721403 +1403638173545096960.0000000000 7.9958428509 7.9405724325 3.1428876101 0.5226916278 0.6831909668 -0.4166504812 0.294016906894 +1403638173595097088.0000000000 8.0049678319 7.8064608737 3.0955749778 0.5202180919 0.6847876715 -0.4145928152 0.29757651024 +1403638173645096960.0000000000 8.0135522858 7.6729676637 3.0482182699 0.5198894997 0.6848719862 -0.4148247022 0.297633561941 +1403638173695097088.0000000000 8.0209017239 7.5393183593 2.9993074038 0.5190533640 0.6851615297 -0.4143553521 0.299076789054 +1403638173745096960.0000000000 8.0274712426 7.4057721852 2.9495772887 0.5188360390 0.6852455753 -0.4150719756 0.29826652736 +1403638173795097088.0000000000 8.0340593124 7.2725764417 2.8998146028 0.5182477879 0.6852666863 -0.4159284836 0.298047471841 +1403638173845096960.0000000000 8.0394575009 7.1396164404 2.8506731004 0.5174810565 0.6854498692 -0.4171102503 0.297306024334 +1403638173895097088.0000000000 8.0438628637 7.0067239169 2.8032281787 0.5158665375 0.6864887942 -0.4166502339 0.298357895043 +1403638173945096960.0000000000 7.9504041005 6.7864928155 2.7562821639 0.5171691397 0.6852797768 -0.4168257363 0.298636926886 +1403638173995097088.0000000000 7.9480387683 6.6503889349 2.7124274319 0.5170432981 0.6852418750 -0.4173614590 0.298193247892 +1403638174045096960.0000000000 7.9437373150 6.5139344674 2.6695461635 0.5151043312 0.6865087999 -0.4178708681 0.297921354126 +1403638174095097088.0000000000 7.9382446351 6.3776141093 2.6290842465 0.5164431972 0.6855089637 -0.4183426927 0.297242790129 +1403638174145096960.0000000000 7.9319838052 6.2408428314 2.5885156879 0.5143544911 0.6869332976 -0.4175466260 0.298692010887 +1403638174195097088.0000000000 7.9254414878 6.1055623506 2.5482152680 0.5119137177 0.6886868795 -0.4189624914 0.296858819017 +1403638174245096960.0000000000 7.9179451572 5.9698350142 2.5066508053 0.5086032900 0.6912810946 -0.4187872434 0.296766552161 +1403638174295097088.0000000000 7.9095518292 5.8347699040 2.4632154746 0.5050942417 0.6940835979 -0.4210366813 0.293011738828 +1403638174345096960.0000000000 7.9020625260 5.7006344414 2.4187699199 0.5025450880 0.6960639603 -0.4206135738 0.293304652674 +1403638174395097088.0000000000 7.8948063352 5.5674500200 2.3731588767 0.5008054879 0.6974521813 -0.4222357471 0.290639453398 +1403638174445096960.0000000000 7.8874633799 5.4347962483 2.3265845406 0.4980578316 0.6997127337 -0.4216344733 0.290800374244 +1403638174495097088.0000000000 7.8803617887 5.3035099328 2.2817374458 0.4973444670 0.7005710595 -0.4227446955 0.288332436964 +1403638174545096960.0000000000 7.8740943770 5.1732448357 2.2375534191 0.4955578728 0.7019954289 -0.4235846904 0.286706858374 +1403638174595097088.0000000000 7.8690164303 5.0437826881 2.1944419832 0.4920258072 0.7047954454 -0.4219799582 0.288282673851 +1403638174645096960.0000000000 7.8641154465 4.9152170348 2.1530619033 0.4886350832 0.7071693392 -0.4225262531 0.287434943312 +1403638174695097088.0000000000 7.8596786467 4.7873258563 2.1126421051 0.4853971053 0.7096166239 -0.4218876585 0.287827553853 +1403638174745096960.0000000000 7.8560210503 4.6608552182 2.0741942492 0.4820170898 0.7119535286 -0.4224426355 0.286921449218 +1403638174795097088.0000000000 7.8526727023 4.5356226554 2.0382550164 0.4796153818 0.7136949100 -0.4227805865 0.286121017605 +1403638174845096960.0000000000 7.8501187781 4.4121020839 2.0038517011 0.4774794180 0.7152275895 -0.4227851057 0.28585950226 +1403638174895097088.0000000000 7.8485892225 4.2904766817 1.9707104419 0.4761842640 0.7161238768 -0.4219625260 0.286989139919 +1403638174945096960.0000000000 7.8473590509 4.1708607559 1.9389868322 0.4749246827 0.7167596857 -0.4226172206 0.286525362779 +1403638174995097088.0000000000 7.8465649161 4.0526874196 1.9089600470 0.4740809036 0.7171116405 -0.4229489177 0.286552621508 +1403638175045096960.0000000000 7.8474487284 3.9367973492 1.8807273015 0.4751493018 0.7162842246 -0.4217782354 0.28857091124 +1403638175095097088.0000000000 7.8492484926 3.8229486261 1.8536220533 0.4752278513 0.7158019465 -0.4227619452 0.288198543287 +1403638175145096960.0000000000 7.8522528965 3.7107169302 1.8283374101 0.4746212404 0.7156055121 -0.4221068834 0.290635868873 +1403638175195097088.0000000000 7.8561150305 3.6006107336 1.8045927851 0.4740240034 0.7156316166 -0.4224290457 0.29107788452 +1403638175245096960.0000000000 7.8611204017 3.4923243182 1.7821190221 0.4727430096 0.7160556436 -0.4221957353 0.29245362571 +1403638175295097088.0000000000 7.8669943594 3.3860706488 1.7615693534 0.4699716808 0.7174151120 -0.4233757912 0.291882023696 +1403638175345096960.0000000000 7.8729773132 3.2814018155 1.7429548081 0.4660997471 0.7195656627 -0.4247322718 0.290824311389 +1403638175395097088.0000000000 7.8799115932 3.1785838407 1.7257361604 0.4611977129 0.7224559611 -0.4251341191 0.290886635267 +1403638175445096960.0000000000 7.8882319828 3.0781954168 1.7100519818 0.4563475273 0.7253814376 -0.4253040482 0.291007166307 +1403638175495097088.0000000000 7.8989012003 2.9810995193 1.6966606026 0.4507061828 0.7288192079 -0.4256941746 0.290638897509 +1403638175545096960.0000000000 7.9113984570 2.8870616578 1.6861177378 0.4442253029 0.7329562123 -0.4256863518 0.290224397661 +1403638175595097088.0000000000 7.9249035068 2.7961078465 1.6778520762 0.4392569214 0.7360524766 -0.4278980618 0.286676398274 +1403638175645096960.0000000000 7.9405768348 2.7084019732 1.6712481040 0.4337406531 0.7393950361 -0.4297091167 0.283750068599 +1403638175695097088.0000000000 7.9582785326 2.6239578207 1.6661427915 0.4291031456 0.7425339009 -0.4310695579 0.280522606575 +1403638175745096960.0000000000 7.9785870699 2.5429493007 1.6626133729 0.4266838066 0.7441436779 -0.4322997572 0.278043226213 +1403638175795097088.0000000000 8.0017933026 2.4652336246 1.6579068254 0.4233062579 0.7463658370 -0.4326198374 0.276748849426 +1403638175845096960.0000000000 8.0277041315 2.3905671267 1.6503395587 0.4209798505 0.7480294311 -0.4323211586 0.276272241679 +1403638175895097088.0000000000 8.0565492087 2.3188761620 1.6393699659 0.4196814844 0.7491363809 -0.4308279824 0.277577708234 +1403638175945096960.0000000000 8.0884865992 2.2507959496 1.6263548680 0.4190056458 0.7500035761 -0.4284627782 0.279908114115 +1403638175995097088.0000000000 8.1233462140 2.1862590704 1.6119462725 0.4193052278 0.7504456831 -0.4238118227 0.285303245052 +1403638176045096960.0000000000 8.1610615384 2.1261226575 1.5976029624 0.4242381311 0.7479372575 -0.4201801162 0.289931952217 +1403638176095097088.0000000000 8.2014369533 2.0698452744 1.5829751565 0.4300490767 0.7449023698 -0.4140185075 0.29793778963 +1403638176145096960.0000000000 8.2437982517 2.0180989483 1.5700242533 0.4398837033 0.7391404369 -0.4090226314 0.304752734403 +1403638176195097088.0000000000 8.2872281141 1.9702788164 1.5590938484 0.4524928629 0.7312081311 -0.4062971448 0.309042890564 +1403638176245096960.0000000000 8.3306357441 1.9255789012 1.5495806730 0.4634631314 0.7240660326 -0.4058440741 0.310194928667 +1403638176295097088.0000000000 8.3741135950 1.8828603242 1.5410729388 0.4711100591 0.7188347740 -0.4034364307 0.313960071155 +1403638176345096960.0000000000 8.4163075447 1.8419790232 1.5332088737 0.4756957949 0.7156721418 -0.4026529395 0.315273700838 +1403638176395097088.0000000000 8.4579867764 1.8028394458 1.5262643443 0.4784068552 0.7134713408 -0.4019687314 0.317027862597 +1403638176445096960.0000000000 8.4988888379 1.7656261951 1.5201618874 0.4778830770 0.7136292136 -0.4015027833 0.318051293357 +1403638176495097088.0000000000 8.5389595527 1.7303167910 1.5160567096 0.4779765324 0.7133407727 -0.4012499491 0.318875923873 +1403638176545096960.0000000000 8.5778026290 1.6968178575 1.5129601933 0.4770316825 0.7136646741 -0.4016289523 0.319088845835 +1403638176595097088.0000000000 8.6154689723 1.6651901924 1.5105694015 0.4757367279 0.7144444788 -0.4021179444 0.318660965941 +1403638176645096960.0000000000 8.6526340248 1.6357000671 1.5098031255 0.4744967386 0.7150023532 -0.4021736252 0.319187805419 +1403638176695097088.0000000000 8.6893103332 1.6084271255 1.5116007193 0.4741426516 0.7151088446 -0.4023761402 0.319220187579 +1403638176745096960.0000000000 8.7252583112 1.5833158941 1.5154380133 0.4739867300 0.7152054807 -0.4024832227 0.319100228182 +1403638176795097088.0000000000 8.7599667821 1.5601910638 1.5212380804 0.4742010149 0.7150734243 -0.4035044361 0.317785407766 +1403638176845096960.0000000000 8.7924149629 1.5386171183 1.5288035035 0.4756638913 0.7141429383 -0.4051504638 0.315589650978 +1403638176895097088.0000000000 8.8234819803 1.5184998211 1.5368697271 0.4758109295 0.7140319547 -0.4069751923 0.313262701125 +1403638176945096960.0000000000 8.8542102758 1.4997916926 1.5443964531 0.4758568199 0.7139394800 -0.4071452921 0.313182721392 +1403638176995097088.0000000000 8.8815784714 1.4816203628 1.5511490917 0.4748413144 0.7145969339 -0.4066978896 0.313805313381 +1403638177045096960.0000000000 8.9095625609 1.4650534267 1.5561896363 0.4733519378 0.7155664736 -0.4064683264 0.314143382018 +1403638177095097088.0000000000 8.9367885130 1.4498650043 1.5597684448 0.4721082817 0.7162659652 -0.4055667702 0.315582686939 +1403638177145096960.0000000000 8.9638101243 1.4363521315 1.5614624009 0.4711478788 0.7166393790 -0.4049166096 0.31700191808 +1403638177195097088.0000000000 8.9904173385 1.4244949448 1.5609807062 0.4700624259 0.7173015052 -0.4040027616 0.318279177875 +1403638177245096960.0000000000 9.0164409490 1.4142668566 1.5589208366 0.4696549078 0.7174367691 -0.4035081989 0.319201947645 +1403638177295097088.0000000000 9.0421691727 1.4059001931 1.5553406482 0.4693365496 0.7175930917 -0.4032968446 0.319585689803 +1403638177345096960.0000000000 9.0673883737 1.3993966845 1.5505067658 0.4693457528 0.7175101500 -0.4029977146 0.320135269853 +1403638177395097088.0000000000 9.0918759771 1.3945990070 1.5443618014 0.4692202507 0.7174660959 -0.4032069322 0.320154536794 +1403638177445096960.0000000000 9.1160917054 1.3916832795 1.5366888501 0.4686128621 0.7175667570 -0.4043194715 0.319414620418 +1403638177495097088.0000000000 9.1392025512 1.3909819953 1.5287241047 0.4705473105 0.7160978948 -0.4069037498 0.316572854285 +1403638177545096960.0000000000 9.1616588381 1.3920346765 1.5200479903 0.4735531055 0.7138990861 -0.4107113355 0.312108555011 +1403638177595097088.0000000000 9.1834783151 1.3944912575 1.5103914868 0.4774214400 0.7112179367 -0.4159821224 0.305281327741 +1403638177645096960.0000000000 9.2053867995 1.3974031848 1.4993519623 0.4797482447 0.7093401384 -0.4189165224 0.30197207989 +1403638177695097088.0000000000 9.2273762133 1.4010062557 1.4871348109 0.4822529324 0.7070266495 -0.4232047538 0.297393951481 +1403638177745096960.0000000000 9.2498601884 1.4048135194 1.4739775401 0.4852113981 0.7039234890 -0.4271213014 0.294328073291 +1403638177795097088.0000000000 9.2728934515 1.4087760794 1.4602272940 0.4896123000 0.6996644362 -0.4303172880 0.292534620291 +1403638177845096960.0000000000 9.2964686294 1.4126141178 1.4460483246 0.4950790138 0.6948200056 -0.4321510843 0.292176950253 +1403638177895097088.0000000000 9.3203393323 1.4157350873 1.4320355498 0.5001100714 0.6902733330 -0.4330645076 0.29303203658 +1403638177945096960.0000000000 9.3438653641 1.4175974059 1.4188491311 0.5037871427 0.6867215255 -0.4334622446 0.294486916231 +1403638177995097088.0000000000 9.3673428980 1.4182382588 1.4073045188 0.5064959156 0.6839375350 -0.4333058870 0.296542313899 +1403638178045096960.0000000000 9.3908439088 1.4170984636 1.3972872590 0.5074100966 0.6819117594 -0.4324874287 0.300808859915 +1403638178095097088.0000000000 9.4144599536 1.4144801171 1.3888460099 0.5063570355 0.6801839135 -0.4329988789 0.305719425729 +1403638178145096960.0000000000 9.4383047879 1.4109584953 1.3831195614 0.5048208596 0.6778592266 -0.4351911775 0.310276340678 +1403638178195097088.0000000000 9.4610811577 1.4056681836 1.3786773280 0.5038566381 0.6741709780 -0.4390309105 0.314442109512 +1403638178245096960.0000000000 9.4833987467 1.3991027235 1.3768860941 0.5032308451 0.6692047251 -0.4441175456 0.318878281062 +1403638178295097088.0000000000 9.5051895287 1.3911089495 1.3778830666 0.5010830216 0.6644248522 -0.4502452709 0.323627281412 +1403638178345096960.0000000000 9.5261885694 1.3818278469 1.3815382066 0.4993068605 0.6586678794 -0.4572027043 0.32835190098 +1403638178395097088.0000000000 9.5455871848 1.3708105143 1.3856535211 0.4958605125 0.6531689318 -0.4646778976 0.334016691435 +1403638178445096960.0000000000 9.5635105933 1.3585365091 1.3892204790 0.4918251256 0.6473067387 -0.4744209828 0.337678490479 +1403638178495097088.0000000000 9.5804296240 1.3448669524 1.3911976998 0.4857619252 0.6423360506 -0.4843800214 0.34178318425 +1403638178545096960.0000000000 9.5962732651 1.3297220039 1.3920841670 0.4790020467 0.6374190476 -0.4953757520 0.344756234796 +1403638178595097088.0000000000 9.6111219321 1.3133433696 1.3915946669 0.4720211081 0.6325221555 -0.5065699091 0.347129260678 +1403638178645096960.0000000000 9.6256966235 1.2958410760 1.3904535089 0.4664426708 0.6266870707 -0.5170305054 0.349819963299 +1403638178695097088.0000000000 9.6400192615 1.2770147477 1.3885467443 0.4609819631 0.6205870379 -0.5266211647 0.353606429617 +1403638178745096960.0000000000 9.6542075086 1.2568249656 1.3859990349 0.4565961826 0.6137862700 -0.5353445402 0.358039891882 +1403638178795097088.0000000000 9.6679937746 1.2353394131 1.3822118977 0.4510984891 0.6078905018 -0.5433361511 0.362994652736 +1403638178845096960.0000000000 9.6815572823 1.2125424744 1.3771798832 0.4443701631 0.6034497991 -0.5511099961 0.36696221914 +1403638178895097088.0000000000 9.6947618832 1.1888886708 1.3713191260 0.4381528745 0.6000136681 -0.5578526635 0.369873035704 +1403638178945096960.0000000000 9.7076332652 1.1642927957 1.3644036403 0.4320025632 0.5975712395 -0.5638411933 0.37197514401 +1403638178995097088.0000000000 9.7202824922 1.1390481738 1.3563204525 0.4256768999 0.5964417797 -0.5693217812 0.372731927553 +1403638179045096960.0000000000 9.7332206030 1.1128272819 1.3470833088 0.4191975000 0.5962726559 -0.5734204730 0.374060605946 +1403638179095097088.0000000000 9.7468785811 1.0858454773 1.3369614514 0.4136283149 0.5963210616 -0.5763061659 0.3757446097 +1403638179145096960.0000000000 9.7611854158 1.0579808398 1.3256437632 0.4080794497 0.5960066347 -0.5792871187 0.377721707246 +1403638179195097088.0000000000 9.7764288587 1.0293618543 1.3134662473 0.4025572877 0.5954665365 -0.5817964824 0.380631169355 +1403638179245096960.0000000000 9.7927781765 1.0003368598 1.3003520209 0.3966786148 0.5951094737 -0.5842139263 0.383646815704 +1403638179295097088.0000000000 9.8104573871 0.9711536390 1.2862338098 0.3909390549 0.5939634222 -0.5877184518 0.385954828887 +1403638179345096960.0000000000 9.8296407768 0.9415859793 1.2717721094 0.3857498067 0.5915741763 -0.5911148659 0.389641240062 +1403638179395097088.0000000000 9.8505457574 0.9120268194 1.2576138806 0.3831983746 0.5863023851 -0.5948609634 0.394396948606 +1403638179445096960.0000000000 9.8729685643 0.8825795953 1.2436305952 0.3838659955 0.5778838867 -0.5990279845 0.399828194215 +1403638179495097088.0000000000 9.8964920205 0.8529075666 1.2290927992 0.3851650817 0.5681867565 -0.6030669964 0.406351901061 +1403638179545096960.0000000000 9.9208935745 0.8226938471 1.2136911685 0.3849599048 0.5584810022 -0.6079268434 0.41271030386 +1403638179595097088.0000000000 9.9456765558 0.7919764602 1.1975804273 0.3829647953 0.5494402189 -0.6131211646 0.418969985704 +1403638179645096960.0000000000 9.9701930526 0.7608387501 1.1817819702 0.3802211963 0.5405887154 -0.6193348224 0.423816069149 +1403638179695097088.0000000000 9.9945177334 0.7291421661 1.1674065507 0.3767334511 0.5317922394 -0.6246993528 0.430139093174 +1403638179745096960.0000000000 10.0184571737 0.6971038154 1.1546466488 0.3718541905 0.5233860608 -0.6310079885 0.435454257959 +1403638179795097088.0000000000 10.0419920925 0.6647511334 1.1437765055 0.3667899629 0.5152676004 -0.6371739404 0.440424559765 +1403638179845096960.0000000000 10.0650864769 0.6319377653 1.1350887735 0.3617059405 0.5068392375 -0.6427681528 0.446241976619 +1403638179895097088.0000000000 10.0882535070 0.5988813613 1.1274762387 0.3556344665 0.4995045142 -0.6495611304 0.44954388488 +1403638179945096960.0000000000 10.1111613127 0.5657081232 1.1207625570 0.3492296784 0.4938539852 -0.6561364885 0.451255782766 +1403638179995097088.0000000000 10.1339052648 0.5324805803 1.1151812599 0.3424842617 0.4896190919 -0.6627303392 0.451404666334 +1403638180045096960.0000000000 10.1568360602 0.4993027314 1.1107461312 0.3369732987 0.4859875797 -0.6689189589 0.450347082479 +1403638180095097088.0000000000 10.1803328320 0.4657297975 1.1075947161 0.3337295589 0.4816056970 -0.6735209580 0.450610755737 +1403638180145096960.0000000000 10.2040893800 0.4318939043 1.1051429483 0.3311204681 0.4780672392 -0.6770567084 0.451004616465 +1403638180195097088.0000000000 10.2281740940 0.3975186540 1.1030728410 0.3285417966 0.4757678669 -0.6785549977 0.453065491774 +1403638180245096960.0000000000 10.2522005358 0.3627181021 1.1001202340 0.3266266447 0.4738534955 -0.6802052910 0.453980904727 +1403638180295097088.0000000000 10.2763458631 0.3274523390 1.0958480059 0.3248494366 0.4727305698 -0.6820858593 0.453605040232 +1403638180345096960.0000000000 10.3011029460 0.2918168506 1.0904766509 0.3242982173 0.4715656155 -0.6835406497 0.453021761897 +1403638180395097088.0000000000 10.3261000133 0.2554108763 1.0833905505 0.3223873180 0.4717684576 -0.6837397521 0.453873210347 +1403638180445096960.0000000000 10.3514589327 0.2185876119 1.0746460807 0.3201222157 0.4729555463 -0.6838019278 0.454147268749 +1403638180495097088.0000000000 10.3774999170 0.1812470955 1.0651699320 0.3190580923 0.4735126253 -0.6826691107 0.456016022396 +1403638180545096960.0000000000 10.4039417012 0.1434453422 1.0547220525 0.3176778089 0.4748808926 -0.6813735905 0.457492052178 +1403638180595097088.0000000000 10.4307995744 0.1054743418 1.0439525373 0.3166226727 0.4760658122 -0.6807788644 0.457877236017 +1403638180645096960.0000000000 10.4581116434 0.0673169732 1.0337861513 0.3143039635 0.4784801344 -0.6802616557 0.457726839183 +1403638180695097088.0000000000 10.4863655446 0.0293251859 1.0254645961 0.3131129386 0.4803518714 -0.6803533839 0.456444564338 +1403638180745096960.0000000000 10.5152517095 -0.0087633649 1.0186621164 0.3106473312 0.4833800683 -0.6810889434 0.45382793694 +1403638180795097088.0000000000 10.5457839909 -0.0469060392 1.0141386483 0.3106947722 0.4847661383 -0.6816724138 0.451434679541 +1403638180845096960.0000000000 10.5777774492 -0.0852093848 1.0118478223 0.3108597660 0.4862482172 -0.6816691496 0.44972886016 +1403638180895097088.0000000000 10.6114217009 -0.1236135037 1.0112975044 0.3124670594 0.4868787674 -0.6813260513 0.44845090531 +1403638180945096960.0000000000 10.6462974596 -0.1623045738 1.0107328840 0.3141055325 0.4873533841 -0.6807451155 0.447672292155 +1403638180995097088.0000000000 10.6823056334 -0.2012771283 1.0094297488 0.3167277017 0.4869262815 -0.6801666912 0.447168459904 +1403638181045096960.0000000000 10.7195013414 -0.2404993816 1.0067934200 0.3195672649 0.4866118737 -0.6791902968 0.446974482788 +1403638181095097088.0000000000 10.7577964700 -0.2800210290 1.0026412219 0.3213301561 0.4868089182 -0.6786634094 0.446295848837 +1403638181145096960.0000000000 10.7972699299 -0.3199576273 0.9972665084 0.3241519623 0.4857638772 -0.6788157211 0.445160844828 +1403638181195097088.0000000000 10.8378731970 -0.3605740991 0.9909798819 0.3273879789 0.4846815049 -0.6773162165 0.446255188198 +1403638181245096960.0000000000 10.8794923128 -0.4018474515 0.9838968876 0.3316871587 0.4818324436 -0.6762845568 0.447727956709 +1403638181295097088.0000000000 10.9216670427 -0.4440828831 0.9760873364 0.3366232793 0.4765222081 -0.6760846010 0.450023294164 +1403638181345096960.0000000000 10.9644682461 -0.4875876308 0.9668770045 0.3391230499 0.4708299667 -0.6768275829 0.45301117268 +1403638181395097088.0000000000 11.0071376077 -0.5322234629 0.9564428276 0.3412887882 0.4635014850 -0.6790816527 0.455561681258 +1403638181445096960.0000000000 11.0491859203 -0.5780261758 0.9447155188 0.3425165334 0.4549288523 -0.6829948724 0.457427773453 +1403638181495097088.0000000000 11.0908930952 -0.6255211377 0.9322610293 0.3431221659 0.4448696736 -0.6862785353 0.461930649265 +1403638181545096960.0000000000 11.1320182838 -0.6745009097 0.9198972718 0.3455267268 0.4321102443 -0.6885461968 0.46882422361 +1403638181595097088.0000000000 11.1710542326 -0.7250587904 0.9070570998 0.3443271105 0.4208949443 -0.6900440735 0.477624814566 +1403638181645096960.0000000000 11.2077600402 -0.7770092213 0.8944601691 0.3393559932 0.4120217700 -0.6931246921 0.484410706097 +1403638181695097088.0000000000 11.2419118357 -0.8300191975 0.8825060467 0.3304264372 0.4058070403 -0.6969926971 0.490245036491 +1403638181745096960.0000000000 11.2739707388 -0.8838142058 0.8728362124 0.3212738837 0.3997817681 -0.7019136105 0.494241755553 +1403638181795097088.0000000000 11.3039740843 -0.9383810728 0.8656356447 0.3108066200 0.3940986386 -0.7064232174 0.499050844956 +1403638181845096960.0000000000 11.3320053283 -0.9933655506 0.8605364110 0.2994982776 0.3892777081 -0.7115286944 0.50248439248 +1403638181895097088.0000000000 11.3581354448 -1.0483811467 0.8579256160 0.2875480754 0.3850915631 -0.7163959912 0.505764150743 +1403638181945096960.0000000000 11.3830582756 -1.1030180883 0.8570062962 0.2786936566 0.3796245703 -0.7219829551 0.506907924565 +1403638181995097088.0000000000 11.4069343300 -1.1571429968 0.8579489980 0.2712224732 0.3752080304 -0.7270566181 0.506997019664 +1403638182045096960.0000000000 11.4300765853 -1.2109606950 0.8605170169 0.2649038340 0.3714627932 -0.7327436762 0.504904007652 +1403638182095097088.0000000000 11.4528326279 -1.2648620595 0.8652677350 0.2598534520 0.3678246146 -0.7371428761 0.503787273208 +1403638182145096960.0000000000 11.4753798146 -1.3188836566 0.8713047193 0.2552886808 0.3648980874 -0.7411217485 0.502409821931 +1403638182195097088.0000000000 11.4980353728 -1.3732019362 0.8772291375 0.2520492583 0.3620739380 -0.7443578859 0.501303273983 +1403638182245096960.0000000000 11.5209218671 -1.4275173769 0.8821844537 0.2512741564 0.3584886557 -0.7484394209 0.498182311316 +1403638182295097088.0000000000 11.5439496372 -1.4822410763 0.8859732006 0.2511933191 0.3556158418 -0.7517628152 0.49526958234 +1403638182345096960.0000000000 11.5655093236 -1.5383838440 0.8927419885 0.2519398637 0.3530230892 -0.7540469219 0.493268936013 +1403638182395097088.0000000000 11.5885669410 -1.5949929828 0.8959444995 0.2520274080 0.3518677481 -0.7565497769 0.490207821709 +1403638182445096960.0000000000 11.6117006810 -1.6534304638 0.9001377731 0.2484526839 0.3536810492 -0.7566751788 0.490534048943 +1403638182495097088.0000000000 11.6350233661 -1.7129410978 0.9058402466 0.2444097032 0.3567350265 -0.7566613160 0.490375030691 +1403638182545096960.0000000000 11.6590664815 -1.7737709283 0.9136664674 0.2391033433 0.3609422552 -0.7555036028 0.491695623113 +1403638182595097088.0000000000 11.6840255742 -1.8355626966 0.9236378283 0.2344844482 0.3650474623 -0.7541379014 0.492984198019 +1403638182645096960.0000000000 11.7102219657 -1.8978611698 0.9360973076 0.2324487611 0.3677042051 -0.7534794218 0.492980681076 +1403638182695097088.0000000000 11.7371463882 -1.9604827852 0.9504652889 0.2316272815 0.3699178986 -0.7526398662 0.492993694285 +1403638182745096960.0000000000 11.7652885183 -2.0234022942 0.9656567882 0.2329692032 0.3705632986 -0.7521721905 0.492590283945 +1403638182795097088.0000000000 11.7944526639 -2.0868956107 0.9805488097 0.2340197598 0.3712433223 -0.7512599823 0.492972196682 +1403638182845096960.0000000000 11.8249529640 -2.1506913098 0.9944691712 0.2355388512 0.3716488770 -0.7501957662 0.493563444936 +1403638182895097088.0000000000 11.8565359596 -2.2148091563 1.0071041825 0.2379143022 0.3714038765 -0.7485890048 0.495045904137 +1403638182945096960.0000000000 11.8889544615 -2.2793113419 1.0182641973 0.2406140384 0.3708288077 -0.7468402418 0.496810359256 +1403638182995097088.0000000000 11.9216927440 -2.3442163697 1.0284469896 0.2434956699 0.3700617791 -0.7439094276 0.500362770386 +1403638183045096960.0000000000 11.9547541822 -2.4093296526 1.0373532385 0.2462430586 0.3694173869 -0.7411952018 0.503512485657 +1403638183095097088.0000000000 11.9879032815 -2.4746477111 1.0448411337 0.2471905977 0.3699862890 -0.7380907599 0.507177468434 +1403638183145096960.0000000000 12.0213133561 -2.5399843941 1.0507581685 0.2463037440 0.3714058981 -0.7351621000 0.51081191373 +1403638183195097088.0000000000 12.0549129505 -2.6049273453 1.0554377926 0.2463987364 0.3721764459 -0.7336277709 0.512408674373 +1403638183245096960.0000000000 12.0884687353 -2.6693362701 1.0583359166 0.2434230145 0.3751507629 -0.7334325661 0.511941219392 +1403638183295097088.0000000000 12.1219767095 -2.7329948245 1.0599238180 0.2412197153 0.3770516085 -0.7345046458 0.510047114251 +1403638183345096960.0000000000 12.1557456071 -2.7957564894 1.0603664460 0.2395743750 0.3785716934 -0.7370419522 0.506020505956 +1403638183395097088.0000000000 12.1901185434 -2.8581093541 1.0598694470 0.2377819458 0.3800737626 -0.7395089899 0.502125616805 +1403638183445096960.0000000000 12.2253292713 -2.9204429050 1.0583081322 0.2348691062 0.3822394463 -0.7415646751 0.498809925065 +1403638183495097088.0000000000 12.2616857529 -2.9827395239 1.0560685633 0.2321923180 0.3840228958 -0.7428515529 0.496774308198 +1403638183545096960.0000000000 12.2992566808 -3.0448502134 1.0525803059 0.2295928912 0.3861235533 -0.7435548253 0.495299836103 +1403638183595097088.0000000000 12.3383602744 -3.1068070354 1.0487121370 0.2293830239 0.3861390780 -0.7442720568 0.494306732938 +1403638183645096960.0000000000 12.3792088291 -3.1686778424 1.0454527481 0.2310276466 0.3850593881 -0.7432015578 0.495990865497 +1403638183695097088.0000000000 12.4218635114 -3.2310257080 1.0437319978 0.2312445060 0.3850884113 -0.7395803014 0.501252303488 +1403638183745096960.0000000000 12.4676007308 -3.2932917149 1.0441089635 0.2351480943 0.3824166955 -0.7364455149 0.506073955473 +1403638183795097088.0000000000 12.5128765755 -3.3548094588 1.0453303266 0.2355223574 0.3821117432 -0.7328339975 0.511345447758 +1403638183845096960.0000000000 12.5587494467 -3.4152027787 1.0487338266 0.2372652054 0.3810416377 -0.7287119208 0.517195735863 +1403638183895097088.0000000000 12.6051215124 -3.4744580886 1.0539639678 0.2389017711 0.3795124963 -0.7265138371 0.520647532807 +1403638183945096960.0000000000 12.6507022556 -3.5319794178 1.0605465472 0.2395707917 0.3789131976 -0.7256681292 0.52195439521 +1403638183995097088.0000000000 12.6965532347 -3.5883595914 1.0691318509 0.2391840089 0.3787637334 -0.7260819823 0.521664642365 +1403638184045096960.0000000000 12.7423993142 -3.6430666936 1.0789529795 0.2393781679 0.3784326847 -0.7274314256 0.519932992742 +1403638184095097088.0000000000 12.7885263925 -3.6969460528 1.0898979876 0.2376562707 0.3793226419 -0.7299667022 0.516509868188 +1403638184145096960.0000000000 12.8347298765 -3.7498249835 1.1003217406 0.2349002194 0.3809018249 -0.7326716975 0.512764927041 +1403638184195097088.0000000000 12.8827484774 -3.8019103782 1.1117233382 0.2338756216 0.3810140886 -0.7361706207 0.508117383184 +1403638184245096960.0000000000 12.9306244884 -3.8534323508 1.1202410388 0.2322959564 0.3816932466 -0.7383344281 0.505184249938 +1403638184295097088.0000000000 12.9793677691 -3.9046970409 1.1277945661 0.2318920633 0.3813790556 -0.7393856144 0.504068447839 +1403638184345096960.0000000000 13.0289980482 -3.9557293506 1.1342369665 0.2314280357 0.3813800815 -0.7386095257 0.505416923158 +1403638184395097088.0000000000 13.0799268477 -4.0063059563 1.1402464375 0.2332942616 0.3798616117 -0.7372279534 0.507714376541 +1403638184445096960.0000000000 13.1315739991 -4.0565719780 1.1450260500 0.2339289742 0.3792315626 -0.7357721867 0.509999947234 +1403638184495097088.0000000000 13.1839599298 -4.1063394353 1.1491613823 0.2340022495 0.3789383606 -0.7340019001 0.512727877898 +1403638184545096960.0000000000 13.2368722022 -4.1551546592 1.1531507464 0.2349032783 0.3779932452 -0.7334106746 0.513858286627 +1403638184595097088.0000000000 13.2905433115 -4.2032738565 1.1572869979 0.2352641796 0.3773604375 -0.7327139285 0.515150623605 +1403638184645096960.0000000000 13.3443913716 -4.2503248701 1.1615933947 0.2365758107 0.3763649687 -0.7321459206 0.516084922373 +1403638184695097088.0000000000 13.3984966417 -4.2966147824 1.1653312376 0.2357007302 0.3767377650 -0.7321991063 0.516137860474 +1403638184745096960.0000000000 13.4532409663 -4.3420439342 1.1697182051 0.2371825542 0.3753997047 -0.7326618353 0.5157772124 +1403638184795097088.0000000000 13.5080357510 -4.3867801005 1.1741608497 0.2375572764 0.3752172023 -0.7323903126 0.516123068218 +1403638184845096960.0000000000 13.5628394408 -4.4307328721 1.1783812443 0.2369133837 0.3750178371 -0.7331117216 0.51553940119 +1403638184895097088.0000000000 13.6178476771 -4.4740592345 1.1828162127 0.2356085230 0.3757557623 -0.7323909211 0.516623431213 +1403638184945096960.0000000000 13.6732147734 -4.5167575747 1.1882826758 0.2362286243 0.3751497931 -0.7311153099 0.518583718734 +1403638184995097088.0000000000 13.7284791816 -4.5583049335 1.1940098605 0.2368099494 0.3745205492 -0.7314581597 0.518289848135 +1403638185045096960.0000000000 13.7838934289 -4.5989964559 1.2002675311 0.2376400875 0.3739544321 -0.7318268573 0.51779795525 +1403638185095097088.0000000000 13.8392956504 -4.6392126409 1.2063801670 0.2358749261 0.3750890401 -0.7318689331 0.517724923072 +1403638185145096960.0000000000 13.8951625684 -4.6784441524 1.2127438745 0.2351847323 0.3758606885 -0.7321073323 0.517141893899 +1403638185195097088.0000000000 13.9516497243 -4.7173591305 1.2194485559 0.2342353267 0.3764338520 -0.7315743705 0.517909555087 +1403638185245096960.0000000000 14.0083013496 -4.7556775698 1.2257289482 0.2312934200 0.3787371951 -0.7307291006 0.518745093871 +1403638185295097088.0000000000 14.0653492168 -4.7928446593 1.2321803072 0.2305756816 0.3795548796 -0.7298288800 0.519733349245 +1403638185345096960.0000000000 14.1232254875 -4.8291768101 1.2384579668 0.2288126663 0.3807354288 -0.7288131712 0.521072603897 +1403638185395097088.0000000000 14.1820217897 -4.8642280302 1.2451425605 0.2290002316 0.3823280215 -0.7263096682 0.523314861055 +1403638185445096960.0000000000 14.2413312952 -4.8976711677 1.2520088900 0.2301084588 0.3848572044 -0.7230274864 0.525515255053 +1403638185495097088.0000000000 14.3015081520 -4.9293540093 1.2591440816 0.2321061638 0.3889071835 -0.7186234791 0.527691412266 +1403638185545096960.0000000000 14.3619222518 -4.9592103965 1.2666053409 0.2347384322 0.3938622638 -0.7144280103 0.528548014502 +1403638185595097088.0000000000 14.4229254627 -4.9871777224 1.2743055484 0.2389727238 0.3987993158 -0.7102434028 0.528588168409 +1403638185645096960.0000000000 14.4844704499 -5.0135118410 1.2817447629 0.2419438089 0.4040956378 -0.7061396801 0.528712266847 +1403638185695097088.0000000000 14.5465837737 -5.0377370868 1.2899819967 0.2478442650 0.4068177914 -0.7032349328 0.527762384197 +1403638185745096960.0000000000 14.6086973805 -5.0601199302 1.2986680793 0.2545182882 0.4085038313 -0.7014561354 0.525646602609 +1403638185795097088.0000000000 14.6705826175 -5.0807058647 1.3073749349 0.2620129639 0.4087742768 -0.7025360137 0.520284486463 +1403638185845096960.0000000000 14.7316767295 -5.0993030646 1.3160834378 0.2719660330 0.4064128525 -0.7065394090 0.511532143377 +1403638185895097088.0000000000 14.7920235153 -5.1173281108 1.3236161769 0.2798798540 0.4048360393 -0.7101135146 0.503501583854 +1403638185945096960.0000000000 14.8513187028 -5.1351437060 1.3297429135 0.2868399168 0.4031239359 -0.7139248644 0.495505037825 +1403638185995097088.0000000000 14.9093386809 -5.1537887392 1.3342887774 0.2904031108 0.4030134470 -0.7151408554 0.491751717498 +1403638186045096960.0000000000 14.9662939973 -5.1732904697 1.3367286066 0.2892660181 0.4055455954 -0.7151064769 0.490388282424 +1403638186095097088.0000000000 15.0224684984 -5.1934534130 1.3377693618 0.2866508640 0.4086713617 -0.7146625740 0.489975923573 +1403638186145096960.0000000000 15.0779226350 -5.2142609498 1.3380237592 0.2837920140 0.4113179636 -0.7132861918 0.491428971663 +1403638186195097088.0000000000 15.1326925175 -5.2352060916 1.3375589862 0.2804562207 0.4142760620 -0.7119694515 0.492766834265 +1403638186245096960.0000000000 15.1873832838 -5.2562010635 1.3383729297 0.2790475258 0.4154275689 -0.7115753570 0.493166224167 +1403638186295097088.0000000000 15.2417980171 -5.2772001042 1.3406252142 0.2771439723 0.4170895339 -0.7105355184 0.494334721036 +1403638186345096960.0000000000 15.2970719212 -5.2986604571 1.3451466657 0.2751965345 0.4183759708 -0.7100078891 0.495093134504 +1403638186395097088.0000000000 15.3528208229 -5.3200128304 1.3512624112 0.2742252578 0.4188255134 -0.7100293429 0.495221192485 +1403638186445096960.0000000000 15.4080100791 -5.3408994978 1.3586553005 0.2740967854 0.4188216173 -0.7096608922 0.495823379159 +1403638186495097088.0000000000 15.4636797379 -5.3618918415 1.3675569723 0.2739322815 0.4183334699 -0.7090146995 0.497248799892 +1403638186545096960.0000000000 15.5191944574 -5.3826424860 1.3763427459 0.2717456004 0.4192989770 -0.7088646372 0.497848995847 +1403638186595097088.0000000000 15.5750193795 -5.4030896844 1.3844148056 0.2702274351 0.4197672587 -0.7084901477 0.498812883194 +1403638186645096960.0000000000 15.6310716771 -5.4232545056 1.3909158645 0.2680383632 0.4207847259 -0.7083537488 0.499330168213 +1403638186695097088.0000000000 15.6877280008 -5.4431253704 1.3960775109 0.2652704262 0.4220989179 -0.7071412607 0.501413344359 +1403638186745096960.0000000000 15.7448737134 -5.4621681838 1.3997881784 0.2628484636 0.4246730677 -0.7049835750 0.503549034093 +1403638186795097088.0000000000 15.8024942077 -5.4803446101 1.4022684156 0.2610543733 0.4283161500 -0.7022403083 0.505227116528 +1403638186845096960.0000000000 15.8607025911 -5.4973742737 1.4036338179 0.2603224997 0.4327460309 -0.6989835846 0.506344761252 +1403638186895097088.0000000000 15.9195101078 -5.5128470921 1.4036655680 0.2600862998 0.4384294599 -0.6963063999 0.505264408796 +1403638186945096960.0000000000 15.9790201051 -5.5264591505 1.4034346667 0.2630397137 0.4437379898 -0.6931325189 0.503462030994 +1403638186995097088.0000000000 16.0394032705 -5.5381070080 1.4039090157 0.2673093720 0.4503127506 -0.6895864683 0.500234574075 +1403638187045096960.0000000000 16.1008498700 -5.5474434200 1.4067054800 0.2770847960 0.4552106391 -0.6852623518 0.496409910366 +1403638187095097088.0000000000 16.1629986690 -5.5555297343 1.4115491285 0.2876975743 0.4610974806 -0.6795673580 0.492754934093 +1403638187145096960.0000000000 16.2254683895 -5.5620702275 1.4184121485 0.2996570990 0.4671656117 -0.6722905003 0.489885086045 +1403638187195097088.0000000000 16.2870996298 -5.5670566488 1.4268653250 0.3117424212 0.4736710983 -0.6650476772 0.48596701588 +1403638187245096960.0000000000 16.3481452433 -5.5712187410 1.4372498601 0.3241629282 0.4803476899 -0.6566866285 0.482646003561 +1403638187295097088.0000000000 16.4089026265 -5.5751427759 1.4495420388 0.3349358871 0.4876411730 -0.6473384631 0.48060061595 +1403638187345096960.0000000000 16.4684734452 -5.5783598587 1.4631220348 0.3442867888 0.4946459452 -0.6391264409 0.477817317092 +1403638187395097088.0000000000 16.5268107406 -5.5811625400 1.4784546789 0.3530794724 0.5003171383 -0.6309217188 0.476398396326 +1403638187445096960.0000000000 16.5839663637 -5.5835545969 1.4943669117 0.3596254083 0.5059337996 -0.6236916913 0.475088655235 +1403638187495097088.0000000000 16.6396172609 -5.5854707052 1.5107816451 0.3645150323 0.5109064227 -0.6190100375 0.472154627089 +1403638187545096960.0000000000 16.6911802345 -5.5852595826 1.5296077037 0.3669304155 0.5161651263 -0.6158766295 0.468648706126 +1403638187595097088.0000000000 16.7425062750 -5.5861823559 1.5460729274 0.3675969374 0.5211738920 -0.6148563456 0.46389863142 +1403638187645096960.0000000000 16.7925917474 -5.5868043107 1.5622414773 0.3671416929 0.5256159026 -0.6150409785 0.458976573529 +1403638187695097088.0000000000 16.8418395161 -5.5874110128 1.5777088293 0.3660730136 0.5293535438 -0.6145152188 0.45623066565 +1403638187745096960.0000000000 16.8905013223 -5.5876950185 1.5917430951 0.3644769134 0.5324690438 -0.6136371643 0.45506343249 +1403638187795097088.0000000000 16.9383700637 -5.5875435220 1.6044728306 0.3628445365 0.5350132648 -0.6127285513 0.454607931298 +1403638187845096960.0000000000 16.9857930393 -5.5869740566 1.6161525403 0.3616600694 0.5364052983 -0.6112092256 0.455954638842 +1403638187895097088.0000000000 17.0325625993 -5.5858039357 1.6265203015 0.3585247575 0.5387483276 -0.6089867661 0.458634229497 +1403638187945096960.0000000000 17.0791171806 -5.5833794091 1.6366714397 0.3578916963 0.5389089825 -0.6070136597 0.461546378134 +1403638187995097088.0000000000 17.1251042722 -5.5800561009 1.6460899484 0.3567311406 0.5388041167 -0.6043059407 0.466098001693 +1403638188045096960.0000000000 17.1700053725 -5.5751846918 1.6546019914 0.3557788985 0.5384905368 -0.6018500468 0.470346508727 +1403638188095097088.0000000000 17.2141780074 -5.5690482881 1.6617295168 0.3542151878 0.5384371348 -0.5995175389 0.474547967133 +1403638188145096960.0000000000 17.2573391807 -5.5612415935 1.6676102616 0.3524229450 0.5384270564 -0.5970789628 0.4789478938 +1403638188195097088.0000000000 17.2996736633 -5.5513661238 1.6724901648 0.3534930273 0.5365663349 -0.5954103436 0.482312938552 +1403638188245096960.0000000000 17.3408685789 -5.5393493096 1.6763681494 0.3575981120 0.5325309234 -0.5943300212 0.485083736897 +1403638188295097088.0000000000 17.3812039850 -5.5251029683 1.6795515838 0.3657660419 0.5261527142 -0.5930477947 0.487517012138 +1403638188345096960.0000000000 17.4197356360 -5.5091745057 1.6816566695 0.3743959674 0.5194306476 -0.5917555006 0.489739614014 +1403638188395097088.0000000000 17.4560352708 -5.4919910094 1.6824375779 0.3815479145 0.5132922187 -0.5898287557 0.493005401732 +1403638188445096960.0000000000 17.4893460929 -5.4734646130 1.6820021632 0.3876826872 0.5079392589 -0.5886573078 0.49515898183 +1403638188495097088.0000000000 17.5191727455 -5.4538417035 1.6804317069 0.3931483514 0.5034037523 -0.5879503232 0.496319910332 +1403638188545096960.0000000000 17.5456570659 -5.4333021843 1.6777260749 0.3974728322 0.4995051583 -0.5867505438 0.498230613107 +1403638188595097088.0000000000 17.5679719781 -5.4114148817 1.6747059962 0.4002555979 0.4982851454 -0.5863393236 0.4977083161 +1403638188645096960.0000000000 17.5856172227 -5.3883790590 1.6723269108 0.4006043997 0.4999707518 -0.5858601395 0.496299566016 +1403638188695097088.0000000000 17.5984698082 -5.3641520304 1.6718865915 0.4010160048 0.5029140193 -0.5856732641 0.493204299217 +1403638188745096960.0000000000 17.6065485559 -5.3387757527 1.6733440632 0.4008706178 0.5073014631 -0.5862046085 0.488172234317 +1403638188795097088.0000000000 17.6096777763 -5.3128846385 1.6749919963 0.3985349226 0.5128966309 -0.5868913815 0.483389561046 +1403638188845096960.0000000000 17.6109735724 -5.2864467422 1.6796947380 0.3975143934 0.5173634104 -0.5873631230 0.478875735778 +1403638188895097088.0000000000 17.6103620743 -5.2594303950 1.6880054728 0.3969564639 0.5210886255 -0.5874139118 0.47522321732 +1403638188945096960.0000000000 17.6075926080 -5.2321528539 1.6981836507 0.3963942045 0.5242984385 -0.5879041849 0.471541569106 +1403638188995097088.0000000000 17.6022591212 -5.2042836174 1.7110266973 0.3956371431 0.5276435345 -0.5875696986 0.468855415612 +1403638189045096960.0000000000 17.5935894219 -5.1754530850 1.7255032983 0.3970496145 0.5305221663 -0.5868129223 0.465347643064 +1403638189095097088.0000000000 17.5826067881 -5.1460167839 1.7411389605 0.3998896434 0.5334637917 -0.5846610607 0.462251122242 +1403638189145096960.0000000000 17.5692333533 -5.1162935124 1.7560322574 0.4029501738 0.5373460110 -0.5817556977 0.458749092644 +1403638189195097088.0000000000 17.5534531557 -5.0860615380 1.7695813204 0.4072920196 0.5415591675 -0.5786370046 0.45387894388 +1403638189245096960.0000000000 17.5350545159 -5.0557276680 1.7812476071 0.4110816740 0.5470900555 -0.5750882732 0.44830548346 +1403638189295097088.0000000000 17.5146426564 -5.0252639054 1.7915073861 0.4145669863 0.5535743555 -0.5710843790 0.442212933784 +1403638189345096960.0000000000 17.4919975769 -4.9950888670 1.7999393332 0.4160732560 0.5614177067 -0.5677978133 0.43508487376 +1403638189395097088.0000000000 17.4677465006 -4.9654286698 1.8066072552 0.4143725306 0.5706026549 -0.5661220573 0.426865121919 +1403638189445096960.0000000000 17.4422336158 -4.9360468556 1.8133170720 0.4121670776 0.5794753554 -0.5649581822 0.418507903108 +1403638189495097088.0000000000 17.4157380945 -4.9067859701 1.8212256634 0.4099297994 0.5872543863 -0.5638985717 0.411227730331 +1403638189545096960.0000000000 17.3890785590 -4.8779288540 1.8312396041 0.4089451538 0.5931166418 -0.5631126504 0.404821755126 +1403638189595097088.0000000000 17.3627615552 -4.8495551649 1.8438973970 0.4086927747 0.5974188023 -0.5618602154 0.400467338112 +1403638189645096960.0000000000 17.3372528838 -4.8211865829 1.8583825835 0.4084713882 0.6010549291 -0.5613137931 0.395993589469 +1403638189695097088.0000000000 17.3126018474 -4.7931136860 1.8725962393 0.4076444167 0.6043093196 -0.5622086824 0.390586319848 +1403638189745096960.0000000000 17.2886587930 -4.7654828201 1.8858399371 0.4066387236 0.6068296984 -0.5640234147 0.385071750732 +1403638189795097088.0000000000 17.2659966224 -4.7386076960 1.8976831671 0.4054756207 0.6089182231 -0.5652648631 0.381161059331 +1403638189845096960.0000000000 17.2442891174 -4.7123197032 1.9075436277 0.4031291421 0.6113215922 -0.5665890153 0.377822304003 +1403638189895097088.0000000000 17.2244688706 -4.6864568093 1.9160384683 0.4000679089 0.6139300779 -0.5672698005 0.375819772109 +1403638189945096960.0000000000 17.2065250041 -4.6609375412 1.9234563339 0.3981483727 0.6154325322 -0.5681012825 0.374141155764 +1403638189995097088.0000000000 17.1909243285 -4.6358765662 1.9298989207 0.3981123225 0.6152822768 -0.5676059135 0.375177058898 +1403638190045096960.0000000000 17.1773765081 -4.6112038443 1.9354700647 0.4002793904 0.6135448854 -0.5658496956 0.378355923997 +1403638190095097088.0000000000 17.1657725290 -4.5867311351 1.9399573141 0.4037233929 0.6110277431 -0.5638378397 0.38175831328 +1403638190145096960.0000000000 17.1558698650 -4.5627219099 1.9430502113 0.4072908347 0.6080434931 -0.5607790453 0.387200398736 +1403638190195097088.0000000000 17.1469069524 -4.5389575760 1.9441830671 0.4106806822 0.6051059751 -0.5579837908 0.392227262524 +1403638190245096960.0000000000 17.1385565388 -4.5154538721 1.9440449980 0.4136027288 0.6026480873 -0.5529489976 0.399994339519 +1403638190295097088.0000000000 17.1301158639 -4.4919420638 1.9420162038 0.4145013967 0.6029213569 -0.5455095073 0.40877109361 +1403638190345096960.0000000000 17.1212280703 -4.4679140147 1.9386415442 0.4151996414 0.6044303518 -0.5378392777 0.415935234146 +1403638190395097088.0000000000 17.1115140719 -4.4429020047 1.9342164947 0.4161243445 0.6067931204 -0.5292710059 0.422510167173 +1403638190445096960.0000000000 17.1004941045 -4.4168495356 1.9282861465 0.4155068884 0.6104726031 -0.5223151254 0.42645531566 +1403638190495097088.0000000000 17.0878848082 -4.3892272292 1.9213736030 0.4158240502 0.6133273999 -0.5179835452 0.427332314191 +1403638190545096960.0000000000 17.0752343826 -4.3601531566 1.9133776273 0.4174569213 0.6155691088 -0.5159774400 0.424937257163 +1403638190595097088.0000000000 17.0608113710 -4.3293120683 1.9048661313 0.4182316851 0.6181026798 -0.5147978440 0.421917663256 +1403638190645096960.0000000000 17.0456594416 -4.2970970466 1.8963827949 0.4198815378 0.6195933442 -0.5138567427 0.419231236882 +1403638190695097088.0000000000 17.0294302025 -4.2635343795 1.8884183815 0.4218202383 0.6204689014 -0.5138259397 0.416015543713 +1403638190745096960.0000000000 17.0124224182 -4.2287033920 1.8817252844 0.4236239927 0.6214609592 -0.5127155864 0.414067284979 +1403638190795097088.0000000000 16.9928752790 -4.1927193817 1.8758874522 0.4275725705 0.6205323465 -0.5144153472 0.409265383891 +1403638190845096960.0000000000 16.9728812788 -4.1558721012 1.8714691482 0.4306048831 0.6200408089 -0.5167048666 0.403912008568 +1403638190895097088.0000000000 16.9523569039 -4.1185699315 1.8693752126 0.4333702414 0.6194832065 -0.5185056229 0.39947804678 +1403638190945096960.0000000000 16.9315306244 -4.0806124705 1.8698506585 0.4338985840 0.6201623201 -0.5190500419 0.397136965749 +1403638190995097088.0000000000 16.9087643830 -4.0426958273 1.8718930226 0.4366274934 0.6190606953 -0.5196974963 0.395012404664 +1403638191045096960.0000000000 16.8854148327 -4.0048709079 1.8759046891 0.4397118858 0.6174393602 -0.5187006483 0.395438656941 +1403638191095097088.0000000000 16.8608631046 -3.9671910927 1.8814601062 0.4415536653 0.6164688436 -0.5180169507 0.395796619903 +1403638191145096960.0000000000 16.8354662489 -3.9299848633 1.8878146255 0.4406006324 0.6173747338 -0.5188392404 0.394367041537 +1403638191195097088.0000000000 16.8090595956 -3.8931184729 1.8954849327 0.4378636923 0.6196023559 -0.5205778598 0.39162098952 +1403638191245096960.0000000000 16.7823150341 -3.8563578296 1.9049748358 0.4337455886 0.6224747529 -0.5231737617 0.388174138067 +1403638191295097088.0000000000 16.7544954358 -3.8197457414 1.9156613600 0.4301052208 0.6250003097 -0.5265582222 0.383562968178 +1403638191345096960.0000000000 16.7268072091 -3.7832824548 1.9271144594 0.4263846917 0.6276122945 -0.5275267597 0.382118332778 +1403638191395097088.0000000000 16.6994739906 -3.7469296486 1.9380329708 0.4234298274 0.6292008462 -0.5286775865 0.381200060304 +1403638191445096960.0000000000 16.6724156743 -3.7104994694 1.9478151660 0.4218093528 0.6299611955 -0.5297297805 0.380279005016 +1403638191495097088.0000000000 16.6522736562 -3.6701511392 1.9633523559 0.4214143442 0.6297788424 -0.5308720205 0.379425167812 +1403638191545096960.0000000000 16.6283209923 -3.6328060574 1.9720478144 0.4207262857 0.6298032442 -0.5309294096 0.380067399397 +1403638191595097088.0000000000 16.6049809899 -3.5954398625 1.9791842788 0.4199623594 0.6299628518 -0.5304667466 0.381291820993 +1403638191645096960.0000000000 16.5821981572 -3.5578976275 1.9848102649 0.4192616846 0.6299890387 -0.5303237166 0.382217485882 +1403638191695097088.0000000000 16.5599619347 -3.5203553281 1.9886244172 0.4169378211 0.6313507554 -0.5291831878 0.384088831726 +1403638191745096960.0000000000 16.5385389766 -3.4824744727 1.9908870549 0.4146165400 0.6325637980 -0.5278522495 0.386430031151 +1403638191795097088.0000000000 16.5179529720 -3.4438300879 1.9917950548 0.4127071203 0.6336719191 -0.5263030920 0.388764436705 +1403638191845096960.0000000000 16.4976128372 -3.4043736357 1.9912011215 0.4107959874 0.6347060551 -0.5257623902 0.389831745054 +1403638191895097088.0000000000 16.4778567792 -3.3638206736 1.9899142896 0.4108578657 0.6344040910 -0.5255355104 0.390563299265 +1403638191945096960.0000000000 16.4585940515 -3.3225497383 1.9884403699 0.4109049113 0.6341940066 -0.5259759844 0.390261937437 +1403638191995097088.0000000000 16.4393307830 -3.2806868499 1.9874384969 0.4112468491 0.6341089749 -0.5260869923 0.389890130067 +1403638192045096960.0000000000 16.4209615284 -3.2378528078 1.9877636920 0.4109502409 0.6342565642 -0.5250962693 0.391295819404 +1403638192095097088.0000000000 16.4023044843 -3.1940193214 1.9899298648 0.4106500671 0.6344086607 -0.5251863213 0.391243532234 +1403638192145096960.0000000000 16.3848813366 -3.1488277028 1.9948090029 0.4122104373 0.6335456957 -0.5256055016 0.390437272225 +1403638192195097088.0000000000 16.3680349072 -3.1028425904 2.0018843008 0.4140421156 0.6323729822 -0.5258172321 0.390115080721 +1403638192245096960.0000000000 16.3516799848 -3.0560101388 2.0120278656 0.4166148859 0.6308127852 -0.5252298657 0.390692788469 +1403638192295097088.0000000000 16.3364548604 -3.0082986213 2.0249080297 0.4212823548 0.6276773429 -0.5248814007 0.391205631363 +1403638192345096960.0000000000 16.3219096215 -2.9601206194 2.0400033742 0.4251996412 0.6252665150 -0.5237597597 0.392329917895 +1403638192395097088.0000000000 16.3074950679 -2.9116677615 2.0562702703 0.4275092974 0.6237198623 -0.5232429281 0.392970955935 +1403638192445096960.0000000000 16.2925102402 -2.8629354469 2.0741184689 0.4289511172 0.6228624261 -0.5230295055 0.393043857181 +1403638192495097088.0000000000 16.2754884196 -2.8142993748 2.0911330782 0.4309655344 0.6215839255 -0.5225759797 0.393467250475 +1403638192545096960.0000000000 16.2592090008 -2.7656528814 2.1114638705 0.4324380023 0.6204387466 -0.5216519229 0.394882776656 +1403638192595097088.0000000000 16.2428323892 -2.7168849240 2.1326172310 0.4348960534 0.6186701862 -0.5203026498 0.396733885707 +1403638192645096960.0000000000 16.2265687149 -2.6679197399 2.1542842882 0.4389777373 0.6154317152 -0.5177060981 0.400652899725 +1403638192695097088.0000000000 16.2091854694 -2.6188411340 2.1748432871 0.4435027912 0.6119914570 -0.5172595419 0.401515002185 +1403638192745096960.0000000000 16.1907480975 -2.5702344255 2.1938215829 0.4471437140 0.6089771678 -0.5153959260 0.404445728824 +1403638192795097088.0000000000 16.1706696080 -2.5218735116 2.2113768568 0.4519776589 0.6053640347 -0.5144511339 0.405697685737 +1403638192845096960.0000000000 16.1491266711 -2.4738592037 2.2275434645 0.4561380465 0.6022866947 -0.5138104551 0.406432818789 +1403638192895097088.0000000000 16.1256848911 -2.4261106630 2.2435148998 0.4634322833 0.5968991201 -0.5130896045 0.407039331047 +1403638192945096960.0000000000 16.1003174215 -2.3789766362 2.2590178992 0.4733981332 0.5896406283 -0.5127186567 0.406617407373 +1403638192995097088.0000000000 16.0727194562 -2.3334360843 2.2731423705 0.4815186059 0.5839348658 -0.5122161259 0.405948943847 +1403638193045096960.0000000000 16.0419171162 -2.2896567575 2.2867112633 0.4881893341 0.5806556404 -0.5120564847 0.4028751145 +1403638193095097088.0000000000 16.0078705452 -2.2482008224 2.3002005067 0.4902294362 0.5820003040 -0.5110119377 0.399771866901 +1403638193145096960.0000000000 15.9704802381 -2.2089248862 2.3142576127 0.4883175184 0.5874164792 -0.5097193429 0.395820758102 +1403638193195097088.0000000000 15.9305314636 -2.1718783523 2.3300316539 0.4847078392 0.5939019895 -0.5083056772 0.392382563303 +1403638193245096960.0000000000 15.8876958603 -2.1369412201 2.3478915237 0.4812872987 0.6000261758 -0.5061501459 0.390055321992 +1403638193295097088.0000000000 15.8418154433 -2.1039639256 2.3683687014 0.4786132111 0.6052669547 -0.5041917972 0.387778209005 +1403638193345096960.0000000000 15.7936461502 -2.0728925349 2.3912423783 0.4746632796 0.6107400603 -0.5013073520 0.38779155309 +1403638193395097088.0000000000 15.7445131200 -2.0432932466 2.4167521250 0.4729661194 0.6143564331 -0.4976175207 0.388903620519 +1403638193445096960.0000000000 15.6938269581 -2.0149981601 2.4429838516 0.4717037520 0.6169177679 -0.4944983525 0.390358063096 +1403638193495097088.0000000000 15.6416786911 -1.9873749241 2.4691729324 0.4725542222 0.6179042456 -0.4920459689 0.390867771601 +1403638193545096960.0000000000 15.5877663317 -1.9606910029 2.4939639295 0.4729834176 0.6189465332 -0.4902581358 0.390946078104 +1403638193595097088.0000000000 15.5319068796 -1.9345475706 2.5167851601 0.4719831398 0.6207731601 -0.4901214412 0.389427236282 +1403638193645096960.0000000000 15.4742859201 -1.9091185853 2.5374638375 0.4689693702 0.6238969579 -0.4911034119 0.386830394988 +1403638193695097088.0000000000 15.4150989189 -1.8843198132 2.5563579064 0.4646841959 0.6277638469 -0.4933764595 0.382832626302 +1403638193745096960.0000000000 15.3547718344 -1.8601953989 2.5737153114 0.4615033189 0.6308591886 -0.4964357942 0.377601473832 +1403638193795097088.0000000000 15.2935038493 -1.8368357806 2.5892479956 0.4579151896 0.6337806211 -0.4985400614 0.374290810278 +1403638193845096960.0000000000 15.2319531528 -1.8141220690 2.6033602362 0.4551074195 0.6358379855 -0.4996690392 0.372717244248 +1403638193895097088.0000000000 15.1699587064 -1.7917097069 2.6164000830 0.4531112758 0.6372209054 -0.5012356117 0.370678500929 +1403638193945096960.0000000000 15.1080082261 -1.7696429752 2.6280845975 0.4507776484 0.6387714617 -0.5021779422 0.369577929249 +1403638193995097088.0000000000 15.0462692132 -1.7480053328 2.6384049518 0.4506244501 0.6388328126 -0.5035128772 0.367838313658 +1403638194045096960.0000000000 14.9847309151 -1.7265550260 2.6473972161 0.4503174523 0.6389220304 -0.5034964071 0.368081783545 +1403638194095097088.0000000000 14.9239394853 -1.7052384194 2.6555301684 0.4519753071 0.6371828346 -0.5019849091 0.371116569333 +1403638194145096960.0000000000 14.8634890512 -1.6839935128 2.6622521427 0.4548940856 0.6346915349 -0.5008181025 0.373388878488 +1403638194195097088.0000000000 14.8026441932 -1.6633352641 2.6672895916 0.4574017520 0.6323805105 -0.4991590550 0.376455528573 +1403638194245096960.0000000000 14.7409791810 -1.6431351359 2.6707693905 0.4600317232 0.6300307087 -0.4981654577 0.378501382421 +1403638194295097088.0000000000 14.6783626849 -1.6232281892 2.6724313477 0.4606538024 0.6294149661 -0.4978754709 0.379150221228 +1403638194345096960.0000000000 14.6146731248 -1.6038779786 2.6729001241 0.4589098450 0.6305794812 -0.4997694148 0.376831267379 +1403638194395097088.0000000000 14.5504942981 -1.5850984580 2.6747196649 0.4567389920 0.6319313010 -0.5015626625 0.374816247732 +1403638194445096960.0000000000 14.4854488457 -1.5668224986 2.6775884221 0.4548136940 0.6331488380 -0.5036749117 0.372261515584 +1403638194495097088.0000000000 14.4203394621 -1.5490503976 2.6819380925 0.4527044284 0.6343802319 -0.5058672483 0.369754985096 +1403638194545096960.0000000000 14.3549109980 -1.5319948649 2.6880385026 0.4498088588 0.6361540838 -0.5067459246 0.369037315288 +1403638194595097088.0000000000 14.2883847211 -1.5153570034 2.6955805636 0.4477322545 0.6373850690 -0.5083409840 0.367240447356 +1403638194645096960.0000000000 14.2224730924 -1.4989770322 2.7038598398 0.4444195840 0.6394773981 -0.5100055752 0.365313843135 +1403638194695097088.0000000000 14.1578887061 -1.4826754640 2.7126920567 0.4406186988 0.6418816730 -0.5121204475 0.362733686662 +1403638194745096960.0000000000 14.0947437163 -1.4666199709 2.7212820199 0.4377478929 0.6435038074 -0.5135444177 0.361319475073 +1403638194795097088.0000000000 14.0328398284 -1.4508993276 2.7286952166 0.4347520522 0.6452598723 -0.5145199849 0.360415781231 +1403638194845096960.0000000000 13.9724194574 -1.4350962425 2.7348906572 0.4322827306 0.6466001187 -0.5160074761 0.358854025987 +1403638194895097088.0000000000 13.9135927380 -1.4194870006 2.7397369850 0.4299735511 0.6477928418 -0.5163966682 0.358917345087 +1403638194945096960.0000000000 13.8564202726 -1.4037309878 2.7432675160 0.4283322974 0.6487859991 -0.5165198185 0.358908689617 +1403638194995097088.0000000000 13.8007516237 -1.3878294226 2.7453689775 0.4275890331 0.6491620875 -0.5173017107 0.357987629847 +1403638195045096960.0000000000 13.7466398954 -1.3719797167 2.7458688150 0.4263776019 0.6498141352 -0.5175462927 0.357896025561 +1403638195095097088.0000000000 13.6940515791 -1.3557361998 2.7450002024 0.4258803874 0.6502809190 -0.5175979362 0.35756537656 +1403638195145096960.0000000000 13.6428869612 -1.3392708196 2.7426816493 0.4241817640 0.6513257323 -0.5182092183 0.356796619446 +1403638195195097088.0000000000 13.5930011638 -1.3223479317 2.7388433480 0.4219648301 0.6526745929 -0.5206644847 0.353369568972 +1403638195245096960.0000000000 13.5444700235 -1.3053486876 2.7330567421 0.4170386605 0.6559054735 -0.5235004327 0.349018713502 +1403638195295097088.0000000000 13.4980906454 -1.2878771878 2.7263103865 0.4124314956 0.6588862857 -0.5266224619 0.344148088184 +1403638195345096960.0000000000 13.4544813244 -1.2701573213 2.7189433136 0.4092279225 0.6608514447 -0.5286162725 0.341134448565 +1403638195395097088.0000000000 13.4144898888 -1.2518988331 2.7115065796 0.4093302306 0.6608546627 -0.5282329782 0.341598884292 +1403638195445096960.0000000000 13.3777422057 -1.2332085074 2.7042929355 0.4135799695 0.6579355631 -0.5266825743 0.344496544954 +1403638195495097088.0000000000 13.3435422478 -1.2141944967 2.6969389825 0.4206430687 0.6533798614 -0.5231887114 0.34989675307 +1403638195545096960.0000000000 13.3107309652 -1.1948907402 2.6886434352 0.4272586125 0.6489664536 -0.5207531169 0.353707239687 +1403638195595097088.0000000000 13.2796928108 -1.1756160486 2.6790728847 0.4325266203 0.6454403115 -0.5172654118 0.358837039364 +1403638195645096960.0000000000 13.2495266144 -1.1562703341 2.6684313075 0.4357657381 0.6433796640 -0.5157245447 0.360831017902 +1403638195695097088.0000000000 13.2158545918 -1.1366342552 2.6555815328 0.4359331686 0.6434344223 -0.5151982142 0.361282737952 +1403638195745096960.0000000000 13.1861808656 -1.1173899055 2.6461357908 0.4357449973 0.6436382892 -0.5158867484 0.360162342327 +1403638195795097088.0000000000 13.1570803046 -1.0984042206 2.6377265539 0.4343877123 0.6448000744 -0.5166686608 0.358599601748 +1403638195845096960.0000000000 13.1292682547 -1.0793848663 2.6310801152 0.4320152066 0.6464700494 -0.5179333698 0.356629164361 +1403638195895097088.0000000000 13.1024384742 -1.0604672696 2.6259515266 0.4283126247 0.6493056373 -0.5188422357 0.354617003703 +1403638195945096960.0000000000 13.0773811186 -1.0415307124 2.6224434302 0.4256172092 0.6512523788 -0.5204097870 0.351985772413 +1403638195995097088.0000000000 13.0546337393 -1.0223987438 2.6207459034 0.4230871975 0.6530144649 -0.5215169751 0.350127657671 +1403638196045096960.0000000000 13.0340773080 -1.0029894282 2.6213682574 0.4224709518 0.6535303136 -0.5218428991 0.349422971102 +1403638196095097088.0000000000 13.0161157716 -0.9832526874 2.6246460191 0.4228894129 0.6532609199 -0.5213113969 0.350212995797 +1403638196145096960.0000000000 13.0011502596 -0.9630161840 2.6309350245 0.4246265731 0.6520741161 -0.5199411719 0.352353229316 +1403638196195097088.0000000000 12.9877179780 -0.9425496839 2.6396486408 0.4286113938 0.6496783891 -0.5177724065 0.355136591946 +1403638196245096960.0000000000 12.9749595634 -0.9222646018 2.6495549792 0.4321734014 0.6472524804 -0.5156742733 0.358288182272 +1403638196295097088.0000000000 12.9627294169 -0.9018360573 2.6594862063 0.4346545235 0.6455854739 -0.5144388676 0.36006595598 +1403638196345096960.0000000000 12.9511757062 -0.8814826558 2.6683085457 0.4362523113 0.6444194444 -0.5126577263 0.362752748084 +1403638196395097088.0000000000 12.9392018728 -0.8612639671 2.6774382421 0.4368453827 0.6440478501 -0.5138032381 0.361074384086 +1403638196445096960.0000000000 12.9283790320 -0.8408848189 2.6833449022 0.4366809857 0.6440259819 -0.5140283092 0.360991895676 +1403638196495097088.0000000000 12.9183517228 -0.8204564017 2.6874515872 0.4362194352 0.6441842178 -0.5147739282 0.360204248607 +1403638196545096960.0000000000 12.9087926316 -0.8000786757 2.6899103611 0.4354080722 0.6444226820 -0.5164882628 0.358300281945 +1403638196595097088.0000000000 12.8999271168 -0.7798128307 2.6902432146 0.4326941073 0.6461384758 -0.5183115716 0.355856704738 +1403638196645096960.0000000000 12.8920187081 -0.7599136042 2.6885669241 0.4282095567 0.6488653454 -0.5206943375 0.352828210286 +1403638196695097088.0000000000 12.8856204756 -0.7399757127 2.6858132448 0.4252147895 0.6506335575 -0.5235421913 0.348958350893 +1403638196745096960.0000000000 12.8811058488 -0.7201802663 2.6818955927 0.4229899415 0.6518722149 -0.5248337372 0.347407071099 +1403638196795097088.0000000000 12.8783524094 -0.7002008529 2.6769535011 0.4217866521 0.6524875433 -0.5249863643 0.34748430641 +1403638196845096960.0000000000 12.8772616906 -0.6799712449 2.6710638085 0.4220657732 0.6522809629 -0.5254537426 0.346826170981 +1403638196895097088.0000000000 12.8786201914 -0.6597660780 2.6651939277 0.4245624869 0.6503270005 -0.5237171468 0.350059762427 +1403638196945096960.0000000000 12.8813921739 -0.6395151769 2.6601479935 0.4274969950 0.6485266818 -0.5222080502 0.352077000801 +1403638196995097088.0000000000 12.8861581975 -0.6190885130 2.6564533807 0.4310206755 0.6462170564 -0.5201085661 0.355122194166 +1403638197045096960.0000000000 12.8914627834 -0.5990213111 2.6547042372 0.4336543625 0.6442895518 -0.5189852263 0.357056301308 +1403638197095097088.0000000000 12.8971496825 -0.5793129020 2.6539700945 0.4351199028 0.6431885936 -0.5179960922 0.358690886013 +1403638197145096960.0000000000 12.9033816073 -0.5599357960 2.6539811163 0.4361341198 0.6424299861 -0.5169554550 0.360316250116 +1403638197195097088.0000000000 12.9109226616 -0.5407661829 2.6551121383 0.4356167984 0.6427370185 -0.5156209552 0.362301201367 +1403638197245096960.0000000000 12.9198496734 -0.5211177494 2.6583083820 0.4359982876 0.6426114340 -0.5137957889 0.364650415336 +1403638197295097088.0000000000 12.9291536485 -0.5016560107 2.6635240859 0.4358966172 0.6425953635 -0.5096757066 0.370534765023 +1403638197345096960.0000000000 12.9383226754 -0.4818913549 2.6705318554 0.4356333753 0.6426162505 -0.5058553577 0.376003023878 +1403638197395097088.0000000000 12.9471729988 -0.4616092252 2.6788811338 0.4356031035 0.6425097309 -0.5030539289 0.379957795711 +1403638197445096960.0000000000 12.9556891627 -0.4407224050 2.6890675823 0.4359603014 0.6419915198 -0.5008818836 0.383279066441 +1403638197495097088.0000000000 12.9637639486 -0.4186916355 2.7014147961 0.4369088727 0.6414718381 -0.4998846379 0.384369440177 +1403638197545096960.0000000000 12.9706369216 -0.3961098548 2.7153209226 0.4388606355 0.6402214166 -0.5002210723 0.383792599077 +1403638197595097088.0000000000 12.9766095473 -0.3732219674 2.7304373189 0.4391764705 0.6401097342 -0.4997982282 0.384168305615 +1403638197645096960.0000000000 12.9821413787 -0.3497104947 2.7468275005 0.4395765911 0.6398182337 -0.4993481136 0.384781119419 +1403638197695097088.0000000000 12.9871787324 -0.3256699288 2.7641077671 0.4394347152 0.6400471499 -0.4994498493 0.384430260371 +1403638197745096960.0000000000 12.9946599936 -0.3002856066 2.7842146504 0.4389866819 0.6406198298 -0.4992510456 0.38424643167 +1403638197795097088.0000000000 12.9990892159 -0.2752127831 2.8006405328 0.4398472648 0.6400681099 -0.4995173688 0.383835377047 +1403638197845096960.0000000000 13.0030039530 -0.2495505824 2.8162033507 0.4426289405 0.6383559724 -0.5000310521 0.382818782734 +1403638197895097088.0000000000 13.0065489642 -0.2234498120 2.8304775462 0.4464751257 0.6359046170 -0.5003635113 0.381996906804 +1403638197945096960.0000000000 13.0098671627 -0.1970717795 2.8433325436 0.4525627511 0.6318148434 -0.4988490452 0.383596910959 +1403638197995097088.0000000000 13.0123840909 -0.1707457649 2.8526917161 0.4587834799 0.6273467973 -0.4970058687 0.385926004508 +1403638198045096960.0000000000 13.0138474294 -0.1446763817 2.8574365669 0.4627548635 0.6244569261 -0.4960643283 0.387080955187 +1403638198095097088.0000000000 13.0136919703 -0.1192647464 2.8564940429 0.4624404819 0.6248184159 -0.4965596313 0.386237336966 +1403638198145096960.0000000000 13.0120921068 -0.0942407767 2.8508524381 0.4617548110 0.6253520954 -0.4983595633 0.38386846308 +1403638198195097088.0000000000 13.0087336285 -0.0696801684 2.8403468663 0.4601468438 0.6266771930 -0.4997582246 0.381814477004 +1403638198245096960.0000000000 13.0038934743 -0.0454087742 2.8265674053 0.4578807103 0.6282833252 -0.5008780597 0.380429346614 +1403638198295097088.0000000000 12.9977166760 -0.0215198358 2.8109761952 0.4559704330 0.6297384432 -0.5012064195 0.379884959416 +1403638198345096960.0000000000 12.9905308684 0.0019976264 2.7940174043 0.4545752191 0.6308304672 -0.5012889377 0.379636263822 +1403638198395097088.0000000000 12.9824424933 0.0251507384 2.7751764676 0.4506551906 0.6337538145 -0.5015740279 0.37906397394 +1403638198445096960.0000000000 12.9737028111 0.0478676735 2.7554036517 0.4467434181 0.6365376845 -0.5006194866 0.380289658438 +1403638198495097088.0000000000 12.9642519443 0.0706599597 2.7350347701 0.4441979181 0.6382975566 -0.4990824332 0.382336453475 +1403638198545096960.0000000000 12.9539962498 0.0938066616 2.7133741912 0.4399970848 0.6414568793 -0.4962953766 0.385521123441 +1403638198595097088.0000000000 12.9434697438 0.1173580448 2.6911502940 0.4357151700 0.6440053509 -0.4909880619 0.392861453559 +1403638198645096960.0000000000 12.9321154176 0.1419046365 2.6684779935 0.4320704696 0.6460705311 -0.4848707138 0.401009188161 +1403638198695097088.0000000000 12.9195707572 0.1680682418 2.6465857352 0.4287247334 0.6480065472 -0.4789547370 0.408515578312 +1403638198745096960.0000000000 12.9052702286 0.1962729729 2.6262407367 0.4257932448 0.6496081362 -0.4732086261 0.415671719364 +1403638198795097088.0000000000 12.8888958052 0.2271746172 2.6081085780 0.4250998154 0.6497141306 -0.4691651584 0.420768047379 +1403638198845096960.0000000000 12.8830569422 0.2616150280 2.5953562426 0.4247499804 0.6501308447 -0.4669363810 0.422951244229 +1403638198895097088.0000000000 12.8628484031 0.2981755889 2.5819862012 0.4245772607 0.6502276135 -0.4665330271 0.42342075414 +1403638198945096960.0000000000 12.8404838753 0.3377232466 2.5706305028 0.4241378122 0.6506766649 -0.4671665014 0.422471838016 +1403638198995097088.0000000000 12.8165475398 0.3800994827 2.5612756053 0.4243840486 0.6506225323 -0.4687152158 0.420588333379 +1403638199045096960.0000000000 12.7904501274 0.4251147272 2.5544032491 0.4247089004 0.6505168089 -0.4698511365 0.419154077604 +1403638199095097088.0000000000 12.7628785843 0.4731693981 2.5506682858 0.4251513786 0.6502425922 -0.4715101343 0.417263789251 +1403638199145096960.0000000000 12.7338311199 0.5237261806 2.5499063847 0.4258852467 0.6494839109 -0.4722003918 0.416916293904 +1403638199195097088.0000000000 12.7027821847 0.5769283033 2.5515426226 0.4276369899 0.6482758040 -0.4733741438 0.415670550717 +1403638199245096960.0000000000 12.6701365306 0.6325075509 2.5562964963 0.4305591868 0.6463247139 -0.4739006346 0.415091965013 +1403638199295097088.0000000000 12.6362262848 0.6903511868 2.5637803724 0.4329967629 0.6445394954 -0.4730669030 0.416281572302 +1403638199345096960.0000000000 12.6004553145 0.7502350847 2.5721048683 0.4344763983 0.6433647926 -0.4731366926 0.416477698159 +1403638199395097088.0000000000 12.5621400346 0.8113918829 2.5811581009 0.4331334760 0.6438568868 -0.4715490139 0.418909571053 +1403638199445096960.0000000000 12.5214421456 0.8744394657 2.5921926683 0.4311046912 0.6449048175 -0.4708690762 0.420153346665 +1403638199495097088.0000000000 12.4786811730 0.9394237899 2.6048644420 0.4278326471 0.6465639493 -0.4707584052 0.421071026578 +1403638199545096960.0000000000 12.4344048085 1.0069831716 2.6191248616 0.4239427391 0.6496193652 -0.4699351980 0.42122220255 +1403638199595097088.0000000000 12.3884779791 1.0773724046 2.6348338128 0.4233207036 0.6518043635 -0.4688846773 0.419640099459 +1403638199645096960.0000000000 12.3407761679 1.1505113298 2.6519005123 0.4241742305 0.6543147857 -0.4671202580 0.41682975895 +1403638199695097088.0000000000 12.2911522816 1.2265034244 2.6711211172 0.4282028289 0.6556768822 -0.4660964438 0.41168467137 +1403638199745096960.0000000000 12.2400694001 1.3045239640 2.6910655300 0.4326358006 0.6567782024 -0.4667167608 0.404529507149 +1403638199795097088.0000000000 12.1875683459 1.3840505191 2.7101238212 0.4371805176 0.6573462976 -0.4700491885 0.394743968133 +1403638199845096960.0000000000 12.1343358319 1.4643895417 2.7278701484 0.4407194033 0.6580853387 -0.4718690114 0.387336714868 +1403638199895097088.0000000000 12.0805890416 1.5453674248 2.7438141186 0.4437935287 0.6588365333 -0.4732981241 0.380750064937 +1403638199945096960.0000000000 12.0266105716 1.6267465508 2.7580187621 0.4459946000 0.6596414747 -0.4740066040 0.375871894415 +1403638199995097088.0000000000 11.9723706135 1.7086126861 2.7710479756 0.4483178071 0.6607167205 -0.4729430066 0.372544590149 +1403638200045096960.0000000000 11.9177286148 1.7907117019 2.7827446823 0.4507896665 0.6624461114 -0.4709115238 0.36904764313 +1403638200095097088.0000000000 11.8628824373 1.8725376995 2.7927465668 0.4511743793 0.6662020339 -0.4660000557 0.36804955851 +1403638200145096960.0000000000 11.8077432405 1.9547226597 2.8024688392 0.4529235403 0.6698119211 -0.4590044562 0.368140144649 +1403638200195097088.0000000000 11.7517818507 2.0373053419 2.8130102076 0.4562440816 0.6726838101 -0.4504183407 0.369406480695 +1403638200245096960.0000000000 11.7088212469 2.1124357750 2.8202520045 0.4629683498 0.6739630625 -0.4425890217 0.368169872973 +1403638200295097088.0000000000 11.6500514490 2.1955803129 2.8335360690 0.4682325184 0.6764420581 -0.4341930726 0.366961614415 +1403638200345096960.0000000000 11.5897234382 2.2796336147 2.8486833554 0.4745085075 0.6784357334 -0.4267825802 0.363900070268 +1403638200395097088.0000000000 11.5287169953 2.3642107812 2.8654811982 0.4788059942 0.6812817311 -0.4185496524 0.362513739388 +1403638200445096960.0000000000 11.4660975703 2.4488135862 2.8828122069 0.4791735638 0.6863369844 -0.4107494614 0.361412672075 +1403638200495097088.0000000000 11.4027399598 2.5339866620 2.9024053893 0.4792953017 0.6904951930 -0.4034511081 0.361551663617 +1403638200545096960.0000000000 11.3378790554 2.6201950674 2.9236599201 0.4790128748 0.6949421609 -0.3966808687 0.360896588097 +1403638200595097088.0000000000 11.2709674765 2.7074772649 2.9465314895 0.4792697852 0.6993873417 -0.3905718098 0.358624428548 +1403638200645096960.0000000000 11.2026216607 2.7956324628 2.9707759932 0.4795942930 0.7038870432 -0.3824777088 0.358110523145 +1403638200695097088.0000000000 11.1328984336 2.8851227125 2.9965785620 0.4791150065 0.7087869116 -0.3742594262 0.357770605773 +1403638200745096960.0000000000 11.0457932132 2.9705405180 3.0243992259 0.4785472795 0.7132809036 -0.3690294740 0.355021268539 +1403638200795097088.0000000000 10.9695128361 3.0615591518 3.0502876928 0.4780009433 0.7172161218 -0.3651041900 0.351873646751 +1403638200845096960.0000000000 10.8906339855 3.1535515153 3.0754824565 0.4778237236 0.7202053621 -0.3627949635 0.348379878944 +1403638200895097088.0000000000 10.8108814861 3.2474367276 3.0991747477 0.4783441864 0.7223085252 -0.3624887134 0.343597389878 +1403638200945096960.0000000000 10.7299140798 3.3432136314 3.1217775173 0.4823408067 0.7219047180 -0.3651195746 0.335989018599 +1403638200995097088.0000000000 10.6480744061 3.4401142753 3.1427808135 0.4863033656 0.7209261800 -0.3677148601 0.329484842247 +1403638201045096960.0000000000 10.5652866677 3.5376505369 3.1619889451 0.4904075884 0.7194955524 -0.3708993227 0.322893542275 +1403638201095097088.0000000000 10.4820076591 3.6352606722 3.1786421271 0.4929889347 0.7184441689 -0.3725842012 0.319344483918 +1403638201145096960.0000000000 10.3982045426 3.7331089731 3.1929824973 0.4936936802 0.7183717719 -0.3743595448 0.31632811881 +1403638201195097088.0000000000 10.3142536865 3.8309689780 3.2061518934 0.4959191301 0.7167218720 -0.3760402561 0.314591322713 +1403638201245096960.0000000000 10.2299650557 3.9286985422 3.2172867600 0.4982588533 0.7148866504 -0.3779051935 0.312830396272 +1403638201295097088.0000000000 10.1455043334 4.0259251186 3.2263045870 0.4972095729 0.7151115436 -0.3788111924 0.312890078628 +1403638201345096960.0000000000 10.0607812380 4.1230792969 3.2336569970 0.4962702583 0.7153605728 -0.3793794089 0.313123531087 +1403638201395097088.0000000000 9.9759278767 4.2199473015 3.2395013811 0.4953126688 0.7154369939 -0.3789273399 0.315006887155 +1403638201445096960.0000000000 9.8907122739 4.3165600492 3.2435179738 0.4957417076 0.7144653520 -0.3796570810 0.315657917734 +1403638201495097088.0000000000 9.8055065163 4.4132955490 3.2457934069 0.4963419099 0.7134245271 -0.3803997384 0.31617430583 +1403638201545096960.0000000000 9.7058736926 4.5013004703 3.2495235187 0.4964158144 0.7127160379 -0.3802314758 0.317854075532 +1403638201595097088.0000000000 9.6185042843 4.5966306676 3.2485746668 0.4963576331 0.7119332853 -0.3799975923 0.319971760061 +1403638201645096960.0000000000 9.5304521907 4.6917543561 3.2459471797 0.4977422419 0.7105698864 -0.3804006404 0.320372361333 +1403638201695097088.0000000000 9.4417641758 4.7865124882 3.2407958357 0.4981399624 0.7097567556 -0.3813134714 0.320471468822 +1403638201745096960.0000000000 9.3525072777 4.8807816447 3.2334025707 0.4980516805 0.7093112951 -0.3821342316 0.320617278388 +1403638201795097088.0000000000 9.2626725826 4.9742995766 3.2239971599 0.4971971598 0.7093774569 -0.3818442327 0.32213908471 +1403638201845096960.0000000000 9.1720817824 5.0680204068 3.2135600592 0.4992767037 0.7078762341 -0.3833788748 0.320397641647 +1403638201895097088.0000000000 9.0805472714 5.1608890351 3.2015196437 0.4978635961 0.7088496844 -0.3832951879 0.320544479797 +1403638201945096960.0000000000 8.9874158099 5.2532612448 3.1900071573 0.4982824398 0.7097590803 -0.3822668886 0.319106070219 +1403638201995097088.0000000000 8.8927613531 5.3450462674 3.1795678512 0.4992089886 0.7115057379 -0.3796922923 0.316833921336 +1403638202045096960.0000000000 8.7963336977 5.4357722064 3.1705115446 0.5010353595 0.7128136842 -0.3778286930 0.313218292698 +1403638202095097088.0000000000 8.6987315869 5.5257162832 3.1622310250 0.5028965366 0.7140238514 -0.3781553726 0.307023659166 +1403638202145096960.0000000000 8.6121161776 5.6257786260 3.1489519915 0.5030066419 0.7163624270 -0.3787294145 0.30062139327 +1403638202195097088.0000000000 8.5164061121 5.7163994259 3.1429849922 0.5038387032 0.7177466030 -0.3797224084 0.29461376013 +1403638202245096960.0000000000 8.4206463947 5.8058174849 3.1383523301 0.5032845480 0.7198605144 -0.3807672841 0.289001347624 +1403638202295097088.0000000000 8.3259310983 5.8946044033 3.1350953614 0.5012782833 0.7228422268 -0.3806988212 0.28510981295 +1403638202345096960.0000000000 8.2329657344 5.9834257314 3.1341091025 0.5026766429 0.7230830953 -0.3811534898 0.281405485354 +1403638202395097088.0000000000 8.1413519374 6.0709339898 3.1328545304 0.5011711729 0.7249618179 -0.3798836853 0.280973670916 +1403638202445096960.0000000000 8.0508206697 6.1584889729 3.1307157170 0.5017180700 0.7254338374 -0.3796466949 0.279093376522 +1403638202495097088.0000000000 7.9612297220 6.2452861536 3.1263669266 0.5015311872 0.7261194811 -0.3790585925 0.278444879512 +1403638202545096960.0000000000 7.8724964221 6.3315727037 3.1203233625 0.5019955890 0.7261988608 -0.3801358141 0.275921014266 +1403638202595097088.0000000000 7.7852048297 6.4169965240 3.1125623383 0.5024541184 0.7260920755 -0.3810094609 0.274156793668 +1403638202645096960.0000000000 7.6987803711 6.5012178303 3.1025579227 0.5011416406 0.7270979695 -0.3815837615 0.273092350001 +1403638202695097088.0000000000 7.6138266420 6.5848836867 3.0915010645 0.5011594934 0.7270292639 -0.3819751457 0.272695067216 +1403638202745096960.0000000000 7.5304149885 6.6676367122 3.0792590614 0.5011210130 0.7269864005 -0.3818214958 0.273094945394 +1403638202795097088.0000000000 7.4481675196 6.7492031250 3.0656957696 0.5012785937 0.7266695785 -0.3813645453 0.274284849854 +1403638202845096960.0000000000 7.3670192534 6.8300356182 3.0518369575 0.5019047794 0.7260793337 -0.3809379697 0.275293764503 +1403638202895097088.0000000000 7.2870931368 6.9100871285 3.0375665808 0.5023032411 0.7256126269 -0.3802625065 0.276727656369 +1403638202945096960.0000000000 7.2074571099 6.9890963141 3.0237984081 0.5027160471 0.7250617478 -0.3811356006 0.276220368233 +1403638202995097088.0000000000 7.1285549301 7.0671500060 3.0112383609 0.5037530146 0.7242376382 -0.3813135314 0.276247596272 +1403638203045096960.0000000000 7.0506490740 7.1442352575 2.9995912204 0.5048827014 0.7233235565 -0.3816980301 0.276049097573 +1403638203095097088.0000000000 6.9725767003 7.2237955957 2.9821155197 0.5049076326 0.7232673350 -0.3816185416 0.276260625689 +1403638203145096960.0000000000 6.8965143524 7.2996790186 2.9732050441 0.5055048100 0.7226008114 -0.3806658913 0.278220117271 +1403638203195097088.0000000000 6.8211214753 7.3745433001 2.9661202093 0.5070614021 0.7214217760 -0.3787191416 0.281089251658 +1403638203245096960.0000000000 6.7458762865 7.4481134275 2.9606136369 0.5083041358 0.7204648856 -0.3770838807 0.283487214999 +1403638203295097088.0000000000 6.6710096567 7.5208662858 2.9571616391 0.5105916156 0.7188875661 -0.3770138991 0.283473789454 +1403638203345096960.0000000000 6.5968020975 7.5935458659 2.9537511130 0.5111622777 0.7184591679 -0.3774378065 0.282966874561 +1403638203395097088.0000000000 6.5225673275 7.6643022442 2.9498644200 0.5129472672 0.7173584610 -0.3772855430 0.282732309145 +1403638203445096960.0000000000 6.4486785972 7.7339790629 2.9443953612 0.5141534030 0.7165314852 -0.3777348951 0.282037688967 +1403638203495097088.0000000000 6.3751954882 7.8024456376 2.9370187110 0.5136185963 0.7168596752 -0.3784457735 0.281224003547 +1403638203545096960.0000000000 6.3021422823 7.8704418579 2.9287224991 0.5139198766 0.7167122065 -0.3791213297 0.280137449977 +1403638203595097088.0000000000 6.2296068365 7.9371190702 2.9204102389 0.5144241037 0.7163132254 -0.3804923022 0.27836812441 +1403638203645096960.0000000000 6.1575734349 8.0022842933 2.9125214983 0.5124291859 0.7177928306 -0.3806218837 0.278058920932 +1403638203695097088.0000000000 6.0859356568 8.0663376172 2.9066355968 0.5131478108 0.7173563739 -0.3810195616 0.277314353813 +1403638203745096960.0000000000 6.0147480238 8.1288193150 2.9027670767 0.5135418436 0.7170610393 -0.3808621649 0.27756486114 +1403638203795097088.0000000000 5.9441013604 8.1897760220 2.9003642344 0.5127837050 0.7176137570 -0.3798701193 0.278894353079 +1403638203845096960.0000000000 5.8741063782 8.2498549924 2.8996815771 0.5132640159 0.7174802897 -0.3796877247 0.278602432755 +1403638203895097088.0000000000 5.8043140353 8.3084023562 2.9005285915 0.5133241464 0.7175767252 -0.3787405976 0.27953089981 +1403638203945096960.0000000000 5.7347277107 8.3656652335 2.9025214152 0.5129344838 0.7181854273 -0.3788907800 0.278477439292 +1403638203995097088.0000000000 5.6656147536 8.4217594394 2.9063222620 0.5133374409 0.7182085602 -0.3788123007 0.277781167041 +1403638204045096960.0000000000 5.5963530115 8.4764996455 2.9115581571 0.5123519281 0.7193419683 -0.3794299703 0.275817932941 +1403638204095097088.0000000000 5.5272770189 8.5298506253 2.9188793810 0.5112376795 0.7204416059 -0.3795139810 0.274898282508 +1403638204145096960.0000000000 5.4588119631 8.5823694214 2.9281696274 0.5103773051 0.7215114063 -0.3809060659 0.271747798339 +1403638204195097088.0000000000 5.3912496405 8.6338085696 2.9396033385 0.5100379474 0.7218934738 -0.3830215913 0.26837579131 +1403638204245096960.0000000000 5.3247348352 8.6842952509 2.9525531198 0.5093168566 0.7225005576 -0.3857637100 0.264150797915 +1403638204295097088.0000000000 5.2595593772 8.7339703223 2.9669024936 0.5086714688 0.7228907979 -0.3900953462 0.257891163126 +1403638204345096960.0000000000 5.1958658065 8.7824070150 2.9817358962 0.5080570456 0.7229593747 -0.3953791864 0.250764989253 +1403638204395097088.0000000000 5.1344618485 8.8293383696 2.9968170993 0.5063375192 0.7237705624 -0.3995904819 0.245165120634 +1403638204445096960.0000000000 5.0754355256 8.8748287916 3.0114668250 0.5058753520 0.7235602727 -0.4026056545 0.241783678154 +1403638204495097088.0000000000 5.0188690202 8.9187955217 3.0248532606 0.5056148524 0.7233417229 -0.4042234125 0.240278600381 +1403638204545096960.0000000000 4.9645193776 8.9612736558 3.0369763178 0.5062586843 0.7225871460 -0.4050016034 0.239882600982 +1403638204595097088.0000000000 4.9125718774 9.0027182037 3.0478823710 0.5086911289 0.7214564536 -0.4040359865 0.239768310258 +1403638204645096960.0000000000 4.8624432380 9.0425484631 3.0563300774 0.5093371048 0.7223588480 -0.4017949015 0.239445746211 +1403638204695097088.0000000000 4.8140667491 9.0808551991 3.0627556556 0.5097418744 0.7244586134 -0.3971527895 0.239984584244 +1403638204745096960.0000000000 4.7674384284 9.1175499356 3.0672538484 0.5096448614 0.7278383330 -0.3902756185 0.24124348244 +1403638204795097088.0000000000 4.7224787994 9.1531841925 3.0700248131 0.5097306877 0.7318701391 -0.3817126283 0.242561734334 +1403638204845096960.0000000000 4.6786817922 9.1876790897 3.0709713931 0.5104485206 0.7364035842 -0.3699512822 0.245536387717 +1403638204895097088.0000000000 4.6357726443 9.2217068748 3.0701984255 0.5123720695 0.7410502114 -0.3563734950 0.247623461245 +1403638204945096960.0000000000 4.5929345525 9.2554767540 3.0676743281 0.5143368733 0.7465718315 -0.3430545230 0.245767523133 +1403638204995097088.0000000000 4.5500844431 9.2893209628 3.0639930728 0.5172170945 0.7521628190 -0.3288811938 0.242022170832 +1403638205045096960.0000000000 4.5076792194 9.3235122039 3.0591999578 0.5207085077 0.7580637969 -0.3129826636 0.237157715715 +1403638205095097088.0000000000 4.4649685455 9.3579134577 3.0535156180 0.5241427998 0.7646361981 -0.2964824080 0.229573499757 +1403638205145096960.0000000000 4.4213744831 9.3921688262 3.0483497961 0.5287511875 0.7709171675 -0.2798684790 0.218592170452 +1403638205195097088.0000000000 4.3774345358 9.4267742009 3.0448685863 0.5349317166 0.7762692095 -0.2616961344 0.206807413186 +1403638205245096960.0000000000 4.3333573615 9.4613136765 3.0429418699 0.5398561990 0.7823113542 -0.2421479085 0.194701360752 +1403638205295097088.0000000000 4.2892762636 9.4960861494 3.0434628399 0.5459767845 0.7870453201 -0.2225054798 0.181549790459 +1403638205345096960.0000000000 4.2403864628 9.5360678583 3.0375449460 0.5524972092 0.7908161198 -0.2029027692 0.1678903354 +1403638205395097088.0000000000 4.1962659385 9.5703605771 3.0411364556 0.5583982276 0.7941702375 -0.1819599240 0.156126997355 +1403638205445096960.0000000000 4.1527371989 9.6040623215 3.0466782693 0.5637438310 0.7966194147 -0.1625229388 0.145522147828 +1403638205495097088.0000000000 4.1095856757 9.6373072691 3.0533151073 0.5677741568 0.7986152273 -0.1423455752 0.139942712162 +1403638205545096960.0000000000 4.0661284181 9.6699550749 3.0613036825 0.5705927995 0.8002387588 -0.1250378385 0.135673597522 +1403638205595097088.0000000000 4.0221057275 9.7011548852 3.0716195333 0.5735680281 0.8006994543 -0.1089707763 0.134258969489 +1403638205645096960.0000000000 3.9769580589 9.7320153058 3.0829154118 0.5775136868 0.7995859309 -0.0952222840 0.13443584829 +1403638205695097088.0000000000 3.9299902130 9.7627432383 3.0963517938 0.5808965632 0.7984223207 -0.0834595711 0.134593761385 +1403638205745096960.0000000000 3.8807176961 9.7931486096 3.1113601147 0.5838963517 0.7973991776 -0.0734502568 0.133509032501 +1403638205795097088.0000000000 3.8283844366 9.8223144208 3.1269105485 0.5856082232 0.7975533340 -0.0649208221 0.129448736046 +1403638205845096960.0000000000 3.7728590856 9.8501282830 3.1439159756 0.5866040926 0.7983116731 -0.0564601292 0.124122379182 +1403638205895097088.0000000000 3.7144000197 9.8767457049 3.1616130450 0.5862921951 0.8000838898 -0.0480446684 0.117553991843 +1403638205945096960.0000000000 3.6529536423 9.9030449146 3.1807892120 0.5871487417 0.8011185361 -0.0396423237 0.109059306474 +1403638205995097088.0000000000 3.5886169296 9.9290504213 3.2015192424 0.5874495794 0.8026347525 -0.0321510532 0.0982178975665 +1403638206045096960.0000000000 3.5221861632 9.9534179568 3.2235946653 0.5875437978 0.8039230823 -0.0229879410 0.0892833575735 +1403638206095097088.0000000000 3.4536388028 9.9763643593 3.2472478829 0.5886862411 0.8042468013 -0.0140451490 0.0802391797594 +1403638206145096960.0000000000 3.3832742261 9.9980179777 3.2714471643 0.5903608248 0.8039527791 -0.0047676539 0.071493321446 +1403638206195097088.0000000000 3.3113663335 10.0187511233 3.2954830488 0.5914858465 0.8037907449 0.0043935877 0.0636052528053 +1403638206245096960.0000000000 3.2379853015 10.0384676276 3.3184507480 0.5929530855 0.8032078861 0.0130922788 0.055608653291 +1403638206295097088.0000000000 3.1631320105 10.0571375391 3.3401643266 0.5946885904 0.8023616231 0.0204124632 0.046310232395 +1403638206345096960.0000000000 3.0902351848 10.0684554135 3.3792560005 0.5962730693 0.8017018252 0.0240716700 0.0339582839178 +1403638206395097088.0000000000 3.0139609310 10.0839030822 3.4003899207 0.5971609440 0.8012490365 0.0274788193 0.0253713013268 +1403638206445096960.0000000000 2.9373791080 10.0981841755 3.4202034951 0.5984862356 0.8004079621 0.0294693896 0.0171135920499 +1403638206495097088.0000000000 2.8605960272 10.1110924412 3.4389733800 0.6002663280 0.7991036390 0.0313865603 0.0113399025747 +1403638206545096960.0000000000 2.7839742001 10.1225031193 3.4553897126 0.6015158329 0.7981703744 0.0326039402 0.00630391243597 +1403638206595097088.0000000000 2.7076977169 10.1322365507 3.4697661037 0.6025976580 0.7973079436 0.0341105539 0.00354623259336 +1403638206645096960.0000000000 2.6314102276 10.1405302152 3.4826948179 0.6038938916 0.7962762977 0.0354368916 0.000672357038177 +1403638206695097088.0000000000 2.5549944020 10.1467923469 3.4939089013 0.6046084169 0.7956348022 0.0374031965 -0.003863241074 +1403638206745096960.0000000000 2.4787177192 10.1511057245 3.5028025198 0.6037117651 0.7960776307 0.0418520990 -0.00639627579437 +1403638206795097088.0000000000 2.4027575358 10.1536309607 3.5103005501 0.6033809200 0.7961180590 0.0447509239 -0.0111739103662 +1403638206845096960.0000000000 2.3277136729 10.1547606736 3.5159399364 0.6029630863 0.7961780892 0.0486910827 -0.0128508890556 +1403638206895097088.0000000000 2.2530470917 10.1546493360 3.5205937478 0.6039798089 0.7951983212 0.0511511355 -0.0158613271909 +1403638206945096960.0000000000 2.1785175925 10.1530835695 3.5235533122 0.6053816648 0.7939689877 0.0527316871 -0.0185918188993 +1403638206995097088.0000000000 2.1046249161 10.1499772912 3.5249505247 0.6071228530 0.7924939389 0.0538064147 -0.0214491915354 +1403638207045096960.0000000000 2.0314641046 10.1449826330 3.5244811579 0.6083350095 0.7914397135 0.0548890666 -0.0232139303384 +1403638207095097088.0000000000 1.9592251166 10.1384261596 3.5222096593 0.6102311699 0.7898683240 0.0563523556 -0.0234597975829 +1403638207145096960.0000000000 1.8874683399 10.1297044712 3.5171936125 0.6104121803 0.7896553065 0.0567337861 -0.0249548507252 +1403638207195097088.0000000000 1.8162782546 10.1189996052 3.5105950504 0.6114492374 0.7887365934 0.0572143457 -0.0274031939955 +1403638207245096960.0000000000 1.7457200810 10.1061587180 3.5017113906 0.6117087769 0.7882750114 0.0599894576 -0.028916148139 +1403638207295097088.0000000000 1.6757022853 10.0911537498 3.4911011332 0.6128304044 0.7870001961 0.0637731307 -0.0316634567007 +1403638207345096960.0000000000 1.6061937928 10.0738071752 3.4790802090 0.6138995098 0.7856275068 0.0677784008 -0.0363717037289 +1403638207395097088.0000000000 1.5372650324 10.0543736315 3.4660226427 0.6156106790 0.7835278940 0.0738598048 -0.0406480060804 +1403638207445096960.0000000000 1.4690215733 10.0323465879 3.4535908751 0.6163058080 0.7819397946 0.0811828021 -0.0463320759062 +1403638207495097088.0000000000 1.4016207040 10.0071842953 3.4430788050 0.6167028348 0.7802936774 0.0899064926 -0.0523088243014 +1403638207545096960.0000000000 1.3347776535 9.9812908696 3.4307171621 0.6146120437 0.7804740759 0.0975971910 -0.0598919104802 +1403638207595097088.0000000000 1.2697964590 9.9518311040 3.4217552796 0.6109270645 0.7818782226 0.1065805560 -0.0638369167483 +1403638207645096960.0000000000 1.2059438679 9.9196302420 3.4144314987 0.6055453817 0.7846529199 0.1117140237 -0.071795284915 +1403638207695097088.0000000000 1.1439281359 9.8856743735 3.4084865002 0.5991452780 0.7882723241 0.1176709513 -0.0761920343431 +1403638207745096960.0000000000 1.0830940783 9.8506829847 3.4052488190 0.5948341532 0.7904215514 0.1210611359 -0.0821602256656 +1403638207795097088.0000000000 1.0239960449 9.8147252011 3.4038626157 0.5907916593 0.7924905517 0.1246621460 -0.0859260737032 +1403638207845096960.0000000000 0.9662941028 9.7780904257 3.4048016092 0.5860016012 0.7952886582 0.1269901910 -0.0893955533209 +1403638207895097088.0000000000 0.9100881325 9.7413223033 3.4076202388 0.5807543627 0.7985440236 0.1290717244 -0.0916095109208 +1403638207945096960.0000000000 0.8549270159 9.7040180707 3.4125262633 0.5772200855 0.8006856168 0.1306430224 -0.0930156796335 +1403638207995097088.0000000000 0.8012179794 9.6672102359 3.4183924432 0.5758508843 0.8014548896 0.1319796313 -0.0929903002499 +1403638208045096960.0000000000 0.7488269790 9.6298173312 3.4240477807 0.5744981588 0.8022784885 0.1324758918 -0.0935480118502 +1403638208095097088.0000000000 0.6977874368 9.5925863270 3.4290345216 0.5769956025 0.8004688047 0.1326149003 -0.0934829162368 +1403638208145096960.0000000000 0.6475092767 9.5539329434 3.4333008455 0.5790177686 0.7990500439 0.1307260702 -0.0957504340234 +1403638208195097088.0000000000 0.5986749150 9.5159998893 3.4356910908 0.5828714370 0.7963058155 0.1299871641 -0.0962355092528 +1403638208245096960.0000000000 0.5512336941 9.4775697631 3.4358289953 0.5849509425 0.7949801127 0.1294907887 -0.0952425900911 +1403638208295097088.0000000000 0.5048523256 9.4386809330 3.4341337390 0.5856388767 0.7946638814 0.1289275839 -0.0944145103541 +1403638208345096960.0000000000 0.4595973487 9.3993811129 3.4303259796 0.5835755463 0.7963290257 0.1289074965 -0.0931800506851 +1403638208395097088.0000000000 0.4154333251 9.3596230724 3.4249416055 0.5815338308 0.7979778704 0.1286851142 -0.0921404545355 +1403638208445096960.0000000000 0.3722990608 9.3193691383 3.4182090639 0.5795119768 0.7994096426 0.1296040919 -0.0911749497567 +1403638208495097088.0000000000 0.3299366855 9.2786528841 3.4120748107 0.5777334390 0.8003410293 0.1310710775 -0.0921883020494 +1403638208545096960.0000000000 0.2882847821 9.2373897241 3.4071437719 0.5758273520 0.8009614803 0.1338438966 -0.0947068058501 +1403638208595097088.0000000000 0.2476924286 9.1957040975 3.4035756399 0.5740494745 0.8010580359 0.1392753363 -0.0968277057854 +1403638208645096960.0000000000 0.2077316220 9.1542470194 3.4020587799 0.5738098763 0.7998485395 0.1444069376 -0.100653743486 +1403638208695097088.0000000000 0.1684923134 9.1133406220 3.4023932437 0.5731353527 0.7990459360 0.1485356543 -0.10477890554 +1403638208745096960.0000000000 0.1303915871 9.0724301220 3.4047471323 0.5723374919 0.7983347361 0.1520029136 -0.109483143931 +1403638208795097088.0000000000 0.0936769789 9.0321547010 3.4086296498 0.5721099346 0.7972720724 0.1559395755 -0.11282869379 +1403638208845096960.0000000000 0.0581619642 8.9923647063 3.4127904590 0.5726762684 0.7958062646 0.1591032837 -0.115846561901 +1403638208895097088.0000000000 0.0236738177 8.9530607776 3.4159992471 0.5730115323 0.7945897590 0.1632662224 -0.116743476756 +1403638208945096960.0000000000 -0.0099520555 8.9138582619 3.4181639111 0.5735532173 0.7933211650 0.1663413440 -0.118358748504 +1403638208995097088.0000000000 -0.0424269789 8.8746109098 3.4185145961 0.5736664525 0.7925656285 0.1687343294 -0.119479085291 +1403638209045096960.0000000000 -0.0738976468 8.8352130842 3.4172558734 0.5735545756 0.7920676520 0.1704038480 -0.120940117723 +1403638209095097088.0000000000 -0.1045382570 8.7957885373 3.4143632217 0.5730444795 0.7918839645 0.1715591578 -0.122911621119 +1403638209145096960.0000000000 -0.1340484574 8.7563103420 3.4097579827 0.5728761468 0.7916709027 0.1728993510 -0.123190570834 +1403638209195097088.0000000000 -0.1625013777 8.7164258493 3.4036909703 0.5723303001 0.7917818960 0.1737410864 -0.123828476943 +1403638209245096960.0000000000 -0.1899813473 8.6763300104 3.3962606920 0.5723323736 0.7916063301 0.1739481680 -0.124647932449 +1403638209295097088.0000000000 -0.2167470576 8.6362989068 3.3871993944 0.5718173609 0.7918023996 0.1735874159 -0.126258761062 +1403638209345096960.0000000000 -0.2424612746 8.5960422679 3.3765070381 0.5708752032 0.7924089426 0.1736507170 -0.126629374487 +1403638209395097088.0000000000 -0.2674585812 8.5553920184 3.3646230863 0.5710758810 0.7921685215 0.1731516316 -0.12790576248 +1403638209445096960.0000000000 -0.2914207686 8.5146745733 3.3508570180 0.5705476189 0.7924618923 0.1732291104 -0.128340325926 +1403638209495097088.0000000000 -0.3144846220 8.4748532390 3.3359538764 0.5723904631 0.7911687679 0.1723061381 -0.129351201068 +1403638209545096960.0000000000 -0.3366772747 8.4354230523 3.3177395446 0.5741819692 0.7898868523 0.1721934016 -0.129395746708 +1403638209595097088.0000000000 -0.3578321043 8.3962115159 3.2951830592 0.5751913992 0.7892513103 0.1713309604 -0.129934311798 +1403638209645096960.0000000000 -0.3781889096 8.3568833238 3.2675469722 0.5748430141 0.7896310153 0.1703853539 -0.130411655778 +1403638209695097088.0000000000 -0.3974411465 8.3178187135 3.2352820747 0.5738876379 0.7905083077 0.1699052592 -0.129929970974 +1403638209745096960.0000000000 -0.4156757088 8.2789430177 3.1982252645 0.5737283737 0.7907418429 0.1700317700 -0.129043745628 +1403638209795097088.0000000000 -0.4328445295 8.2403291313 3.1566849116 0.5749223347 0.7899811784 0.1716276898 -0.126245724136 +1403638209845096960.0000000000 -0.4494942064 8.2017825676 3.1112563488 0.5756167521 0.7895609907 0.1723477575 -0.124719874603 +1403638209895097088.0000000000 -0.4651090058 8.1629009359 3.0635448712 0.5775460107 0.7882671068 0.1728591805 -0.123269126388 +1403638209945096960.0000000000 -0.4800406900 8.1238242377 3.0146477854 0.5803275146 0.7863049045 0.1727918135 -0.122831438302 +1403638209995097088.0000000000 -0.4942393881 8.0843647069 2.9647284241 0.5834011073 0.7840701845 0.1728294006 -0.122503437267 +1403638210045096960.0000000000 -0.5076696351 8.0444048268 2.9150355127 0.5869275138 0.7814920811 0.1725338521 -0.122549135652 +1403638210095097088.0000000000 -0.5203436861 8.0038689125 2.8667326425 0.5901845937 0.7790968823 0.1716491223 -0.123396807821 +1403638210145096960.0000000000 -0.5318217367 7.9621286917 2.8203667357 0.5926093776 0.7772701012 0.1706179163 -0.124719052163 +1403638210195097088.0000000000 -0.5428365785 7.9157098894 2.7776007037 0.5959259268 0.7747389283 0.1702346506 -0.125188044512 +1403638210245096960.0000000000 -0.5520694961 7.8733778941 2.7340042634 0.5958354114 0.7748059284 0.1693273055 -0.126428633674 +1403638210295097088.0000000000 -0.5595395450 7.8290587547 2.6915049626 0.5957958999 0.7748564148 0.1695051118 -0.126066645521 +1403638210345096960.0000000000 -0.5654711927 7.7833777647 2.6501568538 0.5959987940 0.7747372664 0.1702543276 -0.124824154495 +1403638210395097088.0000000000 -0.5704252714 7.7361709405 2.6085195838 0.5948884593 0.7756167055 0.1695820417 -0.125572203114 +1403638210445096960.0000000000 -0.5740797490 7.6880211059 2.5659541156 0.5946895237 0.7757853835 0.1698520201 -0.125106756179 +1403638210495097088.0000000000 -0.5767869506 7.6388259389 2.5225712262 0.5951491679 0.7754690360 0.1686529148 -0.126496784803 +1403638210545096960.0000000000 -0.5782221349 7.5889339470 2.4776382007 0.5955711851 0.7752087127 0.1686363116 -0.126127751581 +1403638210595097088.0000000000 -0.5785067289 7.5379051309 2.4312107176 0.5961737841 0.7748493701 0.1683208299 -0.125910170631 +1403638210645096960.0000000000 -0.5780192363 7.4859137048 2.3838158591 0.5972248245 0.7740799972 0.1675639101 -0.126668871058 +1403638210695097088.0000000000 -0.5762077202 7.4322447095 2.3358942497 0.5970385802 0.7742918217 0.1660648915 -0.128216849457 +1403638210745096960.0000000000 -0.5727221830 7.3769718348 2.2887656399 0.5973258504 0.7741160488 0.1660454705 -0.127965124631 +1403638210795097088.0000000000 -0.5677056109 7.3196470211 2.2428890236 0.5972866548 0.7741943997 0.1657450617 -0.128063492387 +1403638210845096960.0000000000 -0.5611235729 7.2598765601 2.1987492979 0.5957837130 0.7753680159 0.1655756875 -0.128183068063 +1403638210895097088.0000000000 -0.5535232477 7.1995295436 2.1561928850 0.5931656143 0.7772888605 0.1649918295 -0.129438315861 +1403638210945096960.0000000000 -0.5442236510 7.1383318679 2.1152765209 0.5903148930 0.7794666688 0.1658623901 -0.128256410216 +1403638210995097088.0000000000 -0.5335700598 7.0755092598 2.0761848623 0.5877758728 0.7813007331 0.1656087966 -0.129082974431 +1403638211045096960.0000000000 -0.5215592611 7.0115064168 2.0389460529 0.5855233378 0.7829240679 0.1656852966 -0.129385884883 +1403638211095097088.0000000000 -0.5083926711 6.9468658765 2.0043159180 0.5832403591 0.7845841802 0.1659705903 -0.12927532956 +1403638211145096960.0000000000 -0.4942998684 6.8822979517 1.9723479885 0.5810618410 0.7861255514 0.1661590681 -0.129479412795 +1403638211195097088.0000000000 -0.4792659453 6.8178938934 1.9417130502 0.5789484472 0.7875991118 0.1656489247 -0.130639841622 +1403638211245096960.0000000000 -0.4633344499 6.7543973589 1.9129635098 0.5779675808 0.7883058726 0.1660411079 -0.130221646757 +1403638211295097088.0000000000 -0.4467497520 6.6918674962 1.8863591907 0.5774049499 0.7889003212 0.1657600238 -0.129473632207 +1403638211345096960.0000000000 -0.4284767998 6.6290752010 1.8612680345 0.5770015990 0.7897593081 0.1640272878 -0.128235872104 +1403638211395097088.0000000000 -0.4090598634 6.5663285331 1.8355621286 0.5778723072 0.7901922657 0.1608739811 -0.12561585087 +1403638211445096960.0000000000 -0.3886365517 6.5036460580 1.8083432112 0.5773381838 0.7919671702 0.1561554689 -0.122817312718 +1403638211495097088.0000000000 -0.3668368528 6.4402233139 1.7803512334 0.5781723578 0.7929998343 0.1506453364 -0.119054483743 +1403638211545096960.0000000000 -0.3441541889 6.3771012726 1.7510018991 0.5785130409 0.7945722896 0.1439857077 -0.115089765457 +1403638211595097088.0000000000 -0.3204227611 6.3145364266 1.7204240843 0.5794405328 0.7959268069 0.1351428662 -0.11173894927 +1403638211645096960.0000000000 -0.2955080607 6.2522712485 1.6885355380 0.5808504673 0.7970239919 0.1256393274 -0.107611572105 +1403638211695097088.0000000000 -0.2691532690 6.1902859107 1.6546861466 0.5825451463 0.7981175694 0.1147042081 -0.102432624742 +1403638211745096960.0000000000 -0.2418108014 6.1290799448 1.6199531288 0.5823837855 0.8005341241 0.1032085189 -0.0965517691295 +1403638211795097088.0000000000 -0.2129269529 6.0680657007 1.5851160609 0.5828504796 0.8024649972 0.0901937948 -0.0905556519765 +1403638211845096960.0000000000 -0.1831173762 6.0073286202 1.5506142525 0.5822673728 0.8048615876 0.0762104681 -0.0857583575618 +1403638211895097088.0000000000 -0.1516560839 5.9474478632 1.5175572674 0.5828319201 0.8062407766 0.0632501431 -0.0792602203978 +1403638211945096960.0000000000 -0.1183449818 5.8876432591 1.4860826100 0.5833892605 0.8074428405 0.0507925703 -0.0715062575011 +1403638211995097088.0000000000 -0.0834360636 5.8276700891 1.4566035623 0.5834266715 0.8087217829 0.0386977239 -0.0639130892821 +1403638212045096960.0000000000 -0.0469660627 5.7673943725 1.4285290007 0.5839188927 0.8093992813 0.0269879923 -0.0564196629391 +1403638212095097088.0000000000 -0.0086197889 5.7077874542 1.4021326072 0.5845012924 0.8098580264 0.0165570354 -0.0470540212019 +1403638212145096960.0000000000 0.0310558036 5.6483550571 1.3777362345 0.5848922366 0.8102075692 0.0065855961 -0.0377014106545 +1403638212195097088.0000000000 0.0722741787 5.5891174476 1.3554876738 0.5860570980 0.8098050640 -0.0029057244 -0.0272835653798 +1403638212245096960.0000000000 0.1144206897 5.5296540308 1.3350806261 0.5860773132 0.8099287148 -0.0137231494 -0.0184535886422 +1403638212295097088.0000000000 0.1576316313 5.4694529983 1.3176587590 0.5864718430 0.8095534330 -0.0240457016 -0.00978880468594 +1403638212345096960.0000000000 0.2018244096 5.4090074114 1.3013248795 0.5855738089 0.8098942993 -0.0342480836 -0.00126770033256 +1403638212395097088.0000000000 0.2468750481 5.3498798842 1.2859431114 0.5864292582 0.8087733537 -0.0436669387 0.0089210897748 +1403638212445096960.0000000000 0.2928063436 5.2902483668 1.2729991300 0.5854027407 0.8087519604 -0.0540995839 0.01723753735 +1403638212495097088.0000000000 0.3396694459 5.2299230729 1.2633518985 0.5865415048 0.8069128311 -0.0651999758 0.024692291014 +1403638212545096960.0000000000 0.3871066132 5.1689188738 1.2546225831 0.5857194951 0.8062613515 -0.0769345198 0.0309254873429 +1403638212595097088.0000000000 0.4355130491 5.1084190581 1.2470537817 0.5845898349 0.8056597506 -0.0871998331 0.0395383392242 +1403638212645096960.0000000000 0.4843719708 5.0470638000 1.2412812653 0.5835549201 0.8046782438 -0.0994061346 0.0455521631083 +1403638212695097088.0000000000 0.5341644474 4.9852404202 1.2370806571 0.5821915311 0.8037729475 -0.1100110745 0.0538482446174 +1403638212745096960.0000000000 0.5845545210 4.9234910111 1.2348734477 0.5795176299 0.8035653668 -0.1200637373 0.0634564175285 +1403638212795097088.0000000000 0.6355571706 4.8616746572 1.2355752990 0.5796288522 0.8010001092 -0.1316501306 0.0713965121943 +1403638212845096960.0000000000 0.6873104997 4.7993269325 1.2368527285 0.5779408009 0.7994315425 -0.1433466093 0.0796579502574 +1403638212895097088.0000000000 0.7395180822 4.7371163391 1.2394385440 0.5760485582 0.7976479826 -0.1563544991 0.0864813572052 +1403638212945096960.0000000000 0.7926397500 4.6749002829 1.2434684842 0.5744296024 0.7953482918 -0.1682820847 0.0955660322651 +1403638212995097088.0000000000 0.8465731228 4.6129892561 1.2490785971 0.5712533305 0.7937983302 -0.1808207744 0.104200244242 +1403638213045096960.0000000000 0.9013495501 4.5513461230 1.2573989920 0.5695984912 0.7907429115 -0.1937213958 0.112939043235 +1403638213095097088.0000000000 0.9565914240 4.4894349487 1.2661540217 0.5668793783 0.7881518818 -0.2070542069 0.120801229356 +1403638213145096960.0000000000 1.0121937266 4.4274485878 1.2752538154 0.5637279523 0.7854808122 -0.2214096817 0.127312380753 +1403638213195097088.0000000000 1.0684827033 4.3650191215 1.2827083659 0.5588247344 0.7837488831 -0.2360325637 0.133196220739 +1403638213245096960.0000000000 1.1252664688 4.3019299061 1.2894219094 0.5528178113 0.7824403330 -0.2516208888 0.137355455449 +1403638213295097088.0000000000 1.1832101628 4.2388137140 1.2944444936 0.5470746567 0.7805267883 -0.2676606561 0.140872374411 +1403638213345096960.0000000000 1.2421699483 4.1754771657 1.2976726893 0.5404874829 0.7788612308 -0.2838533822 0.143790546963 +1403638213395097088.0000000000 1.3028159250 4.1121905659 1.2997636385 0.5352630969 0.7758727346 -0.2998729845 0.146939137197 +1403638213445096960.0000000000 1.3654109485 4.0488058731 1.3005518792 0.5302914319 0.7725111404 -0.3157788905 0.149335955636 +1403638213495097088.0000000000 1.4307284273 3.9854686913 1.3000945105 0.5273042241 0.7676197098 -0.3303714177 0.15350883625 +1403638213545096960.0000000000 1.4988278647 3.9219715524 1.2977751374 0.5245948922 0.7629930408 -0.3421829008 0.159852060258 +1403638213595097088.0000000000 1.5698811636 3.8583843217 1.2944499431 0.5248847328 0.7574076623 -0.3484513638 0.17149722258 +1403638213645096960.0000000000 1.6430050369 3.7943919814 1.2909633195 0.5266280194 0.7518243234 -0.3506148819 0.18572108244 +1403638213695097088.0000000000 1.7172679494 3.7301262697 1.2887890436 0.5290731402 0.7464998745 -0.3511522918 0.198775294455 +1403638213745096960.0000000000 1.7922227181 3.6650436789 1.2874106826 0.5306919457 0.7424242099 -0.3501574298 0.211097431661 +1403638213795097088.0000000000 1.8675817990 3.5998447407 1.2876040012 0.5313174282 0.7394855583 -0.3492815063 0.221055035761 +1403638213845096960.0000000000 1.9429890158 3.5343790191 1.2895427172 0.5310912186 0.7377273791 -0.3484433582 0.228664946639 +1403638213895097088.0000000000 2.0181970826 3.4691845520 1.2932610351 0.5311121021 0.7363891835 -0.3485966963 0.232661231849 +1403638213945096960.0000000000 2.0930307144 3.4033180896 1.2977208381 0.5289369362 0.7370021813 -0.3477295801 0.236933833306 +1403638213995097088.0000000000 2.1667098206 3.3372224502 1.3040464350 0.5285200386 0.7370078869 -0.3486091230 0.236553636238 +1403638214045096960.0000000000 2.2398193820 3.2707683463 1.3110773976 0.5248024602 0.7396012180 -0.3485709882 0.236792487761 +1403638214095097088.0000000000 2.3125060588 3.2046417107 1.3188598065 0.5198815931 0.7432866475 -0.3487848884 0.23579056477 +1403638214145096960.0000000000 2.3849693052 3.1386492507 1.3288648852 0.5160798499 0.7464329137 -0.3491153677 0.233704843485 +1403638214195097088.0000000000 2.4573761434 3.0739350841 1.3394403765 0.5110246529 0.7507298567 -0.3490082033 0.231196367633 +1403638214245096960.0000000000 2.5302103365 3.0101375335 1.3502439703 0.5077348789 0.7538339499 -0.3485093930 0.229087039706 +1403638214295097088.0000000000 2.6028464556 2.9472027773 1.3593206194 0.5046573998 0.7568333189 -0.3481941993 0.226461996489 +1403638214345096960.0000000000 2.6764572756 2.8858073318 1.3671702615 0.5022822890 0.7594061233 -0.3473651232 0.224393211234 +1403638214395097088.0000000000 2.7509174228 2.8256263140 1.3731657338 0.5005825583 0.7615714073 -0.3458479789 0.223193345431 +1403638214445096960.0000000000 2.8263678673 2.7671188631 1.3781487728 0.5007919739 0.7625523848 -0.3438031049 0.222532434617 +1403638214495097088.0000000000 2.9028611734 2.7100429702 1.3824416907 0.5041189441 0.7614093969 -0.3409963150 0.223251727087 +1403638214545096960.0000000000 2.9799928816 2.6543775673 1.3852576396 0.5087521785 0.7592332242 -0.3381666102 0.224453727614 +1403638214595097088.0000000000 3.0577535076 2.5999326714 1.3865882329 0.5131959017 0.7570902625 -0.3351577388 0.226083150505 +1403638214645096960.0000000000 3.1355646541 2.5467205391 1.3866320540 0.5181120020 0.7546045575 -0.3325113909 0.227086085144 +1403638214695097088.0000000000 3.2131719362 2.4940703241 1.3854392619 0.5227229293 0.7522734792 -0.3296171448 0.228468574395 +1403638214745096960.0000000000 3.2901950650 2.4418818996 1.3831280614 0.5271227069 0.7500430497 -0.3269303897 0.229550856691 +1403638214795097088.0000000000 3.3664165812 2.3899581422 1.3794184367 0.5303158188 0.7486057603 -0.3248773725 0.229802612726 +1403638214845096960.0000000000 3.4418376043 2.3382210958 1.3744647189 0.5330219904 0.7474331098 -0.3227109050 0.230410451259 +1403638214895097088.0000000000 3.5165371172 2.2864887057 1.3679079906 0.5347378472 0.7468432467 -0.3211402065 0.230541899682 +1403638214945096960.0000000000 3.5906195375 2.2350967690 1.3599080394 0.5366119682 0.7460072519 -0.3196456382 0.230970651135 +1403638214995097088.0000000000 3.6638994069 2.1840041852 1.3505289761 0.5374381991 0.7458541109 -0.3188018031 0.230710289815 +1403638215045096960.0000000000 3.7365319303 2.1332345291 1.3399491506 0.5380755453 0.7457476069 -0.3182448696 0.23033761595 +1403638215095097088.0000000000 3.8082025523 2.0823462317 1.3280725622 0.5375858126 0.7464374804 -0.3169507478 0.231029879849 +1403638215145096960.0000000000 3.8789163249 2.0314789967 1.3152919019 0.5375581122 0.7466614415 -0.3166529607 0.230778834193 +1403638215195097088.0000000000 3.9486867448 1.9804998999 1.3011906652 0.5359526375 0.7479350746 -0.3165119723 0.230582015738 +1403638215245096960.0000000000 4.0177970874 1.9296565506 1.2863249385 0.5343144266 0.7490900454 -0.3160467146 0.231271856487 +1403638215295097088.0000000000 4.0863770432 1.8790862675 1.2708474625 0.5321239568 0.7506446229 -0.3149481477 0.232775447558 +1403638215345096960.0000000000 4.1542046405 1.8289863339 1.2550344129 0.5306425720 0.7515559460 -0.3142316055 0.234180739715 +1403638215395097088.0000000000 4.2213339606 1.7795343818 1.2392844760 0.5296991309 0.7521211922 -0.3128645493 0.236322484585 +1403638215445096960.0000000000 4.2875435161 1.7308734127 1.2254708024 0.5292144200 0.7524450653 -0.3105375855 0.239426250136 +1403638215495097088.0000000000 4.3522074485 1.6827195555 1.2137608472 0.5286857537 0.7527878349 -0.3101049368 0.24007660781 +1403638215545096960.0000000000 4.4153227179 1.6353838462 1.2042263703 0.5284592084 0.7528670024 -0.3101229656 0.240303741045 +1403638215595097088.0000000000 4.4772166600 1.5886488637 1.1967082755 0.5297178755 0.7519050705 -0.3089021071 0.24210994524 +1403638215645096960.0000000000 4.5372097240 1.5427190060 1.1910763949 0.5312454232 0.7509253068 -0.3094878444 0.241053434178 +1403638215695097088.0000000000 4.5955232727 1.4973264215 1.1869375399 0.5319166895 0.7504394965 -0.3106153607 0.239631582399 +1403638215745096960.0000000000 4.6522515864 1.4526977065 1.1836309321 0.5334340739 0.7493620028 -0.3122403639 0.237509226503 +1403638215795097088.0000000000 4.7081250750 1.4083324526 1.1794052206 0.5335924188 0.7485246298 -0.3140806469 0.237367555695 +1403638215845096960.0000000000 4.7629532249 1.3639186439 1.1738876027 0.5335724165 0.7472283654 -0.3176085536 0.236801716331 +1403638215895097088.0000000000 4.8166218891 1.3197263065 1.1669327666 0.5329202220 0.7464155945 -0.3194943278 0.238292198251 +1403638215945096960.0000000000 4.8694112415 1.2755566790 1.1586317695 0.5327392607 0.7452833424 -0.3218064199 0.239128099106 +1403638215995097088.0000000000 4.9213418675 1.2314599176 1.1491014511 0.5325141250 0.7443739937 -0.3238197771 0.239743229589 +1403638216045096960.0000000000 4.9728395213 1.1875137287 1.1382622100 0.5320981051 0.7436778327 -0.3255173446 0.24052722524 +1403638216095097088.0000000000 5.0237127775 1.1440530327 1.1272827489 0.5313277815 0.7432910244 -0.3257507047 0.243096112758 +1403638216145096960.0000000000 5.0733562202 1.1008971258 1.1175547762 0.5307163121 0.7429728341 -0.3270778983 0.243621863291 +1403638216195097088.0000000000 5.1218721218 1.0578725684 1.1093601361 0.5302923744 0.7426536513 -0.3271709338 0.245386902455 +1403638216245096960.0000000000 5.1693138276 1.0151268718 1.1030577402 0.5310799565 0.7414357958 -0.3274060566 0.247047191094 +1403638216295097088.0000000000 5.2156769765 0.9726889801 1.0983790413 0.5306998896 0.7411559304 -0.3277261896 0.248276174337 +1403638216345096960.0000000000 5.2613759562 0.9309034353 1.0954476205 0.5312850329 0.7403398423 -0.3276158499 0.249601655943 +1403638216395097088.0000000000 5.3056631776 0.8892274038 1.0942139889 0.5317218834 0.7396217343 -0.3276022060 0.250815317381 +1403638216445096960.0000000000 5.3485442649 0.8478983055 1.0949153860 0.5320876572 0.7390359027 -0.3277031597 0.251633262145 +1403638216495097088.0000000000 5.3898384254 0.8068565839 1.0960979462 0.5320361970 0.7389597023 -0.3279157779 0.251688867546 +1403638216545096960.0000000000 5.4298568698 0.7657924296 1.0963309797 0.5312503394 0.7393050919 -0.3280031536 0.252220120529 +1403638216595097088.0000000000 5.4687607000 0.7250083313 1.0946088438 0.5301891455 0.7398474017 -0.3276630072 0.253302676449 +1403638216645096960.0000000000 5.5060257849 0.6839286197 1.0915103819 0.5280566763 0.7411637603 -0.3271507967 0.254567836179 +1403638216695097088.0000000000 5.5424183701 0.6436310684 1.0859458150 0.5266710048 0.7420969662 -0.3269205192 0.255015136032 +1403638216745096960.0000000000 5.5778305927 0.6036721948 1.0788235659 0.5253818165 0.7430508173 -0.3259038342 0.256195473648 +1403638216795097088.0000000000 5.6123488273 0.5645043128 1.0712173049 0.5263512242 0.7418207051 -0.3252236098 0.258623343564 +1403638216845096960.0000000000 5.6457872386 0.5261999427 1.0627181000 0.5282507993 0.7391278989 -0.3260113975 0.261452884528 +1403638216895097088.0000000000 5.6779323827 0.4883912629 1.0532059747 0.5292110110 0.7365219473 -0.3280037080 0.264357134465 +1403638216945096960.0000000000 5.7084438549 0.4506477243 1.0431107175 0.5290335922 0.7341233951 -0.3318074776 0.266627262228 +1403638216995097088.0000000000 5.7376956821 0.4130722572 1.0323804346 0.5284501380 0.7315469487 -0.3373739392 0.267877469505 +1403638217045096960.0000000000 5.7653147363 0.3752367234 1.0201988596 0.5265001987 0.7293313932 -0.3444502076 0.268751398254 +1403638217095097088.0000000000 5.7917140771 0.3373747412 1.0070268113 0.5233683637 0.7275070371 -0.3517869520 0.270305396253 +1403638217145096960.0000000000 5.8171133835 0.2995542717 0.9930976859 0.5200318015 0.7254428349 -0.3594797855 0.272165211767 +1403638217195097088.0000000000 5.8416304749 0.2620304145 0.9783602107 0.5169802890 0.7235791033 -0.3659099406 0.274362128211 +1403638217245096960.0000000000 5.8652810736 0.2249564042 0.9633807933 0.5135289167 0.7224893905 -0.3706548737 0.277330302916 +1403638217295097088.0000000000 5.8880875625 0.1885537196 0.9500648202 0.5111286123 0.7211895520 -0.3750142642 0.279280277487 +1403638217345096960.0000000000 5.9102111809 0.1526151601 0.9380355324 0.5087386951 0.7202635551 -0.3780564808 0.28191957814 +1403638217395097088.0000000000 5.9311309399 0.1172152090 0.9284452264 0.5062780167 0.7197406500 -0.3813078691 0.283302445195 +1403638217445096960.0000000000 5.9510812765 0.0821208650 0.9212568382 0.5049105829 0.7189458671 -0.3834514873 0.284863301135 +1403638217495097088.0000000000 5.9704318506 0.0473490711 0.9158352128 0.5028408050 0.7189329436 -0.3842979759 0.28740496367 +1403638217545096960.0000000000 5.9896016610 0.0131875038 0.9124189803 0.5003400398 0.7193711133 -0.3843730354 0.290555357214 +1403638217595097088.0000000000 6.0078006867 -0.0203708765 0.9109224041 0.4982786194 0.7199911309 -0.3840627626 0.292962426203 +1403638217645096960.0000000000 6.0254336673 -0.0530020401 0.9111937526 0.4960480678 0.7209870401 -0.3822220445 0.296682172053 +1403638217695097088.0000000000 6.0421835823 -0.0845660950 0.9135888898 0.4940559296 0.7217535083 -0.3804337375 0.30041768112 +1403638217745096960.0000000000 6.0578711231 -0.1149611670 0.9179405253 0.4916732941 0.7232663929 -0.3785477716 0.303058874611 +1403638217795097088.0000000000 6.0716994137 -0.1441680507 0.9239195776 0.4894755961 0.7247751497 -0.3767227688 0.30527787134 +1403638217845096960.0000000000 6.0843264688 -0.1716157294 0.9315019791 0.4874776894 0.7261145170 -0.3753677447 0.306956457324 +1403638217895097088.0000000000 6.0958330604 -0.1970013182 0.9400199975 0.4878663487 0.7261388265 -0.3745971249 0.307222760325 +1403638217945096960.0000000000 6.1067450735 -0.2206650641 0.9476662593 0.4884724827 0.7258925791 -0.3721026482 0.309861608454 +1403638217995097088.0000000000 6.1163100026 -0.2424039280 0.9541123199 0.4905466354 0.7250568355 -0.3712916292 0.309514312853 +1403638218045096960.0000000000 6.1248949543 -0.2627413770 0.9588069152 0.4914786574 0.7248486049 -0.3698170860 0.31028785362 +1403638218095097088.0000000000 6.1322342978 -0.2813981797 0.9620550948 0.4925041737 0.7244716153 -0.3688641548 0.310676282918 +1403638218145096960.0000000000 6.1384818407 -0.2984317026 0.9640534058 0.4944390156 0.7236294300 -0.3689593603 0.309450316571 +1403638218195097088.0000000000 6.1433519459 -0.3143344195 0.9643926781 0.4960291094 0.7229793199 -0.3679581363 0.309617240339 +1403638218245096960.0000000000 6.1468663921 -0.3288293670 0.9635688487 0.4988839172 0.7215892187 -0.3666677149 0.309804169517 +1403638218295097088.0000000000 6.1490080269 -0.3421335507 0.9617741260 0.5020133449 0.7200443605 -0.3654738844 0.309754031831 +1403638218345096960.0000000000 6.1493825223 -0.3540561356 0.9603301999 0.5060282332 0.7179062873 -0.3658103937 0.307780353088 +1403638218395097088.0000000000 6.1480387335 -0.3650469539 0.9594853732 0.5079845559 0.7172994280 -0.3665233069 0.305112908668 +1403638218445096960.0000000000 6.1443549477 -0.3755579815 0.9605605590 0.5094175746 0.7169681737 -0.3673398492 0.302509186359 +1403638218495097088.0000000000 6.1399363751 -0.3849395919 0.9634231414 0.5101832452 0.7168899950 -0.3682855590 0.300245796772 +1403638218545096960.0000000000 6.1337289902 -0.3938223272 0.9683856092 0.5096900273 0.7175874138 -0.3681743812 0.29955300827 +1403638218595097088.0000000000 6.1257114054 -0.4022939490 0.9754906880 0.5098604017 0.7177979842 -0.3690047090 0.297731337538 +1403638218645096960.0000000000 6.1162006965 -0.4106376877 0.9833338062 0.5085031510 0.7190709412 -0.3698516384 0.295924470982 +1403638218695097088.0000000000 6.1055102114 -0.4189642230 0.9907856660 0.5059310855 0.7206695139 -0.3721950822 0.293496182892 +1403638218745096960.0000000000 6.0943128383 -0.4272370494 0.9972167486 0.5018504863 0.7221524750 -0.3748384656 0.293492788631 +1403638218795097088.0000000000 6.0827627175 -0.4348722369 1.0028548606 0.4980793127 0.7226113077 -0.3788779161 0.293600784987 +1403638218845096960.0000000000 6.0708682873 -0.4417502577 1.0072654299 0.4945085443 0.7225556991 -0.3825852253 0.294962890311 +1403638218895097088.0000000000 6.0587123016 -0.4477322805 1.0102254966 0.4927245625 0.7213521548 -0.3867753546 0.295429178181 +1403638218945096960.0000000000 6.0457688582 -0.4520673863 1.0128044414 0.4940316960 0.7184439371 -0.3937069072 0.291145777606 +1403638218995097088.0000000000 6.0328526740 -0.4558347508 1.0141690046 0.4961759487 0.7150489336 -0.4004070359 0.286685639756 +1403638219045096960.0000000000 6.0199938429 -0.4592789553 1.0144508018 0.4987159436 0.7114599591 -0.4062630901 0.282944227353 +1403638219095097088.0000000000 6.0076695945 -0.4629571944 1.0137885243 0.5012188516 0.7080807042 -0.4105740080 0.280767453785 +1403638219145096960.0000000000 5.9959116203 -0.4670944060 1.0120165917 0.5017541499 0.7062464470 -0.4125327384 0.281558997126 +1403638219195097088.0000000000 5.9845705465 -0.4718690500 1.0093815741 0.5023278244 0.7048205079 -0.4116965795 0.285308140316 +1403638219245096960.0000000000 5.9734847701 -0.4774322801 1.0061697271 0.5035401154 0.7030109136 -0.4090776667 0.291339098436 +1403638219295097088.0000000000 5.9622104582 -0.4831650722 1.0020981419 0.5057154026 0.7005654678 -0.4068521256 0.296532131193 +1403638219345096960.0000000000 5.9506204186 -0.4890971302 0.9975961905 0.5078844695 0.6983741258 -0.4035795576 0.302407815258 +1403638219395097088.0000000000 5.9380043904 -0.4952229986 0.9941524032 0.5124990722 0.6945058625 -0.4014716786 0.306311604816 +1403638219445096960.0000000000 5.9255774174 -0.5017261588 0.9919905465 0.5154653207 0.6919224070 -0.3989206121 0.310485476476 +1403638219495097088.0000000000 5.9113176553 -0.5086940882 0.9906851510 0.5172296447 0.6904650135 -0.3974118482 0.312722533063 +1403638219545096960.0000000000 5.8957578268 -0.5159600109 0.9905748364 0.5175712130 0.6901465557 -0.3977195751 0.312469055643 +1403638219595097088.0000000000 5.8786223564 -0.5244809605 0.9923815169 0.5172849692 0.6904794472 -0.3991765794 0.310342475633 +1403638219645096960.0000000000 5.8600796378 -0.5331005071 0.9946802282 0.5161743347 0.6915181969 -0.4008692578 0.307685680097 +1403638219695097088.0000000000 5.8398786206 -0.5423962893 0.9977506730 0.5164972197 0.6915254867 -0.4034055033 0.303787957744 +1403638219745096960.0000000000 5.8183072355 -0.5526125447 0.9997861872 0.5152873900 0.6926127183 -0.4058328911 0.300110300755 +1403638219795097088.0000000000 5.7958119897 -0.5636009520 1.0011121754 0.5150810574 0.6929624142 -0.4090518541 0.295247654555 +1403638219845096960.0000000000 5.7726612220 -0.5756179282 1.0009274362 0.5143987990 0.6936054547 -0.4124589024 0.290143072685 +1403638219895097088.0000000000 5.7492259959 -0.5887561663 0.9993895376 0.5144854563 0.6936161004 -0.4154718392 0.285630130375 +1403638219945096960.0000000000 5.7260585079 -0.6029974550 0.9962776545 0.5142134359 0.6937511354 -0.4185081618 0.281326896954 +1403638219995097088.0000000000 5.7030410088 -0.6186236092 0.9918102699 0.5138673252 0.6940597070 -0.4209410989 0.27754294506 +1403638220045096960.0000000000 5.6806519016 -0.6357726611 0.9856594487 0.5127742791 0.6947764628 -0.4226414561 0.275177042864 +1403638220095097088.0000000000 5.6590389415 -0.6544072819 0.9787122187 0.5116148823 0.6956588581 -0.4231778024 0.274279990061 +1403638220145096960.0000000000 5.6387032848 -0.6746392811 0.9715734056 0.5091264523 0.6975166148 -0.4218972950 0.276158469205 +1403638220195097088.0000000000 5.6200779773 -0.6959081751 0.9662857504 0.5058414173 0.6998305221 -0.4189652382 0.280766504472 +1403638220245096960.0000000000 5.6022584204 -0.7182395081 0.9622982315 0.5017087715 0.7027707113 -0.4140312809 0.288062032169 +1403638220295097088.0000000000 5.5844815624 -0.7410905345 0.9598357581 0.4971145642 0.7059574104 -0.4102431388 0.29360145042 +1403638220345096960.0000000000 5.5666413147 -0.7637911030 0.9601119355 0.4947761154 0.7075856646 -0.4069956378 0.298116879254 +1403638220395097088.0000000000 5.5479278018 -0.7864839326 0.9623028969 0.4928622266 0.7086098465 -0.4051312325 0.301376169441 +1403638220445096960.0000000000 5.5286490871 -0.8087801121 0.9659187903 0.4918887186 0.7093013664 -0.4042878879 0.302470434582 +1403638220495097088.0000000000 5.5094367590 -0.8306881235 0.9713172203 0.4910604056 0.7096957306 -0.4031633830 0.304386160268 +1403638220545096960.0000000000 5.4897672360 -0.8518980471 0.9781097760 0.4917663440 0.7090230269 -0.4035682587 0.304277621257 +1403638220595097088.0000000000 5.4706271284 -0.8726843194 0.9848304833 0.4913098301 0.7089519463 -0.4033705781 0.305440608553 +1403638220645096960.0000000000 5.4511499000 -0.8927790358 0.9904923875 0.4912385345 0.7085746877 -0.4038539345 0.305791781566 +1403638220695097088.0000000000 5.4315285530 -0.9122793702 0.9945667101 0.4912316245 0.7081977300 -0.4040160362 0.306461268066 +1403638220745096960.0000000000 5.4116562638 -0.9313021733 0.9971170404 0.4910157719 0.7078907226 -0.4051945952 0.305960089823 +1403638220795097088.0000000000 5.3914318657 -0.9499380777 0.9980058880 0.4910253274 0.7075864654 -0.4059350179 0.305666948051 +1403638220845096960.0000000000 5.3711614237 -0.9681278890 0.9973317310 0.4917447613 0.7067489109 -0.4066793488 0.305458628811 +1403638220895097088.0000000000 5.3510865065 -0.9863090904 0.9948742042 0.4908397004 0.7069762834 -0.4070782219 0.305856574984 +1403638220945096960.0000000000 5.3306940709 -1.0038485707 0.9906717834 0.4906666965 0.7067027259 -0.4086298460 0.304695092106 +1403638220995097088.0000000000 5.3102843772 -1.0210826885 0.9847490212 0.4899383548 0.7070103466 -0.4090972507 0.304526218491 +1403638221045096960.0000000000 5.2898371768 -1.0377195438 0.9777728574 0.4896349624 0.7070559232 -0.4093708913 0.304540635204 +1403638221095097088.0000000000 5.2691178397 -1.0539225313 0.9699957100 0.4890979742 0.7070260632 -0.4101343091 0.304445670141 +1403638221145096960.0000000000 5.2482842047 -1.0697256557 0.9626557794 0.4881040575 0.7074775379 -0.4104270119 0.304597489059 +1403638221195097088.0000000000 5.2272465303 -1.0850543831 0.9568815443 0.4871598367 0.7079976722 -0.4112675443 0.30376569359 +1403638221245096960.0000000000 5.2063388483 -1.0998369459 0.9532554156 0.4863280493 0.7084118283 -0.4119423056 0.303218150536 +1403638221295097088.0000000000 5.1854939177 -1.1140797870 0.9516907146 0.4857669879 0.7087150716 -0.4132682679 0.301600264483 +1403638221345096960.0000000000 5.1643152460 -1.1282190676 0.9513469324 0.4849900076 0.7090670670 -0.4143033207 0.300601639261 +1403638221395097088.0000000000 5.1438160778 -1.1417883630 0.9524212075 0.4849751668 0.7088643617 -0.4158626070 0.298945975764 +1403638221445096960.0000000000 5.1236577642 -1.1549129153 0.9532034451 0.4850270474 0.7086845427 -0.4169163999 0.297818229201 +1403638221495097088.0000000000 5.1037881850 -1.1677273013 0.9527612407 0.4853400638 0.7083547250 -0.4178831016 0.296736110756 +1403638221545096960.0000000000 5.0844330065 -1.1803343080 0.9508561134 0.4858684095 0.7078508231 -0.4188157485 0.295757450877 +1403638221595097088.0000000000 5.0655618205 -1.1929338542 0.9476972150 0.4867656175 0.7068573616 -0.4194741453 0.29572511814 +1403638221645096960.0000000000 5.0473620136 -1.2053031730 0.9432437572 0.4872544808 0.7065123288 -0.4192104305 0.296118245177 +1403638221695097088.0000000000 5.0298477537 -1.2173860435 0.9383706579 0.4892727317 0.7050536581 -0.4193648678 0.296048375959 +1403638221745096960.0000000000 5.0129336269 -1.2292749431 0.9336754002 0.4913360185 0.7034654473 -0.4197836223 0.295815807417 +1403638221795097088.0000000000 4.9959628181 -1.2413036115 0.9296041665 0.4929168829 0.7026158503 -0.4197692311 0.295224839818 +1403638221845096960.0000000000 4.9796313625 -1.2535066709 0.9272109372 0.4931220705 0.7025783223 -0.4191994947 0.295780506978 +1403638221895097088.0000000000 4.9637864710 -1.2658183489 0.9269027595 0.4937305608 0.7022878089 -0.4175566116 0.297772468375 +1403638221945096960.0000000000 4.9478151684 -1.2785974003 0.9285207143 0.4935077860 0.7026058034 -0.4155141221 0.30023851264 +1403638221995097088.0000000000 4.9319274107 -1.2915120443 0.9318801513 0.4931559880 0.7029691511 -0.4142123633 0.301760935468 +1403638222045096960.0000000000 4.9162690250 -1.3043625897 0.9371095362 0.4918934401 0.7038138028 -0.4132540691 0.303163403017 +1403638222095097088.0000000000 4.9003807160 -1.3169555259 0.9424376001 0.4896374359 0.7054509453 -0.4125691838 0.303942122224 +1403638222145096960.0000000000 4.8843003919 -1.3294865897 0.9471712986 0.4870712675 0.7072461756 -0.4133557845 0.302822428078 +1403638222195097088.0000000000 4.8681765952 -1.3418185854 0.9506618661 0.4843471291 0.7090474096 -0.4139875295 0.302115797163 +1403638222245096960.0000000000 4.8521819092 -1.3535974363 0.9530212494 0.4821563975 0.7104783329 -0.4151871562 0.300608336878 +1403638222295097088.0000000000 4.8365948494 -1.3648454087 0.9541769721 0.4799925626 0.7118171489 -0.4163312645 0.299318834302 +1403638222345096960.0000000000 4.8215429045 -1.3755705499 0.9540530827 0.4778998732 0.7133117602 -0.4172086688 0.297884156499 +1403638222395097088.0000000000 4.8072747928 -1.3859159538 0.9529414301 0.4762663279 0.7142297703 -0.4182110877 0.296893425837 +1403638222445096960.0000000000 4.7936582428 -1.3954083714 0.9504407342 0.4743365399 0.7156098315 -0.4188187294 0.29580109512 +1403638222495097088.0000000000 4.7808480353 -1.4041909889 0.9470796048 0.4732535314 0.7163689613 -0.4190738387 0.295336628294 +1403638222545096960.0000000000 4.7690480308 -1.4122176971 0.9432344506 0.4749692244 0.7152011622 -0.4187963496 0.295805934748 +1403638222595097088.0000000000 4.7583308684 -1.4194413827 0.9388329826 0.4783177856 0.7130218377 -0.4173938657 0.297647973044 +1403638222645096960.0000000000 4.7482086919 -1.4259534446 0.9337794485 0.4827551878 0.7099549532 -0.4167417075 0.298726869026 +1403638222695097088.0000000000 4.7385649318 -1.4322478437 0.9278024765 0.4858894375 0.7077861267 -0.4160482882 0.299756693574 +1403638222745096960.0000000000 4.7291352538 -1.4384552393 0.9206733338 0.4873952901 0.7066492576 -0.4150740756 0.301340620658 +1403638222795097088.0000000000 4.7196967578 -1.4443295319 0.9128715317 0.4886660606 0.7057729135 -0.4146913888 0.301862763245 +1403638222845096960.0000000000 4.7104967434 -1.4498722009 0.9046861588 0.4905339159 0.7044608439 -0.4135751270 0.303425462291 +1403638222895097088.0000000000 4.7015314395 -1.4548444694 0.8968315002 0.4954321089 0.7010486587 -0.4114395238 0.306260219307 +1403638222945096960.0000000000 4.6920658519 -1.4596975718 0.8885682996 0.5003470005 0.6976128763 -0.4102116425 0.307758935275 +1403638222995097088.0000000000 4.6818024993 -1.4649761776 0.8798301471 0.5018514822 0.6966731136 -0.4098124463 0.307969838461 +1403638223045096960.0000000000 4.6709364584 -1.4705515892 0.8722757692 0.5011840317 0.6972852598 -0.4099913269 0.307432829573 +1403638223095097088.0000000000 4.6590618952 -1.4765787058 0.8666986788 0.4982949315 0.6993627064 -0.4105440148 0.30667177591 +1403638223145096960.0000000000 4.6456488684 -1.4833546001 0.8622950513 0.4934135474 0.7027314535 -0.4120871504 0.304788050897 +1403638223195097088.0000000000 4.6318246206 -1.4900167916 0.8589110107 0.4873856997 0.7069705033 -0.4158744384 0.299493470032 +1403638223245096960.0000000000 4.6183349213 -1.4962713965 0.8563990973 0.4824947181 0.7102189891 -0.4203121007 0.293471587159 +1403638223295097088.0000000000 4.6056011414 -1.5021888928 0.8542700955 0.4792427033 0.7124723090 -0.4226874989 0.289905016312 +1403638223345096960.0000000000 4.5942735165 -1.5075658990 0.8529159403 0.4805041633 0.7114366503 -0.4233447876 0.289400816212 +1403638223395097088.0000000000 4.5836990949 -1.5126483563 0.8509426218 0.4827980846 0.7097772148 -0.4243102778 0.288241397275 +1403638223445096960.0000000000 4.5739750239 -1.5175327642 0.8486498183 0.4875719673 0.7064294602 -0.4264226219 0.285297637447 +1403638223495097088.0000000000 4.5652726202 -1.5225103643 0.8464274786 0.4931645392 0.7024545815 -0.4290624487 0.281516808243 +1403638223545096960.0000000000 4.5575991500 -1.5285369612 0.8429072602 0.4964982915 0.6999707297 -0.4304073028 0.279785592588 +1403638223595097088.0000000000 4.5509886666 -1.5357751838 0.8383436503 0.4967893410 0.6998177488 -0.4289417518 0.281894382271 +1403638223645096960.0000000000 4.5455272919 -1.5440285204 0.8330142510 0.4953534122 0.7007722840 -0.4254731380 0.287255655819 +1403638223695097088.0000000000 4.5406302594 -1.5528258298 0.8271578795 0.4932443286 0.7022597145 -0.4221405127 0.29212790569 +1403638223745096960.0000000000 4.5362764970 -1.5619697085 0.8209259546 0.4903884910 0.7042155828 -0.4182756526 0.297733134092 +1403638223795097088.0000000000 4.5319469464 -1.5711910590 0.8142412211 0.4877778799 0.7058693393 -0.4158823881 0.301434992991 +1403638223845096960.0000000000 4.5274128242 -1.5802073665 0.8076953012 0.4862172849 0.7070359777 -0.4137525910 0.304140874413 +1403638223895097088.0000000000 4.5226845657 -1.5888924438 0.8008907221 0.4848860424 0.7079277517 -0.4123857705 0.306042154765 +1403638223945096960.0000000000 4.5181811788 -1.5970109178 0.7940853267 0.4839494328 0.7085470468 -0.4104101072 0.308735441745 +1403638223995097088.0000000000 4.5133495641 -1.6046370997 0.7867258021 0.4829275824 0.7092597180 -0.4100015537 0.309241537476 +1403638224045096960.0000000000 4.5081417854 -1.6117481956 0.7787679272 0.4805134938 0.7109515054 -0.4102660516 0.308766102576 +1403638224095097088.0000000000 4.5025629089 -1.6180841758 0.7703056921 0.4779343660 0.7128780983 -0.4117672740 0.306318903801 +1403638224145096960.0000000000 4.4968881430 -1.6239295904 0.7612974728 0.4739391371 0.7157512626 -0.4135743774 0.303377749228 +1403638224195097088.0000000000 4.4917856142 -1.6286044651 0.7523798429 0.4702602924 0.7181946283 -0.4155566714 0.300606696614 +1403638224245096960.0000000000 4.4874346062 -1.6319915834 0.7447555172 0.4700091745 0.7184155936 -0.4160424254 0.299798450583 +1403638224295097088.0000000000 4.4839397281 -1.6342438085 0.7379924854 0.4714139987 0.7175186856 -0.4155445170 0.300430577708 +1403638224345096960.0000000000 4.4811515476 -1.6352970567 0.7323212347 0.4758221074 0.7144575188 -0.4144553222 0.302275638929 +1403638224395097088.0000000000 4.4787453397 -1.6351151071 0.7266999786 0.4807260653 0.7108473820 -0.4154684764 0.301636196199 +1403638224445096960.0000000000 4.4764730420 -1.6342396210 0.7210261980 0.4865447698 0.7068700807 -0.4166358786 0.300039031776 +1403638224495097088.0000000000 4.4746627654 -1.6332051341 0.7153222911 0.4927426747 0.7025464445 -0.4157448888 0.301312690287 +1403638224545096960.0000000000 4.4726667858 -1.6325160766 0.7092460878 0.4960829594 0.7001342887 -0.4137730125 0.304147282264 +1403638224595097088.0000000000 4.4700102293 -1.6319317072 0.7026489801 0.4964381738 0.7000188073 -0.4130555110 0.304808060639 +1403638224645096960.0000000000 4.4669007986 -1.6317160129 0.6951902597 0.4925434727 0.7027673352 -0.4134158812 0.30431284771 +1403638224695097088.0000000000 4.4629173385 -1.6317174852 0.6876682875 0.4864237505 0.7071215147 -0.4154801940 0.301242936395 +1403638224745096960.0000000000 4.4588723040 -1.6315673281 0.6805735315 0.4792778424 0.7120274264 -0.4178410914 0.297856536306 +1403638224795097088.0000000000 4.4555318516 -1.6306246947 0.6750852979 0.4747653780 0.7150164405 -0.4192865278 0.295885337953 +1403638224845096960.0000000000 4.4532255676 -1.6282839746 0.6718739210 0.4758031548 0.7144427871 -0.4193580814 0.295502388108 +1403638224895097088.0000000000 4.4518040088 -1.6247418537 0.6706099489 0.4815499606 0.7105796561 -0.4201873410 0.294327685091 +1403638224945096960.0000000000 4.4510652154 -1.6207612179 0.6704511871 0.4883220514 0.7060634253 -0.4208179067 0.29313529804 +1403638224995097088.0000000000 4.4506701075 -1.6167186296 0.6713259181 0.4953085576 0.7013963825 -0.4215426207 0.291572231515 +1403638225045096960.0000000000 4.4506265394 -1.6134190853 0.6720966701 0.4993233902 0.6988313500 -0.4214625951 0.290998586214 +1403638225095097088.0000000000 4.4512956846 -1.6110222152 0.6730439753 0.5007194953 0.6979889811 -0.4197923894 0.293028529361 +1403638225145096960.0000000000 4.4519425629 -1.6097493363 0.6741538957 0.4988670011 0.6995788418 -0.4176469149 0.295452557628 +1403638225195097088.0000000000 4.4524271448 -1.6092092006 0.6754583218 0.4944650884 0.7029246820 -0.4166171277 0.296363521183 +1403638225245096960.0000000000 4.4525894387 -1.6089655018 0.6769067570 0.4888637613 0.7072446143 -0.4162393313 0.295908934384 +1403638225295097088.0000000000 4.4531664784 -1.6087863354 0.6791009226 0.4836315507 0.7109545531 -0.4164165082 0.295366616822 +1403638225345096960.0000000000 4.4544415585 -1.6079153505 0.6821003841 0.4828246874 0.7115788861 -0.4154750356 0.296506837875 +1403638225395097088.0000000000 4.4563684942 -1.6065305913 0.6846809980 0.4838487955 0.7110413406 -0.4141007947 0.298045444259 +1403638225445096960.0000000000 4.4589593783 -1.6044619313 0.6858501731 0.4875642777 0.7083296316 -0.4126447103 0.30045723691 +1403638225495097088.0000000000 4.4617891649 -1.6021598921 0.6855049370 0.4936414675 0.7041019506 -0.4095629555 0.30465838276 +1403638225545096960.0000000000 4.4645074314 -1.5999705031 0.6836297160 0.4999328872 0.6994027365 -0.4069968543 0.308636487097 +1403638225595097088.0000000000 4.4666528408 -1.5979686720 0.6802864769 0.5061686562 0.6946893150 -0.4040130374 0.313007208744 +1403638225645096960.0000000000 4.4675740653 -1.5961939647 0.6752992579 0.5121365032 0.6903268542 -0.4015281441 0.316133177697 +1403638225695097088.0000000000 4.4668021229 -1.5954053380 0.6664829770 0.5120862865 0.6903177772 -0.4011642322 0.316695848435 +1403638225745096960.0000000000 4.4642443282 -1.5952926260 0.6544316940 0.5090519420 0.6926941619 -0.4017326087 0.315676780148 +1403638225795097088.0000000000 4.4600929538 -1.5955715022 0.6399784607 0.5035022182 0.6968341020 -0.4043307860 0.312128765272 +1403638225845096960.0000000000 4.4549818871 -1.5961390519 0.6233016701 0.4951951864 0.7029056134 -0.4069392555 0.308392393461 +1403638225895097088.0000000000 4.4495211920 -1.5965127420 0.6050260318 0.4875819554 0.7083222669 -0.4094675926 0.304761699606 +1403638225945096960.0000000000 4.4438755814 -1.5963942932 0.5859733822 0.4823376031 0.7120861348 -0.4116156187 0.301423880526 +1403638225995097088.0000000000 4.4382028726 -1.5954832839 0.5659919275 0.4780964316 0.7150414413 -0.4151449850 0.29630082822 +1403638226045096960.0000000000 4.4331451797 -1.5909218941 0.5571146728 0.4706342666 0.7216426671 -0.4155134365 0.291691330267 +1403638226095097088.0000000000 4.4314535531 -1.5833953872 0.5660597734 0.4813292011 0.7145618769 -0.4257597718 0.276499802814 +1403638226145096960.0000000000 4.4308802886 -1.5767858953 0.5690192966 0.4820747212 0.7146871785 -0.4279840915 0.271396052765 +1403638226195097088.0000000000 4.4315517529 -1.5714071069 0.5640751862 0.4744146884 0.7204677903 -0.4251910233 0.273988065939 +1403638226245096960.0000000000 4.4331221163 -1.5663193536 0.5523825207 0.4652904640 0.7249336392 -0.4149829640 0.292856863568 +1403638226295097088.0000000000 4.4294022085 -1.5639826349 0.5554742141 0.4797551747 0.7131214473 -0.4209344085 0.290012064434 +1403638226345096960.0000000000 4.4263733436 -1.5624041737 0.5516408827 0.4718675813 0.7210420484 -0.4142518555 0.29297568228 +1403638226395097088.0000000000 4.4262216730 -1.5617447422 0.5511205349 0.4724204159 0.7216256331 -0.4123699871 0.293302557287 +1403638226445096960.0000000000 4.4270108288 -1.5613997764 0.5524373921 0.4722295672 0.7207154015 -0.4143439798 0.293065883846 +1403638226495097088.0000000000 4.4267213182 -1.5613056180 0.5528097378 0.4725117656 0.7207113331 -0.4142080557 0.292813067165 +1403638226545096960.0000000000 4.4266603155 -1.5607791130 0.5524503953 0.4732196501 0.7203418859 -0.4136003477 0.293437357055 +1403638226595097088.0000000000 4.4262663217 -1.5608618008 0.5527538978 0.4728210607 0.7203777086 -0.4137331712 0.293804466474 +1403638226645096960.0000000000 4.4264229969 -1.5605841087 0.5526822590 0.4733073932 0.7201454421 -0.4140701813 0.293115231298 +1403638226695097088.0000000000 4.4265433249 -1.5609685688 0.5527218552 0.4724628026 0.7207563792 -0.4136508431 0.293567917027 +1403638226745096960.0000000000 4.4262615215 -1.5607811898 0.5528513358 0.4727885231 0.7204156527 -0.4146584160 0.29245631772 +1403638226795097088.0000000000 4.4265273406 -1.5608496515 0.5523350353 0.4726154797 0.7205675536 -0.4135853124 0.293877863164 +1403638226845096960.0000000000 4.4260324935 -1.5607491856 0.5525739872 0.4730960791 0.7202843915 -0.4142929644 0.292799991373 +1403638226895097088.0000000000 4.4263561962 -1.5609992572 0.5522689531 0.4725367925 0.7206612555 -0.4137873636 0.293489952646 +1403638226945096960.0000000000 4.4264694369 -1.5608105147 0.5524651386 0.4726399450 0.7205123796 -0.4141956038 0.293113280136 +1403638226995097088.0000000000 4.4261466669 -1.5608290438 0.5523692612 0.4727104665 0.7204697990 -0.4145520903 0.292599808571 +1403638227045096960.0000000000 4.4261711870 -1.5610119609 0.5520443096 0.4725330562 0.7206265319 -0.4137602555 0.293619419165 +1403638227095097088.0000000000 4.4259835904 -1.5607489522 0.5522113142 0.4728530228 0.7203372687 -0.4146684112 0.292530933348 +1403638227145096960.0000000000 4.4263902015 -1.5609570109 0.5520966923 0.4724269764 0.7206350166 -0.4140780224 0.293321182737 +1403638227195097088.0000000000 4.4261546980 -1.5608495782 0.5520568190 0.4727668091 0.7204116818 -0.4145121733 0.292708406105 +1403638227245096960.0000000000 4.4262302677 -1.5610229470 0.5518861831 0.4725262179 0.7206318324 -0.4141604796 0.293052610807 +1403638227295097088.0000000000 4.4263113836 -1.5608694525 0.5518940261 0.4726099151 0.7205507356 -0.4143022858 0.292916577913 +1403638227345096960.0000000000 4.4260396796 -1.5608294064 0.5519564607 0.4726660221 0.7204989569 -0.4145037319 0.292668312098 +1403638227395097088.0000000000 4.4262890217 -1.5608467929 0.5518435628 0.4725151241 0.7206273719 -0.4141785602 0.293055913936 +1403638227445096960.0000000000 4.4261333672 -1.5607166926 0.5518662051 0.4726173366 0.7205204543 -0.4145322500 0.292653620811 +1403638227495097088.0000000000 4.4261888313 -1.5607683033 0.5519387301 0.4725070405 0.7206223075 -0.4143119451 0.292892811052 +1403638227545096960.0000000000 4.4260096415 -1.5607697351 0.5519794193 0.4726031266 0.7205775876 -0.4143829574 0.292747313651 +1403638227595097088.0000000000 4.4258321182 -1.5608420822 0.5521122602 0.4726344526 0.7205626985 -0.4143949888 0.292716355884 +1403638227645096960.0000000000 4.4256827638 -1.5609091842 0.5523300395 0.4725487375 0.7206066936 -0.4143110540 0.292865215373 +1403638227695097088.0000000000 4.4252461608 -1.5609127549 0.5525184891 0.4726017927 0.7205648505 -0.4145368621 0.292562867899 diff --git a/data/euroc_groundtruth/MH_05_difficult.txt b/data/euroc_groundtruth/MH_05_difficult.txt new file mode 100755 index 00000000..e90d414b --- /dev/null +++ b/data/euroc_groundtruth/MH_05_difficult.txt @@ -0,0 +1,2222 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403638519527829504.0000000000 4.4114848107 -1.6382993190 0.5566335472 0.5168054265 0.7809012394 -0.2896911447 0.197950615321 +1403638519577829376.0000000000 4.4117223430 -1.6383497358 0.5565030977 0.5168002679 0.7809096436 -0.2896862709 0.197938061343 +1403638519627829504.0000000000 4.4119381051 -1.6384016691 0.5564142755 0.5167891427 0.7809082410 -0.2897143265 0.197931579507 +1403638519677829376.0000000000 4.4120858172 -1.6384694491 0.5563356162 0.5167515536 0.7809305733 -0.2897342002 0.197912518047 +1403638519727829504.0000000000 4.4121811145 -1.6385157618 0.5562781838 0.5167334657 0.7809494262 -0.2897339123 0.197885772982 +1403638519777829376.0000000000 4.4122267628 -1.6385318947 0.5562435635 0.5167254954 0.7809495921 -0.2897742156 0.197846913171 +1403638519827829504.0000000000 4.4121863893 -1.6385343752 0.5562542470 0.5167106432 0.7809406892 -0.2898228566 0.197849596824 +1403638519877829376.0000000000 4.4122001584 -1.6385562898 0.5562100697 0.5166669416 0.7809634586 -0.2898573343 0.197823339358 +1403638519927829504.0000000000 4.4121636677 -1.6385266727 0.5562220406 0.5166864443 0.7809345942 -0.2899032465 0.197819072632 +1403638519977829376.0000000000 4.4121296012 -1.6384938939 0.5562095640 0.5166655216 0.7809550159 -0.2899085875 0.197785269463 +1403638520027829504.0000000000 4.4120761491 -1.6384616660 0.5561955235 0.5166655796 0.7809462002 -0.2899559476 0.197750498644 +1403638520077829376.0000000000 4.4120325809 -1.6384421205 0.5561908291 0.5166615517 0.7809350071 -0.2899870764 0.197759579238 +1403638520127829504.0000000000 4.4120039665 -1.6384345784 0.5561990170 0.5166657332 0.7809292265 -0.2900106023 0.197736981784 +1403638520177829376.0000000000 4.4119689471 -1.6384299928 0.5562079993 0.5166398689 0.7809374057 -0.2900462577 0.197719959922 +1403638520227829504.0000000000 4.4119255241 -1.6384288292 0.5562099064 0.5166215626 0.7809423638 -0.2900673862 0.197717214283 +1403638520277829376.0000000000 4.4119022414 -1.6384292971 0.5562381933 0.5166083002 0.7809436023 -0.2900896915 0.197714251338 +1403638520327829504.0000000000 4.4118440464 -1.6384462865 0.5563290931 0.5166186210 0.7809457101 -0.2900665342 0.197712933419 +1403638520377829376.0000000000 4.4119220659 -1.6384779560 0.5562922494 0.5166337326 0.7809269140 -0.2901249375 0.197661989116 +1403638520427829504.0000000000 4.4119466369 -1.6384952992 0.5563160635 0.5166374180 0.7809213102 -0.2901194647 0.197682527485 +1403638520477829376.0000000000 4.4119496605 -1.6384785402 0.5563516989 0.5166455531 0.7809006033 -0.2901931292 0.19763493624 +1403638520527829504.0000000000 4.4119552063 -1.6384793724 0.5563777482 0.5166240299 0.7808948820 -0.2902333710 0.197654712704 +1403638520577829376.0000000000 4.4118906473 -1.6384580420 0.5564528330 0.5166168047 0.7808853695 -0.2902926414 0.197624136184 +1403638520627829504.0000000000 4.4119498586 -1.6384631461 0.5564164153 0.5166037641 0.7808807509 -0.2903215640 0.197633987979 +1403638520677829376.0000000000 4.4119355563 -1.6384475924 0.5564024116 0.5165691967 0.7809006312 -0.2903444493 0.197612170439 +1403638520727829504.0000000000 4.4119154220 -1.6384401204 0.5563646056 0.5165462028 0.7809090498 -0.2903858255 0.197578208919 +1403638520777829376.0000000000 4.4119245016 -1.6384307470 0.5563398154 0.5165201483 0.7809166064 -0.2904100243 0.197580890098 +1403638520827829504.0000000000 4.4119132726 -1.6384314631 0.5563145851 0.5165217261 0.7809077820 -0.2904635297 0.197532985565 +1403638520877829376.0000000000 4.4119186588 -1.6384527633 0.5562584721 0.5165403830 0.7809048008 -0.2904191366 0.197561256037 +1403638520927829504.0000000000 4.4119210107 -1.6385060751 0.5561678938 0.5165583117 0.7809075444 -0.2903774671 0.197564785253 +1403638520977829376.0000000000 4.4119492191 -1.6385378578 0.5561556668 0.5165662851 0.7809104270 -0.2903924935 0.197510450008 +1403638521027829504.0000000000 4.4119648328 -1.6385572268 0.5561848558 0.5165775533 0.7808958222 -0.2903800204 0.197557055205 +1403638521077829376.0000000000 4.4119841951 -1.6385849392 0.5560895965 0.5165817088 0.7809013933 -0.2904047549 0.197487798127 +1403638521127829504.0000000000 4.4120361333 -1.6385874015 0.5561659150 0.5165546238 0.7808577793 -0.2905520837 0.19751439382 +1403638521177829376.0000000000 4.4120487612 -1.6386022810 0.5562408357 0.5165952769 0.7808235060 -0.2906695181 0.197370726304 +1403638521227829504.0000000000 4.4121243729 -1.6387431713 0.5561870151 0.5165048264 0.7808922555 -0.2904884853 0.197601845641 +1403638521277829376.0000000000 4.4122231177 -1.6387722593 0.5562380210 0.5165106519 0.7809184305 -0.2903796205 0.197643181939 +1403638521327829504.0000000000 4.4122827133 -1.6387973784 0.5563526704 0.5164545182 0.7809963408 -0.2902471638 0.197676579922 +1403638521377829376.0000000000 4.4122712318 -1.6387123106 0.5563281573 0.5165502852 0.7809016964 -0.2905058808 0.19742005142 +1403638521427829504.0000000000 4.4122928654 -1.6386702748 0.5563792876 0.5165153694 0.7809064242 -0.2905745862 0.197391589568 +1403638521477829376.0000000000 4.4122981495 -1.6385643661 0.5564629161 0.5164948573 0.7809154184 -0.2906410214 0.197311855524 +1403638521527829504.0000000000 4.4122982768 -1.6384396580 0.5565210533 0.5165158645 0.7807360392 -0.2911766385 0.197176986545 +1403638521577829376.0000000000 4.4122031404 -1.6382238054 0.5566523116 0.5168511200 0.7804114087 -0.2918507178 0.196586142785 +1403638521627829504.0000000000 4.4124217884 -1.6384619647 0.5564786216 0.5165175164 0.7807761251 -0.2909099244 0.197407481166 +1403638521677829376.0000000000 4.4123578211 -1.6385505629 0.5563708623 0.5165006959 0.7808675468 -0.2908261127 0.197213279799 +1403638521727829504.0000000000 4.4122979711 -1.6384838278 0.5564812975 0.5166906273 0.7806866992 -0.2911572629 0.196942940069 +1403638521777829376.0000000000 4.4124744782 -1.6385359849 0.5562855534 0.5165303681 0.7807662656 -0.2909777055 0.197312929691 +1403638521827829504.0000000000 4.4125095068 -1.6385423928 0.5562095060 0.5165942312 0.7808384010 -0.2907951293 0.197129359969 +1403638521877829376.0000000000 4.4126089522 -1.6385516579 0.5561137704 0.5167285978 0.7807610099 -0.2909039320 0.196923091304 +1403638521927829504.0000000000 4.4125002672 -1.6383614170 0.5559204944 0.5168979081 0.7808192676 -0.2909127497 0.1962335243 +1403638521977829376.0000000000 4.4126181916 -1.6379730424 0.5557556452 0.5177264588 0.7809053765 -0.2893055505 0.196082648818 +1403638522027829504.0000000000 4.4123155095 -1.6373367037 0.5550988442 0.5169677580 0.7821224562 -0.2883135374 0.19468976577 +1403638522077829376.0000000000 4.4122334669 -1.6371607265 0.5556865979 0.5148497997 0.7836617788 -0.2877034820 0.195014375318 +1403638522127829504.0000000000 4.4113510653 -1.6368383711 0.5584266493 0.5130823856 0.7853494935 -0.2874097430 0.193308764015 +1403638522177829376.0000000000 4.4104003678 -1.6359806251 0.5643406503 0.5143343233 0.7852013618 -0.2872134160 0.190859841356 +1403638522227829504.0000000000 4.4100471869 -1.6350787119 0.5732505875 0.5177547854 0.7836373780 -0.2861796710 0.189588074057 +1403638522277829376.0000000000 4.4100693646 -1.6336252584 0.5855414445 0.5228860975 0.7812507885 -0.2844066560 0.188016458053 +1403638522327829504.0000000000 4.4107475442 -1.6321904682 0.6011339311 0.5282202893 0.7787144960 -0.2825743949 0.186383397831 +1403638522377829376.0000000000 4.4115581435 -1.6311673144 0.6192995612 0.5317213031 0.7773917892 -0.2810022884 0.184315424664 +1403638522427829504.0000000000 4.4122268304 -1.6301735237 0.6395899303 0.5333967130 0.7776291389 -0.2798598332 0.180164765566 +1403638522477829376.0000000000 4.4128553969 -1.6291238659 0.6611511714 0.5334150041 0.7788685804 -0.2799540894 0.174521848804 +1403638522527829504.0000000000 4.4135401656 -1.6281934251 0.6836360211 0.5321156740 0.7805349930 -0.2812440166 0.168878172753 +1403638522577829376.0000000000 4.4141913508 -1.6268362432 0.7066318335 0.5320090085 0.7814749183 -0.2826570779 0.162383322101 +1403638522627829504.0000000000 4.4156628168 -1.6250651745 0.7297998191 0.5335469938 0.7813486688 -0.2820364235 0.158988424065 +1403638522677829376.0000000000 4.4177507543 -1.6223421458 0.7530075072 0.5366564179 0.7804862269 -0.2784414060 0.159095952783 +1403638522727829504.0000000000 4.4193351523 -1.6189134383 0.7769180400 0.5406337550 0.7793387063 -0.2733612000 0.160062419669 +1403638522777829376.0000000000 4.4206862887 -1.6156458940 0.8021182617 0.5456155065 0.7774910477 -0.2694318029 0.158801427457 +1403638522827829504.0000000000 4.4218491848 -1.6127178649 0.8281605437 0.5511093056 0.7750111559 -0.2678271616 0.154611943287 +1403638522877829376.0000000000 4.4231648074 -1.6098010449 0.8554633908 0.5567199958 0.7716706466 -0.2689573945 0.149161588073 +1403638522927829504.0000000000 4.4250142709 -1.6083101449 0.8823569592 0.5618346643 0.7680957067 -0.2709192073 0.144822575726 +1403638522977829376.0000000000 4.4276505510 -1.6077644692 0.9073487158 0.5657447672 0.7651843857 -0.2717545142 0.143440574061 +1403638523027829504.0000000000 4.4302081302 -1.6079944134 0.9288833349 0.5682443095 0.7632037497 -0.2724962214 0.142703365186 +1403638523077829376.0000000000 4.4327877165 -1.6086080541 0.9460457288 0.5693206014 0.7623118867 -0.2722680871 0.143613122576 +1403638523127829504.0000000000 4.4346766732 -1.6092878653 0.9590825176 0.5700618049 0.7619883774 -0.2716245680 0.143608305387 +1403638523177829376.0000000000 4.4365511902 -1.6112169633 0.9665658510 0.5704627628 0.7614973928 -0.2715590577 0.144739887969 +1403638523227829504.0000000000 4.4389086215 -1.6139853045 0.9677394823 0.5710190017 0.7604628677 -0.2713247468 0.148379271767 +1403638523277829376.0000000000 4.4420546067 -1.6165587633 0.9618095177 0.5712573011 0.7591404150 -0.2708783533 0.154905919784 +1403638523327829504.0000000000 4.4444836490 -1.6181048048 0.9503027068 0.5716323645 0.7580272569 -0.2711322628 0.158487897637 +1403638523377829376.0000000000 4.4462434630 -1.6195327006 0.9343074815 0.5714341894 0.7578226724 -0.2713876575 0.159738861178 +1403638523427829504.0000000000 4.4483535512 -1.6217610767 0.9148699282 0.5695465731 0.7591469032 -0.2708294121 0.161133826096 +1403638523477829376.0000000000 4.4501813627 -1.6250143254 0.8932691745 0.5654338518 0.7622159159 -0.2700996283 0.162350385336 +1403638523527829504.0000000000 4.4514141603 -1.6290419307 0.8702124732 0.5590577952 0.7668647600 -0.2694672034 0.163585597782 +1403638523577829376.0000000000 4.4523963446 -1.6335822568 0.8463260538 0.5513674277 0.7724327625 -0.2689047031 0.164413648309 +1403638523627829504.0000000000 4.4533246434 -1.6384947993 0.8223830969 0.5431514722 0.7779162943 -0.2690638236 0.165642314188 +1403638523677829376.0000000000 4.4540028220 -1.6434748778 0.7989339721 0.5366251635 0.7823357611 -0.2690135388 0.166180343865 +1403638523727829504.0000000000 4.4545485940 -1.6482298719 0.7763366488 0.5320039152 0.7855429317 -0.2685149439 0.166714911014 +1403638523777829376.0000000000 4.4546568558 -1.6509195051 0.7447254121 0.5291589357 0.7876534673 -0.2676293709 0.167234434214 +1403638523827829504.0000000000 4.4541807074 -1.6552472002 0.7222559068 0.5278828960 0.7887306889 -0.2667362110 0.16761665253 +1403638523877829376.0000000000 4.4537387219 -1.6602149497 0.6998797933 0.5272624497 0.7891910935 -0.2650241991 0.170099679559 +1403638523927829504.0000000000 4.4532650560 -1.6650573972 0.6796844234 0.5261259610 0.7897544967 -0.2625320969 0.174803335664 +1403638523977829376.0000000000 4.4522047435 -1.6693242414 0.6628441633 0.5241278380 0.7912341558 -0.2592934758 0.178900568917 +1403638524027829504.0000000000 4.4509858524 -1.6727589128 0.6505451722 0.5209138097 0.7936843159 -0.2557962633 0.182434320307 +1403638524077829376.0000000000 4.4496527442 -1.6753217476 0.6445400966 0.5170558047 0.7969501856 -0.2523955685 0.183902619523 +1403638524127829504.0000000000 4.4485867749 -1.6772846611 0.6458254090 0.5130816548 0.8003005432 -0.2500561502 0.183679551829 +1403638524177829376.0000000000 4.4477079250 -1.6784816077 0.6547398554 0.5104488874 0.8028703722 -0.2492486195 0.180876268624 +1403638524227829504.0000000000 4.4476684084 -1.6788540343 0.6707557233 0.5096541848 0.8042641479 -0.2487896712 0.177526031614 +1403638524277829376.0000000000 4.4486283960 -1.6786588000 0.6919347487 0.5108137213 0.8041686840 -0.2488009115 0.17458572718 +1403638524327829504.0000000000 4.4497147711 -1.6778256900 0.7168703222 0.5136877676 0.8030863217 -0.2491300753 0.17062075779 +1403638524377829376.0000000000 4.4513666137 -1.6761654182 0.7439288730 0.5176317476 0.8010674765 -0.2496961518 0.167332315038 +1403638524427829504.0000000000 4.4534754569 -1.6740486465 0.7723768907 0.5229365156 0.7979995209 -0.2500207734 0.164996297213 +1403638524477829376.0000000000 4.4557836556 -1.6717547136 0.8013973042 0.5290135653 0.7942743418 -0.2495234437 0.16435014053 +1403638524527829504.0000000000 4.4581887717 -1.6687766746 0.8303069053 0.5358231502 0.7899976577 -0.2484438718 0.164538430593 +1403638524577829376.0000000000 4.4607012010 -1.6652940977 0.8582414977 0.5420450308 0.7854937160 -0.2481881224 0.166100760449 +1403638524627829504.0000000000 4.4632515935 -1.6612820616 0.8849540243 0.5468440951 0.7812151320 -0.2495004579 0.168564452688 +1403638524677829376.0000000000 4.4660277982 -1.6570847791 0.9200214587 0.5496703744 0.7775066450 -0.2514398796 0.173562332758 +1403638524727829504.0000000000 4.4678013100 -1.6526131792 0.9425007602 0.5508391339 0.7746914251 -0.2529354322 0.180147471783 +1403638524777829376.0000000000 4.4696178000 -1.6482908911 0.9622916484 0.5508739461 0.7721216466 -0.2550807643 0.187882574999 +1403638524827829504.0000000000 4.4708918641 -1.6443852124 0.9785281457 0.5503962533 0.7704652936 -0.2568881614 0.193534669275 +1403638524877829376.0000000000 4.4711376355 -1.6408373786 0.9920688817 0.5515643077 0.7697753511 -0.2572861095 0.192422922741 +1403638524927829504.0000000000 4.4711963011 -1.6380979334 1.0017688481 0.5530660475 0.7694327363 -0.2566629163 0.190303333714 +1403638524977829376.0000000000 4.4707823571 -1.6365717236 1.0066900917 0.5553894800 0.7691769838 -0.2548080335 0.187035181645 +1403638525027829504.0000000000 4.4707200637 -1.6356535139 1.0058352750 0.5571367431 0.7685435698 -0.2527834883 0.18718957988 +1403638525077829376.0000000000 4.4710647901 -1.6348336231 0.9985693214 0.5578867554 0.7678533787 -0.2507662495 0.190472688402 +1403638525127829504.0000000000 4.4711067443 -1.6336575660 0.9858051090 0.5585978236 0.7676446503 -0.2483543870 0.192380510122 +1403638525177829376.0000000000 4.4711498581 -1.6329306272 0.9687220768 0.5586781488 0.7680938066 -0.2460590641 0.193301752188 +1403638525227829504.0000000000 4.4710097870 -1.6328298292 0.9484123639 0.5575668628 0.7695928997 -0.2437828335 0.193431880108 +1403638525277829376.0000000000 4.4712713793 -1.6326159828 0.9242771912 0.5549237891 0.7723548211 -0.2423124420 0.191865314719 +1403638525327829504.0000000000 4.4703678722 -1.6332830930 0.8989564573 0.5500075381 0.7768141955 -0.2410798084 0.189557219951 +1403638525377829376.0000000000 4.4685540309 -1.6342532465 0.8731932059 0.5436736872 0.7825107517 -0.2405796226 0.184979162303 +1403638525427829504.0000000000 4.4660577759 -1.6356133451 0.8477235630 0.5363563769 0.7886719380 -0.2414816435 0.178899488831 +1403638525477829376.0000000000 4.4630585930 -1.6372014423 0.8233509296 0.5293674034 0.7947891000 -0.2428385463 0.170616174853 +1403638525527829504.0000000000 4.4605113151 -1.6388589825 0.8004020584 0.5230407195 0.7997921831 -0.2445322035 0.164209838514 +1403638525577829376.0000000000 4.4585775747 -1.6405805404 0.7789471757 0.5182595215 0.8032370734 -0.2462852601 0.159877587434 +1403638525627829504.0000000000 4.4574007429 -1.6418951935 0.7594437194 0.5155911927 0.8047806935 -0.2481815141 0.157796366967 +1403638525677829376.0000000000 4.4575376014 -1.6423351404 0.7331848297 0.5144003846 0.8049903124 -0.2501205505 0.157551742283 +1403638525727829504.0000000000 4.4574848603 -1.6427397163 0.7159195914 0.5145471888 0.8038394248 -0.2524522161 0.159220753299 +1403638525777829376.0000000000 4.4573208113 -1.6425571395 0.7007038921 0.5161271792 0.8015135787 -0.2552313365 0.161386749363 +1403638525827829504.0000000000 4.4573279676 -1.6422985288 0.6875943163 0.5178835665 0.7989933530 -0.2570784118 0.165278321598 +1403638525877829376.0000000000 4.4577492169 -1.6425376780 0.6765874407 0.5194046532 0.7965811801 -0.2582338624 0.170271847366 +1403638525927829504.0000000000 4.4592201258 -1.6447523296 0.6679688015 0.5195913525 0.7951244603 -0.2587581580 0.175630676739 +1403638525977829376.0000000000 4.4619836793 -1.6492839012 0.6621169520 0.5187108436 0.7948584436 -0.2589476745 0.179123469305 +1403638526027829504.0000000000 4.4670307346 -1.6556969067 0.6589096253 0.5171869421 0.7952435281 -0.2591921636 0.181451977807 +1403638526077829376.0000000000 4.4743631390 -1.6637172557 0.6579462829 0.5149807623 0.7956401417 -0.2615705430 0.182571713168 +1403638526127829504.0000000000 4.4834129314 -1.6732493618 0.6596977322 0.5127630620 0.7955087284 -0.2660881061 0.182857936789 +1403638526177829376.0000000000 4.4941147590 -1.6842091763 0.6635076047 0.5112035563 0.7947723683 -0.2709660115 0.183262727521 +1403638526227829504.0000000000 4.5059542733 -1.6964161921 0.6687690080 0.5107133786 0.7932569275 -0.2753604941 0.184639893253 +1403638526277829376.0000000000 4.5175458366 -1.7095457804 0.6759946186 0.5114915329 0.7907962304 -0.2792258920 0.187218147813 +1403638526327829504.0000000000 4.5301773856 -1.7237908220 0.6829061116 0.5137683058 0.7876438851 -0.2825604149 0.189258686037 +1403638526377829376.0000000000 4.5426749922 -1.7392215699 0.6903947374 0.5165733978 0.7839310078 -0.2860750528 0.191742441286 +1403638526427829504.0000000000 4.5560818837 -1.7558712304 0.6972476139 0.5197497161 0.7797546459 -0.2900609207 0.194184415451 +1403638526477829376.0000000000 4.5698884181 -1.7733845859 0.7037418923 0.5230958963 0.7753322733 -0.2948520934 0.195685442436 +1403638526527829504.0000000000 4.5850751230 -1.7924403814 0.7091226785 0.5262494436 0.7709286500 -0.2994263258 0.197672494772 +1403638526577829376.0000000000 4.6016346225 -1.8130470588 0.7136265134 0.5296176187 0.7665037511 -0.3035022680 0.199658585577 +1403638526627829504.0000000000 4.6195789735 -1.8352410235 0.7174836077 0.5325858219 0.7623408388 -0.3067223614 0.202756457136 +1403638526677829376.0000000000 4.6383514623 -1.8591264777 0.7207163723 0.5346307486 0.7587481519 -0.3096785626 0.206325937406 +1403638526727829504.0000000000 4.6575996255 -1.8844487383 0.7234077695 0.5357171413 0.7559689305 -0.3121921521 0.209890878164 +1403638526777829376.0000000000 4.6778746035 -1.9111288295 0.7252675211 0.5353672335 0.7539423831 -0.3137326189 0.215695739605 +1403638526827829504.0000000000 4.6980707969 -1.9381631310 0.7264578388 0.5345196323 0.7525953665 -0.3148626096 0.220795185865 +1403638526877829376.0000000000 4.7175619198 -1.9653160165 0.7274472113 0.5331395045 0.7521406411 -0.3164090501 0.223454778141 +1403638526927829504.0000000000 4.7364452994 -1.9920825154 0.7283129761 0.5308753882 0.7523193972 -0.3190382924 0.22450259393 +1403638526977829376.0000000000 4.7553230490 -2.0182537878 0.7289338032 0.5269494165 0.7528362028 -0.3233316385 0.225873007927 +1403638527027829504.0000000000 4.7740567518 -2.0431302877 0.7298041305 0.5220508343 0.7529778358 -0.3295757849 0.227743512185 +1403638527077829376.0000000000 4.7924115322 -2.0666647928 0.7309944131 0.5167774324 0.7524876069 -0.3370045465 0.230502543525 +1403638527127829504.0000000000 4.8106469138 -2.0890991225 0.7327416071 0.5125133764 0.7511347197 -0.3446913110 0.233054869074 +1403638527177829376.0000000000 4.8279276530 -2.1093579612 0.7350386442 0.5095710198 0.7488291833 -0.3517172101 0.236404809878 +1403638527227829504.0000000000 4.8442194896 -2.1270106372 0.7375693535 0.5079902041 0.7453956478 -0.3581819618 0.240908619563 +1403638527277829376.0000000000 4.8593504168 -2.1416102735 0.7401407567 0.5068919492 0.7412136745 -0.3635485467 0.247982448533 +1403638527327829504.0000000000 4.8723837558 -2.1524610600 0.7423750038 0.5062146226 0.7370121408 -0.3674238280 0.256046071722 +1403638527377829376.0000000000 4.8823822373 -2.1593614254 0.7442781768 0.5056524256 0.7332385805 -0.3699302914 0.264250616028 +1403638527427829504.0000000000 4.8897896653 -2.1623577958 0.7454741596 0.5053101234 0.7301877186 -0.3716663403 0.270835201386 +1403638527477829376.0000000000 4.8934722356 -2.1612355485 0.7463935608 0.5049947872 0.7282008385 -0.3727746930 0.275214156603 +1403638527527829504.0000000000 4.8940773539 -2.1555455284 0.7466480317 0.5046092443 0.7272160654 -0.3734452151 0.277605792624 +1403638527577829376.0000000000 4.8912471832 -2.1457013740 0.7465038893 0.5042748956 0.7270650245 -0.3736627328 0.278315364006 +1403638527627829504.0000000000 4.8852442277 -2.1320096195 0.7458702881 0.5043064001 0.7275512360 -0.3729240934 0.277978190337 +1403638527677829376.0000000000 4.8764892685 -2.1149474080 0.7446778096 0.5049621977 0.7286938066 -0.3705793419 0.276928630703 +1403638527727829504.0000000000 4.8659369362 -2.0949397106 0.7434322008 0.5058327046 0.7303912703 -0.3672404968 0.275311250653 +1403638527777829376.0000000000 4.8540661905 -2.0727054970 0.7426587145 0.5066490819 0.7324242346 -0.3645072782 0.272021860236 +1403638527827829504.0000000000 4.8405026203 -2.0492341333 0.7430622647 0.5076861880 0.7347412833 -0.3628866070 0.265938510955 +1403638527877829376.0000000000 4.8251279821 -2.0240101349 0.7444432807 0.5093130934 0.7370241172 -0.3613583014 0.25848752696 +1403638527927829504.0000000000 4.8090360378 -1.9984331553 0.7463778580 0.5111556694 0.7385648817 -0.3598231264 0.252525473748 +1403638527977829376.0000000000 4.7924981258 -1.9726097511 0.7484060429 0.5130397518 0.7394069994 -0.3574669286 0.249569423756 +1403638528027829504.0000000000 4.7755208807 -1.9463523921 0.7499383644 0.5152978031 0.7399728498 -0.3541514328 0.247961929147 +1403638528077829376.0000000000 4.7580410076 -1.9202215396 0.7505979872 0.5182429441 0.7406170659 -0.3505663926 0.24497717655 +1403638528127829504.0000000000 4.7400282491 -1.8941144487 0.7503353966 0.5207624843 0.7419146516 -0.3467628620 0.241090444067 +1403638528177829376.0000000000 4.7235523636 -1.8685936914 0.7489899694 0.5224309402 0.7439008638 -0.3428576649 0.236909348009 +1403638528227829504.0000000000 4.7091701355 -1.8428088601 0.7470074142 0.5242100447 0.7463634255 -0.3385773225 0.231324151172 +1403638528277829376.0000000000 4.6980220517 -1.8168138843 0.7443646972 0.5261946924 0.7488404755 -0.3338711396 0.225581803394 +1403638528327829504.0000000000 4.6903719121 -1.7913462032 0.7411526907 0.5279308800 0.7506828221 -0.3296370726 0.221593517429 +1403638528377829376.0000000000 4.6861277113 -1.7669008439 0.7376605524 0.5298628744 0.7511943082 -0.3265268474 0.219846909265 +1403638528427829504.0000000000 4.6852027833 -1.7433515555 0.7339962477 0.5307407579 0.7511833636 -0.3243397428 0.221001206705 +1403638528477829376.0000000000 4.6866964058 -1.7204991960 0.7305421114 0.5304537776 0.7514403754 -0.3233833395 0.222214688671 +1403638528527829504.0000000000 4.6900558157 -1.6986303810 0.7275332289 0.5289672278 0.7516139251 -0.3248981053 0.22296053623 +1403638528577829376.0000000000 4.6946828624 -1.6775724463 0.7251070774 0.5269986062 0.7515023119 -0.3283753510 0.222904403638 +1403638528627829504.0000000000 4.7013351707 -1.6571157046 0.7228707367 0.5256402170 0.7508558495 -0.3327948688 0.221732791693 +1403638528677829376.0000000000 4.7086570028 -1.6381941869 0.7216835213 0.5250757021 0.7498724555 -0.3361181114 0.221385236026 +1403638528727829504.0000000000 4.7166146838 -1.6214550448 0.7210808211 0.5243224848 0.7486859677 -0.3383501257 0.223773202576 +1403638528777829376.0000000000 4.7241891681 -1.6074840490 0.7215754333 0.5238557032 0.7470446306 -0.3407394317 0.226707215966 +1403638528827829504.0000000000 4.7296084899 -1.5969372702 0.7235102660 0.5244976768 0.7453090781 -0.3438215967 0.226281406397 +1403638528877829376.0000000000 4.7326625483 -1.5896101265 0.7268987946 0.5258922829 0.7433283786 -0.3475770621 0.223808878905 +1403638528927829504.0000000000 4.7330137091 -1.5857008951 0.7320626608 0.5271307025 0.7416159066 -0.3510898869 0.221076821193 +1403638528977829376.0000000000 4.7300688034 -1.5849655674 0.7392560479 0.5279990225 0.7406800931 -0.3538849834 0.217659023405 +1403638529027829504.0000000000 4.7235962357 -1.5871980123 0.7470924413 0.5277561341 0.7405657020 -0.3555635484 0.215894573879 +1403638529077829376.0000000000 4.7140884554 -1.5912819937 0.7542943800 0.5261843248 0.7409000357 -0.3555201190 0.218638144882 +1403638529127829504.0000000000 4.7018960796 -1.5963446084 0.7595067834 0.5230891048 0.7422264976 -0.3527464854 0.225937008232 +1403638529177829376.0000000000 4.6869249455 -1.6021346798 0.7623220178 0.5192410979 0.7439290683 -0.3493259702 0.234370625575 +1403638529227829504.0000000000 4.6696115920 -1.6085044372 0.7628723846 0.5160262228 0.7456991627 -0.3463880408 0.24013542293 +1403638529277829376.0000000000 4.6509150907 -1.6153550636 0.7614800202 0.5125434818 0.7476351250 -0.3443167852 0.244513497764 +1403638529327829504.0000000000 4.6313947982 -1.6225909870 0.7580364310 0.5088403311 0.7503852496 -0.3427886180 0.245966375694 +1403638529377829376.0000000000 4.6116298008 -1.6305610331 0.7521989976 0.5040377731 0.7540088721 -0.3420156373 0.245849238314 +1403638529427829504.0000000000 4.5928594565 -1.6376820790 0.7438496905 0.4977892033 0.7588021984 -0.3419793836 0.243875447647 +1403638529477829376.0000000000 4.5754936342 -1.6439599083 0.7338064454 0.4906726772 0.7642891451 -0.3431614492 0.239463246228 +1403638529527829504.0000000000 4.5598294271 -1.6498451067 0.7225884843 0.4834735757 0.7699189922 -0.3441700871 0.234574078146 +1403638529577829376.0000000000 4.5464444875 -1.6551414975 0.7105767780 0.4769426124 0.7748393007 -0.3440002571 0.231977640385 +1403638529627829504.0000000000 4.5349409777 -1.6591707280 0.6982229866 0.4723245342 0.7780395731 -0.3435276410 0.231414599616 +1403638529677829376.0000000000 4.5248994155 -1.6618715735 0.6862140105 0.4706987428 0.7794546923 -0.3426303404 0.231295322006 +1403638529727829504.0000000000 4.5162025004 -1.6631695907 0.6746514986 0.4724210490 0.7788030415 -0.3416599253 0.231414499193 +1403638529777829376.0000000000 4.5091794638 -1.6634421940 0.6635521963 0.4763032570 0.7763059144 -0.3408614002 0.233018970112 +1403638529827829504.0000000000 4.5030556309 -1.6627890505 0.6530576099 0.4818371582 0.7728542117 -0.3403774034 0.233821606397 +1403638529877829376.0000000000 4.4982423854 -1.6619478843 0.6434374016 0.4861350785 0.7698810794 -0.3397642977 0.235618401325 +1403638529927829504.0000000000 4.4951164349 -1.6604906728 0.6351529367 0.4889701711 0.7680668169 -0.3390990615 0.236629167631 +1403638529977829376.0000000000 4.4941033533 -1.6583925452 0.6280298913 0.4900248301 0.7673370963 -0.3390732187 0.236851850083 +1403638530027829504.0000000000 4.4951398628 -1.6552429565 0.6216521227 0.4892134140 0.7676083963 -0.3392668629 0.237372242034 +1403638530077829376.0000000000 4.4971729113 -1.6515066886 0.6159169442 0.4876826314 0.7683978701 -0.3400846485 0.236796951236 +1403638530127829504.0000000000 4.5007265841 -1.6471405270 0.6104479234 0.4858229019 0.7687651290 -0.3421200671 0.236495547878 +1403638530177829376.0000000000 4.5052412463 -1.6423684827 0.6052799118 0.4844261798 0.7683084354 -0.3448627911 0.236860886938 +1403638530227829504.0000000000 4.5106517284 -1.6371485156 0.6000218152 0.4836478897 0.7670516156 -0.3477934764 0.238235672419 +1403638530277829376.0000000000 4.5164114434 -1.6321806795 0.5948185468 0.4835857137 0.7656261433 -0.3504238539 0.239091172428 +1403638530327829504.0000000000 4.5218447348 -1.6280199099 0.5896162179 0.4835532204 0.7641850359 -0.3532434866 0.239617514199 +1403638530377829376.0000000000 4.5280110765 -1.6241800358 0.5845631955 0.4828790106 0.7630508758 -0.3551520408 0.241760728934 +1403638530427829504.0000000000 4.5338452844 -1.6205245237 0.5802426660 0.4824818601 0.7621212193 -0.3568727506 0.242949257428 +1403638530477829376.0000000000 4.5390730795 -1.6173792443 0.5767125776 0.4826301573 0.7613630548 -0.3588081785 0.24217993532 +1403638530527829504.0000000000 4.5437985574 -1.6151243928 0.5737373531 0.4832823395 0.7605382871 -0.3605667333 0.240855402631 +1403638530577829376.0000000000 4.5482338866 -1.6138409976 0.5707810660 0.4825224932 0.7601142818 -0.3620294091 0.241522315824 +1403638530627829504.0000000000 4.5517283118 -1.6129539185 0.5678866228 0.4804297210 0.7607487261 -0.3633942420 0.241647023224 +1403638530677829376.0000000000 4.5546650321 -1.6124500974 0.5649033247 0.4773864796 0.7620445365 -0.3651783003 0.240904716462 +1403638530727829504.0000000000 4.5570364745 -1.6117970647 0.5618075708 0.4743930782 0.7635140885 -0.3668185471 0.23966976783 +1403638530777829376.0000000000 4.5592310358 -1.6113757042 0.5586694317 0.4720824002 0.7646336068 -0.3678736102 0.239045313111 +1403638530827829504.0000000000 4.5611565323 -1.6108976958 0.5557766476 0.4712454199 0.7652050204 -0.3681478716 0.238445330263 +1403638530877829376.0000000000 4.5624395313 -1.6103730450 0.5536226377 0.4719866716 0.7654457783 -0.3676045579 0.237040568733 +1403638530927829504.0000000000 4.5635831668 -1.6098588948 0.5519151048 0.4736450853 0.7646432559 -0.3672823497 0.236822084917 +1403638530977829376.0000000000 4.5644368742 -1.6092848802 0.5504745698 0.4757899331 0.7633694422 -0.3669112564 0.237207007159 +1403638531027829504.0000000000 4.5648900297 -1.6086853459 0.5490347179 0.4782679213 0.7622462624 -0.3661451288 0.23701935691 +1403638531077829376.0000000000 4.5650823491 -1.6085086251 0.5481117827 0.4807093241 0.7606171858 -0.3644628966 0.23988922334 +1403638531127829504.0000000000 4.5644230719 -1.6079115246 0.5483304261 0.4828060327 0.7593201136 -0.3635290030 0.241201086206 +1403638531177829376.0000000000 4.5641527255 -1.6071115810 0.5483411568 0.4838445218 0.7593071734 -0.3617789436 0.241791420643 +1403638531227829504.0000000000 4.5640315603 -1.6066117269 0.5471954733 0.4827405317 0.7599933618 -0.3607735599 0.243339490323 +1403638531277829376.0000000000 4.5637275124 -1.6059483243 0.5465113948 0.4845946337 0.7586367125 -0.3600424047 0.244964989923 +1403638531327829504.0000000000 4.5632288376 -1.6053129591 0.5461085194 0.4876636878 0.7564730290 -0.3597200648 0.246036905809 +1403638531377829376.0000000000 4.5628408361 -1.6053391564 0.5457392790 0.4865218142 0.7573323437 -0.3597817679 0.245563281116 +1403638531427829504.0000000000 4.5629492258 -1.6056559291 0.5454695643 0.4863938997 0.7573855249 -0.3594090588 0.246197622675 +1403638531477829376.0000000000 4.5627800946 -1.6058348387 0.5455391019 0.4879959488 0.7562082937 -0.3597330568 0.246172903192 +1403638531527829504.0000000000 4.5625034321 -1.6060313642 0.5452535559 0.4877705450 0.7564613802 -0.3595540222 0.246103597737 +1403638531577829376.0000000000 4.5624321086 -1.6062360876 0.5450512675 0.4874447620 0.7568911515 -0.3587925339 0.246538650785 +1403638531627829504.0000000000 4.5622956473 -1.6062534871 0.5449884121 0.4874892182 0.7569653946 -0.3586200381 0.246473775082 +1403638531677829376.0000000000 4.5619910722 -1.6060916738 0.5450307776 0.4875899044 0.7567751167 -0.3593766694 0.24575580825 +1403638531727829504.0000000000 4.5621459640 -1.6062263723 0.5450229185 0.4873327954 0.7568931049 -0.3591061632 0.246297255101 +1403638531777829376.0000000000 4.5621527473 -1.6060601834 0.5451192299 0.4875512425 0.7567097126 -0.3594084971 0.245987253839 +1403638531827829504.0000000000 4.5621709687 -1.6062310046 0.5450678585 0.4873831897 0.7568364348 -0.3592279425 0.246194075127 +1403638531877829376.0000000000 4.5620913201 -1.6062230089 0.5450827799 0.4874634128 0.7567745352 -0.3593218750 0.246088427678 +1403638531927829504.0000000000 4.5621609757 -1.6062501499 0.5451163804 0.4874918375 0.7567269072 -0.3593928844 0.246074888888 +1403638531977829376.0000000000 4.5622587993 -1.6062851141 0.5451359603 0.4873814325 0.7567694389 -0.3593425051 0.246236308469 +1403638532027829504.0000000000 4.5621395163 -1.6062261840 0.5450891114 0.4875577495 0.7566550980 -0.3595201881 0.245979141125 +1403638532077829376.0000000000 4.5623063235 -1.6062782471 0.5450500264 0.4873292271 0.7568074030 -0.3592426157 0.246368671523 +1403638532127829504.0000000000 4.5622597111 -1.6061376678 0.5451141488 0.4875543328 0.7566304723 -0.3596047414 0.245938063059 +1403638532177829376.0000000000 4.5623191989 -1.6062845244 0.5449933588 0.4873667662 0.7567721457 -0.3593048544 0.246311949171 +1403638532227829504.0000000000 4.5622201534 -1.6062358945 0.5449855041 0.4874517336 0.7566904533 -0.3595070172 0.246099715334 +1403638532277829376.0000000000 4.5623034947 -1.6062130785 0.5450100062 0.4874062951 0.7567020770 -0.3594793939 0.246194304411 +1403638532327829504.0000000000 4.5623056959 -1.6061889446 0.5450223313 0.4874068463 0.7566957358 -0.3594886409 0.246199201153 +1403638532377829376.0000000000 4.5622771989 -1.6061179649 0.5450532753 0.4874518294 0.7566905604 -0.3595056662 0.246101169684 +1403638532427829504.0000000000 4.5623206849 -1.6062121150 0.5450602371 0.4873861059 0.7567206838 -0.3594457582 0.246226191502 +1403638532477829376.0000000000 4.5622883729 -1.6060692610 0.5451605976 0.4874884929 0.7566464883 -0.3595899641 0.24604088817 +1403638532527829504.0000000000 4.5622724204 -1.6061990445 0.5451184020 0.4873734131 0.7567053891 -0.3594909474 0.246232347815 +1403638532577829376.0000000000 4.5621914740 -1.6061467776 0.5451318862 0.4874474891 0.7566447619 -0.3596410907 0.24605270896 +1403638532627829504.0000000000 4.5622840739 -1.6061647002 0.5451317061 0.4873495389 0.7567104398 -0.3595471313 0.246182041651 +1403638532677829376.0000000000 4.5623070600 -1.6060928964 0.5451565417 0.4874233312 0.7566454571 -0.3596472406 0.246089436425 +1403638532727829504.0000000000 4.5622866563 -1.6061426706 0.5451002482 0.4873825565 0.7566814478 -0.3595832519 0.246153031792 +1403638532777829376.0000000000 4.5622784246 -1.6061408194 0.5450846996 0.4873594525 0.7567044133 -0.3595579730 0.246165104959 +1403638532827829504.0000000000 4.5622905466 -1.6060038476 0.5451314307 0.4873802173 0.7566731771 -0.3596265667 0.246119806784 +1403638532877829376.0000000000 4.5622400827 -1.6060973338 0.5450604441 0.4873164404 0.7567020286 -0.3595807730 0.246224276858 +1403638532927829504.0000000000 4.5622126339 -1.6060991040 0.5450530250 0.4873711668 0.7566807167 -0.3595866941 0.246172801289 +1403638532977829376.0000000000 4.5622703281 -1.6061226157 0.5450720049 0.4873426156 0.7566915999 -0.3595861147 0.24619671775 +1403638533027829504.0000000000 4.5622652137 -1.6061547081 0.5450617640 0.4873720953 0.7566639750 -0.3596207651 0.246172652744 +1403638533077829376.0000000000 4.5622483220 -1.6061553745 0.5450730404 0.4873181148 0.7566928009 -0.3596275133 0.246181054939 +1403638533127829504.0000000000 4.5622467420 -1.6062119437 0.5450678617 0.4873497144 0.7566648416 -0.3596508185 0.246170392448 +1403638533177829376.0000000000 4.5622694258 -1.6062254429 0.5450495224 0.4873434647 0.7566540251 -0.3596754181 0.246180070742 +1403638533227829504.0000000000 4.5622572179 -1.6062617503 0.5450283523 0.4873408051 0.7566532463 -0.3596883262 0.246168870013 +1403638533277829376.0000000000 4.5622708482 -1.6062563593 0.5450509961 0.4873481497 0.7566336355 -0.3597182684 0.246170855179 +1403638533327829504.0000000000 4.5622988750 -1.6062505810 0.5450492826 0.4873111786 0.7566446560 -0.3597191047 0.246208946728 +1403638533377829376.0000000000 4.5622511902 -1.6062620630 0.5450249832 0.4873094729 0.7566445094 -0.3597053881 0.246232812197 +1403638533427829504.0000000000 4.5621982609 -1.6062222492 0.5450422975 0.4873172751 0.7566353357 -0.3597532204 0.246175674086 +1403638533477829376.0000000000 4.5622401589 -1.6061928420 0.5450806282 0.4872914164 0.7566482975 -0.3597340496 0.246215034067 +1403638533527829504.0000000000 4.5622099730 -1.6060968084 0.5451011238 0.4872971880 0.7566378472 -0.3597819610 0.246165715047 +1403638533577829376.0000000000 4.5621753404 -1.6061799351 0.5450664848 0.4872843989 0.7566412159 -0.3597796436 0.246184063071 +1403638533627829504.0000000000 4.5622225799 -1.6061891881 0.5450795338 0.4872852326 0.7566412493 -0.3597740582 0.246190473018 +1403638533677829376.0000000000 4.5621851694 -1.6061869256 0.5450974743 0.4872999081 0.7566055019 -0.3598565918 0.246150659898 +1403638533727829504.0000000000 4.5621420166 -1.6062429306 0.5450844274 0.4872289596 0.7566390639 -0.3598318975 0.246224030899 +1403638533777829376.0000000000 4.5621462931 -1.6061998631 0.5451157472 0.4872916278 0.7565770101 -0.3599144572 0.246170023897 +1403638533827829504.0000000000 4.5622191654 -1.6061410376 0.5451768650 0.4872705228 0.7565850928 -0.3599192242 0.246179989141 +1403638533877829376.0000000000 4.5621273688 -1.6061606121 0.5451201398 0.4873412884 0.7567263734 -0.3596918322 0.245937899049 +1403638533927829504.0000000000 4.5621952816 -1.6061164350 0.5450684560 0.4872473727 0.7566667012 -0.3598177978 0.246123248621 +1403638533977829376.0000000000 4.5622019725 -1.6060833245 0.5449883676 0.4872437679 0.7566430103 -0.3599199498 0.246053846314 +1403638534027829504.0000000000 4.5622825580 -1.6060899046 0.5449417711 0.4872650089 0.7565671001 -0.3599631674 0.246181949384 +1403638534077829376.0000000000 4.5624361227 -1.6061373951 0.5449329572 0.4871136745 0.7564050530 -0.3603416607 0.246425549684 +1403638534127829504.0000000000 4.5624725602 -1.6061930637 0.5449731227 0.4871455375 0.7565297756 -0.3601807984 0.246214776744 +1403638534177829376.0000000000 4.5625076021 -1.6062065420 0.5450539964 0.4872475858 0.7564725361 -0.3602189178 0.246132938812 +1403638534227829504.0000000000 4.5624966485 -1.6062192829 0.5451430738 0.4872169014 0.7564901618 -0.3602316798 0.246120829908 +1403638534277829376.0000000000 4.5623979742 -1.6061247521 0.5452557092 0.4872338535 0.7566053735 -0.3601362105 0.245872712439 +1403638534327829504.0000000000 4.5624099552 -1.6061068689 0.5453010388 0.4872361458 0.7565621823 -0.3601773563 0.245940794916 +1403638534377829376.0000000000 4.5622870289 -1.6061051041 0.5452200155 0.4872349949 0.7565686131 -0.3601653418 0.245940887169 +1403638534427829504.0000000000 4.5622028764 -1.6060615657 0.5451743717 0.4871958049 0.7565916930 -0.3602205454 0.245866663966 +1403638534477829376.0000000000 4.5622551093 -1.6060717180 0.5451822885 0.4871062363 0.7564762839 -0.3604461043 0.246068592856 +1403638534527829504.0000000000 4.5621216504 -1.6060869553 0.5451424880 0.4870216043 0.7564791646 -0.3605362918 0.246095129626 +1403638534577829376.0000000000 4.5619568325 -1.6061521862 0.5450986077 0.4870819558 0.7566567405 -0.3602200057 0.245892848286 +1403638534627829504.0000000000 4.5620098390 -1.6061867012 0.5451061595 0.4870378626 0.7566704047 -0.3602413085 0.245906931048 +1403638534677829376.0000000000 4.5619775061 -1.6061414052 0.5451491886 0.4871431861 0.7567684456 -0.3600534547 0.245671621519 +1403638534727829504.0000000000 4.5619721602 -1.6061859211 0.5451277044 0.4870952935 0.7568012974 -0.3600057860 0.245735234399 +1403638534777829376.0000000000 4.5619871716 -1.6061630906 0.5451576792 0.4871042928 0.7568099527 -0.3599598799 0.245757987436 +1403638534827829504.0000000000 4.5621076497 -1.6060817251 0.5451836631 0.4870701676 0.7567665352 -0.3600850741 0.24577591937 +1403638534877829376.0000000000 4.5622139036 -1.6061175986 0.5451295560 0.4870071214 0.7566958717 -0.3601492666 0.246024240998 +1403638534927829504.0000000000 4.5623056321 -1.6061261425 0.5450888512 0.4869276732 0.7566626149 -0.3603245686 0.246027099173 +1403638534977829376.0000000000 4.5623768491 -1.6061780051 0.5450885244 0.4869165065 0.7566781523 -0.3602674839 0.246085005026 +1403638535027829504.0000000000 4.5623465147 -1.6061905693 0.5450619548 0.4869338400 0.7566725953 -0.3603240730 0.245984920982 +1403638535077829376.0000000000 4.5623054406 -1.6062501638 0.5450258478 0.4868839988 0.7567227183 -0.3603010358 0.245963133147 +1403638535127829504.0000000000 4.5622970209 -1.6062357228 0.5450079957 0.4868927880 0.7567268656 -0.3602813458 0.24596181767 +1403638535177829376.0000000000 4.5622600294 -1.6061712228 0.5449792919 0.4869314560 0.7566968271 -0.3603302991 0.245905966914 +1403638535227829504.0000000000 4.5621510278 -1.6061502157 0.5449415318 0.4869286306 0.7567134188 -0.3602793403 0.245935169296 +1403638535277829376.0000000000 4.5620521749 -1.6061237664 0.5449281668 0.4869720785 0.7566955645 -0.3603180142 0.245847404128 +1403638535327829504.0000000000 4.5620269448 -1.6061302815 0.5449906559 0.4869118140 0.7567128762 -0.3603385060 0.245883446901 +1403638535377829376.0000000000 4.5619708512 -1.6062038140 0.5449616273 0.4869525337 0.7567048132 -0.3603306869 0.24583907688 +1403638535427829504.0000000000 4.5620267522 -1.6062430189 0.5450040270 0.4868893896 0.7567307217 -0.3603331990 0.245880708624 +1403638535477829376.0000000000 4.5620618978 -1.6062845203 0.5450398037 0.4868618839 0.7567143053 -0.3603998465 0.24588801669 +1403638535527829504.0000000000 4.5621183111 -1.6062989352 0.5450978031 0.4868641825 0.7567143560 -0.3604163253 0.24585915428 +1403638535577829376.0000000000 4.5621354584 -1.6062881231 0.5450834439 0.4868131611 0.7567612872 -0.3603928103 0.245850203694 +1403638535627829504.0000000000 4.5621798440 -1.6062368224 0.5450768083 0.4868039812 0.7567582422 -0.3604091601 0.245853786066 +1403638535677829376.0000000000 4.5622219222 -1.6061817644 0.5451113138 0.4868032637 0.7567447164 -0.3604685553 0.245809758316 +1403638535727829504.0000000000 4.5622405482 -1.6061713410 0.5451127091 0.4867762398 0.7567375445 -0.3604870811 0.245858181804 +1403638535777829376.0000000000 4.5622327944 -1.6061433937 0.5451136934 0.4867969008 0.7567196543 -0.3604961932 0.245858977435 +1403638535827829504.0000000000 4.5621870689 -1.6060969141 0.5451504763 0.4868006356 0.7567479844 -0.3604728849 0.245798552754 +1403638535877829376.0000000000 4.5621321082 -1.6060650093 0.5451462856 0.4868051029 0.7567553750 -0.3604715110 0.245768964617 +1403638535927829504.0000000000 4.5620368505 -1.6060947364 0.5451143620 0.4867958151 0.7567416679 -0.3605293758 0.245744688034 +1403638535977829376.0000000000 4.5620119778 -1.6061525674 0.5450707442 0.4867467901 0.7567941724 -0.3605333692 0.245674240627 +1403638536027829504.0000000000 4.5620865831 -1.6061475899 0.5450618282 0.4867887169 0.7567494070 -0.3606016064 0.245628910396 +1403638536077829376.0000000000 4.5620224046 -1.6062204702 0.5449736267 0.4867792408 0.7567251647 -0.3606481748 0.245654004415 +1403638536127829504.0000000000 4.5620057970 -1.6062712230 0.5449259489 0.4867386829 0.7567449510 -0.3606850032 0.245619344198 +1403638536177829376.0000000000 4.5619874410 -1.6062946235 0.5449176871 0.4867532415 0.7567142893 -0.3607167310 0.245638364793 +1403638536227829504.0000000000 4.5619254469 -1.6063337437 0.5448961081 0.4867079024 0.7567486726 -0.3607356098 0.24559455224 +1403638536277829376.0000000000 4.5619489720 -1.6063433437 0.5448983054 0.4866925599 0.7567559249 -0.3607064135 0.24564548761 +1403638536327829504.0000000000 4.5620591750 -1.6062440923 0.5449853988 0.4867566472 0.7567421259 -0.3607180472 0.245543910134 +1403638536377829376.0000000000 4.5620599540 -1.6062708912 0.5449594856 0.4866837650 0.7567424056 -0.3607447523 0.245648261096 +1403638536427829504.0000000000 4.5620628155 -1.6062319030 0.5449809238 0.4867125226 0.7567310963 -0.3607811973 0.245572587747 +1403638536477829376.0000000000 4.5620900967 -1.6062453541 0.5449979890 0.4866707000 0.7567512565 -0.3607506461 0.245638223499 +1403638536527829504.0000000000 4.5620929619 -1.6062202641 0.5450505370 0.4866719795 0.7567764007 -0.3607811188 0.245513437501 +1403638536577829376.0000000000 4.5621072860 -1.6062175512 0.5450654099 0.4866580300 0.7567703429 -0.3607949806 0.245539389646 +1403638536627829504.0000000000 4.5621374445 -1.6062013218 0.5450851399 0.4866896990 0.7567156431 -0.3608815577 0.245517970135 +1403638536677829376.0000000000 4.5621581307 -1.6061957246 0.5450710496 0.4866284097 0.7567859456 -0.3608165733 0.245518275986 +1403638536727829504.0000000000 4.5621703417 -1.6061955181 0.5450468067 0.4866573904 0.7567262792 -0.3608602000 0.245580615707 +1403638536777829376.0000000000 4.5621420121 -1.6062393570 0.5450025152 0.4866337002 0.7567260604 -0.3608960252 0.245575590075 +1403638536827829504.0000000000 4.5622145147 -1.6061601983 0.5450441777 0.4866603269 0.7566923397 -0.3609414148 0.245560021925 +1403638536877829376.0000000000 4.5621128064 -1.6061178284 0.5450921945 0.4866947784 0.7566462472 -0.3610100466 0.245532880698 +1403638536927829504.0000000000 4.5620812413 -1.6061381957 0.5451508478 0.4866585570 0.7566777765 -0.3609705502 0.245565578508 +1403638536977829376.0000000000 4.5620132066 -1.6061342890 0.5451788213 0.4866650992 0.7566433872 -0.3611180881 0.245441626888 +1403638537027829504.0000000000 4.5619426166 -1.6062014341 0.5451359045 0.4866150786 0.7567023890 -0.3610079066 0.245520978935 +1403638537077829376.0000000000 4.5618952446 -1.6061779467 0.5450941027 0.4866453429 0.7566823977 -0.3610815244 0.245414327374 +1403638537127829504.0000000000 4.5618265133 -1.6062642195 0.5450067098 0.4865864017 0.7567081624 -0.3609846064 0.245594268134 +1403638537177829376.0000000000 4.5618199367 -1.6062817310 0.5449877625 0.4866052436 0.7566633135 -0.3610985345 0.245527626369 +1403638537227829504.0000000000 4.5618382468 -1.6063119833 0.5449904668 0.4865106806 0.7566988122 -0.3611309891 0.245557883217 +1403638537277829376.0000000000 4.5618881020 -1.6063147380 0.5450217532 0.4864709925 0.7567164976 -0.3611118731 0.245610119704 +1403638537327829504.0000000000 4.5619269367 -1.6062676486 0.5450397904 0.4865031338 0.7566842040 -0.3611891229 0.245532347609 +1403638537377829376.0000000000 4.5619913835 -1.6062091582 0.5450502394 0.4864439121 0.7567276163 -0.3611404558 0.245587471887 +1403638537427829504.0000000000 4.5621323026 -1.6060584256 0.5451003985 0.4865000372 0.7567075322 -0.3611889666 0.24546681025 +1403638537477829376.0000000000 4.5621634028 -1.6059729087 0.5450686970 0.4864355560 0.7567379502 -0.3611722612 0.245525400684 +1403638537527829504.0000000000 4.5622740044 -1.6059635855 0.5451080410 0.4864528928 0.7567377047 -0.3611925248 0.245461991958 +1403638537577829376.0000000000 4.5623107845 -1.6060939099 0.5450738573 0.4863900043 0.7567991837 -0.3611261495 0.245494732053 +1403638537627829504.0000000000 4.5622318732 -1.6062016846 0.5450032369 0.4864586593 0.7567560903 -0.3611004659 0.24552931827 +1403638537677829376.0000000000 4.5621460315 -1.6063549103 0.5449412067 0.4863448255 0.7568125619 -0.3611336774 0.245531920405 +1403638537727829504.0000000000 4.5620078213 -1.6064507052 0.5448780114 0.4863634271 0.7568042200 -0.3611270092 0.245530594017 +1403638537777829376.0000000000 4.5617946777 -1.6065797912 0.5449390888 0.4863942542 0.7567865849 -0.3611436642 0.245499385216 +1403638537827829504.0000000000 4.5619188860 -1.6065397354 0.5449568456 0.4863577697 0.7568017820 -0.3611646667 0.245493922911 +1403638537877829376.0000000000 4.5620482570 -1.6064154488 0.5448804155 0.4862562823 0.7568853944 -0.3611030039 0.245527896981 +1403638537927829504.0000000000 4.5622176494 -1.6062381879 0.5449306872 0.4863076439 0.7568201599 -0.3611976363 0.24548806217 +1403638537977829376.0000000000 4.5621173973 -1.6063099748 0.5449925985 0.4862350843 0.7568221502 -0.3612304195 0.245577400731 +1403638538027829504.0000000000 4.5619452116 -1.6063520888 0.5450849750 0.4862255144 0.7568418074 -0.3612557860 0.245498441558 +1403638538077829376.0000000000 4.5618716042 -1.6064105587 0.5452291355 0.4863015191 0.7567867658 -0.3612314843 0.245553331133 +1403638538127829504.0000000000 4.5615745174 -1.6066443191 0.5453744486 0.4863229188 0.7567745438 -0.3611907973 0.245608461668 +1403638538177829376.0000000000 4.5615401136 -1.6066590038 0.5454974354 0.4862993988 0.7567848297 -0.3612379008 0.245554057829 +1403638538227829504.0000000000 4.5618353466 -1.6064653076 0.5454143829 0.4862320479 0.7568145405 -0.3612715930 0.245546294919 +1403638538277829376.0000000000 4.5620461080 -1.6062683086 0.5452449634 0.4862321818 0.7568643701 -0.3611993049 0.245498783686 +1403638538327829504.0000000000 4.5620739639 -1.6062349198 0.5451513594 0.4862272955 0.7568510804 -0.3612146896 0.245526795074 +1403638538377829376.0000000000 4.5621339626 -1.6061079308 0.5451901507 0.4862306950 0.7568147959 -0.3611807130 0.245681843917 +1403638538427829504.0000000000 4.5621656867 -1.6059886084 0.5453427956 0.4863817224 0.7567165936 -0.3612245234 0.245620969888 +1403638538477829376.0000000000 4.5620695038 -1.6060666809 0.5455788978 0.4862348381 0.7568293004 -0.3611844510 0.245623460936 +1403638538527829504.0000000000 4.5619507813 -1.6061996353 0.5457661922 0.4864433630 0.7566589729 -0.3612930678 0.245575594371 +1403638538577829376.0000000000 4.5619453630 -1.6063733766 0.5459610544 0.4862170622 0.7567571892 -0.3612331418 0.245809158295 +1403638538627829504.0000000000 4.5617615010 -1.6063578079 0.5461411910 0.4866295738 0.7564480263 -0.3613305196 0.245801336359 +1403638538677829376.0000000000 4.5617415690 -1.6063145518 0.5460504192 0.4865307149 0.7565585347 -0.3612770446 0.245735516433 +1403638538727829504.0000000000 4.5618601328 -1.6063841912 0.5459862052 0.4870901862 0.7561650347 -0.3611451371 0.246032072704 +1403638538777829376.0000000000 4.5619694762 -1.6061549875 0.5457285130 0.4877520212 0.7558996121 -0.3608535906 0.245964282723 +1403638538827829504.0000000000 4.5624326242 -1.6054490687 0.5450435841 0.4881801737 0.7558395553 -0.3604611385 0.245874871153 +1403638538877829376.0000000000 4.5632383067 -1.6044417125 0.5448827518 0.4895793223 0.7551706876 -0.3600215454 0.24579220202 +1403638538927829504.0000000000 4.5647109925 -1.6032390511 0.5453280966 0.4923800169 0.7534036398 -0.3587598348 0.247459603538 +1403638538977829376.0000000000 4.5661847087 -1.6017119869 0.5465480800 0.4960544235 0.7509384343 -0.3577342835 0.24909367546 +1403638539027829504.0000000000 4.5679422059 -1.6001249506 0.5467459439 0.4983358174 0.7487691400 -0.3577694601 0.251012353319 +1403638539077829376.0000000000 4.5702029231 -1.5981019393 0.5482791926 0.5029355007 0.7451295403 -0.3572126259 0.253450173301 +1403638539127829504.0000000000 4.5729209455 -1.5953341584 0.5508909436 0.5073722378 0.7420331198 -0.3567360835 0.254361215954 +1403638539177829376.0000000000 4.5759841732 -1.5921742356 0.5546357115 0.5103338269 0.7400275217 -0.3558217281 0.255557332269 +1403638539227829504.0000000000 4.5793067928 -1.5887730764 0.5605620882 0.5139540644 0.7377715242 -0.3544500327 0.256728596265 +1403638539277829376.0000000000 4.5827577405 -1.5853504819 0.5683585217 0.5154082932 0.7368531777 -0.3538419358 0.257288884881 +1403638539327829504.0000000000 4.5858391113 -1.5820899355 0.5783410874 0.5154789977 0.7369905522 -0.3538364639 0.256760755841 +1403638539377829376.0000000000 4.5891061618 -1.5788957029 0.5901031067 0.5144099646 0.7379364652 -0.3536472124 0.256448456426 +1403638539427829504.0000000000 4.5925243078 -1.5756408388 0.6036762964 0.5135500459 0.7388630438 -0.3533762313 0.255876907998 +1403638539477829376.0000000000 4.5960890905 -1.5722952902 0.6189608275 0.5119463245 0.7402463176 -0.3533786977 0.255087918501 +1403638539527829504.0000000000 4.5997037784 -1.5689806020 0.6352359187 0.5111943228 0.7411349648 -0.3529959396 0.254545074318 +1403638539577829376.0000000000 4.6035432938 -1.5655689013 0.6520476317 0.5109410702 0.7416246356 -0.3524674613 0.254359610161 +1403638539627829504.0000000000 4.6074485153 -1.5620424271 0.6678077065 0.5107420977 0.7421238241 -0.3523680992 0.253439266783 +1403638539677829376.0000000000 4.6113775407 -1.5585348196 0.6812039463 0.5108743311 0.7423537927 -0.3523147503 0.25257193232 +1403638539727829504.0000000000 4.6153683757 -1.5548135230 0.6916303710 0.5102268878 0.7430949619 -0.3516849158 0.252578939195 +1403638539777829376.0000000000 4.6193017796 -1.5509759695 0.6990164416 0.5091557139 0.7441923629 -0.3510869748 0.252341281212 +1403638539827829504.0000000000 4.6234272661 -1.5468451028 0.7049840940 0.5082439986 0.7450984188 -0.3510091715 0.251612689987 +1403638539877829376.0000000000 4.6276624278 -1.5423473779 0.7101145929 0.5061072543 0.7468243139 -0.3514359832 0.250203199376 +1403638539927829504.0000000000 4.6321050162 -1.5374359874 0.7149591658 0.5036020874 0.7489735611 -0.3517392389 0.248400986643 +1403638539977829376.0000000000 4.6370900622 -1.5320783299 0.7198425609 0.5005940559 0.7512455402 -0.3527508949 0.246175822592 +1403638540027829504.0000000000 4.6429681497 -1.5262458489 0.7246166329 0.4966235391 0.7538952414 -0.3540585139 0.24423266391 +1403638540077829376.0000000000 4.6491700265 -1.5198831120 0.7288235181 0.4924043268 0.7568705759 -0.3546212181 0.242752346993 +1403638540127829504.0000000000 4.6564932782 -1.5122593823 0.7328031084 0.4884765795 0.7594523413 -0.3559223737 0.240711521192 +1403638540177829376.0000000000 4.6652887647 -1.5032943648 0.7369134359 0.4868615485 0.7606850723 -0.3557634555 0.240325648134 +1403638540227829504.0000000000 4.6757768289 -1.4928578195 0.7417277784 0.4884989832 0.7598490802 -0.3547041099 0.241211760149 +1403638540277829376.0000000000 4.6875821278 -1.4811105037 0.7472218811 0.4926924323 0.7572420846 -0.3531304533 0.243181979998 +1403638540327829504.0000000000 4.7004646365 -1.4683673877 0.7526775886 0.4970381597 0.7544200249 -0.3516157171 0.245295497989 +1403638540377829376.0000000000 4.7138069400 -1.4550308923 0.7572388195 0.5010333580 0.7522488550 -0.3492341597 0.247230127701 +1403638540427829504.0000000000 4.7273173780 -1.4409005639 0.7613789538 0.5039904626 0.7515482381 -0.3464344964 0.247289302649 +1403638540477829376.0000000000 4.7406610577 -1.4261515947 0.7651757755 0.5060461806 0.7522716963 -0.3429297362 0.245771751882 +1403638540527829504.0000000000 4.7540171748 -1.4107999243 0.7684601491 0.5075733773 0.7542340013 -0.3383769098 0.242902047754 +1403638540577829376.0000000000 4.7675357974 -1.3947165548 0.7717913115 0.5095601728 0.7566732679 -0.3324171606 0.239359201257 +1403638540627829504.0000000000 4.7810837142 -1.3780167785 0.7750103051 0.5117254108 0.7595022794 -0.3255781351 0.235143082921 +1403638540677829376.0000000000 4.7949194962 -1.3608029268 0.7779626670 0.5135555992 0.7630393218 -0.3165701299 0.23198058709 +1403638540727829504.0000000000 4.8088773423 -1.3429134972 0.7812118744 0.5163495741 0.7664850860 -0.3054153453 0.229358228875 +1403638540777829376.0000000000 4.8223479549 -1.3243127654 0.7840946883 0.5182291467 0.7708765474 -0.2940126132 0.225265362466 +1403638540827829504.0000000000 4.8354717853 -1.3049737585 0.7868491769 0.5204892756 0.7754195194 -0.2807328736 0.221369683259 +1403638540877829376.0000000000 4.8477942240 -1.2847475179 0.7890439727 0.5223258764 0.7803306215 -0.2677858833 0.215755696926 +1403638540927829504.0000000000 4.8596939631 -1.2634924444 0.7910036346 0.5247307597 0.7846817335 -0.2542864220 0.210405851784 +1403638540977829376.0000000000 4.8707245132 -1.2412592473 0.7927603250 0.5275062825 0.7883806874 -0.2428749468 0.202989590443 +1403638541027829504.0000000000 4.8813429275 -1.2182021023 0.7939954563 0.5301972694 0.7912641207 -0.2327873951 0.19647385456 +1403638541077829376.0000000000 4.8913620286 -1.1943096696 0.7946744323 0.5330069501 0.7933909543 -0.2240810976 0.19032090392 +1403638541127829504.0000000000 4.9010587942 -1.1696185838 0.7943435359 0.5353328238 0.7950079398 -0.2169096034 0.185287256426 +1403638541177829376.0000000000 4.9103649901 -1.1441208957 0.7926713472 0.5367034963 0.7965521801 -0.2111795677 0.181265472598 +1403638541227829504.0000000000 4.9192246679 -1.1179882613 0.7901833807 0.5373322838 0.7981310631 -0.2064318352 0.177895251042 +1403638541277829376.0000000000 4.9276151058 -1.0909652002 0.7884390694 0.5380612441 0.7989566460 -0.2027524620 0.176209575723 +1403638541327829504.0000000000 4.9352342573 -1.0629657402 0.7887121222 0.5384129880 0.7996895050 -0.2007758262 0.174060959288 +1403638541377829376.0000000000 4.9421067883 -1.0341821760 0.7903793222 0.5386415601 0.8000929238 -0.1993441942 0.173142933205 +1403638541427829504.0000000000 4.9481778724 -1.0048856710 0.7931127072 0.5388389731 0.8002032006 -0.1997257423 0.171572219873 +1403638541477829376.0000000000 4.9532052902 -0.9750998664 0.7970465146 0.5392561034 0.7999957548 -0.1990460050 0.1720184152 +1403638541527829504.0000000000 4.9576496296 -0.9443597975 0.8026478406 0.5398994374 0.7993830161 -0.1986318784 0.173322727906 +1403638541577829376.0000000000 4.9610300692 -0.9123095011 0.8101887885 0.5408838802 0.7988721004 -0.1979998850 0.173332169063 +1403638541627829504.0000000000 4.9634810534 -0.8785399173 0.8195993191 0.5419145607 0.7987627116 -0.1959935877 0.172896654478 +1403638541677829376.0000000000 4.9642829357 -0.8440039809 0.8311256127 0.5439179300 0.7983907840 -0.1946201213 0.169848314216 +1403638541727829504.0000000000 4.9637049684 -0.8089430641 0.8445459914 0.5456222260 0.7986803226 -0.1914306961 0.166614577112 +1403638541777829376.0000000000 4.9617685483 -0.7735031925 0.8598532873 0.5474669879 0.7992358176 -0.1890159048 0.160545920951 +1403638541827829504.0000000000 4.9588374143 -0.7379377041 0.8766033071 0.5491611142 0.8001227149 -0.1851893735 0.15469520881 +1403638541877829376.0000000000 4.9544288904 -0.7023943317 0.8940663947 0.5508018249 0.8012145433 -0.1802832273 0.148897828246 +1403638541927829504.0000000000 4.9494022484 -0.6666204767 0.9104743111 0.5513064563 0.8033490255 -0.1741049557 0.142755031097 +1403638541977829376.0000000000 4.9436887113 -0.6307196835 0.9253490916 0.5521343224 0.8054165987 -0.1666341614 0.136692533653 +1403638542027829504.0000000000 4.9372405285 -0.5948615549 0.9388372868 0.5532339069 0.8074238638 -0.1590102541 0.129285294855 +1403638542077829376.0000000000 4.9305074513 -0.5589175542 0.9508206254 0.5540612027 0.8096204148 -0.1501465048 0.122421381687 +1403638542127829504.0000000000 4.9232607077 -0.5229841847 0.9613118328 0.5551643856 0.8116708008 -0.1402246329 0.115412600673 +1403638542177829376.0000000000 4.9155839003 -0.4867196424 0.9707370639 0.5569540192 0.8132297225 -0.1303971872 0.107033697925 +1403638542227829504.0000000000 4.9076987363 -0.4506078212 0.9782785590 0.5573574297 0.8156679348 -0.1194346867 0.0988628915567 +1403638542277829376.0000000000 4.8997691495 -0.4142953618 0.9844945693 0.5577568575 0.8179354695 -0.1074283332 0.0913674386487 +1403638542327829504.0000000000 4.8916115228 -0.3776027934 0.9898045221 0.5589177963 0.8194121013 -0.0957470779 0.0837090332263 +1403638542377829376.0000000000 4.8838832085 -0.3402571438 0.9944833067 0.5626961198 0.8185667703 -0.0845774386 0.0785377376574 +1403638542427829504.0000000000 4.8763193501 -0.3026085514 0.9982069426 0.5678830311 0.8163508806 -0.0727452294 0.0760804468378 +1403638542477829376.0000000000 4.8686672076 -0.2650032134 1.0008668109 0.5739525764 0.8130505890 -0.0610541646 0.0761548997272 +1403638542527829504.0000000000 4.8609287839 -0.2276343648 1.0022282594 0.5780685542 0.8106136255 -0.0500828708 0.0789557011917 +1403638542577829376.0000000000 4.8519256586 -0.1904597914 1.0038319522 0.5816680323 0.8082004715 -0.0395848100 0.0831104133283 +1403638542627829504.0000000000 4.8408379444 -0.1540750887 1.0059583892 0.5823089951 0.8080092824 -0.0334117825 0.0831918662899 +1403638542677829376.0000000000 4.8276059797 -0.1181874790 1.0099234942 0.5823200508 0.8082259508 -0.0295462672 0.0824693212749 +1403638542727829504.0000000000 4.8118151833 -0.0833629798 1.0159808297 0.5805885058 0.8099143933 -0.0294770052 0.0780177452101 +1403638542777829376.0000000000 4.7937024952 -0.0487536521 1.0244593763 0.5789140123 0.8116486799 -0.0318263962 0.0712184473439 +1403638542827829504.0000000000 4.7739636199 -0.0150784805 1.0348597625 0.5772054436 0.8131888504 -0.0337371423 0.0664798815332 +1403638542877829376.0000000000 4.7529231326 0.0176230357 1.0463251731 0.5742778653 0.8155105283 -0.0363693662 0.0618448122581 +1403638542927829504.0000000000 4.7309151007 0.0504016915 1.0600692487 0.5721846304 0.8171632272 -0.0387084184 0.0578849482161 +1403638542977829376.0000000000 4.7082399584 0.0822858458 1.0756311608 0.5701906345 0.8186265644 -0.0406779444 0.0554841713297 +1403638543027829504.0000000000 4.6848602661 0.1137468553 1.0918183197 0.5683998195 0.8199377320 -0.0426209732 0.0529831423035 +1403638543077829376.0000000000 4.6611073257 0.1457642297 1.1076662345 0.5671470954 0.8208199320 -0.0446090204 0.051076869564 +1403638543127829504.0000000000 4.6371384361 0.1782156127 1.1222090447 0.5669164280 0.8209370115 -0.0463416283 0.0502059782575 +1403638543177829376.0000000000 4.6128883151 0.2109743743 1.1352328874 0.5666615071 0.8210502615 -0.0471792704 0.0504511728379 +1403638543227829504.0000000000 4.5883553994 0.2436496306 1.1466180509 0.5664301363 0.8211492556 -0.0480734258 0.0505939366009 +1403638543277829376.0000000000 4.5636759343 0.2765627451 1.1567130136 0.5673288060 0.8204668349 -0.0494159338 0.0503017312184 +1403638543327829504.0000000000 4.5391636469 0.3094385439 1.1649115481 0.5666034611 0.8208991412 -0.0504044424 0.0504431364436 +1403638543377829376.0000000000 4.5141131581 0.3425174524 1.1722124607 0.5662172200 0.8211658834 -0.0505654332 0.0502771192798 +1403638543427829504.0000000000 4.4887845525 0.3757444571 1.1784051382 0.5661203479 0.8214083291 -0.0490028278 0.0489370152261 +1403638543477829376.0000000000 4.4633160945 0.4090124124 1.1832765096 0.5659417543 0.8217922271 -0.0459475560 0.0475004031781 +1403638543527829504.0000000000 4.4373192295 0.4422036612 1.1869741110 0.5656843014 0.8223770874 -0.0415976083 0.0443490273594 +1403638543577829376.0000000000 4.4110493314 0.4752149274 1.1895809074 0.5655026377 0.8229837224 -0.0344063795 0.0414820489743 +1403638543627829504.0000000000 4.3840127530 0.5080423594 1.1906658886 0.5650456271 0.8237744478 -0.0254669135 0.0383475522557 +1403638543677829376.0000000000 4.3564145436 0.5408870090 1.1914973919 0.5653529762 0.8240115822 -0.0158119606 0.0336289557552 +1403638543727829504.0000000000 4.3282011819 0.5740182319 1.1926990199 0.5653618307 0.8243455983 -0.0048906837 0.0282208447783 +1403638543777829376.0000000000 4.2994558461 0.6073382357 1.1951725161 0.5659091531 0.8241284266 0.0069645456 0.0225978327841 +1403638543827829504.0000000000 4.2703058675 0.6408636625 1.1994203543 0.5666661829 0.8235072344 0.0201142683 0.0179077721503 +1403638543877829376.0000000000 4.2401652373 0.6748780021 1.2061949590 0.5673931984 0.8227797887 0.0314456028 0.0104666936362 +1403638543927829504.0000000000 4.2093741578 0.7094369473 1.2152420096 0.5676468886 0.8221623080 0.0426434694 0.00277192975862 +1403638543977829376.0000000000 4.1783449159 0.7446288020 1.2262376450 0.5679442243 0.8214422853 0.0514900698 -0.00455002785917 +1403638544027829504.0000000000 4.1469101381 0.7793828633 1.2388303656 0.5672374282 0.8213785255 0.0583413060 -0.0132404642499 +1403638544077829376.0000000000 4.1153278195 0.8144173258 1.2516737940 0.5657761520 0.8218350291 0.0634251674 -0.0214890405575 +1403638544127829504.0000000000 4.0840068658 0.8502655586 1.2653306771 0.5654146693 0.8215523437 0.0682085915 -0.0265628741983 +1403638544177829376.0000000000 4.0523858450 0.8865237629 1.2781253264 0.5651064812 0.8213268517 0.0706203223 -0.0330096604211 +1403638544227829504.0000000000 4.0211320371 0.9233137922 1.2890911271 0.5656661320 0.8205573334 0.0732366112 -0.0366590834848 +1403638544277829376.0000000000 3.9901501977 0.9603985196 1.2985221695 0.5657891819 0.8201746374 0.0747223836 -0.0401588247248 +1403638544327829504.0000000000 3.9596089763 0.9975449973 1.3060732158 0.5654736200 0.8201383388 0.0767964520 -0.0414125029155 +1403638544377829376.0000000000 3.9293547954 1.0350467654 1.3128864685 0.5647620484 0.8205218498 0.0774169504 -0.0423596324582 +1403638544427829504.0000000000 3.8992476050 1.0729024378 1.3184842067 0.5636944776 0.8211805273 0.0777096761 -0.0432698932724 +1403638544477829376.0000000000 3.8695861568 1.1115873556 1.3231777452 0.5632770782 0.8214707181 0.0783163551 -0.0420873016429 +1403638544527829504.0000000000 3.8398939294 1.1505182584 1.3274504532 0.5647026483 0.8205250291 0.0780543758 -0.0419178962032 +1403638544577829376.0000000000 3.8100769202 1.1894072598 1.3324035460 0.5672367783 0.8187110972 0.0783774884 -0.0425622607334 +1403638544627829504.0000000000 3.7801154611 1.2287504201 1.3387448740 0.5718212485 0.8153736848 0.0791914030 -0.0437599774324 +1403638544677829376.0000000000 3.7502498367 1.2685771908 1.3469495636 0.5757706723 0.8124635194 0.0799372510 -0.0447347571593 +1403638544727829504.0000000000 3.7207324439 1.3073571059 1.3561891477 0.5772854433 0.8112670696 0.0807737606 -0.0454187015185 +1403638544777829376.0000000000 3.6917710797 1.3455796704 1.3657174989 0.5760432291 0.8120881979 0.0810614203 -0.0460000358203 +1403638544827829504.0000000000 3.6630927405 1.3832910393 1.3743474972 0.5737036304 0.8136603742 0.0820436273 -0.045714146792 +1403638544877829376.0000000000 3.6346034258 1.4208698861 1.3816613826 0.5702869146 0.8160217238 0.0821495775 -0.0461825536604 +1403638544927829504.0000000000 3.6062716172 1.4587417030 1.3878258760 0.5688953460 0.8169547522 0.0824137815 -0.046378732719 +1403638544977829376.0000000000 3.5778733068 1.4966842961 1.3928187396 0.5686039649 0.8171162923 0.0824812901 -0.046982260341 +1403638545027829504.0000000000 3.5495433662 1.5346985472 1.3964239422 0.5693554425 0.8165302373 0.0827453490 -0.0476020891395 +1403638545077829376.0000000000 3.5214626236 1.5727827295 1.3986036906 0.5700963915 0.8159879799 0.0827727038 -0.0479833375754 +1403638545127829504.0000000000 3.4936935690 1.6108793083 1.3992502010 0.5704628699 0.8156735595 0.0832618754 -0.0481271064582 +1403638545177829376.0000000000 3.4663216262 1.6486633630 1.3978981559 0.5698152066 0.8160895815 0.0838340974 -0.0477521668167 +1403638545227829504.0000000000 3.4390516192 1.6863379558 1.3949084904 0.5690231306 0.8165780183 0.0847024302 -0.0473129498186 +1403638545277829376.0000000000 3.4117303103 1.7242007478 1.3907423000 0.5695620897 0.8161301758 0.0855291185 -0.0470673139401 +1403638545327829504.0000000000 3.3844469302 1.7621800614 1.3853359663 0.5714061758 0.8148177059 0.0857687015 -0.0470193387786 +1403638545377829376.0000000000 3.3570987077 1.7998309436 1.3785842682 0.5734854446 0.8133548021 0.0855385127 -0.04745074895 +1403638545427829504.0000000000 3.3297598026 1.8368326986 1.3703563026 0.5730738250 0.8136057512 0.0853421460 -0.0484643245641 +1403638545477829376.0000000000 3.3022971367 1.8734010046 1.3616240405 0.5727464665 0.8136415879 0.0863153248 -0.049985160204 +1403638545527829504.0000000000 3.2744983853 1.9094512718 1.3541891246 0.5720761593 0.8136744626 0.0890968523 -0.0521966253195 +1403638545577829376.0000000000 3.2465027463 1.9453122722 1.3476015309 0.5706666017 0.8139828592 0.0933053204 -0.0553683281166 +1403638545627829504.0000000000 3.2181340621 1.9807181671 1.3427089443 0.5697412517 0.8136235988 0.0985702120 -0.0607902867084 +1403638545677829376.0000000000 3.1900346491 2.0162457740 1.3394350342 0.5688490071 0.8129490953 0.1059085784 -0.0656349652308 +1403638545727829504.0000000000 3.1620826852 2.0514162830 1.3377934131 0.5666530608 0.8129374596 0.1139925916 -0.0710118622859 +1403638545777829376.0000000000 3.1343833810 2.0864846033 1.3379714467 0.5656715857 0.8116462693 0.1240286559 -0.0765694667416 +1403638545827829504.0000000000 3.1065765383 2.1213257996 1.3400229062 0.5648579769 0.8098505067 0.1349324271 -0.0828906681917 +1403638545877829376.0000000000 3.0787224751 2.1556840077 1.3439956635 0.5626591384 0.8087205198 0.1460252789 -0.0897910504554 +1403638545927829504.0000000000 3.0510266174 2.1901307107 1.3497133988 0.5611347748 0.8066777847 0.1588668168 -0.0957081532768 +1403638545977829376.0000000000 3.0233281927 2.2243237304 1.3573928385 0.5588796733 0.8049677276 0.1709970280 -0.102178690387 +1403638546027829504.0000000000 2.9960056884 2.2585792792 1.3664555451 0.5576454351 0.8027361132 0.1824938242 -0.106500259646 +1403638546077829376.0000000000 2.9685649706 2.2929151875 1.3754212704 0.5565055708 0.8005560855 0.1929397469 -0.110389119351 +1403638546127829504.0000000000 2.9407393086 2.3275146051 1.3833373258 0.5555395717 0.7985919248 0.2013731429 -0.114348499485 +1403638546177829376.0000000000 2.9122319900 2.3622214884 1.3900123145 0.5546471706 0.7968638233 0.2075401263 -0.119589544543 +1403638546227829504.0000000000 2.8833313028 2.3972366617 1.3947103731 0.5532622354 0.7960101746 0.2123870046 -0.12312782424 +1403638546277829376.0000000000 2.8543103945 2.4322197022 1.3980665088 0.5522782092 0.7951805330 0.2162977515 -0.12606340549 +1403638546327829504.0000000000 2.8246889533 2.4673765418 1.4002044673 0.5511275773 0.7947945419 0.2179818049 -0.130552527919 +1403638546377829376.0000000000 2.7948219061 2.5028083631 1.4007396865 0.5503292486 0.7945790668 0.2188789340 -0.133693070196 +1403638546427829504.0000000000 2.7646419491 2.5384322270 1.3997305963 0.5490304288 0.7949086374 0.2191618242 -0.13657943213 +1403638546477829376.0000000000 2.7348087310 2.5740270686 1.3970996744 0.5486764052 0.7947337854 0.2202133145 -0.137326285797 +1403638546527829504.0000000000 2.7045976395 2.6098092188 1.3938850203 0.5482069051 0.7946101932 0.2212667971 -0.138220239361 +1403638546577829376.0000000000 2.6738958834 2.6459281345 1.3920527308 0.5478719856 0.7939995557 0.2239315156 -0.138764798239 +1403638546627829504.0000000000 2.6434646617 2.6812481145 1.3909441642 0.5474636806 0.7929766246 0.2272770782 -0.14077187573 +1403638546677829376.0000000000 2.6126316462 2.7167327379 1.3915884410 0.5471950527 0.7916619867 0.2311113585 -0.142955982816 +1403638546727829504.0000000000 2.5814063945 2.7524424072 1.3946950762 0.5468070131 0.7905562685 0.2344601793 -0.145090665085 +1403638546777829376.0000000000 2.5494628639 2.7889742616 1.4008024695 0.5465758492 0.7895201160 0.2380021193 -0.145834902187 +1403638546827829504.0000000000 2.5172691275 2.8254021147 1.4086438459 0.5462852824 0.7886277028 0.2413831697 -0.146194740227 +1403638546877829376.0000000000 2.4844665863 2.8624221992 1.4181889063 0.5460086930 0.7879679625 0.2438281910 -0.14672699352 +1403638546927829504.0000000000 2.4516112750 2.8990205601 1.4269767911 0.5458344145 0.7873650123 0.2463071993 -0.146471474709 +1403638546977829376.0000000000 2.4184280121 2.9354112607 1.4341804370 0.5461342898 0.7865302868 0.2490306875 -0.145227965843 +1403638547027829504.0000000000 2.3846010188 2.9717130069 1.4398066924 0.5463183078 0.7858970960 0.2509333692 -0.14468761272 +1403638547077829376.0000000000 2.3503273853 3.0078630619 1.4438863376 0.5465687139 0.7853942491 0.2529644738 -0.142924768266 +1403638547127829504.0000000000 2.3151140151 3.0440479763 1.4463518735 0.5467718159 0.7848908408 0.2554196813 -0.140526636917 +1403638547177829376.0000000000 2.2789901278 3.0798045524 1.4476924056 0.5467344627 0.7846999110 0.2566172780 -0.139553035217 +1403638547227829504.0000000000 2.2419989534 3.1152902506 1.4480881119 0.5468872730 0.7844385678 0.2577508425 -0.138329125922 +1403638547277829376.0000000000 2.2039879115 3.1504205941 1.4477998529 0.5475420551 0.7839583648 0.2584568328 -0.137138782875 +1403638547327829504.0000000000 2.1648171368 3.1850909401 1.4468670858 0.5475927884 0.7839818779 0.2586300647 -0.136473597662 +1403638547377829376.0000000000 2.1241992460 3.2187652145 1.4456397150 0.5469675375 0.7846660619 0.2557060186 -0.140499523841 +1403638547427829504.0000000000 2.0828673114 3.2523085584 1.4431966467 0.5456239205 0.7858373729 0.2537603760 -0.142687884197 +1403638547477829376.0000000000 2.0406228841 3.2856951604 1.4404863241 0.5452038117 0.7863791630 0.2510582596 -0.146049190234 +1403638547527829504.0000000000 1.9978849011 3.3189416444 1.4363820534 0.5439030725 0.7875874937 0.2487317473 -0.148350616259 +1403638547577829376.0000000000 1.9546948419 3.3523906235 1.4311183337 0.5431038010 0.7884835299 0.2465975985 -0.150072012303 +1403638547627829504.0000000000 1.9111888196 3.3859919797 1.4242079283 0.5428367413 0.7889079690 0.2453366544 -0.150872180157 +1403638547677829376.0000000000 1.8674990672 3.4199008813 1.4160279126 0.5429100734 0.7891724612 0.2445173441 -0.150554797891 +1403638547727829504.0000000000 1.8234510787 3.4538372260 1.4065848789 0.5432282731 0.7891219897 0.2448282438 -0.149159846137 +1403638547777829376.0000000000 1.7789405338 3.4877466018 1.3961051545 0.5438409974 0.7888250787 0.2451975777 -0.147885471696 +1403638547827829504.0000000000 1.7341135758 3.5218677734 1.3842700006 0.5450821354 0.7879792731 0.2476215901 -0.143727794738 +1403638547877829376.0000000000 1.6885235928 3.5556700574 1.3721722648 0.5466130276 0.7869549709 0.2480404417 -0.142800599048 +1403638547927829504.0000000000 1.6421338599 3.5890655052 1.3603963258 0.5454816569 0.7878096695 0.2476434887 -0.14310272265 +1403638547977829376.0000000000 1.5948690492 3.6227380277 1.3505392278 0.5462913371 0.7870203360 0.2483959712 -0.143053162379 +1403638548027829504.0000000000 1.5470051886 3.6558023654 1.3423970657 0.5445506869 0.7877498807 0.2488445630 -0.144882912297 +1403638548077829376.0000000000 1.4978440178 3.6892626034 1.3363681821 0.5434044489 0.7875766314 0.2506697588 -0.146967093401 +1403638548127829504.0000000000 1.4481493169 3.7225678912 1.3323383376 0.5426996916 0.7867284576 0.2534840871 -0.149268872697 +1403638548177829376.0000000000 1.3973197649 3.7558841234 1.3304068566 0.5409077085 0.7861211358 0.2570950197 -0.152756543469 +1403638548227829504.0000000000 1.3460604888 3.7887958139 1.3308541491 0.5400845610 0.7843834088 0.2616403770 -0.156829997593 +1403638548277829376.0000000000 1.2946323470 3.8209689521 1.3327033581 0.5374421970 0.7833690028 0.2673464199 -0.161290985643 +1403638548327829504.0000000000 1.2425501156 3.8532399927 1.3373513215 0.5364979995 0.7807066664 0.2737331625 -0.166544748992 +1403638548377829376.0000000000 1.1898410510 3.8853311364 1.3438716044 0.5337712364 0.7788277669 0.2814763964 -0.171133325181 +1403638548427829504.0000000000 1.1362995394 3.9173220587 1.3526553016 0.5317633420 0.7763783977 0.2888083728 -0.176221609128 +1403638548477829376.0000000000 1.0825495275 3.9495367503 1.3618863929 0.5303846411 0.7738441103 0.2948983185 -0.181362640288 +1403638548527829504.0000000000 1.0281796520 3.9817192993 1.3705202855 0.5290222809 0.7717370093 0.3000382592 -0.1858344905 +1403638548577829376.0000000000 0.9734650256 4.0143334868 1.3776986958 0.5282442317 0.7694220438 0.3051444589 -0.189300315516 +1403638548627829504.0000000000 0.9184173705 4.0474109360 1.3834735600 0.5273818365 0.7676507106 0.3092708983 -0.192177773259 +1403638548677829376.0000000000 0.8629863540 4.0807835677 1.3883110625 0.5263957623 0.7663514761 0.3122216573 -0.195270461443 +1403638548727829504.0000000000 0.8074083507 4.1146203623 1.3920233476 0.5256516121 0.7652012080 0.3152570156 -0.196902280702 +1403638548777829376.0000000000 0.7516110926 4.1486219138 1.3960666196 0.5250937254 0.7642331704 0.3173592571 -0.198764541229 +1403638548827829504.0000000000 0.6954563096 4.1828489837 1.4015876051 0.5242370525 0.7636909292 0.3192716279 -0.200043258196 +1403638548877829376.0000000000 0.6383930530 4.2181567174 1.4091548370 0.5238192534 0.7632353333 0.3206361122 -0.200693047747 +1403638548927829504.0000000000 0.5807934747 4.2534042443 1.4184157179 0.5236992812 0.7626792158 0.3211244822 -0.202332754435 +1403638548977829376.0000000000 0.5231146355 4.2886997652 1.4291046147 0.5232580451 0.7626496457 0.3218751307 -0.202393024602 +1403638549027829504.0000000000 0.4654450758 4.3237911462 1.4411625898 0.5226475752 0.7627191210 0.3230741824 -0.201797242896 +1403638549077829376.0000000000 0.4075487348 4.3587589585 1.4549714625 0.5227547610 0.7625843262 0.3223727795 -0.203146243623 +1403638549127829504.0000000000 0.3498153850 4.3936316711 1.4701432979 0.5227308268 0.7626678818 0.3215604378 -0.204179013851 +1403638549177829376.0000000000 0.2916311066 4.4289622079 1.4874909665 0.5234543663 0.7622066441 0.3215010422 -0.204141220758 +1403638549227829504.0000000000 0.2327449145 4.4648445005 1.5058649702 0.5230519158 0.7625676831 0.3210845996 -0.204479588117 +1403638549277829376.0000000000 0.1728748838 4.5016032998 1.5258110461 0.5231524820 0.7627034707 0.3202701486 -0.204992507665 +1403638549327829504.0000000000 0.1128968577 4.5383379635 1.5472599655 0.5229690783 0.7630553193 0.3189467184 -0.206210847573 +1403638549377829376.0000000000 0.0528330765 4.5750576194 1.5695796080 0.5229856154 0.7632885727 0.3175398963 -0.207472926342 +1403638549427829504.0000000000 -0.0074367564 4.6122686521 1.5912555687 0.5232568909 0.7633541294 0.3161286450 -0.208699255289 +1403638549477829376.0000000000 -0.0678917337 4.6497974273 1.6113797610 0.5227895698 0.7639167811 0.3150190200 -0.20948802919 +1403638549527829504.0000000000 -0.1282467374 4.6878396057 1.6299007581 0.5229725003 0.7640025786 0.3143670258 -0.209697870511 +1403638549577829376.0000000000 -0.1885747538 4.7260514925 1.6473218651 0.5242051941 0.7633545258 0.3134042681 -0.210419930664 +1403638549627829504.0000000000 -0.2486065405 4.7648345487 1.6634280650 0.5255013169 0.7625949059 0.3128297290 -0.210795958349 +1403638549677829376.0000000000 -0.3080857608 4.8036633992 1.6785783913 0.5261607507 0.7623498067 0.3121335891 -0.211069323401 +1403638549727829504.0000000000 -0.3665963833 4.8425317928 1.6929436430 0.5269462244 0.7620017749 0.3130335921 -0.209023782988 +1403638549777829376.0000000000 -0.4250366797 4.8812506265 1.7080422056 0.5260498473 0.7626882521 0.3125997757 -0.209426761448 +1403638549827829504.0000000000 -0.4838163111 4.9206805054 1.7247202551 0.5251398063 0.7633804630 0.3121284466 -0.209891127647 +1403638549877829376.0000000000 -0.5423622978 4.9605540770 1.7433175530 0.5242624262 0.7641792919 0.3122204045 -0.209039080628 +1403638549927829504.0000000000 -0.6010584967 5.0008690489 1.7634566388 0.5239664646 0.7644484120 0.3125903281 -0.208242781968 +1403638549977829376.0000000000 -0.6600984641 5.0413613035 1.7851440214 0.5230944773 0.7650378887 0.3120089167 -0.209140222369 +1403638550027829504.0000000000 -0.7191357555 5.0823517288 1.8090253945 0.5230728347 0.7651323714 0.3117182282 -0.209282130259 +1403638550077829376.0000000000 -0.7786634903 5.1243436729 1.8348989522 0.5227487361 0.7653089230 0.3116565835 -0.209538028344 +1403638550127829504.0000000000 -0.8370309719 5.1649292031 1.8617094388 0.5218299308 0.7658586817 0.3109245110 -0.210902705988 +1403638550177829376.0000000000 -0.8950485528 5.2062213231 1.8903249469 0.5217608278 0.7657689649 0.3114088811 -0.210684692599 +1403638550227829504.0000000000 -0.9524911130 5.2470438320 1.9206379188 0.5211905408 0.7659600704 0.3117626214 -0.210878303017 +1403638550277829376.0000000000 -1.0097278260 5.2881336505 1.9528616501 0.5214623395 0.7657038013 0.3123743391 -0.210230800293 +1403638550327829504.0000000000 -1.0668669345 5.3296433923 1.9862689808 0.5216664793 0.7654744662 0.3128082641 -0.209914067962 +1403638550377829376.0000000000 -1.1233334283 5.3704310084 2.0183682509 0.5222162082 0.7649656833 0.3131395922 -0.209907911129 +1403638550427829504.0000000000 -1.1799309014 5.4117932203 2.0489307828 0.5222271801 0.7647991139 0.3121938841 -0.211886919209 +1403638550477829376.0000000000 -1.2363447256 5.4537951743 2.0772715221 0.5219071475 0.7650174282 0.3114917181 -0.212918231735 +1403638550527829504.0000000000 -1.2927366677 5.4965106982 2.1042474020 0.5210366556 0.7654942777 0.3103119774 -0.215048345863 +1403638550577829376.0000000000 -1.3490586473 5.5406472453 2.1301610067 0.5218688089 0.7648835742 0.3090824757 -0.216965636577 +1403638550627829504.0000000000 -1.4047567722 5.5853062633 2.1545713045 0.5234559907 0.7638125747 0.3076858453 -0.218891747721 +1403638550677829376.0000000000 -1.4597605872 5.6303879140 2.1779926757 0.5257445669 0.7622444063 0.3064815815 -0.220556468085 +1403638550727829504.0000000000 -1.5148023076 5.6781788550 2.2004502536 0.5264734260 0.7617105673 0.3053582310 -0.222214072795 +1403638550777829376.0000000000 -1.5685275139 5.7253032227 2.2215551980 0.5278527787 0.7608525372 0.3047134014 -0.222765804337 +1403638550827829504.0000000000 -1.6215070766 5.7730429028 2.2420252003 0.5310907929 0.7586981020 0.3035761319 -0.223967166739 +1403638550877829376.0000000000 -1.6736704835 5.8210532919 2.2618087922 0.5350420884 0.7558866197 0.3020231187 -0.226157948153 +1403638550927829504.0000000000 -1.7247645541 5.8692697592 2.2804896857 0.5396582169 0.7528494867 0.3006238658 -0.227182637177 +1403638550977829376.0000000000 -1.7746939243 5.9168148553 2.2978657940 0.5429808295 0.7504303253 0.2992680593 -0.229051902986 +1403638551027829504.0000000000 -1.8232406552 5.9639034191 2.3140768017 0.5455047612 0.7486658986 0.2981140090 -0.230330122766 +1403638551077829376.0000000000 -1.8699092617 6.0104791065 2.3298412293 0.5476658811 0.7471122870 0.2974221390 -0.231139318392 +1403638551127829504.0000000000 -1.9149421393 6.0564647709 2.3461789368 0.5477147153 0.7470306868 0.2961737430 -0.232883785419 +1403638551177829376.0000000000 -1.9579923878 6.1019068440 2.3639968897 0.5478689926 0.7465943298 0.2946592054 -0.235822870485 +1403638551227829504.0000000000 -1.9987810901 6.1471327450 2.3829275656 0.5473973574 0.7467594080 0.2941366259 -0.237044647832 +1403638551277829376.0000000000 -2.0373943491 6.1922801646 2.4030824976 0.5464841958 0.7478385139 0.2930248135 -0.237126631802 +1403638551327829504.0000000000 -2.0733491971 6.2369690446 2.4239940068 0.5442347428 0.7505302032 0.2917412571 -0.235372041165 +1403638551377829376.0000000000 -2.1074182657 6.2814159997 2.4449774983 0.5426208930 0.7538884980 0.2875318798 -0.233538256206 +1403638551427829504.0000000000 -2.1390061957 6.3262659047 2.4645626001 0.5415858732 0.7578096803 0.2818775075 -0.230118015722 +1403638551477829376.0000000000 -2.1686773712 6.3708745917 2.4830886474 0.5410127362 0.7621695357 0.2743996427 -0.226070020683 +1403638551527829504.0000000000 -2.1966551632 6.4159206799 2.5005190059 0.5409515740 0.7667016722 0.2647070150 -0.222418831726 +1403638551577829376.0000000000 -2.2224568334 6.4610233576 2.5163823135 0.5426192263 0.7703135025 0.2537968213 -0.21856041873 +1403638551627829504.0000000000 -2.2462909585 6.5063897327 2.5307417919 0.5421762572 0.7753412864 0.2420427654 -0.215188511288 +1403638551677829376.0000000000 -2.2679811719 6.5524508873 2.5437938565 0.5430298587 0.7794381008 0.2305263009 -0.210837482749 +1403638551727829504.0000000000 -2.2872968654 6.5993750588 2.5558109610 0.5451903707 0.7826515512 0.2193331670 -0.205224197092 +1403638551777829376.0000000000 -2.3042888858 6.6469801041 2.5658057913 0.5472304568 0.7858520709 0.2082053859 -0.199062470111 +1403638551827829504.0000000000 -2.3191311833 6.6955891575 2.5748282987 0.5495746879 0.7884370862 0.1978032063 -0.192895088162 +1403638551877829376.0000000000 -2.3311260620 6.7440594762 2.5832107279 0.5525588483 0.7899849723 0.1898774715 -0.185873636147 +1403638551927829504.0000000000 -2.3405082269 6.7928872503 2.5922084846 0.5561510815 0.7905784260 0.1852130337 -0.177137966185 +1403638551977829376.0000000000 -2.3477977140 6.8420291265 2.6029280086 0.5601570529 0.7902004423 0.1814667361 -0.169932812577 +1403638552027829504.0000000000 -2.3527175799 6.8912128875 2.6159822832 0.5638555197 0.7897713911 0.1786967357 -0.162467163853 +1403638552077829376.0000000000 -2.3557050518 6.9395752699 2.6307277731 0.5662605275 0.7896912266 0.1761986265 -0.157133146167 +1403638552127829504.0000000000 -2.3569557380 6.9873834982 2.6467753361 0.5660872391 0.7910747861 0.1740374404 -0.153156423128 +1403638552177829376.0000000000 -2.3565637111 7.0346032489 2.6644664448 0.5644399520 0.7931184987 0.1715896426 -0.15141856584 +1403638552227829504.0000000000 -2.3545567173 7.0817454313 2.6835834781 0.5628123274 0.7949210248 0.1704117282 -0.149340856527 +1403638552277829376.0000000000 -2.3510950383 7.1288065374 2.7032889870 0.5612732558 0.7964754281 0.1692991213 -0.148111553311 +1403638552327829504.0000000000 -2.3460676836 7.1754582094 2.7232099069 0.5609161645 0.7969795618 0.1683825355 -0.147797010312 +1403638552377829376.0000000000 -2.3401303116 7.2222321672 2.7424730530 0.5616123256 0.7965172272 0.1662752494 -0.150014812328 +1403638552427829504.0000000000 -2.3328016476 7.2694532301 2.7607075514 0.5654748045 0.7938104152 0.1641854130 -0.152139476618 +1403638552477829376.0000000000 -2.3238218678 7.3167666059 2.7778906951 0.5688598147 0.7912453570 0.1623283615 -0.154850893773 +1403638552527829504.0000000000 -2.3130730403 7.3638762993 2.7935481769 0.5719162411 0.7889362803 0.1609391111 -0.156811866193 +1403638552577829376.0000000000 -2.3004952713 7.4103459782 2.8077461928 0.5747897501 0.7866625143 0.1603297281 -0.158345224529 +1403638552627829504.0000000000 -2.2859385080 7.4566154341 2.8205735611 0.5765083858 0.7852466599 0.1607851850 -0.158662813911 +1403638552677829376.0000000000 -2.2691282601 7.5016921988 2.8312434903 0.5764763465 0.7850576749 0.1622532137 -0.158219353032 +1403638552727829504.0000000000 -2.2502135545 7.5460930010 2.8407430543 0.5759243797 0.7852621163 0.1628282510 -0.158623700282 +1403638552777829376.0000000000 -2.2290972557 7.5897604744 2.8487639658 0.5755424225 0.7853390061 0.1645599955 -0.157840340871 +1403638552827829504.0000000000 -2.2061898867 7.6328252788 2.8556543512 0.5752005046 0.7853175228 0.1661533882 -0.157524028208 +1403638552877829376.0000000000 -2.1812095822 7.6750845158 2.8611305664 0.5746263946 0.7855060498 0.1687598999 -0.15590012343 +1403638552927829504.0000000000 -2.1544382562 7.7164377757 2.8650394876 0.5734845476 0.7860031537 0.1720528812 -0.153988058544 +1403638552977829376.0000000000 -2.1259836763 7.7570106584 2.8676501325 0.5738539002 0.7855076378 0.1752570149 -0.151507197487 +1403638553027829504.0000000000 -2.0961430903 7.7966900538 2.8688902279 0.5728247318 0.7859699182 0.1785638562 -0.14912432274 +1403638553077829376.0000000000 -2.0653821154 7.8355487185 2.8689521524 0.5732162748 0.7853348086 0.1811394284 -0.147854144935 +1403638553127829504.0000000000 -2.0339946803 7.8738132462 2.8687128782 0.5743597152 0.7840994927 0.1818783303 -0.149060981044 +1403638553177829376.0000000000 -2.0016628767 7.9115256690 2.8680372917 0.5774896994 0.7813830498 0.1812291385 -0.15199399976 +1403638553227829504.0000000000 -1.9680831206 7.9483712779 2.8671637310 0.5814230659 0.7780816581 0.1802269203 -0.155094838421 +1403638553277829376.0000000000 -1.9328390032 7.9839549392 2.8668631331 0.5851321060 0.7749642799 0.1801752527 -0.156804533524 +1403638553327829504.0000000000 -1.8961401133 8.0184608839 2.8679364698 0.5884645796 0.7721183216 0.1808959064 -0.157541763 +1403638553377829376.0000000000 -1.8573554059 8.0509915836 2.8695770795 0.5903323757 0.7704507178 0.1827851801 -0.156534199272 +1403638553427829504.0000000000 -1.8168565281 8.0819463940 2.8727046779 0.5932618170 0.7681951567 0.1854254469 -0.153408022426 +1403638553477829376.0000000000 -1.7750952162 8.1110951774 2.8771906503 0.5951516125 0.7665955183 0.1880368493 -0.150890731527 +1403638553527829504.0000000000 -1.7321270503 8.1384099500 2.8837053895 0.5968615080 0.7651749031 0.1902110129 -0.148605109347 +1403638553577829376.0000000000 -1.6873860077 8.1626663978 2.8917442701 0.5987828319 0.7636097068 0.1923236104 -0.146188114362 +1403638553627829504.0000000000 -1.6409588960 8.1835701363 2.9002360141 0.5991023092 0.7633284527 0.1936749342 -0.14455489037 +1403638553677829376.0000000000 -1.5935118920 8.2015303029 2.9107223466 0.5986936523 0.7635153376 0.1947466112 -0.143819321796 +1403638553727829504.0000000000 -1.5451665872 8.2173152534 2.9241264779 0.5983688158 0.7636982653 0.1955463257 -0.14311308214 +1403638553777829376.0000000000 -1.4955100938 8.2296869717 2.9381083988 0.5971038869 0.7646367490 0.1962669307 -0.142396917963 +1403638553827829504.0000000000 -1.4458924504 8.2409323852 2.9544332085 0.5958110607 0.7656497403 0.1967719249 -0.141670267771 +1403638553877829376.0000000000 -1.3952881105 8.2494174504 2.9722640391 0.5943033659 0.7668677798 0.1970407843 -0.141039877008 +1403638553927829504.0000000000 -1.3440962760 8.2558091723 2.9904140699 0.5931381262 0.7678296287 0.1973019971 -0.140345097391 +1403638553977829376.0000000000 -1.2926666850 8.2601973573 3.0076498111 0.5904861804 0.7698810412 0.1962942116 -0.14169627926 +1403638554027829504.0000000000 -1.2405656979 8.2629303439 3.0236552631 0.5876890980 0.7720455834 0.1953660340 -0.142825956967 +1403638554077829376.0000000000 -1.1877384958 8.2641746075 3.0385982920 0.5860859273 0.7732978629 0.1960058683 -0.141758247122 +1403638554127829504.0000000000 -1.1344328015 8.2637617503 3.0522492383 0.5846717876 0.7743383540 0.1963399554 -0.141455421625 +1403638554177829376.0000000000 -1.0806426283 8.2620700871 3.0634246825 0.5807323337 0.7772921100 0.1983918550 -0.138591501086 +1403638554227829504.0000000000 -1.0268107758 8.2592900083 3.0729613360 0.5753473211 0.7812215576 0.2003169828 -0.136166972916 +1403638554277829376.0000000000 -0.9729440040 8.2556483648 3.0813312871 0.5703848168 0.7848092482 0.2018458771 -0.134141144634 +1403638554327829504.0000000000 -0.9191690248 8.2513871657 3.0885774304 0.5667447024 0.7873303963 0.2037323386 -0.131925826392 +1403638554377829376.0000000000 -0.8656078738 8.2462483391 3.0946379044 0.5637087179 0.7894294081 0.2050040932 -0.130410938141 +1403638554427829504.0000000000 -0.8128058939 8.2412503492 3.1003594792 0.5619426856 0.7906184876 0.2056450590 -0.12981885454 +1403638554477829376.0000000000 -0.7606800653 8.2359817724 3.1051343295 0.5606020867 0.7915044028 0.2065501198 -0.128775497287 +1403638554527829504.0000000000 -0.7094359797 8.2307621901 3.1093305977 0.5601604195 0.7917930395 0.2065960116 -0.128849427679 +1403638554577829376.0000000000 -0.6588247828 8.2252390877 3.1126762768 0.5594546753 0.7921989493 0.2059401486 -0.130460516328 +1403638554627829504.0000000000 -0.6088583772 8.2193565597 3.1165922108 0.5583906857 0.7929522896 0.2045627995 -0.132591739931 +1403638554677829376.0000000000 -0.5595240254 8.2134913576 3.1225687518 0.5582697185 0.7930178777 0.2015606547 -0.137225615388 +1403638554727829504.0000000000 -0.5097077233 8.2072634378 3.1294306051 0.5590132008 0.7925038491 0.2007191180 -0.138396987452 +1403638554777829376.0000000000 -0.4602038397 8.2006769132 3.1376363718 0.5589224543 0.7924951869 0.1982725555 -0.142285145561 +1403638554827829504.0000000000 -0.4108472170 8.1951824592 3.1466986012 0.5590554337 0.7923218463 0.1978959760 -0.143249072067 +1403638554877829376.0000000000 -0.3616241819 8.1902637907 3.1573278050 0.5595677935 0.7919710227 0.1963471562 -0.145305120041 +1403638554927829504.0000000000 -0.3122512544 8.1856266956 3.1683575868 0.5600190304 0.7916849977 0.1953732546 -0.146433744208 +1403638554977829376.0000000000 -0.2625904710 8.1814536660 3.1787725697 0.5607664865 0.7915164303 0.1930759275 -0.147527537798 +1403638555027829504.0000000000 -0.2124369235 8.1774682589 3.1875554215 0.5615925078 0.7917728531 0.1906909803 -0.146104600192 +1403638555077829376.0000000000 -0.1615748394 8.1736495112 3.1941828941 0.5617102016 0.7928811606 0.1879198421 -0.143203518154 +1403638555127829504.0000000000 -0.1101312878 8.1702211914 3.2001393448 0.5620240225 0.7941942772 0.1844535421 -0.13914502842 +1403638555177829376.0000000000 -0.0583286173 8.1669610483 3.2043894778 0.5617440613 0.7960811377 0.1795322697 -0.13589185351 +1403638555227829504.0000000000 -0.0062426761 8.1640435373 3.2070931841 0.5622401092 0.7974930450 0.1742487309 -0.132394420347 +1403638555277829376.0000000000 0.0461566859 8.1608394313 3.2084550553 0.5624448132 0.7988858824 0.1697602763 -0.128913256093 +1403638555327829504.0000000000 0.0987340388 8.1578424310 3.2089050671 0.5630297873 0.7998201357 0.1659028093 -0.125544681145 +1403638555377829376.0000000000 0.1515971911 8.1552901570 3.2085225260 0.5642841552 0.8000803793 0.1641695489 -0.120428975042 +1403638555427829504.0000000000 0.2044227604 8.1530418011 3.2069692986 0.5647301581 0.8007325570 0.1623514559 -0.116401140252 +1403638555477829376.0000000000 0.2571737403 8.1508734093 3.2042781112 0.5656421639 0.8008689046 0.1605090419 -0.113555218115 +1403638555527829504.0000000000 0.3095493250 8.1487549111 3.2008094335 0.5658182425 0.8013324011 0.1581599131 -0.112701115085 +1403638555577829376.0000000000 0.3619961859 8.1466551720 3.1970590628 0.5667022846 0.8011432136 0.1574937209 -0.110516061681 +1403638555627829504.0000000000 0.4141071842 8.1444812235 3.1941478000 0.5662635079 0.8017588944 0.1563438918 -0.10993135298 +1403638555677829376.0000000000 0.4662690947 8.1421680805 3.1940275052 0.5659140779 0.8021868713 0.1552933194 -0.110097524593 +1403638555727829504.0000000000 0.5186968560 8.1392884085 3.1954810368 0.5653280041 0.8026786884 0.1545314044 -0.110594827927 +1403638555777829376.0000000000 0.5713714163 8.1362877865 3.1996362277 0.5643849648 0.8033746876 0.1550349021 -0.109648994153 +1403638555827829504.0000000000 0.6239376366 8.1331015641 3.2067484886 0.5642517295 0.8034124229 0.1554879740 -0.10941642713 +1403638555877829376.0000000000 0.6766628077 8.1295652614 3.2145737944 0.5636999689 0.8037342537 0.1559595057 -0.109225578401 +1403638555927829504.0000000000 0.7290888246 8.1269676114 3.2230836513 0.5637040552 0.8036644588 0.1570325010 -0.108175641614 +1403638555977829376.0000000000 0.7808092911 8.1255698559 3.2337701228 0.5643044794 0.8031301574 0.1579793872 -0.10763325733 +1403638556027829504.0000000000 0.8322057992 8.1245218235 3.2460224152 0.5643409325 0.8030548472 0.1587024582 -0.106938085516 +1403638556077829376.0000000000 0.8835263725 8.1236572035 3.2579859121 0.5633837103 0.8036959194 0.1592135046 -0.106408289069 +1403638556127829504.0000000000 0.9345043868 8.1224340108 3.2695687115 0.5610404110 0.8052967507 0.1590337979 -0.10695350189 +1403638556177829376.0000000000 0.9855010063 8.1213331813 3.2791358441 0.5572459439 0.8079612501 0.1582279814 -0.107886432379 +1403638556227829504.0000000000 1.0363785023 8.1205977686 3.2869094766 0.5542461121 0.8100065044 0.1586179873 -0.107429251745 +1403638556277829376.0000000000 1.0868501092 8.1204762617 3.2936381909 0.5522255705 0.8113678105 0.1580873369 -0.108340155623 +1403638556327829504.0000000000 1.1368607417 8.1208699004 3.2995609493 0.5503437150 0.8126522037 0.1582923410 -0.107989471799 +1403638556377829376.0000000000 1.1863827915 8.1222130912 3.3048169428 0.5489178044 0.8135991350 0.1580942264 -0.108406212999 +1403638556427829504.0000000000 1.2355191877 8.1248535257 3.3096409701 0.5472540271 0.8147096306 0.1582969117 -0.108181954447 +1403638556477829376.0000000000 1.2840097622 8.1288475026 3.3140818003 0.5440297841 0.8169302134 0.1582397638 -0.107781248735 +1403638556527829504.0000000000 1.3320644928 8.1342890125 3.3185306629 0.5417600231 0.8184751038 0.1583067311 -0.107394416927 +1403638556577829376.0000000000 1.3794862134 8.1412263788 3.3235266351 0.5402975698 0.8195292709 0.1568894481 -0.108793434023 +1403638556627829504.0000000000 1.4259087928 8.1498404795 3.3287809023 0.5396298719 0.8200228418 0.1537020673 -0.112861927877 +1403638556677829376.0000000000 1.4724066765 8.1599899628 3.3350042403 0.5401483073 0.8197485618 0.1502778494 -0.116913085589 +1403638556727829504.0000000000 1.5192089387 8.1719055080 3.3433478004 0.5436445389 0.8174623712 0.1481596383 -0.11939266516 +1403638556777829376.0000000000 1.5669764922 8.1841289578 3.3532989736 0.5471214458 0.8150963880 0.1468559059 -0.121282087082 +1403638556827829504.0000000000 1.6153579958 8.1974658760 3.3648780052 0.5498537261 0.8132324979 0.1449907777 -0.123658637337 +1403638556877829376.0000000000 1.6638842475 8.2129459091 3.3781530277 0.5513605390 0.8121625166 0.1433319982 -0.125894959904 +1403638556927829504.0000000000 1.7132461288 8.2296696597 3.3927355588 0.5533899983 0.8107567647 0.1422106021 -0.127315053589 +1403638556977829376.0000000000 1.7632489181 8.2472211146 3.4067113089 0.5546678632 0.8098597436 0.1413940783 -0.128368500207 +1403638557027829504.0000000000 1.8142055379 8.2656361491 3.4190242703 0.5554172630 0.8093167040 0.1420745079 -0.127800511559 +1403638557077829376.0000000000 1.8660032581 8.2848133003 3.4295046243 0.5559594867 0.8089441580 0.1432823776 -0.126445872442 +1403638557127829504.0000000000 1.9184739976 8.3047068971 3.4381607945 0.5567360433 0.8084152225 0.1447739127 -0.12470092346 +1403638557177829376.0000000000 1.9714221902 8.3252469990 3.4452829648 0.5573451505 0.8079606556 0.1453398626 -0.124266997256 +1403638557227829504.0000000000 2.0248140308 8.3468403663 3.4505859093 0.5580130636 0.8075117054 0.1462212671 -0.123148721103 +1403638557277829376.0000000000 2.0790166758 8.3685631414 3.4545219521 0.5582189642 0.8073143766 0.1467466288 -0.122884141937 +1403638557327829504.0000000000 2.1339913858 8.3910812670 3.4573663134 0.5585206312 0.8071222358 0.1476489250 -0.12168893118 +1403638557377829376.0000000000 2.1895955203 8.4140992430 3.4600696013 0.5588123247 0.8068759890 0.1491895419 -0.120093316952 +1403638557427829504.0000000000 2.2456949743 8.4375698224 3.4636674668 0.5597338437 0.8062395415 0.1511387727 -0.11761333808 +1403638557477829376.0000000000 2.3023640479 8.4619720830 3.4682301553 0.5606836341 0.8055409997 0.1543772352 -0.113601186174 +1403638557527829504.0000000000 2.3589007448 8.4865214809 3.4749301283 0.5613140429 0.8051376901 0.1561686295 -0.110865704152 +1403638557577829376.0000000000 2.4157858534 8.5102410504 3.4832661256 0.5624245635 0.8043405893 0.1581259168 -0.108217471608 +1403638557627829504.0000000000 2.4721402136 8.5345568919 3.4926185839 0.5630428705 0.8038985636 0.1592329749 -0.106652169015 +1403638557677829376.0000000000 2.5279487209 8.5590427262 3.5034400779 0.5630130430 0.8038836669 0.1602599073 -0.105376115538 +1403638557727829504.0000000000 2.5830731096 8.5834548853 3.5155362195 0.5636592670 0.8034894172 0.1600657892 -0.105223240255 +1403638557777829376.0000000000 2.6376953221 8.6076738578 3.5271349181 0.5637263310 0.8034641012 0.1600196158 -0.105127467385 +1403638557827829504.0000000000 2.6919651443 8.6317373255 3.5370296786 0.5638342483 0.8034979980 0.1608266486 -0.103037356019 +1403638557877829376.0000000000 2.7454594739 8.6554219664 3.5454146140 0.5632562228 0.8039107534 0.1613197537 -0.102205015101 +1403638557927829504.0000000000 2.7985916900 8.6788370870 3.5519722643 0.5626503524 0.8043521928 0.1623087728 -0.100488771125 +1403638557977829376.0000000000 2.8510133918 8.7020188329 3.5567535072 0.5608182214 0.8056550094 0.1624013732 -0.100143508708 +1403638558027829504.0000000000 2.9028031063 8.7251238353 3.5598332878 0.5584957118 0.8072477841 0.1623457627 -0.100386295548 +1403638558077829376.0000000000 2.9538900627 8.7480446111 3.5612357502 0.5552715732 0.8094792192 0.1618027073 -0.101176862732 +1403638558127829504.0000000000 3.0046685393 8.7711292698 3.5611894230 0.5511533132 0.8123729090 0.1614268022 -0.101102272701 +1403638558177829376.0000000000 3.0545914569 8.7946191652 3.5613129667 0.5465647356 0.8154797123 0.1611995400 -0.101363390902 +1403638558227829504.0000000000 3.1037491261 8.8191819800 3.5625013232 0.5419016394 0.8187014188 0.1604763046 -0.101577338525 +1403638558277829376.0000000000 3.1522222832 8.8452909567 3.5650996472 0.5400277245 0.8199652448 0.1613427074 -0.099977922312 +1403638558327829504.0000000000 3.1995072240 8.8729473055 3.5698108721 0.5382913950 0.8211498826 0.1620486116 -0.0984656885207 +1403638558377829376.0000000000 3.2455986382 8.9023686009 3.5775639975 0.5367219280 0.8221898894 0.1634136832 -0.0960693805214 +1403638558427829504.0000000000 3.2908853790 8.9320421033 3.5870604009 0.5328986412 0.8246876504 0.1645554483 -0.0939724533303 +1403638558477829376.0000000000 3.3345215699 8.9634832560 3.5978392945 0.5294886682 0.8269061732 0.1655485307 -0.0919870368332 +1403638558527829504.0000000000 3.3763655205 8.9967428442 3.6111999654 0.5275305511 0.8282434409 0.1648892039 -0.0923897759237 +1403638558577829376.0000000000 3.4164477526 9.0319836244 3.6264796680 0.5266606191 0.8288723658 0.1634085698 -0.0943230234016 +1403638558627829504.0000000000 3.4551077171 9.0696004954 3.6441575578 0.5282466962 0.8280579217 0.1606923048 -0.0972290565448 +1403638558677829376.0000000000 3.4921032417 9.1088567705 3.6630849569 0.5296486013 0.8273069397 0.1569790289 -0.101946903671 +1403638558727829504.0000000000 3.5283761998 9.1501957145 3.6819950174 0.5321334514 0.8258414560 0.1530401038 -0.106764254683 +1403638558777829376.0000000000 3.5646045220 9.1931197826 3.6988875256 0.5337259291 0.8248890856 0.1512724775 -0.108679651332 +1403638558827829504.0000000000 3.6006686245 9.2372083190 3.7142253093 0.5353768054 0.8238696911 0.1491289601 -0.111224824524 +1403638558877829376.0000000000 3.6363547404 9.2832061049 3.7286459815 0.5368388580 0.8229615991 0.1496387445 -0.110211130078 +1403638558927829504.0000000000 3.6721648721 9.3303585966 3.7408528341 0.5402933421 0.8207328691 0.1495858006 -0.11002159044 +1403638558977829376.0000000000 3.7079462624 9.3788936942 3.7515015397 0.5443830126 0.8180402073 0.1501136119 -0.109193673603 +1403638559027829504.0000000000 3.7437177667 9.4284741397 3.7601925034 0.5476043570 0.8158806487 0.1512224326 -0.107703347533 +1403638559077829376.0000000000 3.7791491218 9.4790580500 3.7676202433 0.5506783386 0.8138006597 0.1514698901 -0.107418462316 +1403638559127829504.0000000000 3.8143016976 9.5302819507 3.7731747670 0.5529245711 0.8122275033 0.1522615082 -0.106664589522 +1403638559177829376.0000000000 3.8493328877 9.5817787835 3.7773019770 0.5549998880 0.8107477016 0.1530133101 -0.106067033543 +1403638559227829504.0000000000 3.8843247239 9.6334802624 3.7797491377 0.5563721293 0.8096966086 0.1548514114 -0.104223299511 +1403638559277829376.0000000000 3.9188931408 9.6852947029 3.7808827771 0.5573655716 0.8089207917 0.1561774182 -0.102953321196 +1403638559327829504.0000000000 3.9532427980 9.7371469753 3.7803747593 0.5582367534 0.8082205744 0.1575957158 -0.101561905969 +1403638559377829376.0000000000 3.9874266641 9.7886801753 3.7780102767 0.5585323123 0.8079044364 0.1600117199 -0.0986322826071 +1403638559427829504.0000000000 4.0207525113 9.8398166873 3.7746317170 0.5595864685 0.8070361706 0.1619545267 -0.0965729511179 +1403638559477829376.0000000000 4.0531927850 9.8904996208 3.7698541788 0.5602442911 0.8064945158 0.1628707429 -0.0957394968454 +1403638559527829504.0000000000 4.0848540603 9.9410824074 3.7636502292 0.5611570684 0.8057797555 0.1639882052 -0.0944965539717 +1403638559577829376.0000000000 4.1156052370 9.9913604247 3.7563607556 0.5620589502 0.8050011570 0.1650532568 -0.0939164317389 +1403638559627829504.0000000000 4.1454937140 10.0414728983 3.7480820605 0.5628725884 0.8043873151 0.1651379870 -0.0941538196983 +1403638559677829376.0000000000 4.1746167634 10.0909526135 3.7397852102 0.5631770980 0.8040810957 0.1655829800 -0.0941670030961 +1403638559727829504.0000000000 4.2075051034 10.1579088471 3.7396862178 0.5634842227 0.8037642445 0.1659583095 -0.0943737760763 +1403638559777829376.0000000000 4.2353355096 10.2080793629 3.7345196691 0.5636165477 0.8035600201 0.1664626933 -0.0944343847596 +1403638559827829504.0000000000 4.2620400501 10.2581148630 3.7308276111 0.5624482602 0.8043223142 0.1657664887 -0.0961199285375 +1403638559877829376.0000000000 4.2878963035 10.3085934320 3.7285525506 0.5629624441 0.8040274417 0.1654700533 -0.096087569582 +1403638559927829504.0000000000 4.3131691579 10.3592240465 3.7267085604 0.5631691873 0.8044028777 0.1629689517 -0.0960083201951 +1403638559977829376.0000000000 4.3384693560 10.4101244094 3.7235674641 0.5635554865 0.8051717369 0.1586346108 -0.0945449521046 +1403638560027829504.0000000000 4.3632622101 10.4608378171 3.7188397451 0.5640404416 0.8063993270 0.1519649555 -0.0921149169558 +1403638560077829376.0000000000 4.3877476248 10.5116466567 3.7124217720 0.5648732298 0.8077725289 0.1437860321 -0.0880190480101 +1403638560127829504.0000000000 4.4119569975 10.5621201224 3.7041067940 0.5663032559 0.8090008144 0.1339262193 -0.0829582572538 +1403638560177829376.0000000000 4.4360253937 10.6126850523 3.6939745670 0.5680492264 0.8101352087 0.1233902289 -0.0759991536885 +1403638560227829504.0000000000 4.4599319699 10.6628907391 3.6822444169 0.5692523560 0.8116161806 0.1117361102 -0.0688910170223 +1403638560277829376.0000000000 4.4837484170 10.7122983457 3.6700589716 0.5713372575 0.8123419076 0.0996844974 -0.0611339874392 +1403638560327829504.0000000000 4.5071382139 10.7614829634 3.6572136184 0.5752805548 0.8115639359 0.0870292879 -0.0533119520497 +1403638560377829376.0000000000 4.5301941345 10.8096932636 3.6435760890 0.5790454854 0.8106345795 0.0741162811 -0.0456583095754 +1403638560427829504.0000000000 4.5530853820 10.8567937653 3.6288591182 0.5821269053 0.8099433487 0.0610013216 -0.0374015605483 +1403638560477829376.0000000000 4.5758003002 10.9032350267 3.6130038465 0.5854424744 0.8087861806 0.0476854595 -0.0291225040017 +1403638560527829504.0000000000 4.5985950600 10.9484230738 3.5960405503 0.5877915265 0.8080124542 0.0341600581 -0.0212152212997 +1403638560577829376.0000000000 4.6213249457 10.9924100055 3.5782254992 0.5894157457 0.8074598951 0.0192622475 -0.0150519915217 +1403638560627829504.0000000000 4.6442653443 11.0359121059 3.5590634076 0.5900822121 0.8072817551 0.0043168589 -0.00897304633847 +1403638560677829376.0000000000 4.6675197307 11.0775276474 3.5398128472 0.5905050049 0.8069546977 -0.0106305320 -0.00386612312405 +1403638560727829504.0000000000 4.6912262728 11.1187661512 3.5213998687 0.5904828764 0.8066604207 -0.0250691347 -0.000690615117877 +1403638560777829376.0000000000 4.7159558904 11.1579034897 3.5045311870 0.5910309146 0.8057576320 -0.0376544094 0.00438656554615 +1403638560827829504.0000000000 4.7419477626 11.1951367634 3.4894775567 0.5911900729 0.8049493134 -0.0492639154 0.0111340572479 +1403638560877829376.0000000000 4.7687867932 11.2306366075 3.4764056300 0.5921480408 0.8033223268 -0.0612904853 0.016655730811 +1403638560927829504.0000000000 4.7969536426 11.2654979918 3.4648064964 0.5927242596 0.8017950033 -0.0725574942 0.0231977339979 +1403638560977829376.0000000000 4.8263544928 11.2984859590 3.4556281131 0.5941758977 0.7995014256 -0.0824361032 0.0309315696372 +1403638561027829504.0000000000 4.8570617757 11.3299434036 3.4484612778 0.5961949502 0.7966013770 -0.0920122069 0.0388790587285 +1403638561077829376.0000000000 4.8886507564 11.3589215703 3.4433123955 0.5970174956 0.7944167073 -0.1019980676 0.0454818580675 +1403638561127829504.0000000000 4.9210204586 11.3848994125 3.4394447695 0.5986074944 0.7915685265 -0.1109649912 0.0526792768211 +1403638561177829376.0000000000 4.9540766774 11.4088937173 3.4374436750 0.5998348727 0.7890410242 -0.1190826724 0.0585807534781 +1403638561227829504.0000000000 4.9877678311 11.4304997229 3.4373677501 0.6010168608 0.7866649255 -0.1259872373 0.06375142379 +1403638561277829376.0000000000 5.0216867756 11.4492941281 3.4390928532 0.6025524282 0.7842494111 -0.1317635726 0.0672442809801 +1403638561327829504.0000000000 5.0563985656 11.4653850802 3.4417706289 0.6011691687 0.7842942199 -0.1359163788 0.0707456379614 +1403638561377829376.0000000000 5.0915973120 11.4790103328 3.4435275687 0.5971245241 0.7866477241 -0.1378879167 0.0749305237827 +1403638561427829504.0000000000 5.1273316924 11.4906059600 3.4438799295 0.5921023973 0.7899453268 -0.1377520940 0.0801591687393 +1403638561477829376.0000000000 5.1634506133 11.5004810972 3.4430311037 0.5871760966 0.7932488872 -0.1365655416 0.0856170979272 +1403638561527829504.0000000000 5.1996465351 11.5089842271 3.4410462026 0.5834346992 0.7958000108 -0.1347504040 0.0902697251307 +1403638561577829376.0000000000 5.2357522855 11.5165803962 3.4375879417 0.5802119061 0.7980352775 -0.1333964959 0.0932695811524 +1403638561627829504.0000000000 5.2717412408 11.5232637796 3.4331055677 0.5778890904 0.7996549322 -0.1322604673 0.0954115159713 +1403638561677829376.0000000000 5.3073449020 11.5290990934 3.4277742189 0.5767847340 0.8005301528 -0.1313284286 0.0960400377126 +1403638561727829504.0000000000 5.3425939785 11.5341795359 3.4212123567 0.5759095325 0.8012964367 -0.1303067907 0.0962931520957 +1403638561777829376.0000000000 5.3776600040 11.5385659268 3.4133339756 0.5758720386 0.8014569668 -0.1292081524 0.0966611552858 +1403638561827829504.0000000000 5.4127414073 11.5424225073 3.4040706318 0.5758210069 0.8014950520 -0.1283322603 0.0978094096228 +1403638561877829376.0000000000 5.4478279635 11.5456524094 3.3933253319 0.5761448314 0.8010503459 -0.1283811088 0.0994674191773 +1403638561927829504.0000000000 5.4828970200 11.5484337587 3.3808767711 0.5755592459 0.8009326034 -0.1294342908 0.102397674081 +1403638561977829376.0000000000 5.5175174157 11.5508148660 3.3677708691 0.5753198632 0.8002530480 -0.1327489618 0.104784671142 +1403638562027829504.0000000000 5.5520886142 11.5529663969 3.3552561363 0.5749113303 0.7993942942 -0.1368958343 0.108190828166 +1403638562077829376.0000000000 5.5864592366 11.5539811778 3.3442423468 0.5740839466 0.7986287704 -0.1414838896 0.112258711404 +1403638562127829504.0000000000 5.6199269367 11.5533477440 3.3352475613 0.5736033601 0.7975107392 -0.1467276850 0.115874038096 +1403638562177829376.0000000000 5.6524303086 11.5516068683 3.3271567005 0.5727669671 0.7966831832 -0.1511207113 0.119985155355 +1403638562227829504.0000000000 5.6842311357 11.5502907653 3.3199736727 0.5726061771 0.7955935268 -0.1548303620 0.123209841662 +1403638562277829376.0000000000 5.7154929081 11.5489107042 3.3143825872 0.5721401740 0.7945368007 -0.1590647240 0.126748992718 +1403638562327829504.0000000000 5.7458590896 11.5465098130 3.3108916664 0.5721937442 0.7929370452 -0.1643683245 0.129723611829 +1403638562377829376.0000000000 5.7754880857 11.5429851385 3.3083465854 0.5723621228 0.7909296681 -0.1704046814 0.133394546566 +1403638562427829504.0000000000 5.8046594091 11.5385282604 3.3064983469 0.5718719611 0.7890101342 -0.1777356523 0.13724250894 +1403638562477829376.0000000000 5.8338706495 11.5342065781 3.3064382911 0.5707677891 0.7871631593 -0.1860534179 0.141359178194 +1403638562527829504.0000000000 5.8626950659 11.5294166655 3.3085065546 0.5693659065 0.7850685888 -0.1953118601 0.146092616653 +1403638562577829376.0000000000 5.8915535759 11.5244463295 3.3125068055 0.5688746880 0.7819180531 -0.2054483476 0.150919594542 +1403638562627829504.0000000000 5.9200587404 11.5186252660 3.3175367874 0.5681555631 0.7785317965 -0.2168642992 0.155104396033 +1403638562677829376.0000000000 5.9488218925 11.5120363637 3.3233431291 0.5662191571 0.7756965059 -0.2287805314 0.159217666405 +1403638562727829504.0000000000 5.9779419281 11.5049245189 3.3297563686 0.5656123186 0.7715324479 -0.2408002004 0.163815904055 +1403638562777829376.0000000000 6.0071392039 11.4966913465 3.3357772958 0.5642094708 0.7675896720 -0.2535904070 0.167826320631 +1403638562827829504.0000000000 6.0367615185 11.4869673486 3.3402852544 0.5623451015 0.7635586269 -0.2649995574 0.17470387715 +1403638562877829376.0000000000 6.0664548806 11.4759970305 3.3433305903 0.5601071408 0.7596717103 -0.2767107774 0.180582471687 +1403638562927829504.0000000000 6.0922827862 11.4604319532 3.3469605216 0.5574351472 0.7559334782 -0.2875609432 0.187454893687 +1403638562977829376.0000000000 6.1213564772 11.4463413390 3.3477412010 0.5550559899 0.7520894207 -0.2977687378 0.193928157001 +1403638563027829504.0000000000 6.1502992025 11.4312044398 3.3475003528 0.5534408970 0.7476168148 -0.3086300622 0.198795765844 +1403638563077829376.0000000000 6.1792627478 11.4148956316 3.3459431148 0.5517312823 0.7432838789 -0.3198434603 0.202044125018 +1403638563127829504.0000000000 6.2085221819 11.3970680319 3.3430743413 0.5497939792 0.7390986170 -0.3309248432 0.204813483503 +1403638563177829376.0000000000 6.2385594245 11.3775245229 3.3385838831 0.5467589084 0.7360767206 -0.3377525807 0.212529884356 +1403638563227829504.0000000000 6.2686589126 11.3568920056 3.3335204220 0.5463675846 0.7316482663 -0.3447142555 0.217589886963 +1403638563277829376.0000000000 6.2989059702 11.3347308778 3.3267855922 0.5454680499 0.7282721869 -0.3491186486 0.224054452112 +1403638563327829504.0000000000 6.3289179199 11.3112684711 3.3193760303 0.5476311498 0.7234121037 -0.3529194764 0.228523292258 +1403638563377829376.0000000000 6.3589467727 11.2861385807 3.3111334313 0.5517739164 0.7176789095 -0.3550438891 0.23329458817 +1403638563427829504.0000000000 6.3883169618 11.2592246932 3.3016211439 0.5560018338 0.7124236593 -0.3573087675 0.235891787117 +1403638563477829376.0000000000 6.4166029552 11.2303538592 3.2900165274 0.5579272888 0.7096824106 -0.3591356564 0.236832423337 +1403638563527829504.0000000000 6.4443168337 11.1987969035 3.2780531022 0.5570100050 0.7094741053 -0.3588517787 0.240024476103 +1403638563577829376.0000000000 6.4710856811 11.1649091097 3.2669091958 0.5551099046 0.7104378604 -0.3588509034 0.241572079289 +1403638563627829504.0000000000 6.4969949425 11.1289237792 3.2573748146 0.5524297684 0.7123252314 -0.3589472624 0.242014417948 +1403638563677829376.0000000000 6.5217173909 11.0906354913 3.2501443378 0.5506920006 0.7138047537 -0.3600579293 0.239957041216 +1403638563727829504.0000000000 6.5461454172 11.0502049368 3.2443762728 0.5497476899 0.7148601990 -0.3604977297 0.238314414717 +1403638563777829376.0000000000 6.5704664825 11.0083472822 3.2404363395 0.5489664688 0.7158930328 -0.3611379232 0.236034705334 +1403638563827829504.0000000000 6.5945160957 10.9643506802 3.2388407677 0.5494273309 0.7162044663 -0.3610215228 0.234188450873 +1403638563877829376.0000000000 6.6184594771 10.9187091596 3.2396163673 0.5506824069 0.7159254907 -0.3601947887 0.233365148954 +1403638563927829504.0000000000 6.6424646071 10.8721556179 3.2424423706 0.5515037338 0.7161128794 -0.3597992206 0.231453011151 +1403638563977829376.0000000000 6.6664867674 10.8231307476 3.2458596996 0.5534519677 0.7156094929 -0.3582892425 0.230700654133 +1403638564027829504.0000000000 6.6899804522 10.7719030341 3.2479723881 0.5536140961 0.7166015030 -0.3576294826 0.228243010154 +1403638564077829376.0000000000 6.7134064446 10.7187082507 3.2489791816 0.5544645177 0.7171206279 -0.3564822539 0.226334942757 +1403638564127829504.0000000000 6.7369289462 10.6635336386 3.2486234594 0.5553208706 0.7177328127 -0.3544907390 0.22542106405 +1403638564177829376.0000000000 6.7611785908 10.6084920998 3.2489570361 0.5556243837 0.7188155236 -0.3521415923 0.224904615838 +1403638564227829504.0000000000 6.7850820743 10.5501281507 3.2473281313 0.5568787780 0.7190581572 -0.3492126699 0.225592341221 +1403638564277829376.0000000000 6.8087443556 10.4896825076 3.2457302304 0.5578338515 0.7193176992 -0.3464394221 0.226678557567 +1403638564327829504.0000000000 6.8324252826 10.4277242106 3.2458092059 0.5580106083 0.7204081800 -0.3428677367 0.228205894785 +1403638564377829376.0000000000 6.8555366604 10.3638583624 3.2479797617 0.5599918455 0.7198934589 -0.3412495608 0.227401139274 +1403638564427829504.0000000000 6.8787899367 10.2979485465 3.2519274994 0.5608321332 0.7200241160 -0.3385435462 0.228956017955 +1403638564477829376.0000000000 6.9012859641 10.2301000819 3.2574345680 0.5616313281 0.7202960809 -0.3367686537 0.228759001992 +1403638564527829504.0000000000 6.9228531556 10.1599305872 3.2641350104 0.5614038682 0.7209130220 -0.3363815504 0.227942019038 +1403638564577829376.0000000000 6.9433496537 10.0877335184 3.2712069244 0.5604549863 0.7222161488 -0.3369286737 0.225328896571 +1403638564627829504.0000000000 6.9638294713 10.0139058039 3.2779132274 0.5601834430 0.7226704441 -0.3379687816 0.222977671567 +1403638564677829376.0000000000 6.9837887635 9.9381570046 3.2831656663 0.5599015168 0.7228888461 -0.3401791315 0.219590906542 +1403638564727829504.0000000000 7.0034984223 9.8601383679 3.2865663468 0.5599680016 0.7228456364 -0.3414334213 0.217608000831 +1403638564777829376.0000000000 7.0208295053 9.7785708425 3.2933202705 0.5601755140 0.7224144343 -0.3432754509 0.21559857024 +1403638564827829504.0000000000 7.0402568213 9.6969361085 3.2947861083 0.5604227929 0.7219531123 -0.3444054613 0.214697170555 +1403638564877829376.0000000000 7.0598037901 9.6137121423 3.2929253524 0.5612785098 0.7211004544 -0.3454036394 0.213721536031 +1403638564927829504.0000000000 7.0794302654 9.5288428800 3.2865906404 0.5619794464 0.7203220125 -0.3463504614 0.212971026471 +1403638564977829376.0000000000 7.0986380643 9.4415473496 3.2751525119 0.5623484179 0.7200274615 -0.3468364064 0.212200892513 +1403638565027829504.0000000000 7.1180612906 9.3526603197 3.2595558647 0.5623610361 0.7199760696 -0.3472119142 0.211727208771 +1403638565077829376.0000000000 7.1380428839 9.2626537620 3.2403379074 0.5621790970 0.7201498571 -0.3476478598 0.210902375263 +1403638565127829504.0000000000 7.1587116071 9.1713325142 3.2168791862 0.5617909186 0.7203991066 -0.3479739035 0.210547509077 +1403638565177829376.0000000000 7.1798523337 9.0786849909 3.1904415068 0.5613433884 0.7208078624 -0.3480988336 0.210135260823 +1403638565227829504.0000000000 7.2017822981 8.9844536040 3.1626538962 0.5606418365 0.7213630671 -0.3478451110 0.21052276683 +1403638565277829376.0000000000 7.2240494578 8.8883176062 3.1339707320 0.5596392739 0.7220109810 -0.3476583046 0.211276429478 +1403638565327829504.0000000000 7.2467883612 8.7907483334 3.1044976679 0.5588076917 0.7225069864 -0.3473263051 0.21232535438 +1403638565377829376.0000000000 7.2695720152 8.6920215032 3.0746473537 0.5575315629 0.7234078485 -0.3468092180 0.213454930686 +1403638565427829504.0000000000 7.2923793354 8.5918422984 3.0446003386 0.5570370358 0.7237806818 -0.3464088448 0.214131215869 +1403638565477829376.0000000000 7.3159003139 8.4899632457 3.0154695600 0.5574192976 0.7230898507 -0.3456549005 0.216673681529 +1403638565527829504.0000000000 7.3398756486 8.3867247015 2.9877047480 0.5578011495 0.7224081924 -0.3440977225 0.220411067294 +1403638565577829376.0000000000 7.3642615640 8.2823963843 2.9623661954 0.5579533532 0.7218234926 -0.3427324210 0.224038810755 +1403638565627829504.0000000000 7.3880566238 8.1763783908 2.9391624627 0.5569727806 0.7221188504 -0.3402526774 0.229246162744 +1403638565677829376.0000000000 7.4113331559 8.0693515466 2.9175531247 0.5545300757 0.7235676984 -0.3369498661 0.235395345612 +1403638565727829504.0000000000 7.4343041549 7.9621364642 2.8979923521 0.5515528476 0.7253379844 -0.3346581587 0.24016282286 +1403638565777829376.0000000000 7.4557033593 7.8540197586 2.8803519608 0.5481107611 0.7275503151 -0.3337309532 0.242628900574 +1403638565827829504.0000000000 7.4754728402 7.7454117721 2.8650848594 0.5456400111 0.7289620999 -0.3333106062 0.244530724206 +1403638565877829376.0000000000 7.4940912216 7.6361977684 2.8513000417 0.5428178613 0.7306612093 -0.3313659366 0.248353745357 +1403638565927829504.0000000000 7.5112747429 7.5269192463 2.8391746015 0.5404450573 0.7318165038 -0.3322689544 0.248919840019 +1403638565977829376.0000000000 7.5273796930 7.4180594316 2.8269044007 0.5395520400 0.7320835399 -0.3325153299 0.24974155043 +1403638566027829504.0000000000 7.5423614905 7.3097481881 2.8129485541 0.5386095136 0.7325212802 -0.3336269737 0.249008852026 +1403638566077829376.0000000000 7.5563546153 7.2016842827 2.7971301827 0.5376623534 0.7328282723 -0.3332259583 0.250683820375 +1403638566127829504.0000000000 7.5731166150 7.0813910765 2.7680549357 0.5382012418 0.7325010744 -0.3342205747 0.249154985538 +1403638566177829376.0000000000 7.5857597325 6.9732306295 2.7468246019 0.5381660576 0.7324762331 -0.3347731278 0.248561491997 +1403638566227829504.0000000000 7.5970843997 6.8648346523 2.7235365895 0.5385047243 0.7322127191 -0.3339802202 0.249668597234 +1403638566277829376.0000000000 7.6081319543 6.7574563485 2.6987171002 0.5385332055 0.7323440283 -0.3338655031 0.249375292889 +1403638566327829504.0000000000 7.6184355485 6.6507417153 2.6715993793 0.5375146704 0.7331371951 -0.3343316872 0.248616482247 +1403638566377829376.0000000000 7.6266327219 6.5430286657 2.6411777299 0.5372989139 0.7336026683 -0.3332511466 0.249159939492 +1403638566427829504.0000000000 7.6350785408 6.4367517363 2.6106894520 0.5379589191 0.7334140447 -0.3331958892 0.248363725038 +1403638566477829376.0000000000 7.6421125448 6.3303932928 2.5781380412 0.5383443211 0.7335656768 -0.3340142640 0.245970041186 +1403638566527829504.0000000000 7.6488007928 6.2242564381 2.5446605539 0.5384774641 0.7339191148 -0.3327496419 0.24633803903 +1403638566577829376.0000000000 7.6546165574 6.1185275795 2.5087518902 0.5348209592 0.7371337249 -0.3334100259 0.243799441947 +1403638566627829504.0000000000 7.6587996198 6.0125462313 2.4709905956 0.5309423594 0.7405141371 -0.3340056823 0.241203706419 +1403638566677829376.0000000000 7.6626328663 5.9070035393 2.4311758485 0.5232151736 0.7465172664 -0.3348903514 0.238340734326 +1403638566727829504.0000000000 7.6664192859 5.8026500326 2.3903548468 0.5152923475 0.7524000473 -0.3373139194 0.233639220255 +1403638566777829376.0000000000 7.6710714930 5.6997062623 2.3486849949 0.5079020949 0.7581344516 -0.3371658031 0.231488307771 +1403638566827829504.0000000000 7.6762628865 5.5983868211 2.3061490316 0.5020631127 0.7625818987 -0.3377791617 0.228706616877 +1403638566877829376.0000000000 7.6822934596 5.4986536209 2.2629285586 0.4974362593 0.7661208399 -0.3387343063 0.225555084885 +1403638566927829504.0000000000 7.6898708375 5.4009305969 2.2191167097 0.4935841541 0.7693198974 -0.3375166297 0.224953557573 +1403638566977829376.0000000000 7.6987476869 5.3055844802 2.1746957978 0.4920650158 0.7708199273 -0.3373490114 0.223392713431 +1403638567027829504.0000000000 7.7095202761 5.2129535531 2.1309330079 0.4944371352 0.7696197446 -0.3362251702 0.223986613482 +1403638567077829376.0000000000 7.7220927734 5.1230938313 2.0889543539 0.5039185904 0.7637071481 -0.3331038447 0.227726315756 +1403638567127829504.0000000000 7.7356147777 5.0348233341 2.0453979795 0.5115797928 0.7586727682 -0.3294534170 0.232727721613 +1403638567177829376.0000000000 7.7499597835 4.9486871045 2.0007767538 0.5202746065 0.7527981935 -0.3267969648 0.236247661417 +1403638567227829504.0000000000 7.7649698755 4.8639526489 1.9550807745 0.5261761814 0.7485975507 -0.3239905309 0.240354881506 +1403638567277829376.0000000000 7.7796440168 4.7799953305 1.9077166522 0.5306344303 0.7452479708 -0.3220418790 0.243560242278 +1403638567327829504.0000000000 7.7935870896 4.6965233364 1.8584758186 0.5323079038 0.7437130346 -0.3208042652 0.246219091723 +1403638567377829376.0000000000 7.8066048146 4.6136354275 1.8092653330 0.5320378115 0.7436349969 -0.3207177254 0.247149547914 +1403638567427829504.0000000000 7.8189139166 4.5315214507 1.7613513565 0.5320045386 0.7431328441 -0.3208652567 0.24853618248 +1403638567477829376.0000000000 7.8301486886 4.4498301806 1.7143660162 0.5302377422 0.7440479140 -0.3217410877 0.248441765732 +1403638567527829504.0000000000 7.8408264538 4.3689200819 1.6687832701 0.5280232934 0.7450691504 -0.3227948812 0.248730431186 +1403638567577829376.0000000000 7.8500465077 4.2883372655 1.6256010948 0.5250460523 0.7467361516 -0.3244917950 0.247824207503 +1403638567627829504.0000000000 7.8587898337 4.2085223700 1.5840562070 0.5221067519 0.7482335455 -0.3251740114 0.24862212968 +1403638567677829376.0000000000 7.8670176501 4.1300702242 1.5452073970 0.5193511009 0.7495793756 -0.3260543002 0.249186249532 +1403638567727829504.0000000000 7.8743655407 4.0530179870 1.5085334949 0.5168356561 0.7509070459 -0.3268914901 0.249322014118 +1403638567777829376.0000000000 7.8809679244 3.9772155053 1.4741683380 0.5141218748 0.7524113330 -0.3276989726 0.249337657039 +1403638567827829504.0000000000 7.8872927535 3.9031356485 1.4421274263 0.5106607464 0.7544497147 -0.3287075665 0.248962980822 +1403638567877829376.0000000000 7.8936192251 3.8312575170 1.4119536221 0.5097168074 0.7547797179 -0.3310173413 0.246827619044 +1403638567927829504.0000000000 7.9004380782 3.7616390226 1.3836008530 0.5094584379 0.7548879064 -0.3317535428 0.246040516196 +1403638567977829376.0000000000 7.9071413102 3.6930400808 1.3567239539 0.5083966662 0.7552433184 -0.3323348770 0.246361298311 +1403638568027829504.0000000000 7.9138835309 3.6262585826 1.3317823391 0.5080552055 0.7553933895 -0.3321698714 0.246827696395 +1403638568077829376.0000000000 7.9209405179 3.5611911388 1.3090308032 0.5074464546 0.7556322433 -0.3306715181 0.249347860843 +1403638568127829504.0000000000 7.9272683609 3.4976475090 1.2893132288 0.5080877008 0.7550504783 -0.3305775067 0.249928340759 +1403638568177829376.0000000000 7.9333480589 3.4353251089 1.2712171236 0.5076142573 0.7553242949 -0.3293108730 0.251728671828 +1403638568227829504.0000000000 7.9386476215 3.3743622514 1.2556757596 0.5081443907 0.7547044425 -0.3294279442 0.25236424527 +1403638568277829376.0000000000 7.9437627679 3.3148711694 1.2410307779 0.5073474815 0.7550037345 -0.3296166107 0.252825599834 +1403638568327829504.0000000000 7.9486696129 3.2569880552 1.2267066651 0.5075405334 0.7547741947 -0.3295853188 0.253164056452 +1403638568377829376.0000000000 7.9531102892 3.2005550537 1.2118087749 0.5066311978 0.7552439078 -0.3302059386 0.252775606724 +1403638568427829504.0000000000 7.9574194680 3.1455197655 1.1953435915 0.5057298056 0.7557835952 -0.3304685636 0.25262432484 +1403638568477829376.0000000000 7.9615173402 3.0919716629 1.1777599118 0.5052560850 0.7560431187 -0.3304552771 0.252812976675 +1403638568527829504.0000000000 7.9653603847 3.0399710153 1.1593069543 0.5043176424 0.7566373410 -0.3303789745 0.253008661869 +1403638568577829376.0000000000 7.9691783147 2.9899617078 1.1402640227 0.5029895902 0.7574840127 -0.3304219508 0.2530627927 +1403638568627829504.0000000000 7.9730430152 2.9416954286 1.1204415602 0.5018011662 0.7582807979 -0.3306509904 0.252736510439 +1403638568677829376.0000000000 7.9769536556 2.8950677163 1.1001738199 0.5000041090 0.7596360950 -0.3297876515 0.253355479624 +1403638568727829504.0000000000 7.9808518639 2.8503942622 1.0805956638 0.4992136575 0.7601380522 -0.3296636236 0.25357003182 +1403638568777829376.0000000000 7.9845309434 2.8075255211 1.0623791993 0.4983024316 0.7608330530 -0.3303401596 0.252394792048 +1403638568827829504.0000000000 7.9877822669 2.7666820380 1.0469861771 0.5000372073 0.7597204238 -0.3306838815 0.251864724445 +1403638568877829376.0000000000 7.9908646496 2.7272554799 1.0323895559 0.4999262657 0.7596302578 -0.3316915257 0.251030540235 +1403638568927829504.0000000000 7.9946719745 2.6900762461 1.0197048498 0.4996310537 0.7598968466 -0.3301154986 0.252882087677 +1403638568977829376.0000000000 7.9982543462 2.6546912259 1.0092961178 0.4999293274 0.7596985899 -0.3299324911 0.253126986714 +1403638569027829504.0000000000 8.0021381536 2.6214419015 1.0011952396 0.5007442207 0.7590756814 -0.3298959245 0.253432465209 +1403638569077829376.0000000000 8.0063167785 2.5897301377 0.9944321018 0.4995888129 0.7598251843 -0.3289324120 0.254715872258 +1403638569127829504.0000000000 8.0101566726 2.5597942379 0.9900444501 0.4998903421 0.7596065844 -0.3288564096 0.254874370322 +1403638569177829376.0000000000 8.0137431799 2.5314039693 0.9867702280 0.4981943203 0.7605831706 -0.3292035412 0.254834629321 +1403638569227829504.0000000000 8.0169323789 2.5046272122 0.9835429953 0.4968916797 0.7613528972 -0.3285826063 0.255878673144 +1403638569277829376.0000000000 8.0200485070 2.4796464287 0.9796368706 0.4955637505 0.7620782604 -0.3287088985 0.256132298424 +1403638569327829504.0000000000 8.0230292107 2.4561699779 0.9744666540 0.4953654591 0.7620827227 -0.3286780866 0.256541811476 +1403638569377829376.0000000000 8.0261124515 2.4345272645 0.9679766976 0.4952988844 0.7620646149 -0.3284649438 0.256996728536 +1403638569427829504.0000000000 8.0294868147 2.4148533694 0.9604669230 0.4962320409 0.7613479203 -0.3278933611 0.258048541146 +1403638569477829376.0000000000 8.0327528075 2.3970656494 0.9516644588 0.4970366212 0.7608423502 -0.3276000036 0.258363606261 +1403638569527829504.0000000000 8.0359550470 2.3810275131 0.9417434679 0.4978814953 0.7602923138 -0.3272262235 0.258829312219 +1403638569577829376.0000000000 8.0390706528 2.3665998294 0.9319365306 0.4985028126 0.7597487995 -0.3268343026 0.259723018231 +1403638569627829504.0000000000 8.0418217998 2.3539759684 0.9238421880 0.4999648324 0.7587406071 -0.3273354829 0.259228353085 +1403638569677829376.0000000000 8.0443642699 2.3429644831 0.9174522073 0.5004201170 0.7583370772 -0.3273353207 0.259530675773 +1403638569727829504.0000000000 8.0459714079 2.3331467213 0.9123942946 0.5008459991 0.7579689907 -0.3266971128 0.260586436484 +1403638569777829376.0000000000 8.0473822937 2.3253525666 0.9090688287 0.5011928090 0.7577398485 -0.3264614943 0.260881166145 +1403638569827829504.0000000000 8.0481951975 2.3191120563 0.9075620439 0.5017504502 0.7575071598 -0.3260770831 0.260965753245 +1403638569877829376.0000000000 8.0487481925 2.3142544297 0.9072831917 0.5025239228 0.7568861884 -0.3250016124 0.262615606546 +1403638569927829504.0000000000 8.0487249562 2.3108750647 0.9083814419 0.5037912895 0.7559746492 -0.3248315027 0.263023119322 +1403638569977829376.0000000000 8.0480373453 2.3088442548 0.9098551551 0.5051345952 0.7551217119 -0.3252729455 0.262350437067 +1403638570027829504.0000000000 8.0468355989 2.3081488187 0.9106545153 0.5063465581 0.7543855467 -0.3255823996 0.261747418604 +1403638570077829376.0000000000 8.0449919445 2.3087578313 0.9100714895 0.5069249583 0.7539922661 -0.3265136012 0.2605985755 +1403638570127829504.0000000000 8.0424633440 2.3105488083 0.9081298641 0.5076288060 0.7536664496 -0.3278340545 0.258504759664 +1403638570177829376.0000000000 8.0394465915 2.3133417550 0.9049158381 0.5087702094 0.7531378952 -0.3292116179 0.256038855497 +1403638570227829504.0000000000 8.0359327892 2.3170091579 0.9005924440 0.5107194709 0.7520454876 -0.3308477952 0.253244828106 +1403638570277829376.0000000000 8.0318974007 2.3214068731 0.8950294116 0.5124828008 0.7510061883 -0.3333992681 0.24939128303 +1403638570327829504.0000000000 8.0279092106 2.3264552753 0.8887561428 0.5144677986 0.7495234884 -0.3366913030 0.245308766753 +1403638570377829376.0000000000 8.0243607384 2.3315284065 0.8810248628 0.5150152688 0.7481278961 -0.3401647810 0.243622342622 +1403638570427829504.0000000000 8.0215350000 2.3369663002 0.8719724706 0.5156776746 0.7455428004 -0.3460359361 0.24187103922 +1403638570477829376.0000000000 8.0190462498 2.3425979176 0.8618952376 0.5161556018 0.7420037458 -0.3544671071 0.239513895014 +1403638570527829504.0000000000 8.0176515331 2.3480152635 0.8506230991 0.5176981447 0.7364454811 -0.3660032378 0.235962527066 +1403638570577829376.0000000000 8.0176715565 2.3524188780 0.8378181815 0.5192842738 0.7297510745 -0.3787143046 0.233200960099 +1403638570627829504.0000000000 8.0185742039 2.3556052433 0.8238472711 0.5201516845 0.7224186121 -0.3918005308 0.232477779704 +1403638570677829376.0000000000 8.0217408017 2.3572354331 0.8085181991 0.5210863571 0.7142616821 -0.4039722858 0.234745926938 +1403638570727829504.0000000000 8.0265625848 2.3569956658 0.7924608722 0.5233165985 0.7049224003 -0.4144947266 0.239621094515 +1403638570777829376.0000000000 8.0329773562 2.3545335556 0.7763777967 0.5269443136 0.6937393549 -0.4256028326 0.244780772671 +1403638570827829504.0000000000 8.0402181966 2.3489566631 0.7594030419 0.5294024450 0.6832828369 -0.4350772981 0.252121717988 +1403638570877829376.0000000000 8.0482441842 2.3406290116 0.7415526763 0.5305305029 0.6737452928 -0.4440759136 0.259617504819 +1403638570927829504.0000000000 8.0568715259 2.3288087924 0.7226822966 0.5296701058 0.6656725033 -0.4526560478 0.267268029761 +1403638570977829376.0000000000 8.0661258660 2.3135028923 0.7028631510 0.5279675992 0.6581471916 -0.4609029069 0.275065444679 +1403638571027829504.0000000000 8.0757384055 2.2948365431 0.6821027745 0.5249957107 0.6515488949 -0.4696914427 0.281519963549 +1403638571077829376.0000000000 8.0852351135 2.2726396721 0.6595787293 0.5176604196 0.6484625651 -0.4775148637 0.288969802178 +1403638571127829504.0000000000 8.0949486668 2.2472041400 0.6369148302 0.5088487177 0.6466371037 -0.4847200483 0.29661408164 +1403638571177829376.0000000000 8.1042140950 2.2185226879 0.6164313400 0.4996481722 0.6461962158 -0.4897768468 0.304796317095 +1403638571227829504.0000000000 8.1135938242 2.1871589539 0.5978650823 0.4918309223 0.6455599932 -0.4934800169 0.312781252676 +1403638571277829376.0000000000 8.1232376122 2.1536525398 0.5821492207 0.4851257669 0.6447615453 -0.4960964670 0.320661559001 +1403638571327829504.0000000000 8.1329183508 2.1182519027 0.5689113083 0.4795615019 0.6440066113 -0.4980318078 0.327476058702 +1403638571377829376.0000000000 8.1423895355 2.0817406599 0.5585957123 0.4769679438 0.6420287773 -0.5007768179 0.330942908167 +1403638571427829504.0000000000 8.1515196069 2.0438117002 0.5509338894 0.4756057006 0.6397372153 -0.5028057714 0.334248214984 +1403638571477829376.0000000000 8.1603269157 2.0042199208 0.5457652766 0.4753675508 0.6375806547 -0.5041515667 0.336671647403 +1403638571527829504.0000000000 8.1689447176 1.9632085166 0.5414616893 0.4747783330 0.6355933214 -0.5047917566 0.340282157445 +1403638571577829376.0000000000 8.1772600983 1.9208675945 0.5365296294 0.4727736279 0.6336932614 -0.5071770718 0.34305883626 +1403638571627829504.0000000000 8.1855149788 1.8770308109 0.5311986500 0.4698592676 0.6317828018 -0.5106792156 0.345383118956 +1403638571677829376.0000000000 8.1935134264 1.8322088459 0.5240574151 0.4657361735 0.6298891287 -0.5157190078 0.346934298121 +1403638571727829504.0000000000 8.2016963227 1.7861133342 0.5157950365 0.4609980761 0.6273755607 -0.5214085548 0.349304736135 +1403638571777829376.0000000000 8.2098913249 1.7387350320 0.5062502950 0.4558896661 0.6243558938 -0.5278593974 0.351722599205 +1403638571827829504.0000000000 8.2181708344 1.6905794383 0.4956196141 0.4510671582 0.6203768966 -0.5350208290 0.354151997607 +1403638571877829376.0000000000 8.2273994500 1.6414955126 0.4848780378 0.4471919419 0.6150003923 -0.5430841871 0.356164919957 +1403638571927829504.0000000000 8.2369567952 1.5910799273 0.4747532371 0.4436600839 0.6087495864 -0.5510786733 0.359029200575 +1403638571977829376.0000000000 8.2469789470 1.5393785707 0.4662683390 0.4404136905 0.6019504626 -0.5592939257 0.361775795843 +1403638572027829504.0000000000 8.2572072634 1.4861573737 0.4595559274 0.4365490032 0.5954638190 -0.5667053203 0.365640380662 +1403638572077829376.0000000000 8.2678395487 1.4315977603 0.4553636152 0.4334289071 0.5883646964 -0.5744275121 0.368780964619 +1403638572127829504.0000000000 8.2787190365 1.3751732256 0.4528138864 0.4291484813 0.5818766872 -0.5805855029 0.374394946244 +1403638572177829376.0000000000 8.2891092169 1.3170185392 0.4520864019 0.4232576290 0.5762541161 -0.5857912910 0.381618574754 +1403638572227829504.0000000000 8.2994572115 1.2577224231 0.4524347350 0.4164372802 0.5711106638 -0.5921253494 0.387040271764 +1403638572277829376.0000000000 8.3097324005 1.1973262651 0.4528076816 0.4091351954 0.5660053135 -0.5993753866 0.391146421393 +1403638572327829504.0000000000 8.3204374126 1.1358901968 0.4523765182 0.4016568571 0.5604560714 -0.6068905730 0.395277868879 +1403638572377829376.0000000000 8.3317583553 1.0735674943 0.4509516617 0.3943112583 0.5546258636 -0.6143699569 0.39932234974 +1403638572427829504.0000000000 8.3434489747 1.0104428529 0.4485739269 0.3869509048 0.5497041178 -0.6204491875 0.403902446055 +1403638572477829376.0000000000 8.3554411966 0.9468650189 0.4454171407 0.3801292543 0.5459502016 -0.6248279591 0.408693220969 +1403638572527829504.0000000000 8.3679514801 0.8830456225 0.4418521987 0.3744836639 0.5424398310 -0.6288279038 0.412427548346 +1403638572577829376.0000000000 8.3813290230 0.8191644090 0.4385002482 0.3705402128 0.5390755952 -0.6312831282 0.416628210038 +1403638572627829504.0000000000 8.3952181877 0.7549610951 0.4348915853 0.3673226657 0.5368927772 -0.6336482399 0.418700505299 +1403638572677829376.0000000000 8.4098083748 0.6904843138 0.4326131482 0.3643155767 0.5353252841 -0.6355144971 0.420502467108 +1403638572727829504.0000000000 8.4255944381 0.6256648580 0.4320850769 0.3600260036 0.5355658144 -0.6358208581 0.423417490889 +1403638572777829376.0000000000 8.4422191973 0.5607947618 0.4339460091 0.3560803198 0.5366070081 -0.6356532560 0.425681410087 +1403638572827829504.0000000000 8.4595685274 0.4963742591 0.4378926523 0.3528359106 0.5378051233 -0.6357056822 0.426791231473 +1403638572877829376.0000000000 8.4784041761 0.4322504480 0.4440144346 0.3501868153 0.5390881033 -0.6357663805 0.427263760054 +1403638572927829504.0000000000 8.4985227887 0.3688288947 0.4519962222 0.3494586461 0.5397636915 -0.6358139800 0.426936054723 +1403638572977829376.0000000000 8.5196760887 0.3058109073 0.4598957542 0.3473893762 0.5414717447 -0.6355392874 0.426870923273 +1403638573027829504.0000000000 8.5410831320 0.2435127349 0.4671616984 0.3464926204 0.5424791493 -0.6356240617 0.426193956841 +1403638573077829376.0000000000 8.5639746579 0.1817709740 0.4729435245 0.3459527947 0.5438494623 -0.6351375355 0.42561101638 +1403638573127829504.0000000000 8.5871545345 0.1206873871 0.4770920069 0.3455732238 0.5451297437 -0.6349706669 0.424529105848 +1403638573177829376.0000000000 8.6119226037 0.0600566893 0.4804034197 0.3460839132 0.5457943592 -0.6346031374 0.423808094049 +1403638573227829504.0000000000 8.6379029762 -0.0000652704 0.4833537159 0.3468293858 0.5466298084 -0.6337273673 0.423432230377 +1403638573277829376.0000000000 8.6651116137 -0.0596048549 0.4862161799 0.3469340950 0.5478325986 -0.6332957083 0.422436650331 +1403638573327829504.0000000000 8.6942568373 -0.1186948240 0.4895562932 0.3480609655 0.5483469154 -0.6322601753 0.422393531387 +1403638573377829376.0000000000 8.7246942631 -0.1776467799 0.4927821810 0.3471134059 0.5488820066 -0.6327632832 0.42172438129 +1403638573427829504.0000000000 8.7564162622 -0.2362358392 0.4968298636 0.3453374969 0.5491732038 -0.6330147128 0.422425352941 +1403638573477829376.0000000000 8.7911219980 -0.2941968747 0.5019385594 0.3441923990 0.5488926223 -0.6329015226 0.423891665861 +1403638573527829504.0000000000 8.8275978148 -0.3516095248 0.5098481572 0.3429364920 0.5489346252 -0.6330034177 0.424702263809 +1403638573577829376.0000000000 8.8661721210 -0.4084809344 0.5202264725 0.3426135613 0.5486663924 -0.6331388712 0.425107406752 +1403638573627829504.0000000000 8.9060648341 -0.4646025289 0.5325988189 0.3419827945 0.5484019166 -0.6333092819 0.425702313343 +1403638573677829376.0000000000 8.9467728891 -0.5201601537 0.5458238624 0.3391682475 0.5487278532 -0.6337849007 0.426824721263 +1403638573727829504.0000000000 8.9891784014 -0.5749213006 0.5599255181 0.3376302878 0.5470173377 -0.6348608851 0.428636766548 +1403638573777829376.0000000000 9.0346838863 -0.6293715455 0.5755589325 0.3357424853 0.5439942548 -0.6356244875 0.432814908729 +1403638573827829504.0000000000 9.0810343979 -0.6830591209 0.5906903692 0.3350662667 0.5387057361 -0.6360599429 0.439265837305 +1403638573877829376.0000000000 9.1294875955 -0.7362639202 0.6050386464 0.3339348184 0.5321251586 -0.6370719734 0.446620256328 +1403638573927829504.0000000000 9.1791051007 -0.7884093537 0.6182916697 0.3330241233 0.5236266743 -0.6395960914 0.453681473241 +1403638573977829376.0000000000 9.2293404162 -0.8394479409 0.6302746662 0.3341308829 0.5125833315 -0.6440550173 0.459138340908 +1403638574027829504.0000000000 9.2804987895 -0.8896688391 0.6409873420 0.3364467143 0.4997080154 -0.6499551066 0.463307529777 +1403638574077829376.0000000000 9.3309953371 -0.9392494214 0.6502595032 0.3387642592 0.4856407503 -0.6568004475 0.466910066825 +1403638574127829504.0000000000 9.3809361952 -0.9887290624 0.6583289049 0.3406809839 0.4710566858 -0.6634996967 0.470967322116 +1403638574177829376.0000000000 9.4298195240 -1.0382196203 0.6647343564 0.3417302939 0.4560684511 -0.6710969225 0.474184452244 +1403638574227829504.0000000000 9.4770897400 -1.0881620510 0.6698457872 0.3403047921 0.4425541143 -0.6777916652 0.47847357604 +1403638574277829376.0000000000 9.5219942742 -1.1384640163 0.6736458372 0.3366302069 0.4304719782 -0.6849376427 0.481907050517 +1403638574327829504.0000000000 9.5649204664 -1.1892448877 0.6756969735 0.3303019667 0.4200361913 -0.6917338526 0.485772051369 +1403638574377829376.0000000000 9.6059243154 -1.2404906230 0.6765546947 0.3225148895 0.4107496304 -0.6984247180 0.489358560172 +1403638574427829504.0000000000 9.6454102691 -1.2923360910 0.6761341960 0.3137356359 0.4021438628 -0.7042900548 0.493787183987 +1403638574477829376.0000000000 9.6831949388 -1.3444906727 0.6748918581 0.3054805691 0.3933038393 -0.7107385137 0.49683445629 +1403638574527829504.0000000000 9.7194049069 -1.3969432649 0.6746705668 0.2984653074 0.3853569973 -0.7158471557 0.49998129431 +1403638574577829376.0000000000 9.7545992849 -1.4492190401 0.6754610987 0.2930828112 0.3781903603 -0.7198474225 0.502885877188 +1403638574627829504.0000000000 9.7887273825 -1.5022172979 0.6785513324 0.2878224116 0.3724801054 -0.7220618561 0.50699458213 +1403638574677829376.0000000000 9.8212593151 -1.5555525696 0.6830195932 0.2805474003 0.3696394592 -0.7239207150 0.510488613715 +1403638574727829504.0000000000 9.8530285764 -1.6086324507 0.6891213772 0.2736079274 0.3681503689 -0.7246554865 0.514274667733 +1403638574777829376.0000000000 9.8837147535 -1.6611900004 0.6967125967 0.2659187966 0.3685413530 -0.7259726338 0.516166833223 +1403638574827829504.0000000000 9.9136271814 -1.7128412248 0.7057053787 0.2603192342 0.3690861743 -0.7278698932 0.515959989558 +1403638574877829376.0000000000 9.9431327335 -1.7640824106 0.7145621049 0.2566875649 0.3689752317 -0.7306626068 0.513907508721 +1403638574927829504.0000000000 9.9724469282 -1.8149889342 0.7225346062 0.2535688435 0.3695287244 -0.7329665888 0.511772745589 +1403638574977829376.0000000000 10.0014579984 -1.8656462258 0.7292319380 0.2513777573 0.3701460216 -0.7344654928 0.510256392149 +1403638575027829504.0000000000 10.0305098270 -1.9158566005 0.7348622582 0.2526881868 0.3690198923 -0.7367137723 0.507174345838 +1403638575077829376.0000000000 10.0594308405 -1.9659215531 0.7392631981 0.2556251993 0.3670716560 -0.7389961728 0.503784491132 +1403638575127829504.0000000000 10.0882617766 -2.0162257237 0.7424138032 0.2588837855 0.3650311309 -0.7402410378 0.501771526743 +1403638575177829376.0000000000 10.1167781346 -2.0669019845 0.7443616815 0.2618806502 0.3634760462 -0.7411888353 0.499942796019 +1403638575227829504.0000000000 10.1448492015 -2.1183360481 0.7454454400 0.2643809228 0.3623868993 -0.7412454782 0.499333159263 +1403638575277829376.0000000000 10.1724624202 -2.1703273593 0.7453102716 0.2664211706 0.3619751551 -0.7415538375 0.49808799722 +1403638575327829504.0000000000 10.1996049778 -2.2232236876 0.7437541112 0.2668433267 0.3627758192 -0.7420350592 0.496560484606 +1403638575377829376.0000000000 10.2263559272 -2.2769940458 0.7406350377 0.2655649948 0.3651850211 -0.7427629399 0.494386841418 +1403638575427829504.0000000000 10.2531456243 -2.3314236970 0.7363359538 0.2643627731 0.3677017812 -0.7435849267 0.491923958679 +1403638575477829376.0000000000 10.2802788228 -2.3869230909 0.7309998885 0.2622617204 0.3709461311 -0.7431825391 0.49122038993 +1403638575527829504.0000000000 10.3076627859 -2.4431263701 0.7256564455 0.2621222258 0.3728794285 -0.7433407208 0.489589055612 +1403638575577829376.0000000000 10.3348935329 -2.5003305839 0.7208669108 0.2594038587 0.3765858435 -0.7426313437 0.489276433008 +1403638575627829504.0000000000 10.3625853458 -2.5585686540 0.7173845814 0.2558022081 0.3808243636 -0.7415628573 0.489512577014 +1403638575677829376.0000000000 10.3912241495 -2.6184776137 0.7152560936 0.2530106692 0.3843947716 -0.7399211354 0.490655657551 +1403638575727829504.0000000000 10.4198996591 -2.6785665841 0.7153026058 0.2497519655 0.3882536238 -0.7395677401 0.489818984046 +1403638575777829376.0000000000 10.4491512178 -2.7388285748 0.7172951829 0.2462393412 0.3916295675 -0.7393630715 0.489218475964 +1403638575827829504.0000000000 10.4798207478 -2.7997938104 0.7212523008 0.2435222841 0.3946796081 -0.7392689911 0.488268638056 +1403638575877829376.0000000000 10.5123016681 -2.8606132197 0.7285325274 0.2427652026 0.3963398325 -0.7388842892 0.48788297853 +1403638575927829504.0000000000 10.5463279948 -2.9213884424 0.7380105649 0.2431954332 0.3968021855 -0.7389193321 0.487239394423 +1403638575977829376.0000000000 10.5822720545 -2.9826200495 0.7504529078 0.2437157318 0.3969401216 -0.7383066498 0.487795523518 +1403638576027829504.0000000000 10.6187334126 -3.0433905392 0.7642571626 0.2438642718 0.3975940064 -0.7379153443 0.487780860269 +1403638576077829376.0000000000 10.6564149010 -3.1043052358 0.7798239177 0.2437216387 0.3979946028 -0.7372199979 0.488576231075 +1403638576127829504.0000000000 10.6953294699 -3.1652939924 0.7969469696 0.2440808330 0.3975403049 -0.7371903235 0.488811497259 +1403638576177829376.0000000000 10.7358532895 -3.2262852373 0.8150928826 0.2455101540 0.3966208748 -0.7362591813 0.490243881989 +1403638576227829504.0000000000 10.7772072359 -3.2874208736 0.8317358395 0.2444701753 0.3972402777 -0.7353054190 0.491691403228 +1403638576277829376.0000000000 10.8196923818 -3.3484877041 0.8469474994 0.2430962342 0.3979666183 -0.7340080248 0.493719567377 +1403638576327829504.0000000000 10.8572008434 -3.4136029394 0.8585166246 0.2411886828 0.3992172493 -0.7326603017 0.495643510513 +1403638576377829376.0000000000 10.8995777622 -3.4747612149 0.8709989357 0.2391427816 0.4003575140 -0.7316739575 0.497169800934 +1403638576427829504.0000000000 10.9427358566 -3.5353290243 0.8819918379 0.2366472976 0.4018631764 -0.7313952227 0.497559114235 +1403638576477829376.0000000000 10.9873086843 -3.5956870974 0.8917556155 0.2338325228 0.4036687403 -0.7301603858 0.499239131503 +1403638576527829504.0000000000 11.0333149186 -3.6557070927 0.9001084175 0.2290441609 0.4066768270 -0.7292381820 0.500364271944 +1403638576577829376.0000000000 11.0815112429 -3.7149958660 0.9077566470 0.2258017865 0.4085256417 -0.7287852821 0.500991383008 +1403638576627829504.0000000000 11.1313397145 -3.7732776469 0.9145278205 0.2232797728 0.4100715369 -0.7280226331 0.501966655605 +1403638576677829376.0000000000 11.1831292709 -3.8302117761 0.9205167415 0.2223844714 0.4106698577 -0.7272081540 0.503054386298 +1403638576727829504.0000000000 11.2370895586 -3.8858356374 0.9258917904 0.2233035031 0.4102587041 -0.7254530327 0.50551086882 +1403638576777829376.0000000000 11.2927936060 -3.9404633198 0.9301831480 0.2243332104 0.4096946923 -0.7229310515 0.50911252646 +1403638576827829504.0000000000 11.3499268478 -3.9935545221 0.9335470063 0.2273555477 0.4076336330 -0.7207844829 0.512458784155 +1403638576877829376.0000000000 11.4079520226 -4.0450211090 0.9354716732 0.2304177540 0.4055664395 -0.7195638586 0.5144427812 +1403638576927829504.0000000000 11.4672639042 -4.0949220897 0.9364874541 0.2349948010 0.4022404836 -0.7190255632 0.515734695713 +1403638576977829376.0000000000 11.5273457594 -4.1431388056 0.9365804340 0.2398461610 0.3989069198 -0.7190599878 0.516042461837 +1403638577027829504.0000000000 11.5876372314 -4.1899594663 0.9360096296 0.2431122694 0.3966913404 -0.7201546085 0.514693836012 +1403638577077829376.0000000000 11.6481054972 -4.2357278476 0.9367005318 0.2462997652 0.3941506384 -0.7209674449 0.51399187086 +1403638577127829504.0000000000 11.7089072352 -4.2805982645 0.9393100585 0.2489434223 0.3922561963 -0.7213581467 0.513619190784 +1403638577177829376.0000000000 11.7913500860 -4.3337550154 0.9404070294 0.2510972418 0.3907245651 -0.7219670724 0.512882087607 +1403638577227829504.0000000000 11.8550076201 -4.3778839125 0.9452256420 0.2517936032 0.3900263329 -0.7224551730 0.512384586045 +1403638577277829376.0000000000 11.9191418827 -4.4216910022 0.9511638702 0.2502060964 0.3913053201 -0.7219272014 0.512930961854 +1403638577327829504.0000000000 11.9835402252 -4.4648927577 0.9592407217 0.2471777369 0.3932404760 -0.7206758048 0.514676091178 +1403638577377829376.0000000000 12.0477059517 -4.5072512301 0.9689385373 0.2421231579 0.3969660887 -0.7187667860 0.516883553744 +1403638577427829504.0000000000 12.1119135748 -4.5480292123 0.9804475688 0.2389827395 0.3993342620 -0.7177352647 0.5179531709 +1403638577477829376.0000000000 12.1771016346 -4.5875875689 0.9929581011 0.2371498324 0.4004102784 -0.7165497685 0.519603690573 +1403638577527829504.0000000000 12.2430492241 -4.6252993160 1.0048700770 0.2382204494 0.4001210888 -0.7174687603 0.51806631787 +1403638577577829376.0000000000 12.3092232531 -4.6616027476 1.0154949223 0.2386735760 0.3997874909 -0.7182363991 0.517050636941 +1403638577627829504.0000000000 12.3755743770 -4.6965021684 1.0246807353 0.2406517823 0.3986008067 -0.7189917946 0.515998949429 +1403638577677829376.0000000000 12.4417866164 -4.7301940281 1.0322138886 0.2417524764 0.3980886210 -0.7198838720 0.51463423991 +1403638577727829504.0000000000 12.5079833039 -4.7629297040 1.0378120119 0.2421482785 0.3979016024 -0.7202900506 0.514024093728 +1403638577777829376.0000000000 12.5750040939 -4.7948326062 1.0414668291 0.2439041920 0.3971401412 -0.7211874776 0.512522268351 +1403638577827829504.0000000000 12.6412690542 -4.8255122405 1.0432391021 0.2440462300 0.3972589832 -0.7213033556 0.512199382188 +1403638577877829376.0000000000 12.7084951669 -4.8556091821 1.0437630673 0.2443448692 0.3974296508 -0.7210070789 0.512341731403 +1403638577927829504.0000000000 12.7762040092 -4.8847491192 1.0434333745 0.2446456185 0.3977578154 -0.7207131901 0.512357042729 +1403638577977829376.0000000000 12.8443319099 -4.9129318768 1.0439156852 0.2442699706 0.3984879262 -0.7198950367 0.513118592796 +1403638578027829504.0000000000 12.9133529353 -4.9400333688 1.0453498258 0.2448905973 0.3984875717 -0.7194732708 0.513414514039 +1403638578077829376.0000000000 12.9831320305 -4.9660524363 1.0492587805 0.2466904715 0.3977963321 -0.7195995856 0.512911616053 +1403638578127829504.0000000000 13.0534309798 -4.9911389972 1.0549037303 0.2490899729 0.3968190300 -0.7197007672 0.512366712843 +1403638578177829376.0000000000 13.1244373642 -5.0154864242 1.0625323805 0.2534788830 0.3942141278 -0.7208705118 0.510577499015 +1403638578227829504.0000000000 13.1960335374 -5.0394887202 1.0719558243 0.2596010403 0.3902459561 -0.7226807769 0.507984141834 +1403638578277829376.0000000000 13.2677066042 -5.0637846191 1.0822658512 0.2635262250 0.3877954093 -0.7244116019 0.505367668351 +1403638578327829504.0000000000 13.3387260894 -5.0878336205 1.0923866210 0.2664902444 0.3856819265 -0.7252276253 0.504259152361 +1403638578377829376.0000000000 13.4090197034 -5.1122393385 1.1008226496 0.2671503988 0.3850629339 -0.7251317562 0.504520700776 +1403638578427829504.0000000000 13.4783933555 -5.1367233317 1.1075428556 0.2669521630 0.3849577837 -0.7254642477 0.504227798519 +1403638578477829376.0000000000 13.5468715515 -5.1612543278 1.1127534719 0.2670680709 0.3845873785 -0.7253716009 0.504582237562 +1403638578527829504.0000000000 13.6144291481 -5.1856611743 1.1164925825 0.2670858903 0.3842589589 -0.7257842665 0.504229489659 +1403638578577829376.0000000000 13.6813757307 -5.2101361186 1.1194749297 0.2670514928 0.3838541929 -0.7258231596 0.504499950192 +1403638578627829504.0000000000 13.7478003860 -5.2348745242 1.1214890394 0.2670702142 0.3834905055 -0.7253544646 0.505439841735 +1403638578677829376.0000000000 13.8135883806 -5.2599171992 1.1222965150 0.2657766884 0.3841379490 -0.7246829066 0.506592018242 +1403638578727829504.0000000000 13.8786612847 -5.2852595038 1.1218880125 0.2632207349 0.3857860497 -0.7237211251 0.508046948255 +1403638578777829376.0000000000 13.9432252047 -5.3104723346 1.1204334510 0.2601969761 0.3877535632 -0.7223694921 0.510026494206 +1403638578827829504.0000000000 14.0075354414 -5.3351783957 1.1176741012 0.2564101413 0.3905255847 -0.7216185958 0.510891582679 +1403638578877829376.0000000000 14.0722959588 -5.3597825094 1.1145897249 0.2546639332 0.3916542548 -0.7199132544 0.513301209846 +1403638578927829504.0000000000 14.1368519379 -5.3836344947 1.1107270572 0.2530982126 0.3926895183 -0.7194127040 0.513985990356 +1403638578977829376.0000000000 14.2010253950 -5.4066999715 1.1078494769 0.2523598765 0.3937312659 -0.7184155208 0.514945941224 +1403638579027829504.0000000000 14.2657797085 -5.4291998581 1.1071365328 0.2517912939 0.3944853343 -0.7178730916 0.515403424207 +1403638579077829376.0000000000 14.3295184661 -5.4505169965 1.1088488478 0.2520556814 0.3947460287 -0.7177130009 0.51529753996 +1403638579127829504.0000000000 14.3938709992 -5.4713749843 1.1135617103 0.2520562305 0.3951415137 -0.7170814135 0.515873130914 +1403638579177829376.0000000000 14.4574713132 -5.4909496333 1.1198411582 0.2522949987 0.3951453798 -0.7169697639 0.515908635486 +1403638579227829504.0000000000 14.5200430422 -5.5090703150 1.1272340178 0.2526154528 0.3951874698 -0.7168469384 0.515890263136 +1403638579277829376.0000000000 14.5825769817 -5.5260982495 1.1361425717 0.2549783630 0.3938874736 -0.7176618953 0.514587307107 +1403638579327829504.0000000000 14.6445440550 -5.5424521165 1.1461578251 0.2565791915 0.3931287703 -0.7178913454 0.514051461013 +1403638579377829376.0000000000 14.7069903107 -5.5582517904 1.1561307736 0.2617155713 0.3896516144 -0.7201049165 0.511004391811 +1403638579427829504.0000000000 14.7690022992 -5.5740132195 1.1647991143 0.2656309043 0.3869842058 -0.7211913096 0.509476733639 +1403638579477829376.0000000000 14.8304449650 -5.5896044930 1.1718897377 0.2695069765 0.3843398888 -0.7223051128 0.507862347126 +1403638579527829504.0000000000 14.8915316623 -5.6050752348 1.1780610468 0.2728033414 0.3832143107 -0.7222790279 0.506989284814 +1403638579577829376.0000000000 14.9520026026 -5.6207092334 1.1831525455 0.2770988325 0.3829995556 -0.7190052601 0.50946934493 +1403638579627829504.0000000000 15.0120065572 -5.6363430848 1.1875832549 0.2822801543 0.3839454130 -0.7140400462 0.512884632969 +1403638579677829376.0000000000 15.0705872546 -5.6513821596 1.1902881738 0.2868013451 0.3879374542 -0.7080892518 0.515615294206 +1403638579727829504.0000000000 15.1280185266 -5.6657805889 1.1916860857 0.2901781691 0.3952064787 -0.7012948751 0.517488132726 +1403638579777829376.0000000000 15.1840186752 -5.6790160308 1.1916718330 0.2945025519 0.4046203536 -0.6943840607 0.517089346781 +1403638579827829504.0000000000 15.2382479967 -5.6911498181 1.1896519890 0.2972575154 0.4169396338 -0.6885168848 0.513559938705 +1403638579877829376.0000000000 15.2917428751 -5.7021371876 1.1866302971 0.3007042214 0.4311216720 -0.6821149361 0.508360392871 +1403638579927829504.0000000000 15.3442209445 -5.7117771960 1.1825709038 0.3069295450 0.4449020333 -0.6749768081 0.502257646709 +1403638579977829376.0000000000 15.3959825321 -5.7203907974 1.1776131241 0.3149320571 0.4590823775 -0.6664161529 0.495934150116 +1403638580027829504.0000000000 15.4469634237 -5.7279935116 1.1724157217 0.3259734212 0.4722779202 -0.6541326782 0.492752812263 +1403638580077829376.0000000000 15.4964766506 -5.7343829824 1.1671410187 0.3386445727 0.4852154347 -0.6400296723 0.49015084805 +1403638580127829504.0000000000 15.5434718778 -5.7388902875 1.1614097519 0.3529366210 0.4978879223 -0.6255785993 0.485998739295 +1403638580177829376.0000000000 15.5885450306 -5.7420648091 1.1543126882 0.3657892430 0.5120380065 -0.6113530040 0.479857076664 +1403638580227829504.0000000000 15.6313757391 -5.7438476532 1.1461292971 0.3785764016 0.5262776665 -0.5978124235 0.471520977505 +1403638580277829376.0000000000 15.6716554941 -5.7447320232 1.1364100502 0.3897388442 0.5407190259 -0.5855780302 0.461329533951 +1403638580327829504.0000000000 15.7098995070 -5.7448645617 1.1254146621 0.3996189269 0.5544364006 -0.5754096012 0.449231323333 +1403638580377829376.0000000000 15.7462237136 -5.7448787628 1.1135954867 0.4091152078 0.5656686722 -0.5673818606 0.43671675524 +1403638580427829504.0000000000 15.7808740324 -5.7451997692 1.1007164758 0.4170405525 0.5750075008 -0.5618141123 0.424038270578 +1403638580477829376.0000000000 15.8143333328 -5.7460509293 1.0870135100 0.4230858028 0.5827357934 -0.5565467789 0.414334504311 +1403638580527829504.0000000000 15.8469505550 -5.7473201048 1.0729467531 0.4290249532 0.5884866219 -0.5518899980 0.406249326886 +1403638580577829376.0000000000 15.8783375137 -5.7488738693 1.0578266759 0.4331687242 0.5945716275 -0.5469639970 0.399599577227 +1403638580627829504.0000000000 15.9082034311 -5.7506706985 1.0424406093 0.4364665310 0.6014127106 -0.5423282596 0.392020124124 +1403638580677829376.0000000000 15.9369454129 -5.7529933999 1.0274287283 0.4378887269 0.6095104173 -0.5371168427 0.385040272451 +1403638580727829504.0000000000 15.9651593283 -5.7556357958 1.0140759877 0.4388420711 0.6175441968 -0.5318639988 0.378388013053 +1403638580777829376.0000000000 15.9925046499 -5.7591830716 1.0029464464 0.4385332264 0.6245864181 -0.5268459549 0.374184119777 +1403638580827829504.0000000000 16.0194170001 -5.7631039707 0.9937583816 0.4385760962 0.6299774606 -0.5228727325 0.370652819481 +1403638580877829376.0000000000 16.0454904300 -5.7674789185 0.9865577416 0.4373509537 0.6351272391 -0.5191575288 0.36852814516 +1403638580927829504.0000000000 16.0721936922 -5.7715892558 0.9826813356 0.4390531369 0.6370385432 -0.5168466898 0.366447454302 +1403638580977829376.0000000000 16.0991569788 -5.7757060499 0.9812960730 0.4408371191 0.6379012023 -0.5163556988 0.363485189318 +1403638581027829504.0000000000 16.1257267901 -5.7803082352 0.9815884154 0.4411584324 0.6389451562 -0.5153890054 0.362632731484 +1403638581077829376.0000000000 16.1533623191 -5.7847500979 0.9845943707 0.4411439253 0.6396066999 -0.5149095558 0.362164956878 +1403638581127829504.0000000000 16.1812717016 -5.7893576355 0.9894545438 0.4406938338 0.6400635877 -0.5138129524 0.363460862281 +1403638581177829376.0000000000 16.2093669858 -5.7937524223 0.9957995754 0.4402468547 0.6401207814 -0.5133882101 0.364500532198 +1403638581227829504.0000000000 16.2364315004 -5.7981941139 1.0019549763 0.4389959702 0.6404411767 -0.5132761989 0.365602490406 +1403638581277829376.0000000000 16.2628906405 -5.8027461909 1.0075091942 0.4376081106 0.6403089101 -0.5130897125 0.367753433974 +1403638581327829504.0000000000 16.2893576068 -5.8068540924 1.0129070074 0.4367274800 0.6398387032 -0.5136722171 0.368804006995 +1403638581377829376.0000000000 16.3216292599 -5.8113966237 1.0236244930 0.4366818417 0.6387661360 -0.5136009841 0.370811032443 +1403638581427829504.0000000000 16.3493482379 -5.8151261748 1.0317546564 0.4365935254 0.6377142456 -0.5139005768 0.372307442521 +1403638581477829376.0000000000 16.3768372082 -5.8184651314 1.0415765953 0.4369861430 0.6361297390 -0.5144102762 0.373850416368 +1403638581527829504.0000000000 16.4040979388 -5.8215397276 1.0533076447 0.4356609659 0.6356353288 -0.5155550012 0.374660235864 +1403638581577829376.0000000000 16.4312571340 -5.8241554824 1.0663167222 0.4348418394 0.6349481694 -0.5160066831 0.37615222955 +1403638581627829504.0000000000 16.4586640555 -5.8261193729 1.0792938065 0.4357123803 0.6330041128 -0.5156833962 0.378855051162 +1403638581677829376.0000000000 16.4855806906 -5.8276650837 1.0909686375 0.4368443183 0.6310478031 -0.5144990958 0.382408671683 +1403638581727829504.0000000000 16.5117849948 -5.8286416923 1.1014221382 0.4387661753 0.6286551383 -0.5138341731 0.385034288034 +1403638581777829376.0000000000 16.5368103923 -5.8292350647 1.1097243481 0.4394543434 0.6271581310 -0.5146651170 0.38558057013 +1403638581827829504.0000000000 16.5608430173 -5.8295703506 1.1160311606 0.4392418625 0.6265736486 -0.5144821359 0.387014445383 +1403638581877829376.0000000000 16.5841790503 -5.8292996909 1.1213086873 0.4414568183 0.6242959632 -0.5135047822 0.389465360023 +1403638581927829504.0000000000 16.6066569730 -5.8285647769 1.1256821108 0.4458935178 0.6204373949 -0.5115286016 0.393160144852 +1403638581977829376.0000000000 16.6274371517 -5.8276046010 1.1284589204 0.4490908672 0.6177212164 -0.5093041138 0.396670154472 +1403638582027829504.0000000000 16.6459845861 -5.8265122300 1.1300201831 0.4490532300 0.6174168065 -0.5095461785 0.396875768453 +1403638582077829376.0000000000 16.6628154225 -5.8251320783 1.1321140483 0.4470191147 0.6187776111 -0.5115276392 0.394496709109 +1403638582127829504.0000000000 16.6780073997 -5.8237233198 1.1350599369 0.4416019944 0.6225035876 -0.5139042291 0.39163682833 +1403638582177829376.0000000000 16.6920239103 -5.8215442455 1.1411685970 0.4390219145 0.6245589234 -0.5171239862 0.386999602979 +1403638582227829504.0000000000 16.7057117821 -5.8194020301 1.1485976375 0.4347704769 0.6272923708 -0.5182897935 0.385816800926 +1403638582277829376.0000000000 16.7188498109 -5.8165307158 1.1591637807 0.4348059674 0.6273501408 -0.5181788969 0.385831831795 +1403638582327829504.0000000000 16.7312621297 -5.8135097893 1.1721389459 0.4360042118 0.6264891646 -0.5160902942 0.388667547177 +1403638582377829376.0000000000 16.7432927265 -5.8098215620 1.1864774405 0.4382710854 0.6250452915 -0.5149398528 0.389966392523 +1403638582427829504.0000000000 16.7545746311 -5.8059244263 1.2018009696 0.4387022736 0.6246660935 -0.5137845466 0.391609533171 +1403638582477829376.0000000000 16.7642252433 -5.8016641885 1.2191462238 0.4390069594 0.6244666855 -0.5130454700 0.392553937627 +1403638582527829504.0000000000 16.7730160224 -5.7968557323 1.2391882122 0.4398438565 0.6239459442 -0.5124578166 0.393212190627 +1403638582577829376.0000000000 16.7808741392 -5.7916426504 1.2615678951 0.4395014305 0.6242634421 -0.5118435474 0.393890632554 +1403638582627829504.0000000000 16.7871322149 -5.7859485826 1.2846514799 0.4398073956 0.6239750183 -0.5119317226 0.393891536658 +1403638582677829376.0000000000 16.7923569861 -5.7798649573 1.3099815432 0.4381555852 0.6251540784 -0.5124603539 0.393174830237 +1403638582727829504.0000000000 16.7964162971 -5.7730691381 1.3359350958 0.4367368640 0.6260323930 -0.5137254381 0.391702092007 +1403638582777829376.0000000000 16.8000979840 -5.7657597842 1.3644068517 0.4366226929 0.6259752040 -0.5146713253 0.390677737884 +1403638582827829504.0000000000 16.8028815668 -5.7581614362 1.3927946442 0.4349910168 0.6269078286 -0.5150945963 0.390444550041 +1403638582877829376.0000000000 16.8049171000 -5.7499123555 1.4207314907 0.4343700702 0.6269967966 -0.5156512273 0.390258210524 +1403638582927829504.0000000000 16.8061887153 -5.7411808873 1.4468076668 0.4330866809 0.6276690128 -0.5166088962 0.389336339886 +1403638582977829376.0000000000 16.8067295107 -5.7319728822 1.4709943900 0.4315989028 0.6284885036 -0.5179264648 0.387913347323 +1403638583027829504.0000000000 16.8067634552 -5.7225940166 1.4932756284 0.4294890797 0.6296434750 -0.5190681088 0.386854653791 +1403638583077829376.0000000000 16.8063813123 -5.7128067823 1.5138487833 0.4282034410 0.6302281323 -0.5203874883 0.385553078597 +1403638583127829504.0000000000 16.8056698363 -5.7025915494 1.5324235063 0.4266511369 0.6311330895 -0.5208919973 0.385112136716 +1403638583177829376.0000000000 16.8049246767 -5.6917652471 1.5493572291 0.4257859620 0.6314524827 -0.5216272081 0.384550558878 +1403638583227829504.0000000000 16.8042690718 -5.6802527048 1.5647621804 0.4253341971 0.6315487149 -0.5226073091 0.383560480084 +1403638583277829376.0000000000 16.8038038782 -5.6682348608 1.5789828179 0.4253041940 0.6315432746 -0.5230434254 0.383007845887 +1403638583327829504.0000000000 16.8034681673 -5.6559124320 1.5917601743 0.4252422985 0.6314863231 -0.5224286507 0.384008224228 +1403638583377829376.0000000000 16.8029319129 -5.6429135994 1.6030393592 0.4256132160 0.6313928759 -0.5225300327 0.383612814708 +1403638583427829504.0000000000 16.8026482725 -5.6296070691 1.6135900995 0.4249426555 0.6316927479 -0.5227685266 0.383537585407 +1403638583477829376.0000000000 16.8026959598 -5.6156321404 1.6245094941 0.4245488949 0.6319963250 -0.5228534837 0.383357686276 +1403638583527829504.0000000000 16.8030682297 -5.6010190863 1.6372555556 0.4243583063 0.6321994310 -0.5230478989 0.382968409655 +1403638583577829376.0000000000 16.8035087862 -5.5859309409 1.6523264790 0.4245469844 0.6319972203 -0.5227519706 0.383496738957 +1403638583627829504.0000000000 16.8037006720 -5.5704262718 1.6689138772 0.4241915730 0.6322997838 -0.5224776565 0.383765020862 +1403638583677829376.0000000000 16.8032949172 -5.5544667771 1.6868826868 0.4235159737 0.6326960906 -0.5217081023 0.384903277411 +1403638583727829504.0000000000 16.8026485071 -5.5377404366 1.7052237512 0.4237974956 0.6324754043 -0.5217156556 0.384945866843 +1403638583777829376.0000000000 16.8033200176 -5.5204101407 1.7222375202 0.4241353348 0.6323861920 -0.5216135156 0.384858756306 +1403638583827829504.0000000000 16.8034272627 -5.5027460949 1.7376687531 0.4238992338 0.6325061880 -0.5211254678 0.385582168312 +1403638583877829376.0000000000 16.8041369637 -5.4842312304 1.7519193596 0.4249695130 0.6318021319 -0.5208639087 0.385911606172 +1403638583927829504.0000000000 16.8045210892 -5.4651176723 1.7642310255 0.4252332496 0.6317282032 -0.5208051903 0.385821350408 +1403638583977829376.0000000000 16.8048761253 -5.4455632627 1.7748629595 0.4248323891 0.6319129749 -0.5205623596 0.386287798171 +1403638584027829504.0000000000 16.8051025470 -5.4254209997 1.7845089479 0.4257516726 0.6313496500 -0.5198202422 0.387195103988 +1403638584077829376.0000000000 16.8054327586 -5.4048093247 1.7936993160 0.4283477760 0.6294390416 -0.5172854830 0.390820169325 +1403638584127829504.0000000000 16.8056323096 -5.3833547986 1.8023719384 0.4332004349 0.6260121128 -0.5142073857 0.395015167178 +1403638584177829376.0000000000 16.8053302962 -5.3614874023 1.8100631478 0.4385553941 0.6222307555 -0.5109401068 0.399297208336 +1403638584227829504.0000000000 16.8044286314 -5.3391640799 1.8165513222 0.4440235818 0.6182524408 -0.5072571637 0.40410041847 +1403638584277829376.0000000000 16.8018790139 -5.3163839334 1.8211760215 0.4493210998 0.6145236462 -0.5056442371 0.405949680384 +1403638584327829504.0000000000 16.7975430413 -5.2937185567 1.8232124151 0.4507844906 0.6132171661 -0.5039211099 0.408437957558 +1403638584377829376.0000000000 16.7910160416 -5.2706999021 1.8236756118 0.4520976202 0.6123440312 -0.5035136503 0.408798890966 +1403638584427829504.0000000000 16.7822984762 -5.2476376456 1.8225270292 0.4520731742 0.6123364960 -0.5035174782 0.40883249629 +1403638584477829376.0000000000 16.7714699250 -5.2243918510 1.8206131104 0.4519222529 0.6125017264 -0.5028507518 0.409571768804 +1403638584527829504.0000000000 16.7584169357 -5.2006743231 1.8191912010 0.4529639607 0.6117526021 -0.5035934076 0.408627071956 +1403638584577829376.0000000000 16.7431754663 -5.1770844524 1.8186826219 0.4518978235 0.6126420042 -0.5030042492 0.409200265367 +1403638584627829504.0000000000 16.7258170191 -5.1530833371 1.8206137628 0.4518225709 0.6129398481 -0.5038498754 0.407794568392 +1403638584677829376.0000000000 16.7064714246 -5.1287609335 1.8247866848 0.4507582722 0.6138611334 -0.5048927262 0.40629401182 +1403638584727829504.0000000000 16.6848348720 -5.1043581089 1.8300876382 0.4483929231 0.6159434225 -0.5062603668 0.404051887458 +1403638584777829376.0000000000 16.6610373748 -5.0798962588 1.8370222485 0.4438941161 0.6194940581 -0.5093973004 0.399624218517 +1403638584827829504.0000000000 16.6362065793 -5.0551431680 1.8454522402 0.4401966790 0.6223281746 -0.5121466465 0.395778144085 +1403638584877829376.0000000000 16.6100986392 -5.0300509450 1.8544392881 0.4365590687 0.6250922696 -0.5163909063 0.389892633741 +1403638584927829504.0000000000 16.5841282670 -5.0049633969 1.8633793753 0.4342250236 0.6265331586 -0.5181939149 0.387788468857 +1403638584977829376.0000000000 16.5578464649 -4.9797283057 1.8712147915 0.4323363984 0.6277793073 -0.5194661795 0.386177767813 +1403638585027829504.0000000000 16.5316550045 -4.9541685639 1.8777118342 0.4312414352 0.6286014722 -0.5204452589 0.384743740907 +1403638585077829376.0000000000 16.5057492181 -4.9286459161 1.8828201748 0.4306046048 0.6287368766 -0.5205241850 0.385128792946 +1403638585127829504.0000000000 16.4794710601 -4.9027492954 1.8865677502 0.4313290764 0.6283264774 -0.5216789019 0.383421685599 +1403638585177829376.0000000000 16.4531868716 -4.8769929948 1.8887215626 0.4317580732 0.6280045187 -0.5220010895 0.383027614091 +1403638585227829504.0000000000 16.4270485426 -4.8512073281 1.8899336650 0.4326885670 0.6272019847 -0.5215122144 0.383957399425 +1403638585277829376.0000000000 16.4009475064 -4.8251725861 1.8900484182 0.4337514244 0.6265134021 -0.5206673757 0.385027457068 +1403638585327829504.0000000000 16.3742057359 -4.7991633614 1.8888612396 0.4353558316 0.6253649006 -0.5197462871 0.386326077442 +1403638585377829376.0000000000 16.3472531578 -4.7730555590 1.8862307042 0.4363576656 0.6247978732 -0.5193116959 0.386697514651 +1403638585427829504.0000000000 16.3191889383 -4.7471717876 1.8822711418 0.4362638378 0.6248791829 -0.5194221828 0.386523565373 +1403638585477829376.0000000000 16.2911283484 -4.7212019788 1.8792051910 0.4359385222 0.6249752430 -0.5196251200 0.386462527576 +1403638585527829504.0000000000 16.2628914094 -4.6948698924 1.8771457693 0.4348238114 0.6258388908 -0.5197181713 0.386195492149 +1403638585577829376.0000000000 16.2350144023 -4.6681482975 1.8775082690 0.4340375981 0.6266453952 -0.5204411809 0.384795906161 +1403638585627829504.0000000000 16.2065678427 -4.6417514191 1.8794036319 0.4326105618 0.6277225973 -0.5206179712 0.384407818277 +1403638585677829376.0000000000 16.1779732169 -4.6154052190 1.8829157579 0.4306744518 0.6290893107 -0.5213711101 0.383325346568 +1403638585727829504.0000000000 16.1480581284 -4.5890288806 1.8877287654 0.4278787589 0.6311536277 -0.5228822036 0.380997463327 +1403638585777829376.0000000000 16.1188870095 -4.5621487989 1.8954404289 0.4251465096 0.6330801926 -0.5251593162 0.377713658359 +1403638585827829504.0000000000 16.0916253495 -4.5348643441 1.9052963923 0.4225434568 0.6347981475 -0.5265818541 0.375765738064 +1403638585877829376.0000000000 16.0648044253 -4.5071677896 1.9165629306 0.4206919110 0.6360532629 -0.5283434347 0.373239571533 +1403638585927829504.0000000000 16.0394893102 -4.4791461534 1.9299888204 0.4202357358 0.6360745303 -0.5298972947 0.371510397463 +1403638585977829376.0000000000 16.0143781301 -4.4511064078 1.9456759817 0.4210414294 0.6352731041 -0.5302436740 0.371475226721 +1403638586027829504.0000000000 15.9906511324 -4.4227997510 1.9620516109 0.4235707155 0.6333878555 -0.5293177198 0.373135933695 +1403638586077829376.0000000000 15.9678552699 -4.3946275364 1.9771358820 0.4255509887 0.6315997676 -0.5282280939 0.375450623135 +1403638586127829504.0000000000 15.9449604872 -4.3664528137 1.9909760878 0.4270935061 0.6299832565 -0.5277236166 0.377120694251 +1403638586177829376.0000000000 15.9222935198 -4.3381569911 2.0028130588 0.4282595001 0.6291364113 -0.5267951881 0.378507604034 +1403638586227829504.0000000000 15.9001230677 -4.3100030606 2.0138171116 0.4293377669 0.6281639854 -0.5259388549 0.380088687308 +1403638586277829376.0000000000 15.8783470141 -4.2820294605 2.0234805041 0.4305650763 0.6271230735 -0.5248626413 0.381902570806 +1403638586327829504.0000000000 15.8569037731 -4.2540890411 2.0320144045 0.4319771628 0.6258107538 -0.5231336419 0.384821808015 +1403638586377829376.0000000000 15.8355243713 -4.2262574266 2.0391084038 0.4321437017 0.6255171253 -0.5204049638 0.388791487403 +1403638586427829504.0000000000 15.8141465059 -4.1984190589 2.0452270472 0.4319899335 0.6251319035 -0.5176577629 0.393224161306 +1403638586477829376.0000000000 15.7922806594 -4.1703007946 2.0501343656 0.4307359407 0.6257122389 -0.5151916754 0.396898325802 +1403638586527829504.0000000000 15.7697827006 -4.1415876731 2.0540596036 0.4303200076 0.6256806919 -0.5134088376 0.399699547512 +1403638586577829376.0000000000 15.7465017642 -4.1120192517 2.0566219364 0.4305709450 0.6254524940 -0.5138492972 0.399220163288 +1403638586627829504.0000000000 15.7228902109 -4.0818088313 2.0577149785 0.4305818529 0.6255320201 -0.5153846115 0.397099058105 +1403638586677829376.0000000000 15.6988037587 -4.0513590782 2.0574380303 0.4304790585 0.6255162682 -0.5162566617 0.396101297319 +1403638586727829504.0000000000 15.6748649134 -4.0204768893 2.0557607551 0.4319664422 0.6245969674 -0.5178087578 0.393900636631 +1403638586777829376.0000000000 15.6505174045 -3.9893588956 2.0522046980 0.4326235211 0.6242338956 -0.5187083625 0.39256918792 +1403638586827829504.0000000000 15.6260152122 -3.9579971561 2.0475036741 0.4343503608 0.6231139756 -0.5193883549 0.391541152661 +1403638586877829376.0000000000 15.6009564976 -3.9265106843 2.0409948781 0.4351502028 0.6228837298 -0.5192288330 0.391230851466 +1403638586927829504.0000000000 15.5753464513 -3.8949800121 2.0331474093 0.4353291753 0.6227086284 -0.5187702670 0.391918209923 +1403638586977829376.0000000000 15.5491182941 -3.8632923895 2.0241323669 0.4354178696 0.6227328692 -0.5188973695 0.391612783817 +1403638587027829504.0000000000 15.5225509938 -3.8315401223 2.0144779123 0.4359746198 0.6224384416 -0.5189998876 0.391325483336 +1403638587077829376.0000000000 15.4953812814 -3.7997782372 2.0048578428 0.4359576896 0.6223685116 -0.5193289383 0.391018902935 +1403638587127829504.0000000000 15.4669349391 -3.7681185127 1.9941373398 0.4360295831 0.6223785209 -0.5196376370 0.390512362821 +1403638587177829376.0000000000 15.4384050255 -3.7363402785 1.9871946951 0.4347265940 0.6235082323 -0.5197350633 0.390032994422 +1403638587227829504.0000000000 15.4092295732 -3.7044759147 1.9821989297 0.4334667364 0.6246985881 -0.5199845040 0.389197094083 +1403638587277829376.0000000000 15.3799750914 -3.6722650299 1.9797673696 0.4329867016 0.6250450031 -0.5204742378 0.388520048598 +1403638587327829504.0000000000 15.3502918939 -3.6399034338 1.9785437954 0.4314200151 0.6259778790 -0.5210541511 0.387983295149 +1403638587377829376.0000000000 15.3195932940 -3.6074262210 1.9785384036 0.4311406149 0.6264149054 -0.5213761932 0.387155009821 +1403638587427829504.0000000000 15.2888008658 -3.5749785204 1.9797994010 0.4311876975 0.6262033066 -0.5221886791 0.386349028444 +1403638587477829376.0000000000 15.2584905976 -3.5421965884 1.9811052412 0.4315479754 0.6258331289 -0.5230721632 0.385350167787 +1403638587527829504.0000000000 15.2284026402 -3.5094625907 1.9815892714 0.4319485392 0.6255774340 -0.5230784383 0.385308033902 +1403638587577829376.0000000000 15.1983569956 -3.4768795493 1.9808014451 0.4315901295 0.6255295940 -0.5240155901 0.384513131823 +1403638587627829504.0000000000 15.1686723512 -3.4444202011 1.9788004231 0.4321449729 0.6250599024 -0.5242318057 0.384359017953 +1403638587677829376.0000000000 15.1389672389 -3.4121594678 1.9755357584 0.4320644495 0.6249054767 -0.5243984312 0.38447333063 +1403638587727829504.0000000000 15.1093498310 -3.3798993230 1.9712301583 0.4321354107 0.6248945223 -0.5241917244 0.384693200943 +1403638587777829376.0000000000 15.0797532035 -3.3477360669 1.9657114349 0.4324059072 0.6243983209 -0.5246531235 0.384565947919 +1403638587827829504.0000000000 15.0503288326 -3.3155326373 1.9589947649 0.4327377990 0.6239923945 -0.5251508723 0.384171901854 +1403638587877829376.0000000000 15.0207677393 -3.2833913542 1.9511155273 0.4331306342 0.6236842359 -0.5253436555 0.3839659767 +1403638587927829504.0000000000 14.9911209625 -3.2515207915 1.9420540305 0.4332563443 0.6234084478 -0.5255222495 0.384027619573 +1403638587977829376.0000000000 14.9613788131 -3.2198734532 1.9320426108 0.4335701240 0.6231322771 -0.5256650395 0.383926267786 +1403638588027829504.0000000000 14.9315512768 -3.1884133137 1.9212936710 0.4342043868 0.6227645331 -0.5253381860 0.384253402126 +1403638588077829376.0000000000 14.9018388958 -3.1572404466 1.9095189652 0.4339302002 0.6230600913 -0.5244530349 0.385291731269 +1403638588127829504.0000000000 14.8721227354 -3.1265693971 1.8964475638 0.4324699843 0.6238497993 -0.5233941434 0.387091347468 +1403638588177829376.0000000000 14.8422526216 -3.0960333945 1.8823900505 0.4301878213 0.6253676929 -0.5206113608 0.390918787077 +1403638588227829504.0000000000 14.8119757117 -3.0649789351 1.8685966804 0.4288193026 0.6263752430 -0.5193709243 0.392456244317 +1403638588277829376.0000000000 14.7812656430 -3.0333385954 1.8558225414 0.4282489605 0.6269338782 -0.5186096358 0.393193064359 +1403638588327829504.0000000000 14.7506252648 -3.0011810555 1.8443663967 0.4278804158 0.6272657494 -0.5187453009 0.392885914897 +1403638588377829376.0000000000 14.7199221725 -2.9684265255 1.8352167288 0.4276110686 0.6275236028 -0.5180866796 0.393635738148 +1403638588427829504.0000000000 14.6891058949 -2.9349313797 1.8281351150 0.4281659962 0.6271947215 -0.5186325950 0.392836979439 +1403638588477829376.0000000000 14.6582255716 -2.9008821251 1.8234448990 0.4284938582 0.6270753201 -0.5190165278 0.392162466706 +1403638588527829504.0000000000 14.6259314368 -2.8664947702 1.8206714862 0.4294301091 0.6264063089 -0.5198949790 0.391042361389 +1403638588577829376.0000000000 14.5930908688 -2.8319542045 1.8203618953 0.4304177049 0.6258208194 -0.5203161380 0.390333213803 +1403638588627829504.0000000000 14.5594616374 -2.7971487156 1.8219701045 0.4313727017 0.6253471312 -0.5208038041 0.389386639959 +1403638588677829376.0000000000 14.5248233746 -2.7623100525 1.8252879588 0.4325531709 0.6245840402 -0.5212662664 0.388682403238 +1403638588727829504.0000000000 14.4902789804 -2.7271185895 1.8307806974 0.4346227074 0.6230147090 -0.5220303614 0.38786605469 +1403638588777829376.0000000000 14.4556132737 -2.6920873588 1.8358791009 0.4349798118 0.6226803304 -0.5220346642 0.38799687986 +1403638588827829504.0000000000 14.4205834127 -2.6570144187 1.8400235783 0.4357033094 0.6221059317 -0.5225222653 0.387449762257 +1403638588877829376.0000000000 14.3854196454 -2.6221207615 1.8424452958 0.4364714100 0.6212876225 -0.5239561146 0.385959050063 +1403638588927829504.0000000000 14.3530418419 -2.5875329562 1.8451501344 0.4363009997 0.6212922843 -0.5238369388 0.386305833092 +1403638588977829376.0000000000 14.3190738047 -2.5533440434 1.8446231371 0.4362623176 0.6210952775 -0.5241995982 0.386174348968 +1403638589027829504.0000000000 14.2851265414 -2.5194377052 1.8423028057 0.4361165960 0.6209851996 -0.5244885688 0.386123604409 +1403638589077829376.0000000000 14.2510703750 -2.4857345276 1.8382060463 0.4356037835 0.6211515423 -0.5245117872 0.386403274286 +1403638589127829504.0000000000 14.2170180048 -2.4521539102 1.8327622898 0.4351041270 0.6212695710 -0.5241276725 0.387296658598 +1403638589177829376.0000000000 14.1830695057 -2.4187653821 1.8264276718 0.4351227736 0.6211621450 -0.5237623760 0.387941664518 +1403638589227829504.0000000000 14.1486927536 -2.3854239095 1.8188353907 0.4354958329 0.6209500888 -0.5239526223 0.387605490438 +1403638589277829376.0000000000 14.1144665867 -2.3523972218 1.8107253267 0.4366667374 0.6201135872 -0.5234856376 0.388257758011 +1403638589327829504.0000000000 14.0798509151 -2.3197542965 1.8013583933 0.4362570371 0.6202195124 -0.5237986339 0.38812697034 +1403638589377829376.0000000000 14.0452492326 -2.2871714481 1.7933951547 0.4368803077 0.6199965592 -0.5232318924 0.388546329497 +1403638589427829504.0000000000 14.0098916066 -2.2547732921 1.7861884847 0.4365330904 0.6201732714 -0.5240319695 0.387575114459 +1403638589477829376.0000000000 13.9747950363 -2.2227521441 1.7798709307 0.4358239320 0.6205165679 -0.5240850604 0.387751903484 +1403638589527829504.0000000000 13.9396252472 -2.1908131662 1.7752833823 0.4362568917 0.6204466898 -0.5241910882 0.387233176037 +1403638589577829376.0000000000 13.9038294015 -2.1592996557 1.7722268405 0.4361712344 0.6203357085 -0.5244392043 0.387171517674 +1403638589627829504.0000000000 13.8676813758 -2.1277513671 1.7714817660 0.4363375633 0.6203480783 -0.5239090572 0.387681689524 +1403638589677829376.0000000000 13.8318128410 -2.0960860109 1.7730365762 0.4357428670 0.6208107030 -0.5246809100 0.386564571165 +1403638589727829504.0000000000 13.7952060643 -2.0649273441 1.7766040788 0.4342670922 0.6216314874 -0.5252760454 0.386097737147 +1403638589777829376.0000000000 13.7585053151 -2.0340604139 1.7810567815 0.4333231627 0.6221038813 -0.5255733355 0.385992832261 +1403638589827829504.0000000000 13.7216486453 -2.0034162332 1.7851900041 0.4330626200 0.6220385653 -0.5264428055 0.385204832395 +1403638589877829376.0000000000 13.6849137251 -1.9730050034 1.7878988087 0.4322591839 0.6221812230 -0.5266806315 0.385551599794 +1403638589927829504.0000000000 13.6482050610 -1.9426423190 1.7889863793 0.4316544525 0.6224202116 -0.5266358033 0.385904450019 +1403638589977829376.0000000000 13.6115224479 -1.9124385940 1.7895885104 0.4318182367 0.6219953097 -0.5270887944 0.385787827645 +1403638590027829504.0000000000 13.5747959049 -1.8822066566 1.7886434560 0.4322986316 0.6214549100 -0.5278004007 0.385147277041 +1403638590077829376.0000000000 13.5379709426 -1.8522044295 1.7862515934 0.4318315133 0.6216183287 -0.5278457574 0.385345369621 +1403638590127829504.0000000000 13.5011291607 -1.8223753201 1.7831692332 0.4324526473 0.6207996446 -0.5278745030 0.38592877343 +1403638590177829376.0000000000 13.4642926231 -1.7926880609 1.7786763710 0.4326664352 0.6205016197 -0.5277415980 0.38634997285 +1403638590227829504.0000000000 13.4273173704 -1.7631332589 1.7731037445 0.4331535851 0.6198768256 -0.5278401127 0.386672352581 +1403638590277829376.0000000000 13.3901623502 -1.7337496813 1.7666542198 0.4336241819 0.6195504430 -0.5280529630 0.386377258238 +1403638590327829504.0000000000 13.3523410113 -1.7047735253 1.7591477283 0.4334624031 0.6194840893 -0.5279380714 0.386821924107 +1403638590377829376.0000000000 13.3142657552 -1.6758166881 1.7505384457 0.4328654277 0.6196679044 -0.5285739661 0.386327286368 +1403638590427829504.0000000000 13.2760721152 -1.6470292332 1.7411945408 0.4317393858 0.6203304666 -0.5285347695 0.38657756322 +1403638590477829376.0000000000 13.2370288436 -1.6182999540 1.7312302861 0.4319449334 0.6201081500 -0.5290121603 0.386051280491 +1403638590527829504.0000000000 13.1978137442 -1.5898169885 1.7217854199 0.4320917184 0.6200431251 -0.5293461199 0.38553333871 +1403638590577829376.0000000000 13.1586210586 -1.5616464139 1.7130848295 0.4309244864 0.6208711421 -0.5300456134 0.384544873437 +1403638590627829504.0000000000 13.1198964050 -1.5335790280 1.7062858912 0.4297850481 0.6217708438 -0.5305615556 0.383653836027 +1403638590677829376.0000000000 13.0820059123 -1.5055271691 1.7016426359 0.4295173882 0.6220992413 -0.5316097706 0.381966489402 +1403638590727829504.0000000000 13.0445200628 -1.4778106902 1.6992571814 0.4292944229 0.6221896975 -0.5322860044 0.381127128881 +1403638590777829376.0000000000 13.0071034977 -1.4502902870 1.6986914185 0.4287126435 0.6227041678 -0.5323488988 0.380853828545 +1403638590827829504.0000000000 12.9706300984 -1.4230326435 1.6993077338 0.4278671216 0.6232598322 -0.5324753238 0.380718974384 +1403638590877829376.0000000000 12.9356892491 -1.3958898049 1.7018064274 0.4274214975 0.6234875144 -0.5326621043 0.380585424713 +1403638590927829504.0000000000 12.9011978636 -1.3687889674 1.7065812166 0.4274204204 0.6234977483 -0.5333716542 0.379574789102 +1403638590977829376.0000000000 12.8664160070 -1.3420308970 1.7134138099 0.4270501845 0.6237300578 -0.5337441401 0.379085937287 +1403638591027829504.0000000000 12.8313775668 -1.3156687731 1.7207925325 0.4266303287 0.6237666306 -0.5347928947 0.378018932127 +1403638591077829376.0000000000 12.7972227212 -1.2895965598 1.7278907906 0.4261382985 0.6240514876 -0.5353977723 0.377246758293 +1403638591127829504.0000000000 12.7633792323 -1.2640168256 1.7333481999 0.4231956727 0.6259598511 -0.5364810454 0.375856056563 +1403638591177829376.0000000000 12.7302084599 -1.2386132686 1.7373115832 0.4205157943 0.6275903392 -0.5379814857 0.373995660239 +1403638591227829504.0000000000 12.7014589745 -1.2142640632 1.7408966092 0.4168109151 0.6299765277 -0.5398456510 0.371436278123 +1403638591277829376.0000000000 12.6716879934 -1.1890020808 1.7420587073 0.4130914991 0.6323193971 -0.5420947680 0.368321674506 +1403638591327829504.0000000000 12.6435494119 -1.1637018846 1.7423899976 0.4100150236 0.6343102041 -0.5443744420 0.364958507634 +1403638591377829376.0000000000 12.6172598463 -1.1384615362 1.7417662979 0.4080438202 0.6354577238 -0.5460063721 0.362726844522 +1403638591427829504.0000000000 12.5927764193 -1.1131813940 1.7403420522 0.4061504184 0.6364933209 -0.5475785489 0.360660259626 +1403638591477829376.0000000000 12.5700585580 -1.0878947155 1.7373819734 0.4049099267 0.6372687354 -0.5489766903 0.358554185124 +1403638591527829504.0000000000 12.5495138752 -1.0625383357 1.7328379151 0.4033534935 0.6380125946 -0.5507221555 0.356301832432 +1403638591577829376.0000000000 12.5303506745 -1.0373517347 1.7269405928 0.4016408666 0.6390218212 -0.5520934732 0.354300046856 +1403638591627829504.0000000000 12.5138828544 -1.0121373726 1.7199345719 0.4010783693 0.6393732245 -0.5528482543 0.353124381997 +1403638591677829376.0000000000 12.4997879496 -0.9868532445 1.7125520783 0.4015708954 0.6388693357 -0.5532530807 0.352842481238 +1403638591727829504.0000000000 12.4882155486 -0.9617422999 1.7049217965 0.4025360684 0.6380145189 -0.5530912166 0.353542491632 +1403638591777829376.0000000000 12.4790520081 -0.9369236426 1.6972589619 0.4036098774 0.6374643556 -0.5516490388 0.355558152997 +1403638591827829504.0000000000 12.4720367159 -0.9121718967 1.6900701278 0.4056032078 0.6361336440 -0.5511450855 0.35645353073 +1403638591877829376.0000000000 12.4657580977 -0.8880465613 1.6829711547 0.4067158482 0.6355564522 -0.5500594123 0.357889449148 +1403638591927829504.0000000000 12.4628438236 -0.8636433847 1.6782934679 0.4092012897 0.6341091651 -0.5489122963 0.359381638684 +1403638591977829376.0000000000 12.4615559602 -0.8395980401 1.6752267275 0.4103199327 0.6333063414 -0.5484696246 0.360196754013 +1403638592027829504.0000000000 12.4627824814 -0.8155049441 1.6752411068 0.4128504182 0.6317864907 -0.5474244806 0.361561613534 +1403638592077829376.0000000000 12.4662681444 -0.7915366585 1.6768410973 0.4141352382 0.6312257190 -0.5466138687 0.36229735675 +1403638592127829504.0000000000 12.4712109506 -0.7676807327 1.6802118705 0.4155929932 0.6307690053 -0.5456428350 0.362886790384 +1403638592177829376.0000000000 12.4783225053 -0.7434662482 1.6866636973 0.4202748974 0.6292209504 -0.5439492174 0.362724764794 +1403638592227829504.0000000000 12.4862097899 -0.7197427162 1.6963572802 0.4261334520 0.6276713297 -0.5409141305 0.363112773683 +1403638592277829376.0000000000 12.4949468437 -0.6963539653 1.7085470764 0.4335242905 0.6260115918 -0.5371928065 0.362753449473 +1403638592327829504.0000000000 12.5039410623 -0.6738119468 1.7223525977 0.4399436461 0.6257990948 -0.5331008984 0.361425667918 +1403638592377829376.0000000000 12.5131783161 -0.6519073474 1.7378578114 0.4466494308 0.6268828072 -0.5282313170 0.358460468967 +1403638592427829504.0000000000 12.5224227910 -0.6309419718 1.7553982505 0.4523064641 0.6299098144 -0.5223028964 0.354728308232 +1403638592477829376.0000000000 12.5313245868 -0.6113140113 1.7744549453 0.4565165353 0.6343702713 -0.5164747038 0.34988697078 +1403638592527829504.0000000000 12.5407613014 -0.5933236193 1.7946730532 0.4575711194 0.6403536399 -0.5109589830 0.345683098022 +1403638592577829376.0000000000 12.5503911398 -0.5768272116 1.8164584551 0.4571943478 0.6465324330 -0.5060610917 0.341864465698 +1403638592627829504.0000000000 12.5605953493 -0.5613315729 1.8398777078 0.4566910120 0.6522892699 -0.5016458286 0.338087992433 +1403638592677829376.0000000000 12.5715483012 -0.5467683523 1.8642714111 0.4554046905 0.6576977726 -0.4983888921 0.334138773702 +1403638592727829504.0000000000 12.5832861654 -0.5329262932 1.8880554883 0.4536986478 0.6626365604 -0.4956779744 0.330716905408 +1403638592777829376.0000000000 12.5960868653 -0.5196213567 1.9105227174 0.4515765277 0.6671285285 -0.4939925453 0.327092542333 +1403638592827829504.0000000000 12.6103644674 -0.5063623405 1.9336750153 0.4499061332 0.6706927621 -0.4930285615 0.323540612058 +1403638592877829376.0000000000 12.6251340526 -0.4940063834 1.9540462359 0.4486350219 0.6735738542 -0.4915738565 0.321527640489 +1403638592927829504.0000000000 12.6410829698 -0.4821449344 1.9733399034 0.4476077500 0.6755911283 -0.4903768651 0.320553364707 +1403638592977829376.0000000000 12.6584290347 -0.4704451867 1.9912965269 0.4467856659 0.6773120114 -0.4890785130 0.320051895822 +1403638593027829504.0000000000 12.6769958670 -0.4590713134 2.0083450139 0.4470359438 0.6778970117 -0.4885658783 0.319245812787 +1403638593077829376.0000000000 12.6970119712 -0.4478876148 2.0238447889 0.4467761205 0.6785155003 -0.4881391216 0.318948290409 +1403638593127829504.0000000000 12.7185031199 -0.4366628781 2.0396175177 0.4475368808 0.6783706815 -0.4876039627 0.319008360847 +1403638593177829376.0000000000 12.7420704137 -0.4254462803 2.0570950093 0.4493982371 0.6772996064 -0.4866694978 0.320092591987 +1403638593227829504.0000000000 12.7674136501 -0.4144747301 2.0758860945 0.4512069719 0.6758934322 -0.4845179779 0.323763286916 +1403638593277829376.0000000000 12.7938230666 -0.4037180684 2.0958671857 0.4513064551 0.6755640725 -0.4819316182 0.328142625833 +1403638593327829504.0000000000 12.8216220874 -0.3926378829 2.1176823523 0.4515432070 0.6751681168 -0.4791388000 0.332690181052 +1403638593377829376.0000000000 12.8495319920 -0.3818172033 2.1403126764 0.4522861260 0.6742417395 -0.4758778048 0.338194695278 +1403638593427829504.0000000000 12.8776259890 -0.3709144578 2.1625405440 0.4534091322 0.6728792330 -0.4722498710 0.344432512869 +1403638593477829376.0000000000 12.9054214426 -0.3593410747 2.1835726038 0.4548068264 0.6713448333 -0.4704589554 0.348016144295 +1403638593527829504.0000000000 12.9330727662 -0.3472732689 2.2029845913 0.4556662991 0.6700789852 -0.4690886910 0.351166879737 +1403638593577829376.0000000000 12.9604065226 -0.3346523909 2.2206727578 0.4561816568 0.6691641434 -0.4681596769 0.353474414945 +1403638593627829504.0000000000 12.9873033208 -0.3215247349 2.2367620649 0.4563868943 0.6683498283 -0.4681338551 0.354781909527 +1403638593677829376.0000000000 13.0135894183 -0.3078983541 2.2512023459 0.4562241457 0.6681609787 -0.4673713002 0.356348850379 +1403638593727829504.0000000000 13.0391738426 -0.2935824415 2.2644471877 0.4577966932 0.6666820949 -0.4671215448 0.357427803003 +1403638593777829376.0000000000 13.0643120990 -0.2784820062 2.2764497918 0.4596851069 0.6649522971 -0.4664351484 0.359118779076 +1403638593827829504.0000000000 13.0883858850 -0.2623620663 2.2894382408 0.4662830951 0.6604240552 -0.4657468601 0.359861090936 +1403638593877829376.0000000000 13.1112149730 -0.2457234178 2.3038984615 0.4756138883 0.6551963477 -0.4628364998 0.360959207675 +1403638593927829504.0000000000 13.1318265722 -0.2294006125 2.3187864691 0.4818689023 0.6527154395 -0.4604145034 0.360254633634 +1403638593977829376.0000000000 13.1503024833 -0.2134196747 2.3340126690 0.4846759771 0.6532352014 -0.4588202619 0.357570882653 +1403638594027829504.0000000000 13.1666746446 -0.1980220984 2.3495010894 0.4842688823 0.6561337787 -0.4588232589 0.352779437064 +1403638594077829376.0000000000 13.1812788734 -0.1833142184 2.3667826641 0.4831777998 0.6592788227 -0.4590274881 0.348115516599 +1403638594127829504.0000000000 13.1943059463 -0.1694770856 2.3849102049 0.4808772129 0.6628499217 -0.4583286400 0.345430087155 +1403638594177829376.0000000000 13.2061171502 -0.1563177368 2.4028840408 0.4780113448 0.6667119083 -0.4569837705 0.343753136817 +1403638594227829504.0000000000 13.2174917981 -0.1435674828 2.4202295065 0.4761850896 0.6692271195 -0.4555220001 0.343340254402 +1403638594277829376.0000000000 13.2279897831 -0.1306994426 2.4371183136 0.4759877046 0.6707317195 -0.4534556840 0.343413174037 +1403638594327829504.0000000000 13.2377759924 -0.1179201692 2.4533045722 0.4768414243 0.6710768872 -0.4516547291 0.343927424309 +1403638594377829376.0000000000 13.2465560553 -0.1053950728 2.4699023936 0.4771206486 0.6716109536 -0.4485549426 0.346544480709 +1403638594427829504.0000000000 13.2543255829 -0.0925320214 2.4871203287 0.4776595502 0.6721146568 -0.4452720551 0.349050195749 +1403638594477829376.0000000000 13.2606359693 -0.0793932784 2.5059247073 0.4780108883 0.6723581220 -0.4430450338 0.350929115958 +1403638594527829504.0000000000 13.2646973853 -0.0660129753 2.5266803479 0.4792251083 0.6723070940 -0.4440421774 0.348099140439 +1403638594577829376.0000000000 13.2667728222 -0.0529436877 2.5497004451 0.4804202477 0.6719853421 -0.4449612540 0.345892422662 +1403638594627829504.0000000000 13.2680617170 -0.0394748355 2.5744109199 0.4812637512 0.6719333302 -0.4465826277 0.342716731824 +1403638594677829376.0000000000 13.2685119715 -0.0262604913 2.5991750983 0.4820593399 0.6714172360 -0.4482167350 0.34046944997 +1403638594727829504.0000000000 13.2682114385 -0.0133407384 2.6234378137 0.4819726125 0.6713641036 -0.4495446903 0.338942786691 +1403638594777829376.0000000000 13.2675617488 -0.0006597405 2.6459869422 0.4818017783 0.6713798496 -0.4503666106 0.33806221325 +1403638594827829504.0000000000 13.2662595324 0.0118132783 2.6667176367 0.4819350795 0.6710511505 -0.4513066492 0.337270278786 +1403638594877829376.0000000000 13.2637284952 0.0240559180 2.6863694771 0.4819615758 0.6708528123 -0.4519860437 0.336716735647 +1403638594927829504.0000000000 13.2604978637 0.0355200876 2.7036340402 0.4806389844 0.6714831858 -0.4525621889 0.336576830745 +1403638594977829376.0000000000 13.2561777342 0.0466392849 2.7191993937 0.4788337394 0.6723887604 -0.4530900164 0.336631908489 +1403638595027829504.0000000000 13.2512942676 0.0575372393 2.7332031034 0.4786616436 0.6723227352 -0.4546062560 0.33496018068 +1403638595077829376.0000000000 13.2458003490 0.0682095177 2.7454731335 0.4775890188 0.6728656596 -0.4551721369 0.33463242375 +1403638595127829504.0000000000 13.2400078322 0.0786027860 2.7559590184 0.4772647396 0.6727669564 -0.4560111606 0.334150882343 +1403638595177829376.0000000000 13.2339237254 0.0886698104 2.7646683953 0.4767044898 0.6728857041 -0.4564742648 0.334079188489 +1403638595227829504.0000000000 13.2274991371 0.0983066842 2.7714739548 0.4761294507 0.6730793484 -0.4564800643 0.334500953366 +1403638595277829376.0000000000 13.2205958107 0.1077518023 2.7765212873 0.4757531353 0.6732085102 -0.4568685901 0.334245938606 +1403638595327829504.0000000000 13.2134299185 0.1169226328 2.7801989654 0.4757349837 0.6730857991 -0.4567119943 0.334732559769 +1403638595377829376.0000000000 13.2058374477 0.1260365816 2.7823529665 0.4760761419 0.6726671879 -0.4574293896 0.334108837028 +1403638595427829504.0000000000 13.1980100199 0.1346790599 2.7832267526 0.4759383244 0.6726359634 -0.4574358124 0.334359162624 +1403638595477829376.0000000000 13.1899795754 0.1429946163 2.7825715417 0.4755357421 0.6729132005 -0.4577406901 0.333956648595 +1403638595527829504.0000000000 13.1817320533 0.1509333321 2.7810449085 0.4751884588 0.6732016586 -0.4576440552 0.334002057129 +1403638595577829376.0000000000 13.1732188777 0.1585983778 2.7795749383 0.4745753612 0.6737855314 -0.4577299069 0.333578501396 +1403638595627829504.0000000000 13.1648884549 0.1662673726 2.7798190977 0.4742759215 0.6740612532 -0.4571962371 0.334178661778 +1403638595677829376.0000000000 13.1562215120 0.1736161799 2.7825615452 0.4736223487 0.6744552999 -0.4561664379 0.335714313344 +1403638595727829504.0000000000 13.1471302345 0.1806392035 2.7860590640 0.4720215405 0.6756632249 -0.4545635316 0.337708257972 +1403638595777829376.0000000000 13.1370949246 0.1874941278 2.7901963360 0.4707263085 0.6764347653 -0.4537234658 0.339098462646 +1403638595827829504.0000000000 13.1267625538 0.1943652093 2.7939722174 0.4698104737 0.6770036755 -0.4533506394 0.339731275915 +1403638595877829376.0000000000 13.1161306281 0.2014513165 2.7950037300 0.4696597156 0.6770550986 -0.4532305944 0.339997313574 +1403638595927829504.0000000000 13.1053395430 0.2086398407 2.7920238935 0.4695988557 0.6769669345 -0.4527178767 0.340938716442 +1403638595977829376.0000000000 13.0943403477 0.2161449232 2.7852192632 0.4690408063 0.6773102923 -0.4517612175 0.342291239135 +1403638596027829504.0000000000 13.0834700111 0.2238976914 2.7765593090 0.4682626040 0.6777193920 -0.4501331802 0.344683448296 +1403638596077829376.0000000000 13.0722576280 0.2317959295 2.7656331641 0.4649765595 0.6797359657 -0.4474326325 0.348654349519 +1403638596127829504.0000000000 13.0604663062 0.2403853923 2.7549895184 0.4624284948 0.6812667474 -0.4440921250 0.353295472187 +1403638596177829376.0000000000 13.0472942607 0.2496119457 2.7444548081 0.4582807496 0.6838965260 -0.4405182022 0.35806146096 +1403638596227829504.0000000000 13.0327204653 0.2600736936 2.7357494699 0.4546582059 0.6862663606 -0.4366732275 0.362823497767 +1403638596277829376.0000000000 13.0173414928 0.2722876892 2.7289351242 0.4508030758 0.6886106490 -0.4329518271 0.367620288293 +1403638596327829504.0000000000 13.0021807749 0.2854473628 2.7248805456 0.4481827037 0.6902885776 -0.4293711981 0.371852548761 +1403638596377829376.0000000000 12.9851503495 0.3019870718 2.7230696374 0.4463406252 0.6914966360 -0.4258561492 0.375844367872 +1403638596427829504.0000000000 12.9660672599 0.3211053871 2.7239225015 0.4451764745 0.6922264870 -0.4241461555 0.377810052944 +1403638596477829376.0000000000 12.9455538358 0.3428149149 2.7263514885 0.4442386659 0.6929126529 -0.4212044806 0.380934178896 +1403638596527829504.0000000000 12.9236196700 0.3676463998 2.7310669180 0.4423687318 0.6940643818 -0.4187272667 0.383734302791 +1403638596577829376.0000000000 12.9002760056 0.3955333898 2.7384114367 0.4398920704 0.6955926614 -0.4162654377 0.386482730591 +1403638596627829504.0000000000 12.8752686702 0.4270845911 2.7475888763 0.4380575537 0.6966125229 -0.4134337053 0.389755235869 +1403638596677829376.0000000000 12.8478454341 0.4619954192 2.7584566824 0.4355854333 0.6979793716 -0.4106976925 0.392959962939 +1403638596727829504.0000000000 12.8185094645 0.5009170881 2.7712437662 0.4339255501 0.6989487926 -0.4090441800 0.394793694331 +1403638596777829376.0000000000 12.7873320248 0.5439724882 2.7861364482 0.4334229017 0.6992791645 -0.4075493087 0.396303922866 +1403638596827829504.0000000000 12.7536411325 0.5905806279 2.8026064906 0.4322914684 0.6998404668 -0.4056109211 0.39853128862 +1403638596877829376.0000000000 12.7176841380 0.6411900242 2.8208122907 0.4323823677 0.6997152138 -0.4045208278 0.399758686602 +1403638596927829504.0000000000 12.6796880985 0.6956092138 2.8393881993 0.4323725876 0.6995849156 -0.4034284067 0.4010990053 +1403638596977829376.0000000000 12.6396606881 0.7534497765 2.8572515860 0.4330027902 0.6988273708 -0.4032230379 0.401945358348 +1403638597027829504.0000000000 12.5975408683 0.8146365182 2.8734196721 0.4325687661 0.6986127575 -0.4029998537 0.40300818291 +1403638597077829376.0000000000 12.5535184346 0.8792988830 2.8880223748 0.4323792658 0.6983991314 -0.4018520138 0.404724329285 +1403638597127829504.0000000000 12.5077830410 0.9475836614 2.9013447170 0.4329743352 0.6974859496 -0.4014321896 0.406077298534 +1403638597177829376.0000000000 12.4598506887 1.0192633743 2.9132082559 0.4331427529 0.6967976694 -0.4009342861 0.407568474959 +1403638597227829504.0000000000 12.4094628579 1.0947887546 2.9235308519 0.4352300241 0.6950174113 -0.4018203642 0.407511986349 +1403638597277829376.0000000000 12.3568594698 1.1738668981 2.9324510539 0.4377463347 0.6932258669 -0.4028583185 0.406842990692 +1403638597327829504.0000000000 12.3015998171 1.2557783498 2.9398011269 0.4397640745 0.6917560459 -0.4045490872 0.405488801003 +1403638597377829376.0000000000 12.2440504625 1.3406752399 2.9457965940 0.4423375027 0.6898553639 -0.4068735113 0.403597641622 +1403638597427829504.0000000000 12.1842132181 1.4283748715 2.9505394513 0.4455561788 0.6877569950 -0.4091577523 0.40132273927 +1403638597477829376.0000000000 12.1221695120 1.5187181550 2.9546486391 0.4510040941 0.6843445848 -0.4123167359 0.397822454859 +1403638597527829504.0000000000 12.0579822412 1.6112130073 2.9576487715 0.4575267282 0.6803538859 -0.4159984869 0.393361337586 +1403638597577829376.0000000000 11.9917854050 1.7050623571 2.9592126939 0.4632706441 0.6766948511 -0.4196318538 0.389067469956 +1403638597627829504.0000000000 11.9239528803 1.7996036900 2.9594393269 0.4661970436 0.6745588452 -0.4217209371 0.387016966172 +1403638597677829376.0000000000 11.8544519543 1.8948223338 2.9581234528 0.4680952151 0.6731152885 -0.4226016225 0.386277810084 +1403638597727829504.0000000000 11.7833297257 1.9903582311 2.9549305534 0.4673174410 0.6735974593 -0.4220008906 0.387035037721 +1403638597777829376.0000000000 11.7102143044 2.0863717180 2.9501119590 0.4642564774 0.6766629490 -0.4184483336 0.389222518267 +1403638597827829504.0000000000 11.6353799420 2.1837389276 2.9444405016 0.4627068807 0.6796644307 -0.4138551442 0.390746111557 +1403638597877829376.0000000000 11.5582096673 2.2820856805 2.9374199851 0.4606105409 0.6832764068 -0.4087895729 0.392252937034 +1403638597927829504.0000000000 11.4789842382 2.3816665407 2.9296466121 0.4588759325 0.6863736912 -0.4042816860 0.393548412514 +1403638597977829376.0000000000 11.3975530089 2.4830031712 2.9224898710 0.4595936162 0.6882063324 -0.4008391173 0.393031492454 +1403638598027829504.0000000000 11.3143813207 2.5866043820 2.9165412109 0.4603786467 0.6897669372 -0.3986096379 0.391641967373 +1403638598077829376.0000000000 11.2289902725 2.6927252692 2.9134160499 0.4643411756 0.6894062960 -0.3986381833 0.387548487915 +1403638598127829504.0000000000 11.1406042122 2.8005900711 2.9123270762 0.4691092900 0.6889114820 -0.4026086089 0.378475563258 +1403638598177829376.0000000000 11.0494866249 2.9089574213 2.9126630527 0.4743905217 0.6876694812 -0.4079348834 0.368311618711 +1403638598227829504.0000000000 10.9569768058 3.0177652303 2.9142487309 0.4789433747 0.6864268442 -0.4121012908 0.36000549651 +1403638598277829376.0000000000 10.8632420485 3.1264592055 2.9156183674 0.4807691697 0.6865337720 -0.4166241707 0.352074829663 +1403638598327829504.0000000000 10.7693000317 3.2347206531 2.9167415784 0.4828007347 0.6861751831 -0.4199280268 0.346016648353 +1403638598377829376.0000000000 10.6751667359 3.3423651734 2.9158916167 0.4836988342 0.6863620786 -0.4222948115 0.341481517805 +1403638598427829504.0000000000 10.5811601501 3.4493626909 2.9136585567 0.4836614170 0.6867521629 -0.4239912752 0.338636233923 +1403638598477829376.0000000000 10.4865136269 3.5554627643 2.9100413627 0.4828162678 0.6878653298 -0.4248032981 0.336558906531 +1403638598527829504.0000000000 10.3915142293 3.6609351904 2.9048932590 0.4838360597 0.6883366571 -0.4244679573 0.334547854793 +1403638598577829376.0000000000 10.2963633832 3.7655704881 2.8970893288 0.4835358590 0.6904838022 -0.4237035234 0.331512467738 +1403638598627829504.0000000000 10.2010099589 3.8692040665 2.8875025953 0.4834766706 0.6932406322 -0.4209987530 0.329283745232 +1403638598677829376.0000000000 10.1059493766 3.9723168119 2.8776009038 0.4848610953 0.6958180253 -0.4166438310 0.327345249072 +1403638598727829504.0000000000 10.0111662359 4.0749586978 2.8684060411 0.4866394730 0.6987924366 -0.4122100331 0.323966113081 +1403638598777829376.0000000000 9.9159432450 4.1766434738 2.8596422015 0.4888046533 0.7019337971 -0.4074771190 0.319877090267 +1403638598827829504.0000000000 9.8208705369 4.2779199257 2.8534640024 0.4923071804 0.7046322651 -0.4009877978 0.316758262974 +1403638598877829376.0000000000 9.6794081824 4.3921590895 2.8711122130 0.4948147306 0.7084163906 -0.3945274095 0.312494356892 +1403638598927829504.0000000000 9.5834580923 4.4932454367 2.8659140119 0.4962736226 0.7129691801 -0.3875636636 0.308515553009 +1403638598977829376.0000000000 9.4875726057 4.5940403247 2.8617805286 0.4992178876 0.7168998296 -0.3803347767 0.303614216724 +1403638599027829504.0000000000 9.3916213364 4.6942370531 2.8591753877 0.5024526658 0.7206161716 -0.3738626733 0.29745647302 +1403638599077829376.0000000000 9.2967363045 4.7950683809 2.8573227262 0.5055029899 0.7245152322 -0.3655008213 0.293178367471 +1403638599127829504.0000000000 9.2011159881 4.8945843589 2.8579974456 0.5081411278 0.7286202057 -0.3575907650 0.288156268145 +1403638599177829376.0000000000 9.1045529168 4.9931315261 2.8599875597 0.5112780734 0.7323962921 -0.3497190500 0.28264286499 +1403638599227829504.0000000000 9.0079489417 5.0906627154 2.8620161499 0.5129877325 0.7370771330 -0.3411438531 0.277816050323 +1403638599277829376.0000000000 8.9112206396 5.1878993958 2.8659187055 0.5150997189 0.7413692073 -0.3328916685 0.272446536153 +1403638599327829504.0000000000 8.8140205875 5.2845252791 2.8722191292 0.5171670065 0.7458500693 -0.3253100722 0.265366385317 +1403638599377829376.0000000000 8.7167185277 5.3798388112 2.8796670336 0.5171283226 0.7508972141 -0.3180999896 0.259892416989 +1403638599427829504.0000000000 8.6198719571 5.4746916544 2.8887865727 0.5178238631 0.7547382735 -0.3112561276 0.255632956171 +1403638599477829376.0000000000 8.5235917633 5.5695237998 2.8983381585 0.5183808204 0.7579344778 -0.3065456032 0.250691933373 +1403638599527829504.0000000000 8.4279927128 5.6639263837 2.9075352480 0.5178650218 0.7609914592 -0.3018487869 0.248183658104 +1403638599577829376.0000000000 8.3329737012 5.7582047325 2.9155821830 0.5175862439 0.7633120014 -0.2994803284 0.244480677212 +1403638599627829504.0000000000 8.2385362356 5.8519268458 2.9216808867 0.5180118728 0.7645862692 -0.2976015937 0.241877712987 +1403638599677829376.0000000000 8.1442691984 5.9448572974 2.9255104986 0.5170632289 0.7664518645 -0.2956925926 0.240339441961 +1403638599727829504.0000000000 8.0504346544 6.0376627213 2.9275738912 0.5172411970 0.7669332471 -0.2950836415 0.239166433959 +1403638599777829376.0000000000 7.9576973002 6.1308949592 2.9279095975 0.5174207376 0.7669908141 -0.2946902322 0.239078519234 +1403638599827829504.0000000000 7.8659711758 6.2241699673 2.9264786007 0.5168678241 0.7672288022 -0.2960941544 0.237772726098 +1403638599877829376.0000000000 7.7748370826 6.3172032646 2.9242598513 0.5164960176 0.7673685808 -0.2973601298 0.23654656679 +1403638599927829504.0000000000 7.6842853143 6.4101550727 2.9212062614 0.5164440703 0.7670007597 -0.3000257280 0.234477972079 +1403638599977829376.0000000000 7.5946206583 6.5033807318 2.9171226534 0.5177885692 0.7655644659 -0.3025808910 0.232918119562 +1403638600027829504.0000000000 7.5061746814 6.5967988434 2.9124185411 0.5193426275 0.7640260284 -0.3058732367 0.230193454009 +1403638600077829376.0000000000 7.4190067347 6.6902448619 2.9068345737 0.5187085188 0.7638668777 -0.3101992055 0.226330109753 +1403638600127829504.0000000000 7.3333293251 6.7832785890 2.9010042308 0.5196877465 0.7625427572 -0.3153953605 0.2213118979 +1403638600177829376.0000000000 7.2487693834 6.8756225149 2.8943074529 0.5206368065 0.7613172974 -0.3217375068 0.214052014808 +1403638600227829504.0000000000 7.1659293987 6.9664536655 2.8861757391 0.5200239956 0.7609238940 -0.3272421003 0.208524529309 +1403638600277829376.0000000000 7.0849615164 7.0560142898 2.8768589753 0.5208808452 0.7595047621 -0.3323751630 0.203377512295 +1403638600327829504.0000000000 7.0068721293 7.1445306959 2.8669686545 0.5204375281 0.7590283379 -0.3367348625 0.199073840449 +1403638600377829376.0000000000 6.9317121242 7.2318049946 2.8577429310 0.5210386152 0.7577784550 -0.3408371781 0.195244955506 +1403638600427829504.0000000000 6.8593997654 7.3174164901 2.8492853145 0.5209355724 0.7571609179 -0.3448950377 0.190737743332 +1403638600477829376.0000000000 6.7906840323 7.4010999828 2.8431386194 0.5210341450 0.7565684205 -0.3472484822 0.18853683059 +1403638600527829504.0000000000 6.7257627838 7.4827306631 2.8391004848 0.5201658840 0.7568072583 -0.3477323405 0.189083172989 +1403638600577829376.0000000000 6.6645488270 7.5627640975 2.8375081681 0.5195555295 0.7568437373 -0.3479885405 0.190140960332 +1403638600627829504.0000000000 6.6061448182 7.6407868920 2.8376933010 0.5180903410 0.7575622140 -0.3494308580 0.18862652489 +1403638600677829376.0000000000 6.5511077700 7.7171327670 2.8401619799 0.5181804635 0.7571706080 -0.3512712767 0.186521226069 +1403638600727829504.0000000000 6.5000464812 7.7920628777 2.8440139336 0.5151476162 0.7591693662 -0.3512838201 0.186773886715 +1403638600777829376.0000000000 6.4520933240 7.8654864704 2.8494355654 0.5128347892 0.7607298960 -0.3523846922 0.184703906016 +1403638600827829504.0000000000 6.4082286873 7.9373253602 2.8555674386 0.5085644231 0.7640396989 -0.3497507069 0.187829734457 +1403638600877829376.0000000000 6.3676802813 8.0078662121 2.8624896390 0.5044072691 0.7674279971 -0.3454355546 0.193136878568 +1403638600927829504.0000000000 6.3300822999 8.0774786848 2.8680283106 0.4993217389 0.7715055351 -0.3392727215 0.200875659908 +1403638600977829376.0000000000 6.2951544694 8.1471323966 2.8723358730 0.4961468812 0.7741906143 -0.3335333801 0.207900575635 +1403638601027829504.0000000000 6.2625267685 8.2170987653 2.8755595055 0.4935046132 0.7763388047 -0.3291533508 0.213094647267 +1403638601077829376.0000000000 6.2318380496 8.2879273204 2.8777695681 0.4923954684 0.7774040678 -0.3261870477 0.216313725923 +1403638601127829504.0000000000 6.2031818281 8.3593494885 2.8790218838 0.4928085614 0.7772678936 -0.3234043203 0.220009065698 +1403638601177829376.0000000000 6.1760706775 8.4311363083 2.8785099406 0.4914640074 0.7783562879 -0.3197149878 0.224514910502 +1403638601227829504.0000000000 6.1506357126 8.5041076538 2.8776680622 0.4937232438 0.7770717119 -0.3155281221 0.229867173021 +1403638601277829376.0000000000 6.1268729558 8.5782950876 2.8757901535 0.4969255583 0.7749642281 -0.3104437632 0.236896822565 +1403638601327829504.0000000000 6.1034338601 8.6537960260 2.8740636379 0.5015740217 0.7724859696 -0.3067964169 0.239926834918 +1403638601377829376.0000000000 6.0796778737 8.7303421217 2.8729270040 0.5051609458 0.7716148856 -0.3051475876 0.237292724173 +1403638601427829504.0000000000 6.0561648733 8.8084160995 2.8735645453 0.5118780385 0.7693690384 -0.3030329191 0.232858769145 +1403638601477829376.0000000000 6.0325156317 8.8865579018 2.8751439062 0.5163960443 0.7692983478 -0.2993994726 0.227761132033 +1403638601527829504.0000000000 6.0089562737 8.9648116615 2.8782809170 0.5219834217 0.7691080416 -0.2927601535 0.224271309797 +1403638601577829376.0000000000 5.9851268814 9.0426804319 2.8826121484 0.5266589316 0.7701721692 -0.2845240714 0.220252701075 +1403638601627829504.0000000000 5.9614462685 9.1205354051 2.8876933889 0.5298659584 0.7724550820 -0.2759242730 0.215455350433 +1403638601677829376.0000000000 5.9374339302 9.1982274354 2.8941747150 0.5331621018 0.7752749908 -0.2650409299 0.210808366223 +1403638601727829504.0000000000 5.9127759266 9.2754682542 2.9020523946 0.5358380070 0.7788328112 -0.2537397534 0.204727184221 +1403638601777829376.0000000000 5.8875814623 9.3522655730 2.9117899121 0.5390962561 0.7821272414 -0.2404283767 0.199615632195 +1403638601827829504.0000000000 5.8613141658 9.4288867277 2.9234312108 0.5428797680 0.7853077556 -0.2265957654 0.192944669762 +1403638601877829376.0000000000 5.8344025657 9.5050898708 2.9364546103 0.5463571252 0.7883345575 -0.2117364086 0.187590539603 +1403638601927829504.0000000000 5.8065738385 9.5808983346 2.9499323934 0.5488173832 0.7915806342 -0.1994453506 0.18005868938 +1403638601977829376.0000000000 5.7785311919 9.6566533859 2.9626716020 0.5508448594 0.7942270769 -0.1889526562 0.173407568905 +1403638602027829504.0000000000 5.7501589502 9.7321525987 2.9740100938 0.5516697641 0.7970843356 -0.1799975188 0.167086583865 +1403638602077829376.0000000000 5.7215028123 9.8073082602 2.9835244911 0.5526765519 0.7991072542 -0.1726942222 0.161718678207 +1403638602127829504.0000000000 5.6925635486 9.8823209516 2.9914040041 0.5544113002 0.8000834456 -0.1647136405 0.159260814305 +1403638602177829376.0000000000 5.6627471200 9.9568584138 2.9975760780 0.5567190541 0.8005847348 -0.1565247692 0.156933023583 +1403638602227829504.0000000000 5.6320031909 10.0567701300 3.0251152972 0.5598444847 0.8005325078 -0.1469347944 0.155344852286 +1403638602277829376.0000000000 5.6014029259 10.1337283131 3.0299945190 0.5632343552 0.8005503222 -0.1378671084 0.151257737436 +1403638602327829504.0000000000 5.5691657587 10.2104966707 3.0353714051 0.5696112993 0.7987200576 -0.1289624602 0.144768508973 +1403638602377829376.0000000000 5.5348301649 10.2865376573 3.0427647162 0.5788377625 0.7951194995 -0.1223990065 0.13323028726 +1403638602427829504.0000000000 5.4987029874 10.3619050226 3.0540137622 0.5935971165 0.7872674668 -0.1162340236 0.119758301373 +1403638602477829376.0000000000 5.4616925175 10.4350547147 3.0676325652 0.6101575757 0.7772922440 -0.1087791936 0.108127643151 +1403638602527829504.0000000000 5.4235709799 10.5047736583 3.0831725905 0.6255320996 0.7676104163 -0.1029951324 0.0942116971702 +1403638602577829376.0000000000 5.3851949920 10.5699455162 3.1004391692 0.6383315025 0.7593184956 -0.0966456697 0.0814120976493 +1403638602627829504.0000000000 5.3463197941 10.6295158982 3.1187998235 0.6455600575 0.7551576757 -0.0894465962 0.0706286298765 +1403638602677829376.0000000000 5.3079926653 10.6832043529 3.1370311291 0.6477555660 0.7549649936 -0.0806019835 0.0628005200185 +1403638602727829504.0000000000 5.2698960867 10.7305015389 3.1566871645 0.6483808874 0.7559302759 -0.0715448094 0.055253805777 +1403638602777829376.0000000000 5.2323007116 10.7722441965 3.1775282568 0.6469770593 0.7584004028 -0.0608255838 0.0504951699894 +1403638602827829504.0000000000 5.1948019410 10.8081149378 3.1994328469 0.6457440539 0.7605458690 -0.0504956447 0.0451086230148 +1403638602877829376.0000000000 5.1572807890 10.8382992868 3.2222765291 0.6442931543 0.7627440077 -0.0414127376 0.037321509965 +1403638602927829504.0000000000 5.1198438693 10.8631868335 3.2461951198 0.6412976459 0.7660716592 -0.0331258415 0.0278248249582 +1403638602977829376.0000000000 5.0822435365 10.8835931465 3.2704338274 0.6385959271 0.7689365879 -0.0272483323 0.0137584173644 +1403638603027829504.0000000000 5.0458455156 10.9001031382 3.2935031450 0.6374357265 0.7702402838 -0.0199963448 0.00239709024903 +1403638603077829376.0000000000 5.0108281261 10.9128177566 3.3152033461 0.6378341348 0.7700506046 -0.0118885738 -0.00695303006821 +1403638603127829504.0000000000 4.9774154581 10.9218431015 3.3352701226 0.6396976207 0.7684664516 -0.0041656125 -0.0151299235171 +1403638603177829376.0000000000 4.9458718437 10.9270589901 3.3524342756 0.6392330319 0.7687508743 0.0040155655 -0.0196748417844 +1403638603227829504.0000000000 4.9161086600 10.9279915966 3.3659826919 0.6327005908 0.7739749972 0.0109159386 -0.0230977992558 +1403638603277829376.0000000000 4.8880728802 10.9252222967 3.3767283324 0.6224609915 0.7820690312 0.0173578416 -0.024678935039 +1403638603327829504.0000000000 4.8614075156 10.9192394139 3.3851346342 0.6103955437 0.7913608298 0.0222587477 -0.0258817605118 +1403638603377829376.0000000000 4.8358711231 10.9115843384 3.3917019921 0.5997237811 0.7993306559 0.0262926123 -0.026656845328 +1403638603427829504.0000000000 4.8113241941 10.9026856886 3.3969927664 0.5909628590 0.8057020362 0.0288340004 -0.0278519037884 +1403638603477829376.0000000000 4.7880064304 10.8931506397 3.4012663716 0.5851879418 0.8098215417 0.0301219803 -0.0289276632812 +1403638603527829504.0000000000 4.7654643213 10.8834424442 3.4047550513 0.5833878807 0.8110166927 0.0326348802 -0.029076956315 +1403638603577829376.0000000000 4.7434670720 10.8736574683 3.4073752309 0.5854350618 0.8093871102 0.0350783074 -0.030459916716 +1403638603627829504.0000000000 4.7223215179 10.8633339069 3.4085823229 0.5895429907 0.8062675855 0.0371382626 -0.031502257345 +1403638603677829376.0000000000 4.7021997818 10.8524365515 3.4074947031 0.5938076841 0.8030455349 0.0403613141 -0.0296861499399 +1403638603727829504.0000000000 4.6831998343 10.8403448812 3.4040421471 0.5974641766 0.8002336405 0.0449841250 -0.0252805625361 +1403638603777829376.0000000000 4.6401570405 10.8179847465 3.4241628640 0.6015287658 0.7970595390 0.0495531714 -0.0200927471381 +1403638603827829504.0000000000 4.6206735631 10.8021461629 3.4189177237 0.6045811459 0.7946059246 0.0531894753 -0.0159355713838 +1403638603877829376.0000000000 4.6012119461 10.7844681516 3.4120931763 0.6082878520 0.7915861501 0.0571575559 -0.0105009502637 +1403638603927829504.0000000000 4.5809382741 10.7650221548 3.4037111397 0.6108619410 0.7894201621 0.0602113141 -0.00617206889389 +1403638603977829376.0000000000 4.5598217156 10.7436789182 3.3945517079 0.6148499656 0.7861654654 0.0624180598 -0.00271414305135 +1403638604027829504.0000000000 4.5378754242 10.7197520853 3.3833715981 0.6154317498 0.7855380636 0.0645898571 0.00136464960591 +1403638604077829376.0000000000 4.5144153846 10.6942114572 3.3727677137 0.6174329549 0.7838118478 0.0662880557 0.00462894438913 +1403638604127829504.0000000000 4.4891129601 10.6663506173 3.3633617833 0.6180473035 0.7832254291 0.0673600338 0.00617119716962 +1403638604177829376.0000000000 4.4656160354 10.6366178443 3.3558341607 0.6176702890 0.7835206308 0.0674151934 0.00583326404093 +1403638604227829504.0000000000 4.4381212747 10.6043767357 3.3515098887 0.6173175427 0.7839856256 0.0654153127 0.00253517526424 +1403638604277829376.0000000000 4.4092749699 10.5693738951 3.3488222590 0.6151250488 0.7859529798 0.0624119418 -0.00195892649048 +1403638604327829504.0000000000 4.3792608229 10.5315230160 3.3473940563 0.6119108563 0.7886690105 0.0593252471 -0.00684185357544 +1403638604377829376.0000000000 4.3492631234 10.4912825811 3.3470862376 0.6076436239 0.7921101185 0.0567211197 -0.0106536850295 +1403638604427829504.0000000000 4.3187527523 10.4490745182 3.3480864604 0.6028127944 0.7958743911 0.0550947984 -0.0128550214308 +1403638604477829376.0000000000 4.2880146887 10.4060346139 3.3506222704 0.5971855792 0.8000951600 0.0553579657 -0.0123537238759 +1403638604527829504.0000000000 4.2567378020 10.3623846879 3.3550999609 0.5927117489 0.8034685020 0.0542748406 -0.0136158225951 +1403638604577829376.0000000000 4.2255159215 10.3179316581 3.3591688125 0.5906494412 0.8049644140 0.0548186277 -0.0126668003117 +1403638604627829504.0000000000 4.1938308512 10.2728996814 3.3619867684 0.5882616661 0.8067521441 0.0538328465 -0.0141850198153 +1403638604677829376.0000000000 4.1619557905 10.2275937655 3.3637261123 0.5873313493 0.8074989615 0.0520520701 -0.0166701930825 +1403638604727829504.0000000000 4.1300752213 10.1819199947 3.3640746381 0.5862849909 0.8083156524 0.0502419328 -0.0192733947802 +1403638604777829376.0000000000 4.0968792844 10.1252495694 3.3609997592 0.5861428075 0.8084610338 0.0486989248 -0.0213490231398 +1403638604827829504.0000000000 4.0647089382 10.0758725156 3.3598996744 0.5845140397 0.8096757527 0.0471359229 -0.0233819928407 +1403638604877829376.0000000000 4.0330152000 10.0259514982 3.3592360128 0.5822984483 0.8112795581 0.0467817163 -0.0237795457409 +1403638604927829504.0000000000 4.0018018459 9.9757628532 3.3593449355 0.5785624172 0.8139571177 0.0465098504 -0.0240036208119 +1403638604977829376.0000000000 3.9704744079 9.9249698575 3.3604269599 0.5734276337 0.8175876067 0.0461728467 -0.0244810642929 +1403638605027829504.0000000000 3.9397311572 9.8748361938 3.3635384159 0.5678449390 0.8214758609 0.0457744700 -0.0251839839765 +1403638605077829376.0000000000 3.9095228115 9.8249843705 3.3691023545 0.5636275413 0.8243746466 0.0456341611 -0.0254550610016 +1403638605127829504.0000000000 3.8799209726 9.7761649433 3.3764663830 0.5593536925 0.8272760914 0.0456632153 -0.0255457659516 +1403638605177829376.0000000000 3.8511211328 9.7302185485 3.3860968265 0.5570028503 0.8288467463 0.0460700617 -0.0252674741235 +1403638605227829504.0000000000 3.8229899913 9.6867896519 3.3965959990 0.5555618214 0.8298054882 0.0470011374 -0.0237656784081 +1403638605277829376.0000000000 3.7950080757 9.6449751749 3.4059343429 0.5543225100 0.8306032059 0.0483225131 -0.0221315154512 +1403638605327829504.0000000000 3.7679236734 9.6057971265 3.4145558859 0.5550760215 0.8300490920 0.0505449337 -0.0188235206458 +1403638605377829376.0000000000 3.7407842898 9.5679697068 3.4218389944 0.5583477525 0.8277282116 0.0540317544 -0.0139414689375 +1403638605427829504.0000000000 3.7133630365 9.5313092387 3.4279137991 0.5625075216 0.8247036813 0.0581139904 -0.00847881735035 +1403638605477829376.0000000000 3.6855709485 9.4960151518 3.4328365730 0.5685725900 0.8202298768 0.0628010862 -0.00204515186961 +1403638605527829504.0000000000 3.6566178127 9.4603925510 3.4362106493 0.5731949091 0.8167460228 0.0660875468 0.00244264159133 +1403638605577829376.0000000000 3.6267355989 9.4249792734 3.4380379295 0.5767867002 0.8138799060 0.0697483296 0.00719524566796 +1403638605627829504.0000000000 3.5954966011 9.3892822527 3.4383917251 0.5798439355 0.8113669019 0.0729729458 0.011819905291 +1403638605677829376.0000000000 3.5623051858 9.3530139894 3.4382408593 0.5819818908 0.8096229593 0.0748889086 0.0141206897608 +1403638605727829504.0000000000 3.5273056401 9.3158758897 3.4388074108 0.5825754722 0.8090436590 0.0761612198 0.0159262580378 +1403638605777829376.0000000000 3.4900624478 9.2782164344 3.4414328290 0.5824050070 0.8091551108 0.0762739197 0.0159594364959 +1403638605827829504.0000000000 3.4505231988 9.2396913377 3.4467926682 0.5813197698 0.8098666334 0.0767782375 0.0169842189998 +1403638605877829376.0000000000 3.4088774628 9.2013397091 3.4538036382 0.5813832090 0.8096859980 0.0778293480 0.0185672177708 +1403638605927829504.0000000000 3.3650137827 9.1636485606 3.4627813395 0.5810040221 0.8098673751 0.0784316087 0.019941008852 +1403638605977829376.0000000000 3.3191641326 9.1264363088 3.4729821554 0.5809814495 0.8096658615 0.0798886097 0.0227938163189 +1403638606027829504.0000000000 3.2713055193 9.0889797381 3.4828185963 0.5806627644 0.8098142476 0.0802870154 0.0241998692234 +1403638606077829376.0000000000 3.2214109247 9.0516414493 3.4915441585 0.5802622337 0.8100421773 0.0805259810 0.0253570009792 +1403638606127829504.0000000000 3.1694231334 9.0144491543 3.4989594195 0.5799097789 0.8101835935 0.0810893300 0.0270502085551 +1403638606177829376.0000000000 3.1154238883 8.9769607723 3.5047082350 0.5794118153 0.8103844475 0.0820454251 0.0287670604633 +1403638606227829504.0000000000 3.0589894499 8.9388984719 3.5087146522 0.5786470413 0.8108565110 0.0823687297 0.0299117459991 +1403638606277829376.0000000000 3.0003385200 8.9010571196 3.5114447461 0.5775854349 0.8116388163 0.0819499550 0.0303595462099 +1403638606327829504.0000000000 2.9387607820 8.8625004232 3.5122345827 0.5750381259 0.8138408201 0.0791073474 0.0271348641416 +1403638606377829376.0000000000 2.8749546178 8.8237822966 3.5111695254 0.5700443390 0.8179583662 0.0744002391 0.0214048386044 +1403638606427829504.0000000000 2.8095196800 8.7854859163 3.5087510390 0.5658717865 0.8213647777 0.0699754346 0.015889043718 +1403638606477829376.0000000000 2.7418321076 8.7459854508 3.5045349854 0.5610211290 0.8252348453 0.0644981687 0.00909555334708 +1403638606527829504.0000000000 2.6735281220 8.7081132489 3.4986185540 0.5563387193 0.8288031621 0.0597078919 0.00274145708416 +1403638606577829376.0000000000 2.6046566984 8.6713841408 3.4910913397 0.5522804899 0.8317005422 0.0570706253 -0.00184724250792 +1403638606627829504.0000000000 2.5350875708 8.6362167919 3.4819996873 0.5487534571 0.8340683873 0.0562076046 -0.00634616386883 +1403638606677829376.0000000000 2.4650824823 8.6027148470 3.4717860963 0.5462374973 0.8355650659 0.0578947536 -0.0101889498873 +1403638606727829504.0000000000 2.3944354459 8.5702612645 3.4590915885 0.5420349552 0.8379769953 0.0617161194 -0.0135566689054 +1403638606777829376.0000000000 2.3234002803 8.5394436504 3.4458378494 0.5397159563 0.8390194265 0.0665261150 -0.0180932195913 +1403638606827829504.0000000000 2.2520525164 8.5105153461 3.4315921144 0.5372287339 0.8399633051 0.0729888761 -0.0227938032276 +1403638606877829376.0000000000 2.1799251667 8.4834283506 3.4173226455 0.5351583104 0.8404752108 0.0796796061 -0.0292944221731 +1403638606927829504.0000000000 2.1077584632 8.4596265738 3.4048053422 0.5342372142 0.8399713212 0.0885164254 -0.034693240101 +1403638606977829376.0000000000 2.0347577176 8.4388799501 3.3933429923 0.5327947258 0.8396377060 0.0967362785 -0.0421947286828 +1403638607027829504.0000000000 1.9619341175 8.4212279179 3.3849505349 0.5327092174 0.8382201163 0.1054437996 -0.0498952054363 +1403638607077829376.0000000000 1.8892494103 8.4059781667 3.3790410082 0.5321654366 0.8370364651 0.1133031764 -0.0577260286331 +1403638607127829504.0000000000 1.8165109275 8.3937383298 3.3756902379 0.5331585953 0.8350999228 0.1171216977 -0.0680627581409 +1403638607177829376.0000000000 1.7443538936 8.3850975967 3.3738600242 0.5377659233 0.8308008258 0.1232998153 -0.0733140856065 +1403638607227829504.0000000000 1.6724473978 8.3784002676 3.3723965242 0.5434836828 0.8258499226 0.1275111670 -0.0796134044291 +1403638607277829376.0000000000 1.6015713788 8.3736831079 3.3699191116 0.5507614181 0.8199325168 0.1321737678 -0.0830820279138 +1403638607327829504.0000000000 1.5311539855 8.3701199665 3.3656310764 0.5556137368 0.8158069678 0.1337343647 -0.0886988525782 +1403638607377829376.0000000000 1.4614189481 8.3675761242 3.3595430423 0.5597715695 0.8122004182 0.1352121581 -0.0932949249224 +1403638607427829504.0000000000 1.3926261981 8.3658520497 3.3512727180 0.5620592299 0.8100257575 0.1367421977 -0.096173102743 +1403638607477829376.0000000000 1.3248263917 8.3646378300 3.3410269276 0.5617450360 0.8098065023 0.1373990301 -0.098880988342 +1403638607527829504.0000000000 1.2582393549 8.3637400002 3.3291682646 0.5618221014 0.8094462569 0.1376454991 -0.101026729927 +1403638607577829376.0000000000 1.1932204665 8.3631819155 3.3156414525 0.5616040642 0.8093508128 0.1390129481 -0.101131287007 +1403638607627829504.0000000000 1.1292354539 8.3629507541 3.3014561126 0.5622047493 0.8087531771 0.1392786746 -0.102203567131 +1403638607677829376.0000000000 1.0663922153 8.3632952047 3.2865019852 0.5635616528 0.8077600055 0.1395898478 -0.102160224006 +1403638607727829504.0000000000 1.0046514231 8.3642700420 3.2713435223 0.5651849373 0.8066611064 0.1404847361 -0.100637393623 +1403638607777829376.0000000000 0.9442629259 8.3655011397 3.2545099569 0.5655171630 0.8065412862 0.1405084154 -0.0996939178987 +1403638607827829504.0000000000 0.8848901176 8.3667879881 3.2367608349 0.5648139080 0.8070915657 0.1399324997 -0.100036740528 +1403638607877829376.0000000000 0.8263308983 8.3684007944 3.2182340134 0.5639550943 0.8078737196 0.1377575856 -0.101575352844 +1403638607927829504.0000000000 0.7688401551 8.3704476210 3.1981818733 0.5613694650 0.8097961841 0.1352247950 -0.1039649885 +1403638607977829376.0000000000 0.7126598524 8.3733395405 3.1771029271 0.5601404860 0.8108188482 0.1330390350 -0.105432663281 +1403638608027829504.0000000000 0.6578676981 8.3773895705 3.1550646823 0.5615139557 0.8100582455 0.1312064377 -0.106266585109 +1403638608077829376.0000000000 0.6047150116 8.3821486141 3.1318608693 0.5637538485 0.8087208369 0.1310729494 -0.104747735389 +1403638608127829504.0000000000 0.5530386400 8.3875145320 3.1071603446 0.5662864380 0.8072045462 0.1312180043 -0.102578390084 +1403638608177829376.0000000000 0.5026828055 8.3932000096 3.0808776636 0.5684205633 0.8059834758 0.1324675679 -0.0986967247039 +1403638608227829504.0000000000 0.4533079760 8.3989749219 3.0538718272 0.5719550231 0.8036426570 0.1331636968 -0.0964020807845 +1403638608277829376.0000000000 0.4050623871 8.4045267362 3.0257611616 0.5753122353 0.8014291954 0.1334196407 -0.0944789722176 +1403638608327829504.0000000000 0.3577108767 8.4098770186 2.9968685168 0.5796755829 0.7984185331 0.1335019385 -0.0931734781803 +1403638608377829376.0000000000 0.3112234713 8.4145685938 2.9666223798 0.5836821186 0.7955693320 0.1342861911 -0.0913884088431 +1403638608427829504.0000000000 0.2655331929 8.4183105413 2.9347616170 0.5847437836 0.7948022468 0.1340281655 -0.0916544976469 +1403638608477829376.0000000000 0.2209527535 8.4210359826 2.9011421103 0.5840710231 0.7953446015 0.1339494945 -0.0913539154715 +1403638608527829504.0000000000 0.1772516289 8.4231503533 2.8658835219 0.5821315285 0.7968061307 0.1339840605 -0.0909458365442 +1403638608577829376.0000000000 0.1345603459 8.4247113035 2.8298559805 0.5819274702 0.7970229424 0.1340412779 -0.0902650792011 +1403638608627829504.0000000000 0.0924345022 8.4257166119 2.7948959849 0.5845418464 0.7952063995 0.1320515803 -0.0923038036385 +1403638608677829376.0000000000 0.0513491076 8.4254878709 2.7616477987 0.5873348423 0.7930661251 0.1313157414 -0.0940217013496 +1403638608727829504.0000000000 0.0115091667 8.4238954928 2.7288021123 0.5890102481 0.7917955441 0.1309574933 -0.0947463923787 +1403638608777829376.0000000000 -0.0269929950 8.4207639720 2.6963314656 0.5872910407 0.7930904936 0.1309769155 -0.0945608273836 +1403638608827829504.0000000000 -0.0645336383 8.4166381053 2.6652578679 0.5848752961 0.7948107017 0.1312659239 -0.0946894594108 +1403638608877829376.0000000000 -0.1010937973 8.4118633053 2.6364021400 0.5821669168 0.7967772192 0.1309791614 -0.0952481137037 +1403638608927829504.0000000000 -0.1364019617 8.4060825028 2.6095183208 0.5791483016 0.7989448096 0.1311034239 -0.0953222333743 +1403638608977829376.0000000000 -0.1704649206 8.3991804569 2.5845982083 0.5763639376 0.8009188846 0.1303747443 -0.0966228633781 +1403638609027829504.0000000000 -0.2036970001 8.3926702030 2.5612751810 0.5741574624 0.8024567889 0.1298936433 -0.097641957543 +1403638609077829376.0000000000 -0.2358594750 8.3865052381 2.5400422320 0.5724971476 0.8036573201 0.1298690473 -0.0975497741235 +1403638609127829504.0000000000 -0.2667818821 8.3800994945 2.5203309005 0.5718530113 0.8041138146 0.1299821768 -0.0974152987534 +1403638609177829376.0000000000 -0.2967772109 8.3740037345 2.5023860299 0.5725828693 0.8035850899 0.1283995455 -0.0995661480612 +1403638609227829504.0000000000 -0.3257589211 8.3677010856 2.4849891733 0.5741913903 0.8023700275 0.1254080578 -0.103823914406 +1403638609277829376.0000000000 -0.3532878687 8.3611198582 2.4661837469 0.5750952607 0.8016615416 0.1229745226 -0.107151671136 +1403638609327829504.0000000000 -0.3789746406 8.3545204234 2.4451944306 0.5751442967 0.8016487847 0.1224454328 -0.107588939804 +1403638609377829376.0000000000 -0.4029447512 8.3480448466 2.4222858268 0.5746959431 0.8020287945 0.1233628900 -0.10609421846 +1403638609427829504.0000000000 -0.4255423147 8.3414679910 2.3978616308 0.5744291537 0.8022806845 0.1242970812 -0.10453270445 +1403638609477829376.0000000000 -0.4466563885 8.3345454407 2.3717060162 0.5738266316 0.8028055484 0.1253557163 -0.102528984689 +1403638609527829504.0000000000 -0.4665881576 8.3276837749 2.3442470014 0.5735126509 0.8030892234 0.1262851780 -0.100910813672 +1403638609577829376.0000000000 -0.4854037769 8.3206062604 2.3149334653 0.5730965138 0.8034632342 0.1272182602 -0.0991096938643 +1403638609627829504.0000000000 -0.5033676139 8.3135383145 2.2845087590 0.5731983287 0.8034162686 0.1271873112 -0.0989412105745 +1403638609677829376.0000000000 -0.5203543421 8.3065727632 2.2523907335 0.5736909238 0.8030459247 0.1290090956 -0.0967089449194 +1403638609727829504.0000000000 -0.5364524836 8.2994596922 2.2202189438 0.5736803121 0.8030934482 0.1296606053 -0.0954983787281 +1403638609777829376.0000000000 -0.5518812954 8.2919635701 2.1889272705 0.5732362557 0.8034004157 0.1296649726 -0.0955769953693 +1403638609827829504.0000000000 -0.5667860047 8.2847993374 2.1593345617 0.5724711617 0.8039318198 0.1290793845 -0.096482696018 +1403638609877829376.0000000000 -0.5805144698 8.2777441228 2.1318559463 0.5730851048 0.8034881313 0.1293452410 -0.096177409798 +1403638609927829504.0000000000 -0.5931022040 8.2701924465 2.1064137900 0.5731657014 0.8034585332 0.1289936085 -0.096416352887 +1403638609977829376.0000000000 -0.6047596546 8.2625944345 2.0822012249 0.5741662008 0.8027510748 0.1287279728 -0.0967108823253 +1403638610027829504.0000000000 -0.6157314537 8.2553954782 2.0604717041 0.5754758309 0.8018005720 0.1278975975 -0.0979061560909 +1403638610077829376.0000000000 -0.6256425241 8.2478302678 2.0410108926 0.5783448089 0.7997639014 0.1271608493 -0.0986159344004 +1403638610127829504.0000000000 -0.6343300170 8.2397216351 2.0225727961 0.5803379717 0.7983026933 0.1267751031 -0.0992407256174 +1403638610177829376.0000000000 -0.6418937424 8.2312598153 2.0038132545 0.5827924850 0.7965649775 0.1274197160 -0.0979865908966 +1403638610227829504.0000000000 -0.6486415570 8.2220596631 1.9842162021 0.5844199964 0.7953448266 0.1268326257 -0.0989614046358 +1403638610277829376.0000000000 -0.6542887959 8.2124287303 1.9630320283 0.5854590106 0.7946507030 0.1259892092 -0.0994722388232 +1403638610327829504.0000000000 -0.6589438565 8.2022607490 1.9402457261 0.5862501819 0.7940618081 0.1259950553 -0.0995078646579 +1403638610377829376.0000000000 -0.6626918337 8.1915999060 1.9159573714 0.5862421798 0.7940767673 0.1254977103 -0.100062574933 +1403638610427829504.0000000000 -0.6652681232 8.1803331662 1.8906541304 0.5873372635 0.7933021448 0.1249991023 -0.100408517363 +1403638610477829376.0000000000 -0.6666772181 8.1684349823 1.8638015087 0.5886192493 0.7923941156 0.1256606636 -0.0992388156633 +1403638610527829504.0000000000 -0.6670568526 8.1557057756 1.8361674551 0.5912320661 0.7905007777 0.1260041082 -0.0983673177114 +1403638610577829376.0000000000 -0.6665526307 8.1419609272 1.8081718382 0.5962419559 0.7867127032 0.1254378556 -0.0992169186797 +1403638610627829504.0000000000 -0.6648837313 8.1267704385 1.7799918759 0.6019439555 0.7823580960 0.1248588065 -0.0999477988263 +1403638610677829376.0000000000 -0.6619053599 8.1092422603 1.7517883217 0.6038748948 0.7808409681 0.1242247445 -0.100949030562 +1403638610727829504.0000000000 -0.6575034738 8.0891694803 1.7238775272 0.6008386822 0.7831076652 0.1248673265 -0.100714514368 +1403638610777829376.0000000000 -0.6516378023 8.0666923475 1.6969288003 0.5958562033 0.7867889443 0.1248779126 -0.101607327879 +1403638610827829504.0000000000 -0.6447146616 8.0435019544 1.6714770250 0.5898489675 0.7911810873 0.1254329262 -0.10186885503 +1403638610877829376.0000000000 -0.6367006488 8.0197629635 1.6491641303 0.5856602775 0.7941627910 0.1263491164 -0.101702514857 +1403638610927829504.0000000000 -0.6278650441 7.9967132208 1.6292577268 0.5844789015 0.7948804892 0.1267657778 -0.102371183601 +1403638610977829376.0000000000 -0.6179108323 7.9730333148 1.6103474125 0.5847632948 0.7946518943 0.1265687278 -0.102764843216 +1403638611027829504.0000000000 -0.6068966585 7.9486464159 1.5912525667 0.5865254586 0.7932904847 0.1255304054 -0.104499811396 +1403638611077829376.0000000000 -0.5944135333 7.9235202397 1.5710245659 0.5890503484 0.7913579644 0.1259198274 -0.104481846978 +1403638611127829504.0000000000 -0.5808049404 7.8975701374 1.5491024652 0.5901049599 0.7904527516 0.1255971381 -0.105763617018 +1403638611177829376.0000000000 -0.5660502982 7.8711773029 1.5253698091 0.5898410036 0.7905318931 0.1264145054 -0.105670663816 +1403638611227829504.0000000000 -0.5500376887 7.8443633290 1.5017956441 0.5901065882 0.7902976729 0.1267045183 -0.105592460845 +1403638611277829376.0000000000 -0.5328822898 7.8170256991 1.4790839682 0.5897133565 0.7905219831 0.1274701028 -0.105188042254 +1403638611327829504.0000000000 -0.5139437938 7.7885023944 1.4576131489 0.5897306813 0.7905432666 0.1291484649 -0.102857868671 +1403638611377829376.0000000000 -0.4935813777 7.7589298017 1.4366705698 0.5907589094 0.7898425507 0.1325228052 -0.097930394418 +1403638611427829504.0000000000 -0.4724240930 7.7291039519 1.4173647519 0.5922791628 0.7887672035 0.1374872067 -0.0902715905277 +1403638611477829376.0000000000 -0.4511738290 7.6984639948 1.4003680879 0.5924129796 0.7886292858 0.1415213991 -0.0841570242713 +1403638611527829504.0000000000 -0.4299234234 7.6663123273 1.3852512726 0.5924002063 0.7885645201 0.1450536810 -0.0786601738102 +1403638611577829376.0000000000 -0.4092001092 7.6324195961 1.3720769554 0.5904500642 0.7900523912 0.1466012415 -0.0754587097193 +1403638611627829504.0000000000 -0.3893080652 7.5971646627 1.3607880435 0.5889426496 0.7912351037 0.1467898517 -0.074473522189 +1403638611677829376.0000000000 -0.3703492118 7.5609965752 1.3504231751 0.5874394756 0.7924337085 0.1461405144 -0.0748774346857 +1403638611727829504.0000000000 -0.3520390906 7.5227298485 1.3398762543 0.5848600629 0.7944728226 0.1436222552 -0.0782578353626 +1403638611777829376.0000000000 -0.3342991835 7.4843554508 1.3280413100 0.5825200067 0.7963357804 0.1401160165 -0.082989569157 +1403638611827829504.0000000000 -0.3165638901 7.4450446260 1.3145673449 0.5802635436 0.7981228981 0.1367968184 -0.0870671574845 +1403638611877829376.0000000000 -0.2987079228 7.4055463000 1.2996813139 0.5777277785 0.8000479720 0.1340123763 -0.090523695446 +1403638611927829504.0000000000 -0.2804656751 7.3651389460 1.2833893343 0.5761189381 0.8013244276 0.1317755138 -0.0927434358285 +1403638611977829376.0000000000 -0.2621287076 7.3251200538 1.2661543807 0.5747943561 0.8022863698 0.1303831461 -0.0945952660837 +1403638612027829504.0000000000 -0.2434372982 7.2853196497 1.2490729386 0.5735352654 0.8032522966 0.1292433879 -0.0955991317477 +1403638612077829376.0000000000 -0.2242928839 7.2457072162 1.2333392669 0.5725481319 0.8040079432 0.1294668324 -0.0948588595402 +1403638612127829504.0000000000 -0.2049667277 7.2059411006 1.2197584045 0.5720033958 0.8044339633 0.1270590962 -0.097745076836 +1403638612177829376.0000000000 -0.1846444119 7.1664784673 1.2073902576 0.5718291465 0.8046123669 0.1275529089 -0.0966468914436 +1403638612227829504.0000000000 -0.1642968263 7.1285439522 1.1975351911 0.5713423023 0.8049915564 0.1269988809 -0.0970971263156 +1403638612277829376.0000000000 -0.1435231628 7.0917389088 1.1897405903 0.5722282471 0.8043768160 0.1269561422 -0.0970304541446 +1403638612327829504.0000000000 -0.1218695895 7.0549169263 1.1833374894 0.5716994521 0.8047701692 0.1273745776 -0.0963349791111 +1403638612377829376.0000000000 -0.0998518325 7.0185745875 1.1775049835 0.5726939186 0.8041692976 0.1276575575 -0.0950629498248 +1403638612427829504.0000000000 -0.0774538858 6.9822151883 1.1710091158 0.5734135394 0.8037222726 0.1275234016 -0.0946847575375 +1403638612477829376.0000000000 -0.0545119934 6.9462275415 1.1629870752 0.5749713412 0.8027729346 0.1274372126 -0.0933987637678 +1403638612527829504.0000000000 -0.0310600063 6.9102025221 1.1531196767 0.5765439655 0.8017832669 0.1281543021 -0.0911982657069 +1403638612577829376.0000000000 -0.0071850103 6.8740974633 1.1415458566 0.5779466283 0.8009197069 0.1287336605 -0.0890671803653 +1403638612627829504.0000000000 0.0167422696 6.8379802283 1.1282121591 0.5781995948 0.8008601091 0.1305004512 -0.0853108814387 +1403638612677829376.0000000000 0.0402673814 6.8021384160 1.1137121330 0.5796352963 0.7999594262 0.1317035067 -0.0821098417805 +1403638612727829504.0000000000 0.0636235684 6.7661086099 1.0977224397 0.5803877216 0.7995746398 0.1321644958 -0.0797686285887 +1403638612777829376.0000000000 0.0867374654 6.7295865766 1.0806555016 0.5814324772 0.7990111607 0.1318903061 -0.0782456810542 +1403638612827829504.0000000000 0.1095340773 6.6923632322 1.0637044788 0.5830040192 0.7980753294 0.1309852821 -0.0776204741071 +1403638612877829376.0000000000 0.1320141872 6.6544337384 1.0474549767 0.5845721210 0.7971087830 0.1301504943 -0.0771613391374 +1403638612927829504.0000000000 0.1538413197 6.6159471789 1.0322931031 0.5852373592 0.7967757142 0.1288647397 -0.0777146930123 +1403638612977829376.0000000000 0.1753153035 6.5769611522 1.0179759789 0.5851875676 0.7969380004 0.1279972390 -0.0778591098827 +1403638613027829504.0000000000 0.1961591184 6.5378992233 1.0057005376 0.5828763553 0.7987165703 0.1270418246 -0.0785326020175 +1403638613077829376.0000000000 0.2168101744 6.4980570796 0.9959675114 0.5823840874 0.7991453925 0.1259233286 -0.0796161517081 +1403638613127829504.0000000000 0.2374233485 6.4580495123 0.9878613481 0.5815658370 0.7998109054 0.1256763492 -0.079304149886 +1403638613177829376.0000000000 0.2577434736 6.4175939230 0.9810763813 0.5795254721 0.8013300609 0.1248210632 -0.0802500024756 +1403638613227829504.0000000000 0.2777431053 6.3778350231 0.9764150817 0.5795647981 0.8013301525 0.1247494277 -0.0800762879046 +1403638613277829376.0000000000 0.2978376861 6.3380097472 0.9736107840 0.5788855162 0.8018543135 0.1248543489 -0.0795777015093 +1403638613327829504.0000000000 0.3175647831 6.2978747500 0.9726255081 0.5785803317 0.8020688565 0.1250201006 -0.0793745781052 +1403638613377829376.0000000000 0.3371477207 6.2576069790 0.9729302153 0.5791875489 0.8016299522 0.1254821515 -0.0786475210333 +1403638613427829504.0000000000 0.3565705772 6.2168572754 0.9725436738 0.5791984260 0.8016189502 0.1257038860 -0.0783248051873 +1403638613477829376.0000000000 0.3757580932 6.1760491952 0.9713958133 0.5805582394 0.8007640421 0.1246318326 -0.0787145850024 +1403638613527829504.0000000000 0.3947865422 6.1354390276 0.9686411454 0.5817712975 0.8002433625 0.1224885210 -0.0784173475731 +1403638613577829376.0000000000 0.4139435154 6.0946028975 0.9644725739 0.5822639154 0.8003719385 0.1201003894 -0.0771322849166 +1403638613627829504.0000000000 0.4324365350 6.0535236455 0.9594338243 0.5840520880 0.7994351300 0.1161091494 -0.079405898893 +1403638613677829376.0000000000 0.4511231953 6.0118619855 0.9523129469 0.5856575606 0.7985804893 0.1135494811 -0.0798807810786 +1403638613727829504.0000000000 0.4697057800 5.9695168114 0.9438115905 0.5894657741 0.7960954189 0.1101832549 -0.0813746613583 +1403638613777829376.0000000000 0.4889706064 5.9262944915 0.9332849252 0.5921058866 0.7946074134 0.1067758303 -0.0812932943632 +1403638613827829504.0000000000 0.5090342355 5.8825141877 0.9206779961 0.5941474984 0.7937850256 0.1031076211 -0.0791384970388 +1403638613877829376.0000000000 0.5298388057 5.8371967746 0.9063389705 0.5955029527 0.7936272396 0.0983944041 -0.0764890787757 +1403638613927829504.0000000000 0.5513339669 5.7915077078 0.8906775778 0.5959040640 0.7943152870 0.0932883136 -0.0725180104929 +1403638613977829376.0000000000 0.5736466160 5.7447334880 0.8741074721 0.5958453401 0.7954942460 0.0869036193 -0.0678601223861 +1403638614027829504.0000000000 0.5967789264 5.6972459076 0.8559323025 0.5957744899 0.7967581434 0.0807120494 -0.0609490213204 +1403638614077829376.0000000000 0.6201444331 5.6492894540 0.8370650627 0.5950641206 0.7984714444 0.0728760702 -0.0550556373398 +1403638614127829504.0000000000 0.6442596448 5.6008172590 0.8177661895 0.5938462315 0.8005351031 0.0650680290 -0.0475010918279 +1403638614177829376.0000000000 0.6686420184 5.5518657843 0.7992642406 0.5917721466 0.8030716113 0.0570645443 -0.0403156477915 +1403638614227829504.0000000000 0.6932332665 5.5025293327 0.7827150572 0.5907562511 0.8046502031 0.0489510707 -0.0338953544465 +1403638614277829376.0000000000 0.7176981215 5.4523313365 0.7671734286 0.5894185359 0.8062494810 0.0411827291 -0.0291812748857 +1403638614327829504.0000000000 0.7419995632 5.4019942967 0.7528719606 0.5880589117 0.8076779638 0.0354992707 -0.0241417654726 +1403638614377829376.0000000000 0.7661465619 5.3508544873 0.7408469342 0.5868078718 0.8089069195 0.0298956650 -0.0207934213961 +1403638614427829504.0000000000 0.7899560908 5.2995345746 0.7313920639 0.5863968909 0.8094365195 0.0242969164 -0.0189965020513 +1403638614477829376.0000000000 0.8138688900 5.2474336040 0.7242219763 0.5858585105 0.8099859217 0.0198149819 -0.0173198969499 +1403638614527829504.0000000000 0.8379868350 5.1948980091 0.7193848687 0.5852733699 0.8105358089 0.0150441159 -0.0161387590737 +1403638614577829376.0000000000 0.8625986058 5.1420861217 0.7158150597 0.5847361982 0.8110460699 0.0103715616 -0.0134269026556 +1403638614627829504.0000000000 0.8873763628 5.0895307945 0.7140581271 0.5849719077 0.8109506370 0.0040266215 -0.0122767192868 +1403638614677829376.0000000000 0.9128093365 5.0375505184 0.7148880529 0.5843217734 0.8114541096 -0.0027304161 -0.0101409050454 +1403638614727829504.0000000000 0.9388810419 4.9855211687 0.7187195647 0.5825643030 0.8126287193 -0.0119659954 -0.0104982138286 +1403638614777829376.0000000000 0.9659918174 4.9326017611 0.7245583912 0.5795712087 0.8145706679 -0.0217628964 -0.00991046921981 +1403638614827829504.0000000000 0.9943824771 4.8793263021 0.7321304226 0.5769376134 0.8161428241 -0.0316857364 -0.00706364436979 +1403638614877829376.0000000000 1.0239882373 4.8260802039 0.7415496207 0.5730862152 0.8184013185 -0.0421205638 -0.00416292503401 +1403638614927829504.0000000000 1.0555153953 4.7744936418 0.7523722451 0.5713958789 0.8190340178 -0.0518094725 0.00240951251843 +1403638614977829376.0000000000 1.0896173977 4.7269306281 0.7648138296 0.5691158585 0.8197788358 -0.0632172255 0.0085663490117 +1403638615027829504.0000000000 1.1251218254 4.6781221775 0.7776736481 0.5680050884 0.8194953705 -0.0742311172 0.0169498843068 +1403638615077829376.0000000000 1.1624039627 4.6298847729 0.7911388027 0.5671721364 0.8187211386 -0.0851910641 0.0274581038022 +1403638615127829504.0000000000 1.2022889870 4.5852787590 0.8065091815 0.5669523637 0.8171738937 -0.0963189879 0.038916542427 +1403638615177829376.0000000000 1.2431989382 4.5388735493 0.8232476965 0.5693993718 0.8134282772 -0.1069918257 0.0516869663707 +1403638615227829504.0000000000 1.2852781392 4.4922214265 0.8411817916 0.5697640138 0.8107900352 -0.1164892552 0.0664736092483 +1403638615277829376.0000000000 1.3277268444 4.4457991252 0.8596837348 0.5706273280 0.8073271345 -0.1277075094 0.0793608373057 +1403638615327829504.0000000000 1.3702359859 4.3988429987 0.8772414237 0.5704716327 0.8041990911 -0.1398951971 0.0908585271627 +1403638615377829376.0000000000 1.4128227217 4.3514312016 0.8934915856 0.5697651256 0.8010251602 -0.1525798441 0.102204626327 +1403638615427829504.0000000000 1.4554128303 4.3041842067 0.9085882785 0.5693721260 0.7973552632 -0.1651248285 0.113021048266 +1403638615477829376.0000000000 1.4979789771 4.2571045334 0.9221267254 0.5680571168 0.7940278733 -0.1776743393 0.123542210134 +1403638615527829504.0000000000 1.5401369856 4.2098200223 0.9340839509 0.5659289018 0.7911686954 -0.1900720851 0.132850201042 +1403638615577829376.0000000000 1.5818751831 4.1625265882 0.9447291458 0.5646449016 0.7879043399 -0.2014108076 0.140771349248 +1403638615627829504.0000000000 1.6230459578 4.1151021522 0.9541519221 0.5630304198 0.7853476720 -0.2103889287 0.148196758359 +1403638615677829376.0000000000 1.6634976837 4.0678355393 0.9634683416 0.5613994862 0.7832905528 -0.2181914795 0.153879839944 +1403638615727829504.0000000000 1.7033577350 4.0207987676 0.9741361472 0.5603311334 0.7813793797 -0.2247072055 0.158056817805 +1403638615777829376.0000000000 1.7427003008 3.9738761448 0.9867814116 0.5593382701 0.7797967639 -0.2301951152 0.161455614926 +1403638615827829504.0000000000 1.7816597763 3.9265862972 1.0015190460 0.5583398512 0.7783517748 -0.2351952919 0.164645983528 +1403638615877829376.0000000000 1.8201846438 3.8790076425 1.0174330412 0.5576322538 0.7765280594 -0.2415507299 0.166444247266 +1403638615927829504.0000000000 1.8587241485 3.8314023130 1.0328135623 0.5570038491 0.7744767582 -0.2472310440 0.169732948658 +1403638615977829376.0000000000 1.8970567399 3.7836050743 1.0468138461 0.5546922077 0.7734946200 -0.2531073882 0.173087485489 +1403638616027829504.0000000000 1.9353795110 3.7355879473 1.0597600561 0.5536874648 0.7714138406 -0.2587494798 0.177199279274 +1403638616077829376.0000000000 1.9735545877 3.6872181682 1.0707019987 0.5522011398 0.7694143723 -0.2646480955 0.181760310578 +1403638616127829504.0000000000 2.0116262081 3.6387120502 1.0794261482 0.5504650370 0.7674178340 -0.2707112529 0.186476616998 +1403638616177829376.0000000000 2.0494784415 3.5899769865 1.0841422123 0.5483741101 0.7651969981 -0.2780897319 0.190854631885 +1403638616227829504.0000000000 2.0873458221 3.5409018004 1.0845611578 0.5463134615 0.7624790811 -0.2863599179 0.195359284654 +1403638616277829376.0000000000 2.1255478116 3.4917174229 1.0807557907 0.5441239567 0.7592598731 -0.2952610746 0.200684983565 +1403638616327829504.0000000000 2.1634750945 3.4418743010 1.0726378605 0.5413160127 0.7560958000 -0.3042065377 0.206771608459 +1403638616377829376.0000000000 2.2015905496 3.3919252356 1.0618302793 0.5386296429 0.7525975636 -0.3133317747 0.212833770909 +1403638616427829504.0000000000 2.2394446046 3.3417598456 1.0489039640 0.5357356421 0.7494458671 -0.3218717075 0.218441795431 +1403638616477829376.0000000000 2.2769122614 3.2922731696 1.0344205501 0.5335668873 0.7463002906 -0.3300657558 0.222258520163 +1403638616527829504.0000000000 2.3140696813 3.2424951844 1.0192499380 0.5305935117 0.7442338686 -0.3365194788 0.226585777629 +1403638616577829376.0000000000 2.3509857178 3.1926782893 1.0032734403 0.5271430119 0.7430956803 -0.3422120475 0.229825954623 +1403638616627829504.0000000000 2.3884833687 3.1442549256 0.9850436924 0.5230759929 0.7427717457 -0.3476390014 0.23201026725 +1403638616677829376.0000000000 2.4252720141 3.0948627498 0.9667722997 0.5179999986 0.7437623224 -0.3527719831 0.232476960636 +1403638616727829504.0000000000 2.4618928671 3.0460363427 0.9464702940 0.5120141831 0.7458462139 -0.3591173236 0.229324332271 +1403638616777829376.0000000000 2.4988897265 2.9976068651 0.9254146925 0.5066860022 0.7478808622 -0.3653061670 0.224710737401 +1403638616827829504.0000000000 2.5369816783 2.9497650109 0.9038822961 0.5024707473 0.7495335995 -0.3703707652 0.220336169504 +1403638616877829376.0000000000 2.5767380027 2.9024399285 0.8827474487 0.4993812116 0.7507804179 -0.3736167630 0.217618206982 +1403638616927829504.0000000000 2.6185431022 2.8553405991 0.8632542319 0.4993578823 0.7504320142 -0.3736827018 0.218757253176 +1403638616977829376.0000000000 2.6626930335 2.8085478729 0.8459637698 0.5001729569 0.7499369977 -0.3706967158 0.223619001022 +1403638617027829504.0000000000 2.7088119671 2.7627808531 0.8310547648 0.5017179100 0.7491482612 -0.3679022330 0.227385066464 +1403638617077829376.0000000000 2.7561806609 2.7175584026 0.8187008262 0.5035952293 0.7483453766 -0.3646374137 0.231107331877 +1403638617127829504.0000000000 2.8045969872 2.6725007529 0.8081297109 0.5049284054 0.7480174462 -0.3601025717 0.236311962123 +1403638617177829376.0000000000 2.8535218860 2.6284655783 0.7998945315 0.5057706830 0.7481850906 -0.3571135584 0.238505750006 +1403638617227829504.0000000000 2.9031922503 2.5853102940 0.7930761500 0.5042038008 0.7499566674 -0.3547296032 0.239813329213 +1403638617277829376.0000000000 2.9531081477 2.5431261691 0.7879963841 0.5021613675 0.7521605073 -0.3535770198 0.238897097756 +1403638617327829504.0000000000 3.0038540356 2.5020349229 0.7845690467 0.5002918492 0.7540592193 -0.3531442444 0.237469791769 +1403638617377829376.0000000000 3.0551846969 2.4619645902 0.7825396714 0.4968219328 0.7570390390 -0.3523522749 0.236448165132 +1403638617427829504.0000000000 3.1069629000 2.4234191949 0.7827493700 0.4944022456 0.7593254703 -0.3512385327 0.235844743171 +1403638617477829376.0000000000 3.1590648101 2.3862869278 0.7850472259 0.4931964909 0.7608406320 -0.3503785037 0.23476298299 +1403638617527829504.0000000000 3.2120800609 2.3507722461 0.7889931511 0.4921459003 0.7622224796 -0.3488411103 0.234774751876 +1403638617577829376.0000000000 3.2648822052 2.3150335306 0.7972971738 0.4923316202 0.7626486987 -0.3479302875 0.234352412335 +1403638617627829504.0000000000 3.3188134666 2.2821071941 0.8059640266 0.4928963418 0.7628717534 -0.3460949029 0.23515569791 +1403638617677829376.0000000000 3.3733967708 2.2508944669 0.8168435251 0.4940208099 0.7628232032 -0.3438324226 0.236269899148 +1403638617727829504.0000000000 3.4273139561 2.2200073287 0.8312090284 0.4948229447 0.7628245227 -0.3415744197 0.23785692517 +1403638617777829376.0000000000 3.4822424374 2.1916550672 0.8469541046 0.4962995994 0.7623570702 -0.3407576895 0.237450209848 +1403638617827829504.0000000000 3.5378275286 2.1645391332 0.8637956385 0.4949677756 0.7637419122 -0.3390433951 0.238232594133 +1403638617877829376.0000000000 3.5940249894 2.1392604900 0.8832571436 0.4959590602 0.7636435395 -0.3376853997 0.238415028787 +1403638617927829504.0000000000 3.6505791051 2.1159594304 0.9043070293 0.4972504148 0.7630836912 -0.3376463397 0.237571577506 +1403638617977829376.0000000000 3.7075873020 2.0942880928 0.9249261446 0.4982007400 0.7629033825 -0.3369515357 0.237145765651 +1403638618027829504.0000000000 3.7650446024 2.0741030633 0.9441659395 0.4983711020 0.7631090896 -0.3364045114 0.236902441629 +1403638618077829376.0000000000 3.8230824903 2.0554931970 0.9620683110 0.4990319082 0.7630690334 -0.3356746845 0.23667553984 +1403638618127829504.0000000000 3.8816043596 2.0383981454 0.9781624373 0.4990339059 0.7634187535 -0.3360516583 0.235002660513 +1403638618177829376.0000000000 3.9409546549 2.0226067841 0.9929471262 0.4997672508 0.7632964747 -0.3356728288 0.234382035595 +1403638618227829504.0000000000 4.0006841334 2.0079102797 1.0058272663 0.4996571997 0.7636405542 -0.3348850868 0.234622601848 +1403638618277829376.0000000000 4.0604339951 1.9945392473 1.0173740428 0.4996400580 0.7638924951 -0.3342127772 0.234797546524 +1403638618327829504.0000000000 4.1200671074 1.9821884921 1.0278471446 0.5005303964 0.7635708874 -0.3332396700 0.235329863093 +1403638618377829376.0000000000 4.1798109377 1.9712617472 1.0374935081 0.5008067988 0.7636097870 -0.3329721932 0.234993961694 +1403638618427829504.0000000000 4.2397862401 1.9614191155 1.0463966083 0.5008122924 0.7638755346 -0.3321877732 0.235228609641 +1403638618477829376.0000000000 4.2997008148 1.9528234952 1.0545763173 0.5008012285 0.7642164541 -0.3317963227 0.234696700052 +1403638618527829504.0000000000 4.3596596377 1.9456150974 1.0624455995 0.5018797117 0.7638074005 -0.3309110429 0.234974236124 +1403638618577829376.0000000000 4.4197425413 1.9392539263 1.0697272460 0.5017933817 0.7635604594 -0.3306680783 0.236299489966 +1403638618627829504.0000000000 4.4797771206 1.9339209556 1.0766646926 0.5012541243 0.7627380541 -0.3324638024 0.237576900858 +1403638618677829376.0000000000 4.5399140372 1.9295782191 1.0833629355 0.5002790108 0.7622489063 -0.3334213282 0.239849398908 +1403638618727829504.0000000000 4.5997529041 1.9264674892 1.0914131018 0.4998209910 0.7616135644 -0.3344105842 0.241440089214 +1403638618777829376.0000000000 4.6599338640 1.9250118018 1.1011475776 0.5000725966 0.7603707830 -0.3360878411 0.242504914506 +1403638618827829504.0000000000 4.7200819923 1.9248929276 1.1124980521 0.5007654608 0.7590064589 -0.3376338157 0.243200648064 +1403638618877829376.0000000000 4.7806171076 1.9257233433 1.1256104350 0.5010866498 0.7574471328 -0.3385099098 0.246164683463 +1403638618927829504.0000000000 4.8414313997 1.9278762041 1.1398544567 0.5021520026 0.7544569659 -0.3415763253 0.248925022694 +1403638618977829376.0000000000 4.9024350102 1.9308347349 1.1531956998 0.5036437513 0.7501988172 -0.3452660011 0.253645609172 +1403638619027829504.0000000000 4.9634308923 1.9344565097 1.1646465460 0.5037238089 0.7459453369 -0.3503917214 0.258946944998 +1403638619077829376.0000000000 5.0242725019 1.9384618419 1.1737926718 0.5021670648 0.7416169575 -0.3565798724 0.265863352246 +1403638619127829504.0000000000 5.0850191441 1.9430545119 1.1821001921 0.5009113881 0.7364334302 -0.3636928035 0.272912309736 +1403638619177829376.0000000000 5.1456313454 1.9484221878 1.1882446866 0.4986672251 0.7311199891 -0.3727048594 0.279080002784 +1403638619227829504.0000000000 5.2061117920 1.9547233586 1.1928413869 0.4967226101 0.7247205424 -0.3824067183 0.286027770971 +1403638619277829376.0000000000 5.2660461842 1.9614092534 1.1952704244 0.4937114163 0.7183615503 -0.3935270885 0.29213378978 +1403638619327829504.0000000000 5.3254393908 1.9680317851 1.1947331774 0.4900353592 0.7118089909 -0.4040113377 0.299946905709 +1403638619377829376.0000000000 5.3830550205 1.9745289881 1.1918802117 0.4869978940 0.7049143713 -0.4144788792 0.306815969388 +1403638619427829504.0000000000 5.4393878658 1.9815410891 1.1879721260 0.4846780395 0.6986002882 -0.4238774081 0.312046115687 +1403638619477829376.0000000000 5.4943290117 1.9890160563 1.1833701158 0.4824046028 0.6929574863 -0.4324915103 0.316301778219 +1403638619527829504.0000000000 5.5480241503 1.9972594718 1.1783796980 0.4812798910 0.6879072084 -0.4393537574 0.319564727517 +1403638619577829376.0000000000 5.6009747133 2.0057931658 1.1723823464 0.4797340461 0.6836535279 -0.4456907656 0.322231035666 +1403638619627829504.0000000000 5.6515442749 2.0141470136 1.1652662003 0.4797126646 0.6792983206 -0.4525701813 0.321884734076 +1403638619677829376.0000000000 5.7019832213 2.0228757064 1.1578621062 0.4818153295 0.6743515470 -0.4596724524 0.319069296198 +1403638619727829504.0000000000 5.7516521753 2.0307896982 1.1492044328 0.4819980045 0.6713098139 -0.4653954066 0.316904043848 +1403638619777829376.0000000000 5.8009181215 2.0379912392 1.1402979360 0.4834939239 0.6678441901 -0.4695195624 0.315862539371 +1403638619827829504.0000000000 5.8498948042 2.0442708310 1.1305196829 0.4841984294 0.6653389780 -0.4726885397 0.315343415746 +1403638619877829376.0000000000 5.8984316923 2.0493239569 1.1199059448 0.4843859485 0.6634869727 -0.4747235570 0.315900038616 +1403638619927829504.0000000000 5.9468741383 2.0531749949 1.1085851986 0.4843337345 0.6619985488 -0.4767689387 0.31602236324 +1403638619977829376.0000000000 5.9954742786 2.0557096134 1.0964133804 0.4835825720 0.6613104446 -0.4778064708 0.317044741993 +1403638620027829504.0000000000 6.0439704053 2.0567907297 1.0844129389 0.4838639615 0.6600759679 -0.4781368996 0.31868556383 +1403638620077829376.0000000000 6.0926344917 2.0566970220 1.0734091398 0.4851498273 0.6583710177 -0.4783263381 0.319970564857 +1403638620127829504.0000000000 6.1405563606 2.0548239229 1.0639601839 0.4855193743 0.6574115759 -0.4771759415 0.32308524863 +1403638620177829376.0000000000 6.1881636867 2.0517180256 1.0566326763 0.4868499411 0.6558726508 -0.4761860319 0.325660964408 +1403638620227829504.0000000000 6.2350685960 2.0471732020 1.0508669832 0.4869936620 0.6554985930 -0.4758434986 0.326698228712 +1403638620277829376.0000000000 6.2810533836 2.0409715425 1.0466427487 0.4849434217 0.6568577557 -0.4752833983 0.327831447363 +1403638620327829504.0000000000 6.3264156243 2.0335048840 1.0446999617 0.4834008256 0.6579530954 -0.4741168568 0.329597591281 +1403638620377829376.0000000000 6.3709016473 2.0249462461 1.0450540796 0.4822906009 0.6589426054 -0.4737877348 0.329720489765 +1403638620427829504.0000000000 6.4147047762 2.0153121246 1.0472937425 0.4817534402 0.6596359229 -0.4729311149 0.330348653018 +1403638620477829376.0000000000 6.4577642751 2.0047245154 1.0503767376 0.4808733542 0.6608118081 -0.4722257033 0.330289958418 +1403638620527829504.0000000000 6.5004816880 1.9934018691 1.0531617545 0.4804213479 0.6616415957 -0.4713889474 0.330481750786 +1403638620577829376.0000000000 6.5424952817 1.9812712958 1.0552465365 0.4798146382 0.6626933475 -0.4712649061 0.329431067764 +1403638620627829504.0000000000 6.5842068254 1.9685940193 1.0559182204 0.4789007501 0.6640027664 -0.4714905299 0.327797312408 +1403638620677829376.0000000000 6.6255393510 1.9551659268 1.0553459093 0.4781823530 0.6651551787 -0.4720865718 0.32564473616 +1403638620727829504.0000000000 6.6661595594 1.9409254430 1.0531126418 0.4766857472 0.6668097645 -0.4732713298 0.322722302887 +1403638620777829376.0000000000 6.7064955349 1.9260568116 1.0496930223 0.4756343523 0.6682423903 -0.4736614639 0.32073180114 +1403638620827829504.0000000000 6.7469076795 1.9104544411 1.0450972470 0.4738528185 0.6702294713 -0.4730412418 0.320137385674 +1403638620877829376.0000000000 6.7870351487 1.8936621464 1.0393459770 0.4710257471 0.6728721708 -0.4706067230 0.322346241857 +1403638620927829504.0000000000 6.8273402424 1.8769518831 1.0331429136 0.4703853374 0.6742115269 -0.4681296474 0.324084995806 +1403638620977829376.0000000000 6.8676774549 1.8599773062 1.0257077851 0.4694528381 0.6756091790 -0.4652914456 0.326603950918 +1403638621027829504.0000000000 6.9079845240 1.8427851100 1.0179404855 0.4704713570 0.6756500020 -0.4623843847 0.329172383025 +1403638621077829376.0000000000 6.9477546049 1.8254148455 1.0104244708 0.4709363247 0.6759777627 -0.4600229842 0.331137277231 +1403638621127829504.0000000000 6.9864786270 1.8083257576 1.0043761782 0.4724522723 0.6757090536 -0.4592191172 0.330641690826 +1403638621177829376.0000000000 7.0248494567 1.7914070029 1.0000686420 0.4737903768 0.6755243811 -0.4579295361 0.330892776249 +1403638621227829504.0000000000 7.0629887398 1.7748377036 0.9974910728 0.4752989005 0.6751588852 -0.4564901940 0.331463629447 +1403638621277829376.0000000000 7.1011229939 1.7585797178 0.9968571149 0.4758792502 0.6753744771 -0.4551617215 0.332018165497 +1403638621327829504.0000000000 7.1383032882 1.7421136024 0.9975823523 0.4745979845 0.6766790605 -0.4539672962 0.332830131116 +1403638621377829376.0000000000 7.1750941482 1.7261516152 0.9980991491 0.4745824732 0.6773150818 -0.4526742584 0.333319324232 +1403638621427829504.0000000000 7.2109867738 1.7102796396 0.9975445982 0.4767247111 0.6763616765 -0.4516348786 0.333608106742 +1403638621477829376.0000000000 7.2460055444 1.6942887805 0.9952821591 0.4771811779 0.6763598654 -0.4501357802 0.334982440259 +1403638621527829504.0000000000 7.2802663365 1.6787698917 0.9919191405 0.4794455464 0.6753954322 -0.4486510141 0.335686230999 +1403638621577829376.0000000000 7.3132606789 1.6633981204 0.9872528638 0.4805378261 0.6751072664 -0.4474617538 0.336290879219 +1403638621627829504.0000000000 7.3456107702 1.6484676723 0.9817268058 0.4819930834 0.6743854791 -0.4467598316 0.336589581032 +1403638621677829376.0000000000 7.3767615879 1.6334229518 0.9746882679 0.4822491948 0.6745989025 -0.4461929121 0.336547054841 +1403638621727829504.0000000000 7.4069169867 1.6185164039 0.9668646798 0.4832092479 0.6739960326 -0.4454850951 0.337314690996 +1403638621777829376.0000000000 7.4360828387 1.6035364117 0.9580291913 0.4841569556 0.6735178407 -0.4444557258 0.338267450922 +1403638621827829504.0000000000 7.4642339188 1.5883456436 0.9484785288 0.4857078783 0.6724384663 -0.4431784647 0.339863523257 +1403638621877829376.0000000000 7.4908451476 1.5731079196 0.9381644419 0.4879108957 0.6709803646 -0.4415237893 0.341738279608 +1403638621927829504.0000000000 7.5157836389 1.5578377476 0.9269410188 0.4895846420 0.6698350247 -0.4404584517 0.342963949024 +1403638621977829376.0000000000 7.5392116737 1.5427020533 0.9150618726 0.4910178728 0.6688567607 -0.4400243498 0.343381207832 +1403638622027829504.0000000000 7.5611149607 1.5275248249 0.9022227095 0.4919245467 0.6683946255 -0.4399885481 0.343029069435 +1403638622077829376.0000000000 7.5815246375 1.5123523836 0.8883376196 0.4921156729 0.6680788540 -0.4409328872 0.342156394625 +1403638622127829504.0000000000 7.6003768784 1.4971547192 0.8735908586 0.4920689086 0.6682049067 -0.4422601658 0.340259221233 +1403638622177829376.0000000000 7.6172104811 1.4817020008 0.8586438156 0.4922035892 0.6683264927 -0.4430815791 0.338753657024 +1403638622227829504.0000000000 7.6328663785 1.4658663015 0.8449435287 0.4925603740 0.6678969031 -0.4440156153 0.337858162838 +1403638622277829376.0000000000 7.6470519904 1.4499410738 0.8328459818 0.4939794085 0.6668733850 -0.4450957438 0.336383726139 +1403638622327829504.0000000000 7.6595287884 1.4331145781 0.8217505864 0.4933401750 0.6671528328 -0.4458949103 0.335708651039 +1403638622377829376.0000000000 7.6704312484 1.4157532440 0.8128419899 0.4922770675 0.6676074573 -0.4459292692 0.33631928091 +1403638622427829504.0000000000 7.6792943291 1.3975015818 0.8063782256 0.4910422702 0.6681784161 -0.4456369888 0.337376299266 +1403638622477829376.0000000000 7.6868791403 1.3786716703 0.8018286907 0.4897183610 0.6689110590 -0.4447122145 0.339064843687 +1403638622527829504.0000000000 7.6930669618 1.3595044047 0.7985582038 0.4896535838 0.6686400047 -0.4445363292 0.339922585344 +1403638622577829376.0000000000 7.6979937145 1.3400940496 0.7962899613 0.4883871089 0.6691749196 -0.4433804940 0.342193945681 +1403638622627829504.0000000000 7.7014817076 1.3207504401 0.7962803739 0.4894016757 0.6681050009 -0.4415967240 0.34512902074 +1403638622677829376.0000000000 7.7031517669 1.3012319849 0.7989060769 0.4917204909 0.6659694196 -0.4403035661 0.347603884826 +1403638622727829504.0000000000 7.7029518024 1.2814660245 0.8052531885 0.4977498480 0.6612161626 -0.4371895094 0.351999443168 +1403638622777829376.0000000000 7.7012039118 1.2619092462 0.8143333762 0.5040611030 0.6559948165 -0.4349980843 0.355485403141 +1403638622827829504.0000000000 7.6976643234 1.2423182120 0.8245476396 0.5082505881 0.6523661131 -0.4332448103 0.358327683164 +1403638622877829376.0000000000 7.6913409124 1.2222736504 0.8345133511 0.5089212427 0.6516335514 -0.4328869999 0.359140263341 +1403638622927829504.0000000000 7.6816998245 1.2015801240 0.8445579455 0.5081899755 0.6519495121 -0.4344162646 0.357753115317 +1403638622977829376.0000000000 7.6691306979 1.1800600903 0.8531991846 0.5047452869 0.6543134379 -0.4364935336 0.355780150484 +1403638623027829504.0000000000 7.6538407889 1.1581647433 0.8604858134 0.5017255172 0.6565730845 -0.4394773437 0.35219732323 +1403638623077829376.0000000000 7.6363470264 1.1355584963 0.8662845490 0.4981297501 0.6591672471 -0.4421127337 0.349144129443 +1403638623127829504.0000000000 7.6168804454 1.1124640543 0.8709222606 0.4961648294 0.6606391542 -0.4449064435 0.345593151837 +1403638623177829376.0000000000 7.5954111722 1.0887873447 0.8746542131 0.4952189405 0.6615121742 -0.4470595598 0.342487363686 +1403638623227829504.0000000000 7.5724343100 1.0644787724 0.8769735855 0.4939356688 0.6624356326 -0.4487595726 0.340325482165 +1403638623277829376.0000000000 7.5482186925 1.0394980076 0.8778626825 0.4921889718 0.6638007816 -0.4505198039 0.337861576254 +1403638623327829504.0000000000 7.5230574373 1.0141569495 0.8777993453 0.4905602176 0.6649711863 -0.4517493179 0.336283434101 +1403638623377829376.0000000000 7.4970930376 0.9883341689 0.8764818025 0.4897384181 0.6656299807 -0.4530956808 0.334361054302 +1403638623427829504.0000000000 7.4704714725 0.9618323476 0.8737544871 0.4869923289 0.6675165651 -0.4528465527 0.334947916255 +1403638623477829376.0000000000 7.4430467286 0.9354306278 0.8709876997 0.4872933905 0.6672459664 -0.4535715205 0.334067130502 +1403638623527829504.0000000000 7.4149407458 0.9087206307 0.8684607191 0.4868311251 0.6676893102 -0.4538505054 0.333475875242 +1403638623577829376.0000000000 7.3862877167 0.8814705988 0.8675683989 0.4865497487 0.6676196636 -0.4529753440 0.335211372955 +1403638623627829504.0000000000 7.3574015106 0.8539288182 0.8685698795 0.4863096233 0.6675749806 -0.4524598478 0.336343101118 +1403638623677829376.0000000000 7.3279143545 0.8259959218 0.8717093267 0.4852487003 0.6682214948 -0.4526986419 0.336270237319 +1403638623727829504.0000000000 7.2981771025 0.7977722493 0.8770352358 0.4845077042 0.6683275479 -0.4523984668 0.337529555062 +1403638623777829376.0000000000 7.2675008664 0.7692053219 0.8833606773 0.4827481838 0.6692431648 -0.4528338140 0.337652653434 +1403638623827829504.0000000000 7.2361053476 0.7403920348 0.8917342360 0.4825286419 0.6692101336 -0.4524469167 0.338549397172 +1403638623877829376.0000000000 7.2032575638 0.7110716649 0.9005379544 0.4804681706 0.6702585436 -0.4533155505 0.338243748587 +1403638623927829504.0000000000 7.1700448210 0.6819020604 0.9092654692 0.4792291663 0.6705524961 -0.4536744031 0.338937003024 +1403638623977829376.0000000000 7.1365164549 0.6528881117 0.9168652921 0.4779463668 0.6710738194 -0.4542118572 0.33899673762 +1403638624027829504.0000000000 7.1027385494 0.6241378720 0.9234157579 0.4778959480 0.6706654759 -0.4550943967 0.338692149975 +1403638624077829376.0000000000 7.0682969385 0.5955860667 0.9283453119 0.4777105578 0.6703356349 -0.4569218578 0.337142663287 +1403638624127829504.0000000000 7.0339681027 0.5671365233 0.9325981027 0.4777541162 0.6700169278 -0.4579721091 0.336288370707 +1403638624177829376.0000000000 6.9991054696 0.5386055939 0.9355113680 0.4784806764 0.6692541825 -0.4593170411 0.334937214037 +1403638624227829504.0000000000 6.9640234794 0.5098489655 0.9370242634 0.4784190747 0.6688525177 -0.4607034645 0.333921871728 +1403638624277829376.0000000000 6.9285837034 0.4810335045 0.9377260920 0.4792770469 0.6679662574 -0.4616859129 0.333107653984 +1403638624327829504.0000000000 6.8933681060 0.4521162355 0.9373313050 0.4793750370 0.6674040561 -0.4623154465 0.333220389016 +1403638624377829376.0000000000 6.8581696463 0.4231041338 0.9354861412 0.4795913702 0.6668411667 -0.4631626439 0.332859341595 +1403638624427829504.0000000000 6.8227568874 0.3936565621 0.9323166384 0.4793439999 0.6666462621 -0.4634620083 0.333189222191 +1403638624477829376.0000000000 6.7878411284 0.3636595097 0.9275239843 0.4789351941 0.6664565170 -0.4634189858 0.334214952281 +1403638624527829504.0000000000 6.7526209497 0.3339442067 0.9233094331 0.4832838840 0.6627960456 -0.4645353449 0.333683986304 +1403638624577829376.0000000000 6.7183969030 0.3039849027 0.9184265949 0.4906238992 0.6568991074 -0.4649576068 0.334045170765 +1403638624627829504.0000000000 6.6830125255 0.2732018413 0.9124408626 0.4960342012 0.6527869446 -0.4633462804 0.336347291734 +1403638624677829376.0000000000 6.6477507618 0.2411460919 0.9048226244 0.4956265538 0.6537003828 -0.4613416785 0.337926004191 +1403638624727829504.0000000000 6.6108507550 0.2079771525 0.8977671636 0.4924646082 0.6575517446 -0.4579861717 0.339636540029 +1403638624777829376.0000000000 6.5726810287 0.1742079994 0.8918394901 0.4883360070 0.6628057712 -0.4543550751 0.340261545965 +1403638624827829504.0000000000 6.5340900184 0.1405767735 0.8882718248 0.4845497815 0.6676505003 -0.4516434492 0.339812468134 +1403638624877829376.0000000000 6.4939196251 0.1066035846 0.8873808265 0.4820996449 0.6715266288 -0.4489145522 0.339275174566 +1403638624927829504.0000000000 6.4530017243 0.0730304162 0.8881840389 0.4817745462 0.6738763261 -0.4483166999 0.33585133673 +1403638624977829376.0000000000 6.4111971315 0.0397799699 0.8908259057 0.4826441255 0.6753181407 -0.4482540202 0.331765565228 +1403638625027829504.0000000000 6.3694642481 0.0066290665 0.8938505812 0.4842834362 0.6760056966 -0.4473923520 0.329129055197 +1403638625077829376.0000000000 6.3276060817 -0.0264306082 0.8958871679 0.4858203834 0.6766295899 -0.4478526825 0.324929112136 +1403638625127829504.0000000000 6.2855733371 -0.0597018248 0.8972061190 0.4873068300 0.6768072105 -0.4484017174 0.321558630964 +1403638625177829376.0000000000 6.2434696171 -0.0932267142 0.8970908479 0.4880401412 0.6774365326 -0.4484478356 0.319047180919 +1403638625227829504.0000000000 6.2013055977 -0.1270300134 0.8956914871 0.4882454895 0.6782253435 -0.4480832556 0.31756593252 +1403638625277829376.0000000000 6.1591812238 -0.1612035216 0.8936194894 0.4884372131 0.6788093221 -0.4473282501 0.317087416606 +1403638625327829504.0000000000 6.1173722004 -0.1955953524 0.8913547577 0.4888752295 0.6790677223 -0.4468849369 0.316483635637 +1403638625377829376.0000000000 6.0758386613 -0.2303020861 0.8896667208 0.4891013473 0.6793221421 -0.4464659095 0.316179523331 +1403638625427829504.0000000000 6.0347709930 -0.2653664703 0.8895590725 0.4896164917 0.6793720656 -0.4457252834 0.316319868659 +1403638625477829376.0000000000 5.9936372184 -0.3007281969 0.8913583364 0.4904226618 0.6789387280 -0.4459534611 0.31567915196 +1403638625527829504.0000000000 5.9528492098 -0.3364431623 0.8941452940 0.4899865692 0.6793709486 -0.4452175095 0.316464287653 +1403638625577829376.0000000000 5.9119251906 -0.3726114314 0.8983637816 0.4895119751 0.6797102214 -0.4455095001 0.316059055408 +1403638625627829504.0000000000 5.8716405501 -0.4089232579 0.9044520681 0.4878301812 0.6808241062 -0.4455642014 0.316184745332 +1403638625677829376.0000000000 5.8319123382 -0.4450910074 0.9127552224 0.4873313354 0.6812563971 -0.4460478951 0.31533976301 +1403638625727829504.0000000000 5.7921684183 -0.4817668505 0.9210455906 0.4844098772 0.6832911543 -0.4473560454 0.313580672161 +1403638625777829376.0000000000 5.7527364477 -0.5186472651 0.9286939875 0.4817412183 0.6850979332 -0.4487220841 0.311792738455 +1403638625827829504.0000000000 5.7140025955 -0.5555010224 0.9351261969 0.4788051770 0.6869897312 -0.4498772965 0.310485313476 +1403638625877829376.0000000000 5.6763171067 -0.5921313458 0.9407951281 0.4780112088 0.6874104131 -0.4500403511 0.310541286548 +1403638625927829504.0000000000 5.6393887250 -0.6287462633 0.9453224179 0.4768354596 0.6880322295 -0.4500283056 0.310988938436 +1403638625977829376.0000000000 5.6031932428 -0.6651193889 0.9488987865 0.4768150453 0.6877401113 -0.4503324210 0.311226063241 +1403638626027829504.0000000000 5.5674388704 -0.7014665541 0.9508292231 0.4755888928 0.6883468888 -0.4512683185 0.310404043944 +1403638626077829376.0000000000 5.5323992521 -0.7376703476 0.9518001534 0.4754370638 0.6882785217 -0.4524795733 0.309021861232 +1403638626127829504.0000000000 5.4986787955 -0.7734507394 0.9515844703 0.4754304688 0.6880360747 -0.4532037346 0.308510298194 +1403638626177829376.0000000000 5.4657693992 -0.8091368959 0.9499479058 0.4746583660 0.6884908567 -0.4530093238 0.308969785571 +1403638626227829504.0000000000 5.4336195614 -0.8447432234 0.9471513767 0.4749140741 0.6881345921 -0.4525737902 0.310007048017 +1403638626277829376.0000000000 5.4021462914 -0.8803363109 0.9431701092 0.4753862324 0.6876033475 -0.4511814774 0.312481745108 +1403638626327829504.0000000000 5.3714019344 -0.9159167076 0.9380193167 0.4750251826 0.6877395597 -0.4482502923 0.316918048245 +1403638626377829376.0000000000 5.3409494469 -0.9508349778 0.9321839492 0.4749311964 0.6877232460 -0.4455894849 0.320822546729 +1403638626427829504.0000000000 5.3106506889 -0.9849658964 0.9257766371 0.4757974853 0.6872298635 -0.4436140993 0.323323984055 +1403638626477829376.0000000000 5.2802660552 -1.0186409605 0.9181543246 0.4757623607 0.6873534070 -0.4431060360 0.32380937429 +1403638626527829504.0000000000 5.2500607306 -1.0519317655 0.9099786870 0.4736375680 0.6889568979 -0.4427861589 0.323954108748 +1403638626577829376.0000000000 5.2198952357 -1.0844963903 0.9015622609 0.4725073250 0.6898642209 -0.4431230785 0.323212193266 +1403638626627829504.0000000000 5.1898768725 -1.1164475233 0.8932737840 0.4713437144 0.6906439062 -0.4442466170 0.32170023467 +1403638626677829376.0000000000 5.1602707420 -1.1477417136 0.8853058149 0.4705219135 0.6915069791 -0.4442063527 0.321104255599 +1403638626727829504.0000000000 5.1311470351 -1.1782542613 0.8780800112 0.4682975450 0.6930361061 -0.4459761214 0.318596396847 +1403638626777829376.0000000000 5.1031194298 -1.2078605893 0.8723098642 0.4662528000 0.6945243096 -0.4472482988 0.316564794374 +1403638626827829504.0000000000 5.0767073569 -1.2363414143 0.8690658653 0.4646468970 0.6956726283 -0.4480844721 0.315219227174 +1403638626877829376.0000000000 5.0514005270 -1.2642188104 0.8675025382 0.4628745347 0.6971230453 -0.4480727470 0.314638583557 +1403638626927829504.0000000000 5.0273647233 -1.2908913818 0.8681856427 0.4616532718 0.6979816839 -0.4484598004 0.313977121685 +1403638626977829376.0000000000 5.0042136966 -1.3165295734 0.8696622929 0.4619755179 0.6979027531 -0.4485381815 0.313566369096 +1403638627027829504.0000000000 4.9819310777 -1.3414351107 0.8705478923 0.4619515244 0.6981114813 -0.4483402382 0.31342013277 +1403638627077829376.0000000000 4.9604438799 -1.3654629268 0.8703275290 0.4622798312 0.6981506577 -0.4482373691 0.312995651333 +1403638627127829504.0000000000 4.9399642716 -1.3886530589 0.8693449336 0.4626854289 0.6979874236 -0.4481224204 0.312924985707 +1403638627177829376.0000000000 4.9202220721 -1.4112035152 0.8673111628 0.4628299141 0.6980960422 -0.4481323291 0.312454480125 +1403638627227829504.0000000000 4.9015738007 -1.4331021000 0.8646154973 0.4632055177 0.6979706109 -0.4479095084 0.312497595158 +1403638627277829376.0000000000 4.8837732610 -1.4543214910 0.8609132269 0.4624070159 0.6986019471 -0.4468989188 0.313713926225 +1403638627327829504.0000000000 4.8669500010 -1.4746354977 0.8568238240 0.4622702418 0.6988334530 -0.4458032744 0.314956297094 +1403638627377829376.0000000000 4.8508297912 -1.4942099866 0.8520735647 0.4625467065 0.6987336943 -0.4449409272 0.315989461946 +1403638627427829504.0000000000 4.8356282634 -1.5128510207 0.8462946517 0.4620239846 0.6991138348 -0.4447885851 0.316127819349 +1403638627477829376.0000000000 4.8213021487 -1.5304594759 0.8402370944 0.4619572575 0.6992157742 -0.4448035654 0.315978767619 +1403638627527829504.0000000000 4.8078496048 -1.5472346472 0.8339208032 0.4625800249 0.6987034117 -0.4449290546 0.316024365282 +1403638627577829376.0000000000 4.7950789060 -1.5630712920 0.8271356505 0.4629369484 0.6982779214 -0.4440057205 0.317736127106 +1403638627627829504.0000000000 4.7829217355 -1.5781716089 0.8203993440 0.4639259074 0.6973320931 -0.4427601487 0.320100226487 +1403638627677829376.0000000000 4.7714306637 -1.5923304888 0.8136063436 0.4661032770 0.6957215135 -0.4421712825 0.321253587806 +1403638627727829504.0000000000 4.7603882644 -1.6057099315 0.8064807326 0.4676127817 0.6945592294 -0.4414140400 0.322613404246 +1403638627777829376.0000000000 4.7494286240 -1.6184118704 0.7987281008 0.4678546996 0.6942875486 -0.4406667330 0.323866655209 +1403638627827829504.0000000000 4.7387019941 -1.6302971582 0.7911118280 0.4688242752 0.6934196275 -0.4406260617 0.324378934271 +1403638627877829376.0000000000 4.7282453840 -1.6413484097 0.7829304674 0.4682144753 0.6936552271 -0.4404265081 0.325026340424 +1403638627927829504.0000000000 4.7178031057 -1.6516907142 0.7746544112 0.4668269923 0.6945106513 -0.4410022444 0.324414141094 +1403638627977829376.0000000000 4.7076117105 -1.6613330870 0.7662675423 0.4653407225 0.6954303414 -0.4412235626 0.324278306555 +1403638628027829504.0000000000 4.6977656750 -1.6700986955 0.7583402413 0.4640509131 0.6959803318 -0.4414983917 0.324572484832 +1403638628077829376.0000000000 4.6879704119 -1.6779067345 0.7508854015 0.4632577609 0.6963445762 -0.4418288952 0.324474506884 +1403638628127829504.0000000000 4.6784848298 -1.6847623559 0.7438271728 0.4623024907 0.6966595001 -0.4423344208 0.324472199571 +1403638628177829376.0000000000 4.6695621401 -1.6905720763 0.7371984835 0.4617243233 0.6966777906 -0.4425055848 0.325022326602 +1403638628227829504.0000000000 4.6608811609 -1.6952298817 0.7311067121 0.4617705449 0.6964768467 -0.4430400799 0.324658980255 +1403638628277829376.0000000000 4.6527985306 -1.6991032846 0.7255802339 0.4611650172 0.6966169329 -0.4432272213 0.324963545592 +1403638628327829504.0000000000 4.6453895482 -1.7015085340 0.7207714404 0.4608119628 0.6966602914 -0.4443420186 0.323847099465 +1403638628377829376.0000000000 4.6383598257 -1.7030186007 0.7168032547 0.4607987912 0.6965590412 -0.4448491761 0.323387054092 +1403638628427829504.0000000000 4.6318242200 -1.7031516498 0.7134928592 0.4623034856 0.6955035581 -0.4461247568 0.321749886154 +1403638628477829376.0000000000 4.6258587011 -1.7021851920 0.7115053626 0.4667422718 0.6922621257 -0.4482029467 0.319435313522 +1403638628527829504.0000000000 4.6204008863 -1.7005504830 0.7109936518 0.4731971929 0.6877495236 -0.4499177186 0.317268113486 +1403638628577829376.0000000000 4.6151244295 -1.6989390083 0.7109245299 0.4792466665 0.6834973576 -0.4509669990 0.315884093623 +1403638628627829504.0000000000 4.6100226572 -1.6974710387 0.7115373743 0.4843438099 0.6796908720 -0.4518322326 0.315085743686 +1403638628677829376.0000000000 4.6046470547 -1.6966738320 0.7115044178 0.4864479213 0.6782550766 -0.4532662016 0.312870934179 +1403638628727829504.0000000000 4.5993646222 -1.6969353083 0.7105950563 0.4858685188 0.6785946657 -0.4532888330 0.313002070342 +1403638628777829376.0000000000 4.5942001412 -1.6980975945 0.7081360592 0.4842025664 0.6795685845 -0.4530298414 0.313844509948 +1403638628827829504.0000000000 4.5894138552 -1.7000053216 0.7042317415 0.4825893180 0.6806528780 -0.4519502370 0.315531604058 +1403638628877829376.0000000000 4.5851047152 -1.7024744080 0.6989439343 0.4817624261 0.6811110380 -0.4506670421 0.317634909652 +1403638628927829504.0000000000 4.5810675304 -1.7053399448 0.6929306150 0.4807068218 0.6815918680 -0.4497416041 0.319508945727 +1403638628977829376.0000000000 4.5769822838 -1.7083880732 0.6870002527 0.4789851146 0.6827786692 -0.4481710531 0.321759624688 +1403638629027829504.0000000000 4.5729666000 -1.7113407396 0.6817583214 0.4775233597 0.6837804378 -0.4469150924 0.323546988863 +1403638629077829376.0000000000 4.5688227257 -1.7142863864 0.6772334335 0.4757156387 0.6850896052 -0.4453904399 0.325536818137 +1403638629127829504.0000000000 4.5646312817 -1.7168629123 0.6734774896 0.4745498295 0.6860186041 -0.4448421601 0.326031266499 +1403638629177829376.0000000000 4.5603424049 -1.7192129622 0.6703102957 0.4733177884 0.6869291661 -0.4439763283 0.327083493603 +1403638629227829504.0000000000 4.5556874992 -1.7212091936 0.6679307426 0.4726172759 0.6875363391 -0.4438152950 0.327039258832 +1403638629277829376.0000000000 4.5509620737 -1.7228292791 0.6665793438 0.4727482811 0.6875192825 -0.4433756318 0.32748182844 +1403638629327829504.0000000000 4.5460053927 -1.7242423113 0.6654800376 0.4709546945 0.6885262684 -0.4435479548 0.327717050596 +1403638629377829376.0000000000 4.5405762763 -1.7249798102 0.6645785401 0.4681153322 0.6903606783 -0.4446133842 0.32647987415 +1403638629427829504.0000000000 4.5354076625 -1.7250381110 0.6639629076 0.4655081326 0.6920140723 -0.4459078119 0.324938341184 +1403638629477829376.0000000000 4.5302927629 -1.7243620796 0.6633523352 0.4624175808 0.6938926067 -0.4478733429 0.322633693267 +1403638629527829504.0000000000 4.5255941813 -1.7228575841 0.6630796078 0.4601182975 0.6953820602 -0.4500497860 0.319671914387 +1403638629577829376.0000000000 4.5219810882 -1.7201609188 0.6634980956 0.4595626329 0.6956729898 -0.4516033116 0.317640876934 +1403638629627829504.0000000000 4.5190855272 -1.7165092737 0.6648174432 0.4622484905 0.6936474486 -0.4552764083 0.312894458528 +1403638629677829376.0000000000 4.5171083973 -1.7124477180 0.6668648460 0.4662399825 0.6906787223 -0.4586713361 0.308551108709 +1403638629727829504.0000000000 4.5164538783 -1.7083001937 0.6695085341 0.4711566360 0.6870357304 -0.4610519972 0.305654028715 +1403638629777829376.0000000000 4.5170755594 -1.7044597771 0.6720410711 0.4759271549 0.6834836542 -0.4616746765 0.305286636895 +1403638629827829504.0000000000 4.5186561449 -1.7010068535 0.6735766733 0.4803764301 0.6802108775 -0.4619118538 0.305268876376 +1403638629877829376.0000000000 4.5212582235 -1.6982690621 0.6734969345 0.4847777541 0.6768629129 -0.4609607569 0.307184483473 +1403638629927829504.0000000000 4.5247079503 -1.6967177687 0.6705542341 0.4864547366 0.6754065273 -0.4571773993 0.313331514185 +1403638629977829376.0000000000 4.5284807513 -1.6961776275 0.6652038831 0.4880110010 0.6740791875 -0.4526088139 0.32032448155 +1403638630027829504.0000000000 4.5317561179 -1.6966340586 0.6577126853 0.4900208802 0.6725137400 -0.4483223992 0.326514674875 +1403638630077829376.0000000000 4.5345378966 -1.6974455620 0.6471226386 0.4892580039 0.6728982008 -0.4456116636 0.330552359323 +1403638630127829504.0000000000 4.5363045111 -1.6984371302 0.6338697769 0.4871095135 0.6745466954 -0.4441057710 0.332387035973 +1403638630177829376.0000000000 4.5371237466 -1.6994803052 0.6191479730 0.4841927384 0.6767155670 -0.4433934364 0.333190176982 +1403638630227829504.0000000000 4.5367147051 -1.7008236311 0.6027432501 0.4809526121 0.6791118544 -0.4436622141 0.332649235487 +1403638630277829376.0000000000 4.5363082295 -1.7020266518 0.5847651651 0.4780085033 0.6812212501 -0.4443801458 0.331619910832 +1403638630327829504.0000000000 4.5355028558 -1.7033476467 0.5652803058 0.4710317062 0.6854731339 -0.4456598927 0.331123805544 +1403638630377829376.0000000000 4.5357493620 -1.7000535388 0.5588233861 0.4538180723 0.6991028232 -0.4522099169 0.317506835931 +1403638630427829504.0000000000 4.5405138938 -1.6943831239 0.5650889335 0.4693237918 0.6889837948 -0.4539886423 0.314532703448 +1403638630477829376.0000000000 4.5464684943 -1.6902271408 0.5709906549 0.4788344185 0.6828182091 -0.4442994108 0.327223053173 +1403638630527829504.0000000000 4.5508949603 -1.6863154345 0.5725110996 0.4788095743 0.6826836728 -0.4437154655 0.328330595755 diff --git a/data/euroc_groundtruth/V1_01_easy.txt b/data/euroc_groundtruth/V1_01_easy.txt new file mode 100755 index 00000000..981336f1 --- /dev/null +++ b/data/euroc_groundtruth/V1_01_easy.txt @@ -0,0 +1,2872 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403715274312143104.0000000000 0.8687393558 2.2070275302 0.9257726725 0.4259596512 0.6262011737 -0.5441421096 0.361026079545 +1403715274362142976.0000000000 0.8691033299 2.2061947719 0.9256472293 0.4259403229 0.6261063148 -0.5441748130 0.361164085649 +1403715274412143104.0000000000 0.8693648353 2.2055550838 0.9255692117 0.4258371731 0.6261730257 -0.5442021227 0.361128915443 +1403715274462142976.0000000000 0.8695852871 2.2051432993 0.9255480440 0.4258848709 0.6260224315 -0.5443200517 0.361156023422 +1403715274512143104.0000000000 0.8697087755 2.2048731526 0.9255085442 0.4258841322 0.6262328711 -0.5440339412 0.361223155228 +1403715274562142976.0000000000 0.8697613444 2.2047771590 0.9255325015 0.4260009065 0.6261932119 -0.5441235745 0.361019147279 +1403715274612143104.0000000000 0.8697750289 2.2047088262 0.9255397116 0.4260703795 0.6262367730 -0.5440090116 0.361034252072 +1403715274662142976.0000000000 0.8698110062 2.2046846689 0.9255249065 0.4259791602 0.6262786477 -0.5439174156 0.361207219538 +1403715274712143104.0000000000 0.8697598745 2.2047787792 0.9256188575 0.4262045754 0.6260968063 -0.5439590617 0.361193837466 +1403715274762142976.0000000000 0.8697574351 2.2048802415 0.9256004091 0.4261057224 0.6260827089 -0.5440007454 0.36127211891 +1403715274812143104.0000000000 0.8697769664 2.2050028696 0.9256114190 0.4261366092 0.6260066783 -0.5440845900 0.361241176903 +1403715274862142976.0000000000 0.8697276497 2.2050993607 0.9256334050 0.4262027941 0.6259287580 -0.5441196857 0.361245257209 +1403715274912143104.0000000000 0.8697095377 2.2052939037 0.9256165910 0.4262176857 0.6259154849 -0.5441583043 0.361192511166 +1403715274962142976.0000000000 0.8697107648 2.2054559648 0.9256241203 0.4262906082 0.6258756256 -0.5442420710 0.361049285853 +1403715275012143104.0000000000 0.8696795453 2.2056134407 0.9256739613 0.4263311253 0.6258142510 -0.5442970316 0.361024980119 +1403715275062142976.0000000000 0.8696018254 2.2057909216 0.9256932636 0.4263806245 0.6257926611 -0.5443083865 0.360986826351 +1403715275112143104.0000000000 0.8695932276 2.2059105888 0.9257035883 0.4264222451 0.6257659882 -0.5443687426 0.360892877331 +1403715275162142976.0000000000 0.8695763962 2.2059719462 0.9257185918 0.4263973458 0.6257714731 -0.5443946246 0.360873744808 +1403715275212143104.0000000000 0.8695388514 2.2060079611 0.9257791408 0.4264729238 0.6257110989 -0.5444146844 0.360858860729 +1403715275262142976.0000000000 0.8695416609 2.2060576064 0.9257923326 0.4265148449 0.6256688055 -0.5444933648 0.360763923578 +1403715275312143104.0000000000 0.8695360814 2.2060870695 0.9257901711 0.4265528851 0.6256322257 -0.5445318421 0.360724309405 +1403715275362142976.0000000000 0.8695145347 2.2061060944 0.9257694308 0.4265449402 0.6256456426 -0.5445391123 0.360699458178 +1403715275412143104.0000000000 0.8695089389 2.2060930407 0.9257456809 0.4265647547 0.6256229782 -0.5445617620 0.360681142644 +1403715275462142976.0000000000 0.8695065127 2.2060654764 0.9257443406 0.4265787637 0.6256007579 -0.5445586045 0.360707882363 +1403715275512143104.0000000000 0.8695298564 2.2060556327 0.9257574333 0.4265935056 0.6255564328 -0.5446076917 0.360693211038 +1403715275562142976.0000000000 0.8695373885 2.2060053972 0.9257347863 0.4266184513 0.6255057215 -0.5446410018 0.360701356383 +1403715275612143104.0000000000 0.8695048653 2.2059316201 0.9256947421 0.4265920184 0.6255101547 -0.5446852307 0.360658142315 +1403715275662142976.0000000000 0.8694744558 2.2058992746 0.9256694586 0.4266266395 0.6254910751 -0.5447113585 0.360610817058 +1403715275712143104.0000000000 0.8694759165 2.2058916596 0.9256164932 0.4266480698 0.6255327276 -0.5446860695 0.360551406694 +1403715275762142976.0000000000 0.8694808821 2.2058715527 0.9255846602 0.4266735127 0.6255276031 -0.5447047535 0.360501959534 +1403715275812143104.0000000000 0.8694877466 2.2058210611 0.9255684159 0.4266882435 0.6255016377 -0.5447422146 0.360472972222 +1403715275862142976.0000000000 0.8695027622 2.2057557850 0.9256134978 0.4268293774 0.6254026573 -0.5446856908 0.360563027816 +1403715275912143104.0000000000 0.8695064686 2.2057207266 0.9257204888 0.4268859737 0.6253193424 -0.5446770151 0.360653621476 +1403715275962142976.0000000000 0.8694398023 2.2057069178 0.9259780034 0.4272643800 0.6250607147 -0.5444635308 0.360976060251 +1403715276012143104.0000000000 0.8694776160 2.2057300484 0.9261698742 0.4273674425 0.6249205800 -0.5445404896 0.360980599248 +1403715276062142976.0000000000 0.8695250432 2.2057683284 0.9262217182 0.4271350910 0.6250900705 -0.5445893461 0.360888434122 +1403715276112143104.0000000000 0.8696242879 2.2057870386 0.9260768560 0.4269471029 0.6252570114 -0.5446938304 0.360663932317 +1403715276162142976.0000000000 0.8695811705 2.2058031721 0.9259404822 0.4271041616 0.6251249153 -0.5447315157 0.360650039833 +1403715276212143104.0000000000 0.8695265774 2.2057747985 0.9258470059 0.4269827609 0.6252435380 -0.5447017713 0.360633082811 +1403715276262142976.0000000000 0.8695283598 2.2057591606 0.9257715003 0.4270209839 0.6251952603 -0.5447775231 0.360557091571 +1403715276312143104.0000000000 0.8695430596 2.2057213412 0.9256510523 0.4269855439 0.6252243658 -0.5448093035 0.360500569372 +1403715276362142976.0000000000 0.8695333796 2.2057117866 0.9256466572 0.4269538262 0.6252438880 -0.5448429736 0.360453388018 +1403715276412143104.0000000000 0.8694896517 2.2057320055 0.9256815744 0.4269470383 0.6252600498 -0.5448734950 0.360387251448 +1403715276462142976.0000000000 0.8694401617 2.2057653814 0.9257195709 0.4269843874 0.6252317556 -0.5448314869 0.360455594376 +1403715276512143104.0000000000 0.8693011260 2.2057910128 0.9259869399 0.4273665883 0.6250553137 -0.5446699567 0.36055275936 +1403715276562142976.0000000000 0.8692265926 2.2057178136 0.9261961984 0.4272349525 0.6250852986 -0.5447451779 0.360543140191 +1403715276612143104.0000000000 0.8692164666 2.2056779864 0.9260778135 0.4270969890 0.6251877557 -0.5448175248 0.360419612027 +1403715276662142976.0000000000 0.8691783149 2.2056672740 0.9259607426 0.4271156000 0.6251841877 -0.5448293374 0.360385888603 +1403715276712143104.0000000000 0.8690416108 2.2056514115 0.9260283652 0.4271783326 0.6251784833 -0.5447052692 0.360508953962 +1403715276762142976.0000000000 0.8689167877 2.2055540390 0.9261616224 0.4274341457 0.6250422675 -0.5446397333 0.36054094879 +1403715276812143104.0000000000 0.8689940549 2.2054434173 0.9261529341 0.4273088431 0.6251067683 -0.5447242848 0.360449905505 +1403715276862142976.0000000000 0.8691205060 2.2053500143 0.9262460948 0.4272821177 0.6251027409 -0.5447356444 0.36047140381 +1403715276912143104.0000000000 0.8692363327 2.2055429308 0.9263479943 0.4275282703 0.6249552426 -0.5446221181 0.360606809869 +1403715276962142976.0000000000 0.8694342770 2.2058115131 0.9264091286 0.4276747627 0.6248600992 -0.5444587167 0.360844647275 +1403715277012143104.0000000000 0.8696236618 2.2059679894 0.9266123305 0.4278201851 0.6247605820 -0.5444541580 0.360851457355 +1403715277062142976.0000000000 0.8700057771 2.2058457682 0.9266714458 0.4276043036 0.6249087981 -0.5445393736 0.360722087254 +1403715277112143104.0000000000 0.8703669939 2.2057725790 0.9266868077 0.4276819006 0.6248768272 -0.5444358817 0.360841673683 +1403715277162142976.0000000000 0.8708201437 2.2058063051 0.9267478303 0.4276508198 0.6249561900 -0.5443787291 0.360827294292 +1403715277212143104.0000000000 0.8707574619 2.2057769775 0.9269343520 0.4277425298 0.6248548071 -0.5445380364 0.360653746852 +1403715277262142976.0000000000 0.8704606850 2.2056331885 0.9269381999 0.4274933472 0.6249479574 -0.5445322445 0.36079651228 +1403715277312143104.0000000000 0.8700810716 2.2055384952 0.9268643184 0.4274180502 0.6249290498 -0.5447129990 0.360645590254 +1403715277362142976.0000000000 0.8695702168 2.2054742001 0.9268844824 0.4272308457 0.6250904561 -0.5445760593 0.360794459297 +1403715277412143104.0000000000 0.8690493994 2.2054078348 0.9269312782 0.4274097506 0.6249749524 -0.5445687619 0.360793677151 +1403715277462142976.0000000000 0.8686596319 2.2052969095 0.9268473407 0.4275812325 0.6248678714 -0.5445764362 0.360764380222 +1403715277512143104.0000000000 0.8689049516 2.2053364727 0.9269776227 0.4274512925 0.6249389467 -0.5446285191 0.360716622336 +1403715277562142976.0000000000 0.8691105926 2.2052854385 0.9272863617 0.4275358251 0.6249484413 -0.5443656228 0.360996721006 +1403715277612143104.0000000000 0.8692889589 2.2052908540 0.9272069603 0.4275344642 0.6250068947 -0.5444391591 0.360786177041 +1403715277662142976.0000000000 0.8695771154 2.2053433415 0.9272475714 0.4276894120 0.6248722331 -0.5444854338 0.36076595123 +1403715277712143104.0000000000 0.8696279707 2.2052900224 0.9275500772 0.4276621982 0.6249528012 -0.5444045249 0.360780755856 +1403715277762142976.0000000000 0.8696146365 2.2053551197 0.9277772099 0.4277756264 0.6248965944 -0.5443789052 0.360782299163 +1403715277812143104.0000000000 0.8695206061 2.2053280588 0.9276435347 0.4275392141 0.6250922543 -0.5441653002 0.361045731216 +1403715277862142976.0000000000 0.8694615808 2.2051066438 0.9275550658 0.4275035146 0.6250197349 -0.5446391968 0.360498573118 +1403715277912143104.0000000000 0.8694153604 2.2048905278 0.9276950177 0.4272524146 0.6252564547 -0.5442380523 0.360991249805 +1403715277962142976.0000000000 0.8694332881 2.2047352274 0.9280033510 0.4276461052 0.6250383284 -0.5442261010 0.360920833044 +1403715278012143104.0000000000 0.8696323881 2.2045281633 0.9280984562 0.4275012831 0.6251696946 -0.5443811909 0.360630870647 +1403715278062142976.0000000000 0.8698018156 2.2045599054 0.9280399783 0.4274771816 0.6252367274 -0.5441381913 0.360909853953 +1403715278112143104.0000000000 0.8699207684 2.2047514760 0.9282154357 0.4276618210 0.6250244547 -0.5440582327 0.361179231599 +1403715278162142976.0000000000 0.8700876099 2.2050201539 0.9284372775 0.4276586668 0.6251226843 -0.5442414351 0.360736683285 +1403715278212143104.0000000000 0.8704029906 2.2051637918 0.9284757707 0.4277864293 0.6251089578 -0.5440987749 0.360824174507 +1403715278262142976.0000000000 0.8702995514 2.2052097048 0.9282723685 0.4277372038 0.6249898355 -0.5438445054 0.361471636518 +1403715278312143104.0000000000 0.8702653439 2.2052672696 0.9286694653 0.4278103604 0.6243019262 -0.5442555047 0.3619548951 +1403715278362142976.0000000000 0.8703622862 2.2051476091 0.9294179822 0.4277321150 0.6235252885 -0.5444532984 0.363086846772 +1403715278412143104.0000000000 0.8708207527 2.2051795622 0.9301646980 0.4274049186 0.6232228945 -0.5444620668 0.363977083356 +1403715278462142976.0000000000 0.8723348895 2.2057901098 0.9310349993 0.4285647408 0.6218091732 -0.5447677004 0.364573405115 +1403715278512143104.0000000000 0.8750917799 2.2069771447 0.9321762497 0.4299106730 0.6201374095 -0.5447561997 0.365851184906 +1403715278562142976.0000000000 0.8791483777 2.2089433096 0.9350705015 0.4334191202 0.6169573477 -0.5439682182 0.368252732415 +1403715278612143104.0000000000 0.8842869498 2.2114391537 0.9399381553 0.4369311037 0.6138478918 -0.5431969317 0.370430924339 +1403715278662142976.0000000000 0.8904270234 2.2144524940 0.9468184971 0.4376532235 0.6130779324 -0.5420946855 0.372462691805 +1403715278712143104.0000000000 0.8975052812 2.2183291242 0.9570613639 0.4402331184 0.6108676600 -0.5424756345 0.372499247504 +1403715278762142976.0000000000 0.9054323518 2.2224753777 0.9704680994 0.4437171718 0.6081986604 -0.5419550854 0.373489151686 +1403715278812143104.0000000000 0.9137361710 2.2267330647 0.9861705274 0.4462479370 0.6064455185 -0.5412847631 0.37429589512 +1403715278862142976.0000000000 0.9223647718 2.2309425869 1.0043522497 0.4493335573 0.6043917886 -0.5404198563 0.375175024577 +1403715278912143104.0000000000 0.9304926779 2.2347412430 1.0233080973 0.4500145011 0.6039743920 -0.5401339195 0.375442714142 +1403715278962142976.0000000000 0.9381452083 2.2383112521 1.0417256202 0.4504961830 0.6035863653 -0.5395755839 0.376290948641 +1403715279012143104.0000000000 0.9452606290 2.2414589946 1.0563603072 0.4502177335 0.6037684473 -0.5389260291 0.377261699049 +1403715279062142976.0000000000 0.9517637487 2.2446141162 1.0659779441 0.4498372849 0.6040446502 -0.5388332847 0.377405841165 +1403715279112143104.0000000000 0.9579898541 2.2476501666 1.0702966254 0.4497441747 0.6040807919 -0.5386062526 0.377782846165 +1403715279162142976.0000000000 0.9635460385 2.2505729261 1.0695497651 0.4490408947 0.6047993103 -0.5381824012 0.378073765554 +1403715279212143104.0000000000 0.9685106852 2.2531736505 1.0655800760 0.4480662640 0.6055611156 -0.5380675126 0.378174179829 +1403715279262142976.0000000000 0.9733639770 2.2557828286 1.0608579498 0.4475912828 0.6061932276 -0.5379252421 0.377926247283 +1403715279312143104.0000000000 0.9776649525 2.2582108796 1.0562781501 0.4469019076 0.6068035706 -0.5383134847 0.377209098406 +1403715279362142976.0000000000 0.9814980792 2.2604337758 1.0528127023 0.4464426389 0.6070973591 -0.5391179553 0.376129760864 +1403715279412143104.0000000000 0.9850130008 2.2625135496 1.0506811982 0.4469494337 0.6068961385 -0.5395382258 0.375248962253 +1403715279462142976.0000000000 0.9881015011 2.2640573769 1.0494038901 0.4463986818 0.6074651083 -0.5400226409 0.374285861793 +1403715279512143104.0000000000 0.9909593802 2.2653990657 1.0496097885 0.4464624301 0.6075731911 -0.5402307970 0.373733597645 +1403715279562142976.0000000000 0.9937423396 2.2665889201 1.0508705038 0.4462181629 0.6078337163 -0.5397252203 0.374331685875 +1403715279612143104.0000000000 0.9960904129 2.2675749799 1.0531890722 0.4456674870 0.6081751603 -0.5399430791 0.374118880472 +1403715279662142976.0000000000 0.9980832392 2.2682131358 1.0563464177 0.4454704183 0.6084848206 -0.5398838169 0.373935547619 +1403715279712143104.0000000000 1.0001309899 2.2686834569 1.0603323773 0.4456695102 0.6083210574 -0.5397889806 0.374101637482 +1403715279762142976.0000000000 1.0019071609 2.2690208739 1.0652577464 0.4456524925 0.6083661623 -0.5398568628 0.373950579869 +1403715279812143104.0000000000 1.0032807992 2.2690157306 1.0708731000 0.4457004072 0.6082225735 -0.5402150055 0.373609683945 +1403715279862142976.0000000000 1.0041970775 2.2686431121 1.0771213728 0.4454773414 0.6084890067 -0.5402638257 0.373371217106 +1403715279912143104.0000000000 1.0049799906 2.2681493868 1.0840319328 0.4449135981 0.6088281667 -0.5405167987 0.373124301097 +1403715279962142976.0000000000 1.0056276004 2.2675433915 1.0911307888 0.4430736263 0.6101592045 -0.5412630088 0.372056262111 +1403715280012143104.0000000000 1.0060496693 2.2669088815 1.0978069639 0.4394439201 0.6127371562 -0.5434279348 0.368955686016 +1403715280062142976.0000000000 1.0066403386 2.2662603840 1.1041541790 0.4347930788 0.6161331576 -0.5459498545 0.365066661165 +1403715280112143104.0000000000 1.0079466628 2.2653417519 1.1104562908 0.4288245689 0.6203322788 -0.5468501370 0.363665066589 +1403715280162142976.0000000000 1.0102629583 2.2646022192 1.1174763003 0.4250037440 0.6232497845 -0.5466006057 0.363537207985 +1403715280212143104.0000000000 1.0136805950 2.2640153334 1.1249514539 0.4216127389 0.6257770777 -0.5446442008 0.366071634972 +1403715280262142976.0000000000 1.0181737901 2.2640899672 1.1331698725 0.4197504886 0.6271074942 -0.5422246865 0.369510632415 +1403715280312143104.0000000000 1.0234806882 2.2652496516 1.1417453712 0.4190842233 0.6276834682 -0.5398826719 0.372704411073 +1403715280362142976.0000000000 1.0295451181 2.2673944857 1.1506758163 0.4192324066 0.6273258467 -0.5378104267 0.376120215265 +1403715280412143104.0000000000 1.0363942698 2.2704072206 1.1596057704 0.4193354600 0.6261070209 -0.5365293411 0.379847385971 +1403715280462142976.0000000000 1.0438759782 2.2744925438 1.1686750103 0.4203134639 0.6233257031 -0.5384463641 0.380627341237 +1403715280512143104.0000000000 1.0520847976 2.2794976583 1.1778038809 0.4223143801 0.6180385903 -0.5426983317 0.380995257148 +1403715280562142976.0000000000 1.0606022314 2.2851656948 1.1867093888 0.4234403275 0.6122121490 -0.5477138959 0.381973902097 +1403715280612143104.0000000000 1.0695720745 2.2909072633 1.1953391299 0.4238613664 0.6053115632 -0.5536233940 0.38397993588 +1403715280662142976.0000000000 1.0790896993 2.2964354433 1.2034048116 0.4220669345 0.5983793603 -0.5599433243 0.387640448764 +1403715280712143104.0000000000 1.0887783656 2.3019574779 1.2109588665 0.4197762136 0.5906958360 -0.5670530196 0.391557445157 +1403715280762142976.0000000000 1.0986707268 2.3073762180 1.2176745183 0.4160495603 0.5831509778 -0.5746018071 0.395816199343 +1403715280812143104.0000000000 1.1085764915 2.3125919352 1.2235505761 0.4114723888 0.5756497800 -0.5825903960 0.399882775931 +1403715280862142976.0000000000 1.1187246264 2.3177123705 1.2293765546 0.4071301987 0.5676334920 -0.5898875882 0.405055370732 +1403715280912143104.0000000000 1.1286714270 2.3229133051 1.2346804286 0.4026059660 0.5604684597 -0.5965612142 0.409753901246 +1403715280962142976.0000000000 1.1384374185 2.3283325077 1.2398540176 0.3988260657 0.5542113164 -0.6020482478 0.413914838279 +1403715281012143104.0000000000 1.1477283817 2.3338254505 1.2447417028 0.3956510223 0.5485038474 -0.6070767409 0.417206937369 +1403715281062142976.0000000000 1.1567646692 2.3394909785 1.2493028184 0.3918678309 0.5442245775 -0.6112076128 0.420338514105 +1403715281112143104.0000000000 1.1659344006 2.3452901801 1.2538171306 0.3892119207 0.5401537431 -0.6146528952 0.423024624631 +1403715281162142976.0000000000 1.1751796395 2.3513276011 1.2581670708 0.3870686489 0.5367542174 -0.6171384096 0.42569114931 +1403715281212143104.0000000000 1.1846252095 2.3573533032 1.2623565464 0.3848214693 0.5337022911 -0.6196995540 0.427839647621 +1403715281262142976.0000000000 1.1942286931 2.3631928565 1.2663131273 0.3825691815 0.5302182111 -0.6229273849 0.429500806912 +1403715281312143104.0000000000 1.2036594306 2.3686978608 1.2696333390 0.3793508248 0.5266719258 -0.6266801466 0.43125587317 +1403715281362142976.0000000000 1.2130391286 2.3739485631 1.2721672927 0.3757881618 0.5226527560 -0.6308565336 0.433171314854 +1403715281412143104.0000000000 1.2227034358 2.3790138764 1.2741129589 0.3716477942 0.5183437590 -0.6352860592 0.43544148582 +1403715281462142976.0000000000 1.2327240584 2.3836275211 1.2756336118 0.3671536235 0.5129460323 -0.6398321583 0.438975390893 +1403715281512143104.0000000000 1.2429058535 2.3879447646 1.2768707555 0.3620989656 0.5067071117 -0.6450476701 0.442770533415 +1403715281562142976.0000000000 1.2532160413 2.3918615024 1.2773565041 0.3560129342 0.4998900024 -0.6507866692 0.447036337957 +1403715281612143104.0000000000 1.2636971413 2.3955916614 1.2772060224 0.3498913758 0.4918783198 -0.6570113578 0.451627965598 +1403715281662142976.0000000000 1.2743649790 2.3992653359 1.2764059227 0.3435391481 0.4828317365 -0.6638918090 0.456182018464 +1403715281712143104.0000000000 1.2851673320 2.4028305961 1.2751154330 0.3362651949 0.4735043923 -0.6709554471 0.461018543175 +1403715281762142976.0000000000 1.2961629045 2.4062529023 1.2737477443 0.3289058189 0.4635441960 -0.6784648628 0.465438686255 +1403715281812143104.0000000000 1.3072944251 2.4097563164 1.2719386640 0.3212401234 0.4532957498 -0.6860390134 0.469764002935 +1403715281862142976.0000000000 1.3186641547 2.4133651917 1.2696985514 0.3138731231 0.4423470325 -0.6931642657 0.474695761761 +1403715281912143104.0000000000 1.3301832428 2.4169544752 1.2668158262 0.3057486126 0.4318349144 -0.7001997585 0.479329417909 +1403715281962142976.0000000000 1.3419914861 2.4206552083 1.2634459314 0.2983805046 0.4209472673 -0.7070687554 0.483555837293 +1403715282012143104.0000000000 1.3541023219 2.4244372665 1.2596608235 0.2911543623 0.4100264967 -0.7138037090 0.487433764069 +1403715282062142976.0000000000 1.3666639960 2.4280806678 1.2551661151 0.2841122946 0.3992524277 -0.7201040217 0.491251362304 +1403715282112143104.0000000000 1.3795328490 2.4316297899 1.2501218721 0.2761441689 0.3895244516 -0.7253880900 0.495809659524 +1403715282162142976.0000000000 1.3926957873 2.4352169031 1.2449379226 0.2693485034 0.3792523283 -0.7311110862 0.499094815425 +1403715282212143104.0000000000 1.4062292973 2.4387685778 1.2396141909 0.2620545023 0.3695046763 -0.7358955206 0.50324101061 +1403715282262142976.0000000000 1.4201562290 2.4422798670 1.2340902928 0.2546541208 0.3595252700 -0.7412202515 0.506443874176 +1403715282312143104.0000000000 1.4346381405 2.4457097282 1.2285439112 0.2473968263 0.3496228334 -0.7463001978 0.509504366468 +1403715282362142976.0000000000 1.4494088530 2.4491105609 1.2228692191 0.2399738810 0.3396583185 -0.7511072309 0.512720870239 +1403715282412143104.0000000000 1.4643806005 2.4522632418 1.2168253977 0.2310597889 0.3309275300 -0.7556551574 0.515832944737 +1403715282462142976.0000000000 1.4800177217 2.4556591801 1.2108176847 0.2242590571 0.3204453869 -0.7605181312 0.518299914583 +1403715282512143104.0000000000 1.4964881251 2.4587243285 1.2045525699 0.2170781022 0.3104158724 -0.7644424444 0.521676942963 +1403715282562142976.0000000000 1.5134891888 2.4618130433 1.1980111688 0.2100504190 0.3002991574 -0.7684246472 0.524616811723 +1403715282612143104.0000000000 1.5310667748 2.4649849056 1.1916261263 0.2035956204 0.2902344911 -0.7713024281 0.528588051274 +1403715282662142976.0000000000 1.5491467535 2.4682383007 1.1851732429 0.1980495037 0.2797040310 -0.7742183471 0.532097735457 +1403715282712143104.0000000000 1.5675592503 2.4716432372 1.1784604427 0.1927822368 0.2687237295 -0.7772295439 0.535291324929 +1403715282762142976.0000000000 1.5862038165 2.4753446563 1.1714425534 0.1884823014 0.2576334979 -0.7802769400 0.537835755327 +1403715282812143104.0000000000 1.6049366276 2.4787508121 1.1639016180 0.1836320329 0.2468033451 -0.7837876410 0.539485235344 +1403715282862142976.0000000000 1.6237114441 2.4819400302 1.1561850484 0.1776016793 0.2367091999 -0.7863330085 0.542316142045 +1403715282912143104.0000000000 1.6423910495 2.4852501949 1.1484561096 0.1713571887 0.2266880993 -0.7883725478 0.545635359291 +1403715282962142976.0000000000 1.6611945248 2.4885665248 1.1405783757 0.1653833345 0.2163542301 -0.7910179366 0.547841057066 +1403715283012143104.0000000000 1.6800243300 2.4919430031 1.1330098525 0.1597245807 0.2056618072 -0.7933233440 0.550299328737 +1403715283062142976.0000000000 1.6988533762 2.4953392350 1.1255458111 0.1546115579 0.1944798637 -0.7955582292 0.552593840622 +1403715283112143104.0000000000 1.7175503785 2.4989693515 1.1181717487 0.1498703029 0.1833067502 -0.7979648891 0.554246843434 +1403715283162142976.0000000000 1.7358917431 2.5026036332 1.1111447731 0.1458554232 0.1718355565 -0.8000613755 0.555968103783 +1403715283212143104.0000000000 1.7536446146 2.5063658299 1.1042716299 0.1414597686 0.1605499307 -0.8018953151 0.557832194536 +1403715283262142976.0000000000 1.7708216842 2.5101435701 1.0975323511 0.1362444064 0.1502005543 -0.8035471631 0.55963310474 +1403715283312143104.0000000000 1.7876068954 2.5139203937 1.0908797814 0.1315737598 0.1396779149 -0.8053817605 0.560837450279 +1403715283362142976.0000000000 1.8034714372 2.5176098181 1.0845862215 0.1258764138 0.1301922613 -0.8064178366 0.562934611079 +1403715283412143104.0000000000 1.8184142919 2.5214923676 1.0780305224 0.1199794610 0.1213441342 -0.8088258260 0.562744447548 +1403715283462142976.0000000000 1.8325415714 2.5254029204 1.0714364986 0.1140663576 0.1129941369 -0.8114402914 0.561948257861 +1403715283512143104.0000000000 1.8458449374 2.5292351027 1.0650315988 0.1066806030 0.1059478995 -0.8139108512 0.561198198433 +1403715283562142976.0000000000 1.8583869395 2.5330428032 1.0589935852 0.0990981335 0.0994270618 -0.8162334953 0.560407619907 +1403715283612143104.0000000000 1.8705354583 2.5368707724 1.0532778692 0.0921708478 0.0934924179 -0.8186532019 0.559080170988 +1403715283662142976.0000000000 1.8826688919 2.5404408694 1.0478042252 0.0865023528 0.0888213387 -0.8204614470 0.55809598349 +1403715283712143104.0000000000 1.8947768853 2.5435224857 1.0424893130 0.0820070335 0.0847863427 -0.8214392356 0.557963891947 +1403715283762142976.0000000000 1.9070053559 2.5463321482 1.0373676324 0.0791213019 0.0811983349 -0.8220169373 0.558063441481 +1403715283812143104.0000000000 1.9194374174 2.5487493707 1.0327142413 0.0777389399 0.0775707885 -0.8216828367 0.559264468584 +1403715283862142976.0000000000 1.9318113247 2.5507896911 1.0277879320 0.0756820814 0.0753732332 -0.8210483199 0.560776920579 +1403715283912143104.0000000000 1.9441846470 2.5525379647 1.0230540793 0.0756029743 0.0729734892 -0.8201988446 0.562345903738 +1403715283962142976.0000000000 1.9564231597 2.5540053560 1.0180098362 0.0751407224 0.0713762804 -0.8196580491 0.563400373569 +1403715284012143104.0000000000 1.9688633763 2.5554264901 1.0121222369 0.0751339956 0.0705249085 -0.8206863000 0.562009890536 +1403715284062142976.0000000000 1.9814122753 2.5565240998 1.0061648998 0.0751181226 0.0704489966 -0.8218360699 0.56033889806 +1403715284112143104.0000000000 1.9939642442 2.5573326100 1.0004844795 0.0761920523 0.0700512893 -0.8230653027 0.558436294915 +1403715284162142976.0000000000 2.0062860667 2.5579987120 0.9950542642 0.0781365643 0.0696795300 -0.8240470445 0.556763781887 +1403715284212143104.0000000000 2.0183900077 2.5580900323 0.9900254416 0.0820056185 0.0682727099 -0.8248853406 0.555137902166 +1403715284262142976.0000000000 2.0299092665 2.5574300586 0.9854626276 0.0859324878 0.0670287624 -0.8254141454 0.553908152187 +1403715284312143104.0000000000 2.0409280337 2.5558423908 0.9813028953 0.0904479175 0.0656502878 -0.8257672305 0.552827002793 +1403715284362142976.0000000000 2.0510502013 2.5531849932 0.9775121318 0.0938132143 0.0651139316 -0.8254183820 0.552850568812 +1403715284412143104.0000000000 2.0599828335 2.5493760766 0.9737592563 0.0930013172 0.0675704176 -0.8244234795 0.554175892781 +1403715284462142976.0000000000 2.0680845964 2.5446298849 0.9700985307 0.0914767787 0.0707650935 -0.8233721360 0.555592140052 +1403715284512143104.0000000000 2.0754516732 2.5389813351 0.9665626951 0.0885649057 0.0751079386 -0.8220676303 0.557422520401 +1403715284562142976.0000000000 2.0826007762 2.5324148475 0.9633907142 0.0867080073 0.0788243037 -0.8204050512 0.559646319109 +1403715284612143104.0000000000 2.0895379598 2.5254675117 0.9604127040 0.0850632863 0.0824821256 -0.8185678155 0.562056641028 +1403715284662142976.0000000000 2.0963551829 2.5184132418 0.9572831909 0.0833502947 0.0860972542 -0.8172985500 0.563616067397 +1403715284712143104.0000000000 2.1032581256 2.5110992982 0.9545658795 0.0828064501 0.0886715109 -0.8161281543 0.564991407675 +1403715284762142976.0000000000 2.1100949566 2.5036689057 0.9520166261 0.0816803417 0.0904622562 -0.8150111481 0.566481888911 +1403715284812143104.0000000000 2.1167809337 2.4961610721 0.9495195834 0.0798835299 0.0903990293 -0.8139853980 0.568220387694 +1403715284862142976.0000000000 2.1233678795 2.4887261827 0.9475452396 0.0779840921 0.0880876128 -0.8126620171 0.570735928218 +1403715284912143104.0000000000 2.1300314950 2.4813989307 0.9460435789 0.0771267971 0.0827625135 -0.8116526674 0.573080946296 +1403715284962142976.0000000000 2.1363857576 2.4741037932 0.9449289793 0.0748428708 0.0755496010 -0.8100736874 0.576603350176 +1403715285012143104.0000000000 2.1425896793 2.4672010952 0.9443044635 0.0734301496 0.0654623372 -0.8081841500 0.580655728645 +1403715285062142976.0000000000 2.1484273128 2.4606808111 0.9440901083 0.0702853535 0.0551831940 -0.8067675263 0.584072720348 +1403715285112143104.0000000000 2.1534185382 2.4546956548 0.9440974519 0.0639992318 0.0453848708 -0.8062489467 0.586350533174 +1403715285162142976.0000000000 2.1578437839 2.4503249381 0.9447263379 0.0575687484 0.0356071610 -0.8072117294 0.586367796924 +1403715285212143104.0000000000 2.1618305831 2.4472319868 0.9454085818 0.0518579120 0.0251842458 -0.8094001351 0.584421022947 +1403715285262142976.0000000000 2.1656050240 2.4450466823 0.9472434218 0.0474623713 0.0157096919 -0.8118530025 0.581717484037 +1403715285312143104.0000000000 2.1690896783 2.4442017753 0.9512065970 0.0450151494 0.0068512667 -0.8150810676 0.577554802272 +1403715285362142976.0000000000 2.1719829661 2.4437383835 0.9583532069 0.0428567766 -0.0007160538 -0.8184083213 0.573036302188 +1403715285412143104.0000000000 2.1742604861 2.4432287751 0.9692200739 0.0407784165 -0.0062308324 -0.8217901871 0.568294981389 +1403715285462142976.0000000000 2.1757003736 2.4424801376 0.9839258254 0.0388076014 -0.0102449580 -0.8241355292 0.564968707427 +1403715285512143104.0000000000 2.1761750072 2.4415943593 1.0013329694 0.0377421555 -0.0137817939 -0.8258759170 0.562418493287 +1403715285562142976.0000000000 2.1757542225 2.4398152927 1.0211573186 0.0377477312 -0.0173699963 -0.8266593268 0.561166418694 +1403715285612143104.0000000000 2.1745417291 2.4374275593 1.0415998248 0.0379005499 -0.0203628034 -0.8269380499 0.560644598846 +1403715285662142976.0000000000 2.1722312500 2.4344286345 1.0616918024 0.0370954878 -0.0219957068 -0.8272742192 0.560140589379 +1403715285712143104.0000000000 2.1687670511 2.4304161501 1.0813498038 0.0369398075 -0.0238711684 -0.8275246799 0.559703959353 +1403715285762142976.0000000000 2.1639436054 2.4256349858 1.1007246668 0.0348515057 -0.0241924771 -0.8266962335 0.561046730831 +1403715285812143104.0000000000 2.1579421940 2.4201596445 1.1195588939 0.0330042422 -0.0243896951 -0.8261295094 0.561983893357 +1403715285862142976.0000000000 2.1508565809 2.4141310335 1.1369878727 0.0287854975 -0.0224722165 -0.8259769122 0.56251980867 +1403715285912143104.0000000000 2.1428861121 2.4073311102 1.1540510719 0.0236232905 -0.0194230087 -0.8257558167 0.563198027357 +1403715285962142976.0000000000 2.1343896230 2.4001115780 1.1704172150 0.0188706975 -0.0164364306 -0.8264513955 0.562451625814 +1403715286012143104.0000000000 2.1257535709 2.3922239659 1.1861517920 0.0143056460 -0.0133451032 -0.8266518156 0.562373570173 +1403715286062142976.0000000000 2.1172832454 2.3836820662 1.2010075917 0.0103149516 -0.0109743596 -0.8267529488 0.562363518442 +1403715286112143104.0000000000 2.1092812259 2.3746407085 1.2152200376 0.0089102997 -0.0103857181 -0.8269427448 0.562119595974 +1403715286162142976.0000000000 2.1017373571 2.3649600111 1.2291038262 0.0098095606 -0.0115207293 -0.8271804006 0.561732703558 +1403715286212143104.0000000000 2.0943487774 2.3547264590 1.2423409659 0.0117415265 -0.0135282239 -0.8276942198 0.560893396514 +1403715286262142976.0000000000 2.0869896603 2.3438044960 1.2549271543 0.0129810626 -0.0145673727 -0.8280160798 0.56036475204 +1403715286312143104.0000000000 2.0794665087 2.3320017981 1.2670326585 0.0121200508 -0.0140347533 -0.8278920345 0.560580867735 +1403715286362142976.0000000000 2.0720109266 2.3196442656 1.2786506702 0.0110006933 -0.0133046843 -0.8273032653 0.561490229024 +1403715286412143104.0000000000 2.0648527835 2.3066572772 1.2893579769 0.0097988198 -0.0125105384 -0.8270449535 0.561911126845 +1403715286462142976.0000000000 2.0578333211 2.2929207483 1.2993207082 0.0080374107 -0.0114298517 -0.8263790724 0.562940838069 +1403715286512143104.0000000000 2.0509821302 2.2785814128 1.3090035968 0.0061696563 -0.0106648967 -0.8259543898 0.563602289971 +1403715286562142976.0000000000 2.0445240344 2.2636113126 1.3184979642 0.0046975014 -0.0104055741 -0.8249572973 0.565079742273 +1403715286612143104.0000000000 2.0382653033 2.2480561043 1.3278389157 0.0037781732 -0.0120647682 -0.8237638522 0.566792098265 +1403715286662142976.0000000000 2.0320669754 2.2318761718 1.3372989985 0.0016167915 -0.0154071962 -0.8216317444 0.569808108855 +1403715286712143104.0000000000 2.0260179789 2.2153531904 1.3462627239 0.0011889674 0.0199767513 0.8184400428 -0.574243338799 +1403715286762142976.0000000000 2.0200850595 2.1988448118 1.3542182576 0.0051693105 0.0252745522 0.8163051782 -0.577044479407 +1403715286812143104.0000000000 2.0143310482 2.1830100750 1.3608227447 0.0098285691 0.0303176008 0.8164791060 -0.576494676309 +1403715286862142976.0000000000 2.0090840223 2.1677928063 1.3663235639 0.0135762837 0.0352610244 0.8181734480 -0.573728641117 +1403715286912143104.0000000000 2.0042703249 2.1526428172 1.3716306343 0.0177587342 0.0388053507 0.8204179397 -0.570169427757 +1403715286962142976.0000000000 1.9999563352 2.1373565705 1.3771090948 0.0215290195 0.0420573260 0.8221398316 -0.567321584226 +1403715287012143104.0000000000 1.9962028345 2.1216300281 1.3828437556 0.0254818618 0.0447215307 0.8231652396 -0.565464099437 +1403715287062142976.0000000000 1.9930928316 2.1058047800 1.3889895818 0.0280700806 0.0478606894 0.8235678701 -0.564497465325 +1403715287112143104.0000000000 1.9906493752 2.0894641114 1.3951650241 0.0315108876 0.0495686432 0.8232788546 -0.564590064617 +1403715287162142976.0000000000 1.9889658060 2.0723714761 1.4016732408 0.0338050261 0.0516762641 0.8217242741 -0.566529788494 +1403715287212143104.0000000000 1.9879449279 2.0547210917 1.4085404957 0.0357575101 0.0533931566 0.8190557580 -0.57010370683 +1403715287262142976.0000000000 1.9876167064 2.0370265399 1.4152389166 0.0374935785 0.0549873937 0.8168717354 -0.572967002572 +1403715287312143104.0000000000 1.9880175673 2.0191696037 1.4221440895 0.0377386587 0.0567746916 0.8145769518 -0.576035430811 +1403715287362142976.0000000000 1.9890288092 2.0014468504 1.4286341546 0.0379712204 0.0582656301 0.8131997381 -0.577814406814 +1403715287412143104.0000000000 1.9909589133 1.9840900106 1.4351953622 0.0362344210 0.0602599638 0.8124543977 -0.57876908621 +1403715287462142976.0000000000 1.9933898224 1.9670775572 1.4420825293 0.0331448840 0.0637610814 0.8119958758 -0.5792224433 +1403715287512143104.0000000000 1.9958427790 1.9504593925 1.4491583795 0.0308226292 0.0679893962 0.8117456447 -0.579220524378 +1403715287562142976.0000000000 1.9980218961 1.9344220180 1.4563454745 0.0296757656 0.0738814113 0.8113968605 -0.579047511656 +1403715287612143104.0000000000 1.9996771605 1.9189767069 1.4638101800 0.0291101896 0.0815959067 0.8114945221 -0.577902539785 +1403715287662142976.0000000000 2.0004157661 1.9039062707 1.4716883173 0.0300162528 0.0902058815 0.8112540623 -0.576913139001 +1403715287712143104.0000000000 1.9999392049 1.8892391343 1.4799003860 0.0328281767 0.0991289799 0.8107584950 -0.575991683039 +1403715287762142976.0000000000 1.9982794382 1.8749746642 1.4885089390 0.0374847286 0.1079988326 0.8097922836 -0.575471636773 +1403715287812143104.0000000000 1.9952213165 1.8611467594 1.4973735855 0.0447526731 0.1164202842 0.8081856449 -0.575568830809 +1403715287862142976.0000000000 1.9909705660 1.8478054527 1.5066990394 0.0526895530 0.1254524984 0.8061615974 -0.57583761651 +1403715287912143104.0000000000 1.9853241333 1.8344850535 1.5162930183 0.0624415387 0.1347453724 0.8036646298 -0.576253331145 +1403715287962142976.0000000000 1.9788472573 1.8219416677 1.5259540315 0.0727871649 0.1445366988 0.8010541225 -0.576301539286 +1403715288012143104.0000000000 1.9718383656 1.8100222487 1.5354252502 0.0828535463 0.1552182472 0.7983226749 -0.575954418622 +1403715288062142976.0000000000 1.9647056299 1.7988771010 1.5450722794 0.0920075732 0.1662128807 0.7951712862 -0.575856327834 +1403715288112143104.0000000000 1.9576654787 1.7884201851 1.5543218135 0.0993051691 0.1765702504 0.7926053185 -0.575098460443 +1403715288162142976.0000000000 1.9506233401 1.7788564379 1.5619388565 0.1058784929 0.1851668980 0.7906698544 -0.573885133081 +1403715288212143104.0000000000 1.9437796608 1.7702083569 1.5666037956 0.1114861922 0.1922711171 0.7894578755 -0.572152872262 +1403715288262142976.0000000000 1.9371502687 1.7623853277 1.5682383350 0.1159186868 0.1985001141 0.7886902642 -0.570200166503 +1403715288312143104.0000000000 1.9304481809 1.7550612176 1.5665700633 0.1209569882 0.2024741687 0.7879023879 -0.568843955044 +1403715288362142976.0000000000 1.9241982586 1.7482621232 1.5615787640 0.1239306820 0.2062565068 0.7874564722 -0.56746078617 +1403715288412143104.0000000000 1.9182177710 1.7415959701 1.5543832297 0.1252547658 0.2096984208 0.7869249786 -0.566645298149 +1403715288462142976.0000000000 1.9121929473 1.7355180048 1.5478850758 0.1258102255 0.2124098865 0.7863037582 -0.566374634985 +1403715288512143104.0000000000 1.9058247631 1.7303110704 1.5437388088 0.1266209977 0.2139891406 0.7855580212 -0.566634243573 +1403715288562142976.0000000000 1.8995180774 1.7259731342 1.5424826837 0.1260703703 0.2155376050 0.7855436471 -0.566189880725 +1403715288612143104.0000000000 1.8928766325 1.7223611924 1.5448359514 0.1249390691 0.2167954032 0.7850258396 -0.566678403856 +1403715288662142976.0000000000 1.8854868746 1.7188383632 1.5506320477 0.1240126290 0.2175994886 0.7852657905 -0.566241087009 +1403715288712143104.0000000000 1.8777157432 1.7159116886 1.5589713706 0.1241491050 0.2171064945 0.7851714006 -0.566531236108 +1403715288762142976.0000000000 1.8695895151 1.7134980871 1.5674716062 0.1261083820 0.2150774380 0.7862000141 -0.565444877416 +1403715288812143104.0000000000 1.8612485244 1.7116608834 1.5750220647 0.1273300030 0.2136246405 0.7869246043 -0.564713423318 +1403715288862142976.0000000000 1.8526681448 1.7102457658 1.5791680928 0.1299319078 0.2121700017 0.7877023742 -0.563583675601 +1403715288912143104.0000000000 1.8436825579 1.7091106106 1.5801363830 0.1338120914 0.2114420350 0.7881696140 -0.56229462878 +1403715288962142976.0000000000 1.8344136599 1.7079540179 1.5779129573 0.1376388664 0.2122791980 0.7881449897 -0.561088727135 +1403715289012143104.0000000000 1.8253301821 1.7073517581 1.5722660397 0.1405294765 0.2150142187 0.7882907708 -0.559122538141 +1403715289062142976.0000000000 1.8163236594 1.7068512777 1.5632558861 0.1434608390 0.2188913145 0.7880223744 -0.557248882933 +1403715289112143104.0000000000 1.8074579963 1.7063900737 1.5510699101 0.1474739099 0.2230900075 0.7875647254 -0.555179338373 +1403715289162142976.0000000000 1.7989207756 1.7058427054 1.5372140973 0.1519260475 0.2266191219 0.7871278701 -0.553165405537 +1403715289212143104.0000000000 1.7906146135 1.7049333556 1.5231072988 0.1563563426 0.2297298060 0.7863620637 -0.551735095137 +1403715289262142976.0000000000 1.7829376675 1.7039396054 1.5090403226 0.1596198825 0.2336605531 0.7857738300 -0.549985206271 +1403715289312143104.0000000000 1.7753567285 1.7028217632 1.4945444091 0.1642640063 0.2377396698 0.7850100197 -0.54795661749 +1403715289362142976.0000000000 1.7682289340 1.7017717599 1.4797502348 0.1692556357 0.2427388925 0.7836228707 -0.546228483712 +1403715289412143104.0000000000 1.7615374290 1.7001529968 1.4640949246 0.1734538389 0.2492848568 0.7823768746 -0.543743737473 +1403715289462142976.0000000000 1.7551333958 1.6980315838 1.4472901708 0.1774388988 0.2566996237 0.7808936081 -0.541133914351 +1403715289512143104.0000000000 1.7490854711 1.6954318376 1.4295750943 0.1817343567 0.2644429253 0.7795456069 -0.53791375672 +1403715289562142976.0000000000 1.7432751451 1.6921367814 1.4112371684 0.1861372703 0.2724863800 0.7774850700 -0.53537001715 +1403715289612143104.0000000000 1.7378542354 1.6880556601 1.3922760162 0.1899894535 0.2802918034 0.7758562136 -0.532341665084 +1403715289662142976.0000000000 1.7329123160 1.6833740161 1.3725482355 0.1932226253 0.2869171278 0.7751247313 -0.528701456127 +1403715289712143104.0000000000 1.7282864264 1.6776761498 1.3526988308 0.1948755760 0.2930342552 0.7739860650 -0.526402893628 +1403715289762142976.0000000000 1.7239715924 1.6712061317 1.3340048477 0.1975068562 0.2965058664 0.7728921416 -0.525083850859 +1403715289812143104.0000000000 1.7200589981 1.6638971561 1.3178194304 0.1986375326 0.2991752647 0.7720372584 -0.524400384509 +1403715289862142976.0000000000 1.7163952539 1.6556361795 1.3043737616 0.1990871036 0.3008410262 0.7709294819 -0.524906407029 +1403715289912143104.0000000000 1.7129596382 1.6462576459 1.2939202380 0.1978443208 0.3022275775 0.7699062035 -0.526080368378 +1403715289962142976.0000000000 1.7098653100 1.6364195484 1.2858651477 0.1967482164 0.3020579351 0.7703638716 -0.525918861108 +1403715290012143104.0000000000 1.7066954364 1.6256808994 1.2804295257 0.1952558211 0.3014136862 0.7709351098 -0.526007614569 +1403715290062142976.0000000000 1.7036011315 1.6143167124 1.2781227311 0.1941453711 0.2994147581 0.7713071394 -0.527013922268 +1403715290112143104.0000000000 1.7009052486 1.6023488342 1.2786677301 0.1938665221 0.2961994789 0.7711478583 -0.529162187697 +1403715290162142976.0000000000 1.6981277971 1.5895677431 1.2816420190 0.1925950716 0.2927868677 0.7720733674 -0.530175163417 +1403715290212143104.0000000000 1.6952146290 1.5762448100 1.2872983810 0.1913337880 0.2894186512 0.7744004144 -0.529086216064 +1403715290262142976.0000000000 1.6925910731 1.5623865758 1.2951692610 0.1886595523 0.2871608791 0.7768181929 -0.527730705954 +1403715290312143104.0000000000 1.6898561912 1.5470804028 1.3030530794 0.1858832378 0.2852582509 0.7788156368 -0.526802957535 +1403715290362142976.0000000000 1.6870910253 1.5306723466 1.3100544172 0.1828641601 0.2838320961 0.7809829297 -0.525419550152 +1403715290412143104.0000000000 1.6845627302 1.5133091783 1.3163757878 0.1784324410 0.2842073980 0.7826790474 -0.524215153999 +1403715290462142976.0000000000 1.6822581085 1.4952892534 1.3219407095 0.1750138265 0.2843279983 0.7843435259 -0.522812569987 +1403715290512143104.0000000000 1.6794317878 1.4762484468 1.3275023575 0.1731454934 0.2838883962 0.7840377043 -0.52413060864 +1403715290562142976.0000000000 1.6756990419 1.4560561861 1.3323093405 0.1732726357 0.2827923016 0.7832092798 -0.525916658685 +1403715290612143104.0000000000 1.6717776475 1.4349927461 1.3371168633 0.1727493127 0.2828707253 0.7810950893 -0.529180771764 +1403715290662142976.0000000000 1.6679601726 1.4134980474 1.3407444022 0.1717959297 0.2837656554 0.7800510106 -0.530550310732 +1403715290712143104.0000000000 1.6633397126 1.3913594183 1.3437962670 0.1738148449 0.2830478805 0.7781033489 -0.533129886136 +1403715290762142976.0000000000 1.6584884146 1.3688620816 1.3466266105 0.1761682211 0.2823616837 0.7760078165 -0.535769079147 +1403715290812143104.0000000000 1.6537571383 1.3461297908 1.3495233740 0.1768188491 0.2829038064 0.7739531084 -0.538235187321 +1403715290862142976.0000000000 1.6492972224 1.3232301041 1.3520677542 0.1758489795 0.2845175031 0.7728428387 -0.539296646954 +1403715290912143104.0000000000 1.6449540657 1.3002682799 1.3536729396 0.1755319792 0.2860568983 0.7725171616 -0.539052140632 +1403715290962142976.0000000000 1.6410693232 1.2772834447 1.3551010922 0.1745291645 0.2888682717 0.7707184356 -0.540451464343 +1403715291012143104.0000000000 1.6371140348 1.2542002216 1.3566496730 0.1728395916 0.2927963470 0.7680720601 -0.542643607964 +1403715291062142976.0000000000 1.6330249103 1.2311893254 1.3582517639 0.1701437920 0.2974230239 0.7652982798 -0.544893730829 +1403715291112143104.0000000000 1.6282170332 1.2086345705 1.3593251085 0.1676561380 0.3026740155 0.7629256784 -0.546099138431 +1403715291162142976.0000000000 1.6227236485 1.1866628030 1.3603361343 0.1655267641 0.3076783550 0.7602399862 -0.54769524696 +1403715291212143104.0000000000 1.6163945489 1.1657031863 1.3609666266 0.1647625080 0.3124461604 0.7577572101 -0.548666313342 +1403715291262142976.0000000000 1.6090166327 1.1458579113 1.3603750749 0.1652330452 0.3168490599 0.7556062334 -0.548966241311 +1403715291312143104.0000000000 1.6006954770 1.1273948292 1.3584400337 0.1667183193 0.3208210385 0.7540606397 -0.548335130113 +1403715291362142976.0000000000 1.5911849724 1.1099588079 1.3559216385 0.1689240267 0.3244669442 0.7523417176 -0.547875729847 +1403715291412143104.0000000000 1.5809177731 1.0936531249 1.3522772023 0.1709311061 0.3284015594 0.7513762898 -0.546231309826 +1403715291462142976.0000000000 1.5699136016 1.0784812035 1.3480414288 0.1735972400 0.3321412826 0.7506690135 -0.544097600496 +1403715291512143104.0000000000 1.5578822912 1.0645651259 1.3428986607 0.1768401490 0.3355122323 0.7512915983 -0.5401111349 +1403715291562142976.0000000000 1.5451225413 1.0517557284 1.3375842602 0.1791556302 0.3399423794 0.7510819540 -0.536859699798 +1403715291612143104.0000000000 1.5313026956 1.0397915578 1.3324113196 0.1808260888 0.3447006022 0.7504766578 -0.534105051879 +1403715291662142976.0000000000 1.5162515054 1.0283532707 1.3271929484 0.1822512057 0.3492489085 0.7494841746 -0.532055607943 +1403715291712143104.0000000000 1.4998683714 1.0176338931 1.3218215812 0.1834562000 0.3535672225 0.7487255741 -0.529852863146 +1403715291762142976.0000000000 1.4820672270 1.0074002802 1.3165763459 0.1879398292 0.3549034113 0.7488409552 -0.527218562983 +1403715291812143104.0000000000 1.4631854476 0.9975702855 1.3112678768 0.1932164735 0.3551172557 0.7490406447 -0.524878311221 +1403715291862142976.0000000000 1.4430003685 0.9881817322 1.3051281784 0.2016247889 0.3524170476 0.7505679760 -0.521341905482 +1403715291912143104.0000000000 1.4219174952 0.9786943764 1.2984352157 0.2092405646 0.3497737140 0.7520193192 -0.518018994485 +1403715291962142976.0000000000 1.4004531233 0.9687946320 1.2915717914 0.2130433775 0.3492258611 0.7527740837 -0.515737332452 +1403715292012143104.0000000000 1.3788005615 0.9586056628 1.2844653531 0.2163746104 0.3484119218 0.7537970847 -0.513401515177 +1403715292062142976.0000000000 1.3570540407 0.9475417854 1.2778207950 0.2182105530 0.3478182335 0.7543829323 -0.512165034448 +1403715292112143104.0000000000 1.3353298710 0.9354226388 1.2712907912 0.2177962408 0.3464082645 0.7552699795 -0.51198961893 +1403715292162142976.0000000000 1.3140035312 0.9227212078 1.2640676760 0.2161709270 0.3436425364 0.7569541838 -0.512054978582 +1403715292212143104.0000000000 1.2927571032 0.9091872278 1.2569925052 0.2141129083 0.3387042675 0.7592023893 -0.512880896324 +1403715292262142976.0000000000 1.2715375872 0.8946970231 1.2503071847 0.2108031555 0.3326475571 0.7621522921 -0.513839971239 +1403715292312143104.0000000000 1.2505350542 0.8795567170 1.2434281274 0.2065749384 0.3249281119 0.7659633284 -0.514828803102 +1403715292362142976.0000000000 1.2292904788 0.8635453950 1.2365950545 0.2030997020 0.3151834771 0.7701998915 -0.515947685311 +1403715292412143104.0000000000 1.2085311272 0.8463619974 1.2304088970 0.1976928242 0.3056726551 0.7737708006 -0.51842118337 +1403715292462142976.0000000000 1.1877315662 0.8280419658 1.2241829895 0.1918524959 0.2947767161 0.7788600588 -0.519303683948 +1403715292512143104.0000000000 1.1671101865 0.8084407733 1.2189486745 0.1851166171 0.2837958267 0.7817048643 -0.523573559247 +1403715292562142976.0000000000 1.1468849101 0.7879485760 1.2142572369 0.1785126709 0.2713211534 0.7833864059 -0.529928105516 +1403715292612143104.0000000000 1.1269183288 0.7666928240 1.2100113049 0.1729340414 0.2570960436 0.7846847873 -0.536903367672 +1403715292662142976.0000000000 1.1073167678 0.7447095540 1.2070625715 0.1685661011 0.2411350578 0.7840988508 -0.546468979607 +1403715292712143104.0000000000 1.0889602772 0.7227109690 1.2041499920 0.1628563795 0.2256630668 0.7852849721 -0.553065540939 +1403715292762142976.0000000000 1.0715990651 0.7004715905 1.2024424377 0.1573621819 0.2097249766 0.7861460591 -0.559666821967 +1403715292812143104.0000000000 1.0559552588 0.6785953910 1.2025008498 0.1505606732 0.1946258992 0.7877236349 -0.564751023101 +1403715292862142976.0000000000 1.0422170195 0.6571763618 1.2048833406 0.1424935048 0.1806686330 0.7907882975 -0.567193366192 +1403715292912143104.0000000000 1.0303537348 0.6360700737 1.2099210313 0.1324582419 0.1682180483 0.7952012246 -0.567285214597 +1403715292962142976.0000000000 1.0199755953 0.6151424188 1.2184110231 0.1201406880 0.1580593534 0.7990067417 -0.567601693631 +1403715293012143104.0000000000 1.0107296662 0.5945917079 1.2300511378 0.1078729633 0.1488279496 0.8011688627 -0.569510420119 +1403715293062142976.0000000000 1.0025560260 0.5744802673 1.2444716717 0.0958414624 0.1394690299 0.8030414463 -0.571390618811 +1403715293112143104.0000000000 0.9950738243 0.5544764210 1.2604086013 0.0841892051 0.1306176970 0.8040197921 -0.573936729031 +1403715293162142976.0000000000 0.9879464192 0.5348925495 1.2763377666 0.0736060275 0.1216615119 0.8056695104 -0.575045449768 +1403715293212143104.0000000000 0.9810819580 0.5158190454 1.2922273699 0.0643072609 0.1118245972 0.8073465985 -0.575804919649 +1403715293262142976.0000000000 0.9742774020 0.4968068283 1.3084566887 0.0550901637 0.1026408599 0.8076397642 -0.578055307886 +1403715293312143104.0000000000 0.9674180222 0.4780662184 1.3243704030 0.0479579745 0.0922009538 0.8075299098 -0.580598365149 +1403715293362142976.0000000000 0.9605690027 0.4599002688 1.3401932107 0.0410886907 0.0821307811 0.8067204539 -0.583753684034 +1403715293412143104.0000000000 0.9537529262 0.4423678129 1.3562430509 0.0334113563 0.0729939744 0.8046762886 -0.588261533327 +1403715293462142976.0000000000 0.9466186837 0.4259505582 1.3718814370 0.0268559018 0.0638599726 0.8033686509 -0.591438479677 +1403715293512143104.0000000000 0.9394401672 0.4109666754 1.3870681255 0.0204193679 0.0550588911 0.8041318242 -0.591543385715 +1403715293562142976.0000000000 0.9322773496 0.3970634867 1.4024011481 0.0137098770 0.0468336881 0.8053803117 -0.590746306352 +1403715293612143104.0000000000 0.9248842884 0.3840700880 1.4177503231 0.0076368863 0.0387618360 0.8074020803 -0.588677397802 +1403715293662142976.0000000000 0.9172762838 0.3718042163 1.4331866953 0.0021060169 0.0308339255 0.8100506613 -0.585544840153 +1403715293712143104.0000000000 0.9093522037 0.3601837617 1.4490278902 0.0031077465 -0.0227156179 -0.8118081146 0.583474016353 +1403715293762142976.0000000000 0.9010693822 0.3491434680 1.4648736616 0.0084393339 -0.0148206949 -0.8137400558 0.580978696893 +1403715293812143104.0000000000 0.8927153319 0.3385518173 1.4805119850 0.0133635337 -0.0065648366 -0.8150162519 0.57924677647 +1403715293862142976.0000000000 0.8844444839 0.3282250250 1.4960418873 0.0194155691 0.0010113281 -0.8161083885 0.577571736715 +1403715293912143104.0000000000 0.8761198468 0.3178718701 1.5111778407 0.0249159330 0.0092823368 -0.8171220947 0.575851123929 +1403715293962142976.0000000000 0.8676170960 0.3074055496 1.5257800740 0.0305020810 0.0179703806 -0.8171589453 0.575324209946 +1403715294012143104.0000000000 0.8590376471 0.2971437257 1.5380381397 0.0364947504 0.0269653540 -0.8167275294 0.575236599683 +1403715294062142976.0000000000 0.8504984983 0.2869224835 1.5468583878 0.0427536536 0.0362328732 -0.8161848840 0.575066551899 +1403715294112143104.0000000000 0.8419252163 0.2768348729 1.5527490669 0.0499184644 0.0450321587 -0.8145851658 0.576134757901 +1403715294162142976.0000000000 0.8331733958 0.2668897570 1.5556562238 0.0573054433 0.0536641612 -0.8123437939 0.577870058455 +1403715294212143104.0000000000 0.8243306306 0.2572888516 1.5554281952 0.0648014273 0.0622952851 -0.8099761345 0.579533203582 +1403715294262142976.0000000000 0.8154397225 0.2485167121 1.5519017366 0.0728822715 0.0707239416 -0.8079774645 0.580395309644 +1403715294312143104.0000000000 0.8061604045 0.2402570412 1.5448516255 0.0803807381 0.0794272673 -0.8060935103 0.580898871438 +1403715294362142976.0000000000 0.7963737963 0.2326635107 1.5342352178 0.0875466400 0.0884863445 -0.8047067216 0.58047639484 +1403715294412143104.0000000000 0.7862843866 0.2253141964 1.5214075061 0.0944442616 0.0978932849 -0.8027758604 0.580558441709 +1403715294462142976.0000000000 0.7755702528 0.2186475083 1.5074831480 0.1002746659 0.1079541588 -0.8010302716 0.580208061771 +1403715294512143104.0000000000 0.7644140228 0.2127556461 1.4933426014 0.1059413226 0.1183171162 -0.7993609594 0.579482141939 +1403715294562142976.0000000000 0.7529131959 0.2080066073 1.4787831373 0.1120588125 0.1286916613 -0.7993604410 0.576111242865 +1403715294612143104.0000000000 0.7409428968 0.2041064943 1.4641531291 0.1173699652 0.1398576592 -0.8000948023 0.571412665077 +1403715294662142976.0000000000 0.7284629853 0.2005328359 1.4495882941 0.1210384443 0.1521275004 -0.8004822803 0.566952412011 +1403715294712143104.0000000000 0.7160078133 0.1972090202 1.4350770707 0.1247717953 0.1644307147 -0.8008196096 0.562212141505 +1403715294762142976.0000000000 0.7036822478 0.1939203785 1.4207832329 0.1289854525 0.1760839369 -0.8003638131 0.558368128489 +1403715294812143104.0000000000 0.6918356340 0.1906252647 1.4068160459 0.1343464174 0.1867686824 -0.7994719264 0.554899214583 +1403715294862142976.0000000000 0.6804392643 0.1871086992 1.3927626344 0.1394411962 0.1973247227 -0.7978273804 0.552350049914 +1403715294912143104.0000000000 0.6699881224 0.1832288771 1.3791639043 0.1444868638 0.2076355547 -0.7953205147 0.550886831819 +1403715294962142976.0000000000 0.6603028052 0.1791353958 1.3664852736 0.1502429734 0.2172503880 -0.7912776008 0.551460856615 +1403715295012143104.0000000000 0.6515426804 0.1751014853 1.3542513407 0.1572063479 0.2257069988 -0.7871913427 0.551971289895 +1403715295062142976.0000000000 0.6435018451 0.1713982248 1.3420401787 0.1643393670 0.2339627490 -0.7836197284 0.551537964092 +1403715295112143104.0000000000 0.6361916437 0.1677906991 1.3308188380 0.1737106204 0.2407215108 -0.7794424182 0.551676799705 +1403715295162142976.0000000000 0.6290910149 0.1646064672 1.3204940131 0.1830827608 0.2469251618 -0.7751885414 0.551897991049 +1403715295212143104.0000000000 0.6220291087 0.1620539432 1.3113448331 0.1919226889 0.2535467647 -0.7709691039 0.551802827473 +1403715295262142976.0000000000 0.6146072386 0.1603023107 1.3045282967 0.2002635172 0.2605165853 -0.7677592211 0.5500649152 +1403715295312143104.0000000000 0.6069394630 0.1589444689 1.3012034524 0.2075144499 0.2690280980 -0.7643494794 0.548025098764 +1403715295362142976.0000000000 0.5988918549 0.1585188395 1.3006596405 0.2140470172 0.2794271782 -0.7620803793 0.543449926 +1403715295412143104.0000000000 0.5904224233 0.1583980966 1.3027798091 0.2202037819 0.2902781689 -0.7589623205 0.539652735782 +1403715295462142976.0000000000 0.5819593693 0.1584745031 1.3078508225 0.2266021040 0.3015110876 -0.7553943842 0.535837545249 +1403715295512143104.0000000000 0.5733557248 0.1586156230 1.3130842619 0.2324967636 0.3127301465 -0.7514239019 0.532453969904 +1403715295562142976.0000000000 0.5644558413 0.1584082944 1.3154944566 0.2364913773 0.3237805615 -0.7468262601 0.530554911086 +1403715295612143104.0000000000 0.5555309843 0.1583219988 1.3144502304 0.2407175885 0.3328138942 -0.7429032752 0.528568517828 +1403715295662142976.0000000000 0.5466425239 0.1581895458 1.3099359392 0.2444147556 0.3399880011 -0.7388013770 0.528055027221 +1403715295712143104.0000000000 0.5379628097 0.1583779957 1.3024750706 0.2483296983 0.3455142702 -0.7352615035 0.52758200451 +1403715295762142976.0000000000 0.5294595694 0.1592838585 1.2931555829 0.2525296758 0.3512423136 -0.7317929143 0.5266276964 +1403715295812143104.0000000000 0.5209238968 0.1610833775 1.2828379755 0.2587389336 0.3557705565 -0.7285304125 0.525095147063 +1403715295862142976.0000000000 0.5123641481 0.1634016900 1.2724062827 0.2654230246 0.3596426516 -0.7248022310 0.524279989182 +1403715295912143104.0000000000 0.5031285338 0.1664657634 1.2612145940 0.2718665926 0.3641645033 -0.7219057582 0.521847532047 +1403715295962142976.0000000000 0.4934920542 0.1697587125 1.2497416732 0.2793534595 0.3674019079 -0.7186810144 0.520072189411 +1403715296012143104.0000000000 0.4828842916 0.1733408193 1.2367567991 0.2858897200 0.3702728433 -0.7160738966 0.518076504195 +1403715296062142976.0000000000 0.4712440911 0.1770606852 1.2229633643 0.2921605335 0.3723861957 -0.7153879231 0.5139950033 +1403715296112143104.0000000000 0.4587285732 0.1808043204 1.2083672092 0.2969999210 0.3745448803 -0.7165385469 0.508015443015 +1403715296162142976.0000000000 0.4452240870 0.1844645874 1.1928690689 0.2996025088 0.3788712007 -0.7181597870 0.500940585731 +1403715296212143104.0000000000 0.4309568079 0.1875079905 1.1767820505 0.3008877923 0.3843295030 -0.7191821289 0.494504231475 +1403715296262142976.0000000000 0.4161012048 0.1897805322 1.1604214237 0.3021609526 0.3902483746 -0.7200760797 0.487745224811 +1403715296312143104.0000000000 0.4009049661 0.1911483086 1.1445888217 0.3017442217 0.3974890773 -0.7217166748 0.47966436112 +1403715296362142976.0000000000 0.3854514440 0.1913701791 1.1310547370 0.3006015869 0.4053985577 -0.7224483313 0.47260882763 +1403715296412143104.0000000000 0.3706630110 0.1903121173 1.1207857530 0.3019875692 0.4122344847 -0.7217096231 0.46690626201 +1403715296462142976.0000000000 0.3568817967 0.1875835991 1.1135825654 0.3055913386 0.4174623629 -0.7199732461 0.462577165788 +1403715296512143104.0000000000 0.3436776844 0.1832020541 1.1085918323 0.3091939076 0.4214817795 -0.7187039616 0.45849411408 +1403715296562142976.0000000000 0.3312487408 0.1768387623 1.1060328115 0.3117281299 0.4257760914 -0.7161105281 0.456865411893 +1403715296612143104.0000000000 0.3192263927 0.1686184122 1.1059275048 0.3123943656 0.4304513669 -0.7125965050 0.457523334996 +1403715296662142976.0000000000 0.3081422641 0.1589181199 1.1071910386 0.3136471859 0.4339496442 -0.7077624590 0.460852959895 +1403715296712143104.0000000000 0.2979003621 0.1479737428 1.1083519237 0.3149675390 0.4366907016 -0.7037707221 0.463468932322 +1403715296762142976.0000000000 0.2886220141 0.1359665154 1.1098569259 0.3166421032 0.4384630725 -0.7008819641 0.465029445232 +1403715296812143104.0000000000 0.2799771319 0.1232140070 1.1105766873 0.3168649938 0.4414531876 -0.6973090586 0.467413880475 +1403715296862142976.0000000000 0.2720340086 0.1098436684 1.1114537864 0.3167805268 0.4447571639 -0.6929953109 0.47074267067 +1403715296912143104.0000000000 0.2647443205 0.0967429117 1.1120061336 0.3173686109 0.4491278696 -0.6881629985 0.473278996929 +1403715296962142976.0000000000 0.2579840778 0.0840674257 1.1123286530 0.3192621506 0.4539095812 -0.6828655740 0.475113017197 +1403715297012143104.0000000000 0.2513080972 0.0724592726 1.1122165870 0.3231799076 0.4591630916 -0.6795079310 0.472221319245 +1403715297062142976.0000000000 0.2440054746 0.0621232897 1.1115481199 0.3286716519 0.4647738445 -0.6785497422 0.464252588631 +1403715297112143104.0000000000 0.2370142466 0.0520487838 1.1107203406 0.3347706864 0.4707435505 -0.6765442086 0.456746134157 +1403715297162142976.0000000000 0.2307707127 0.0418631553 1.1078363296 0.3394056100 0.4787890522 -0.6762162932 0.445304839621 +1403715297212143104.0000000000 0.2254327730 0.0312372274 1.1041970526 0.3436323658 0.4881857170 -0.6746219869 0.434139007238 +1403715297262142976.0000000000 0.2214239392 0.0199980099 1.1005249476 0.3495740817 0.4971587261 -0.6713198071 0.424217961837 +1403715297312143104.0000000000 0.2190768001 0.0074349746 1.0963477093 0.3561150799 0.5061160000 -0.6661895944 0.416197151139 +1403715297362142976.0000000000 0.2179893221 -0.0063064194 1.0910092255 0.3621653766 0.5152889283 -0.6600498181 0.409448162715 +1403715297412143104.0000000000 0.2183059658 -0.0216874407 1.0854357490 0.3673297746 0.5246355280 -0.6518143892 0.406158099079 +1403715297462142976.0000000000 0.2204396202 -0.0386013836 1.0800756367 0.3721429122 0.5331585893 -0.6441152991 0.402947953197 +1403715297512143104.0000000000 0.2244454958 -0.0567344726 1.0752149667 0.3765968349 0.5414844855 -0.6356891695 0.40108434988 +1403715297562142976.0000000000 0.2298919295 -0.0756278919 1.0702204882 0.3811949221 0.5484695637 -0.6293083939 0.397293989965 +1403715297612143104.0000000000 0.2366910930 -0.0949965484 1.0648197069 0.3852960526 0.5552310562 -0.6247943193 0.391021079709 +1403715297662142976.0000000000 0.2452858712 -0.1149093226 1.0595264453 0.3893908130 0.5611089787 -0.6212922221 0.384093066219 +1403715297712143104.0000000000 0.2554227491 -0.1353542988 1.0547363875 0.3947062439 0.5655789539 -0.6180479939 0.377285177589 +1403715297762142976.0000000000 0.2677489906 -0.1565208448 1.0502019653 0.4004708217 0.5695579752 -0.6143060764 0.371288133898 +1403715297812143104.0000000000 0.2824594688 -0.1787119445 1.0470329201 0.4083935297 0.5719206104 -0.6077937212 0.36974089943 +1403715297862142976.0000000000 0.2990178685 -0.2019954242 1.0450893022 0.4174226572 0.5736584347 -0.5999840985 0.369720714819 +1403715297912143104.0000000000 0.3172355516 -0.2263071084 1.0439018347 0.4263837382 0.5754552642 -0.5910987756 0.371012646928 +1403715297962142976.0000000000 0.3366012437 -0.2514992771 1.0437101380 0.4384113067 0.5752719512 -0.5811119407 0.373050426471 +1403715298012143104.0000000000 0.3556481189 -0.2776642377 1.0432872756 0.4496677893 0.5764017268 -0.5691994550 0.376260427079 +1403715298062142976.0000000000 0.3735453547 -0.3046425446 1.0425802554 0.4582684018 0.5801295096 -0.5568806025 0.378581323511 +1403715298112143104.0000000000 0.3904660449 -0.3327304358 1.0415640932 0.4633806958 0.5865444235 -0.5433078779 0.382178649222 +1403715298162142976.0000000000 0.4060114880 -0.3616055129 1.0393162676 0.4638019266 0.5966534644 -0.5297097651 0.385097365841 +1403715298212143104.0000000000 0.4197796549 -0.3910748950 1.0364641736 0.4615643600 0.6084900066 -0.5162471768 0.387539812025 +1403715298262142976.0000000000 0.4317068927 -0.4200169914 1.0339699510 0.4593285447 0.6201020047 -0.5035832060 0.388451729896 +1403715298312143104.0000000000 0.4418903855 -0.4481521510 1.0321879332 0.4577712864 0.6298483640 -0.4933579249 0.38772986161 +1403715298362142976.0000000000 0.4501885874 -0.4749309685 1.0304949117 0.4553013160 0.6389791997 -0.4860090851 0.384969431405 +1403715298412143104.0000000000 0.4566963632 -0.5000477568 1.0301370881 0.4528111592 0.6464992077 -0.4810072176 0.381618769393 +1403715298462142976.0000000000 0.4617309327 -0.5235749901 1.0305521834 0.4504114275 0.6526196371 -0.4771031225 0.37893240272 +1403715298512143104.0000000000 0.4659041211 -0.5452714958 1.0313094590 0.4478930433 0.6576692376 -0.4730998339 0.378205688636 +1403715298562142976.0000000000 0.4695096862 -0.5645691186 1.0326058637 0.4444261965 0.6621579545 -0.4689729534 0.379600537629 +1403715298612143104.0000000000 0.4722715903 -0.5810104761 1.0343697177 0.4412840226 0.6654887309 -0.4649088388 0.382430297 +1403715298662142976.0000000000 0.4737533527 -0.5945728488 1.0363800242 0.4386486067 0.6680872369 -0.4611607274 0.385457685449 +1403715298712143104.0000000000 0.4739461647 -0.6048261895 1.0391597228 0.4363834785 0.6697507029 -0.4587061403 0.388062021525 +1403715298762142976.0000000000 0.4726386300 -0.6113072600 1.0429077525 0.4354378215 0.6699881110 -0.4577213989 0.389872999438 +1403715298812143104.0000000000 0.4694269548 -0.6140627798 1.0474234203 0.4354179571 0.6695862564 -0.4596113960 0.38835912845 +1403715298862142976.0000000000 0.4639028827 -0.6130750703 1.0518562246 0.4367461413 0.6687951113 -0.4682183025 0.377806204821 +1403715298912143104.0000000000 0.4572695082 -0.6084197795 1.0569524362 0.4404051848 0.6672176368 -0.4782856285 0.363464930865 +1403715298962142976.0000000000 0.4500108468 -0.6013422121 1.0617524168 0.4445537357 0.6663068566 -0.4870515990 0.348120509104 +1403715299012143104.0000000000 0.4430472772 -0.5925285869 1.0661880247 0.4471874836 0.6672372924 -0.4919111518 0.335918396241 +1403715299062142976.0000000000 0.4367105728 -0.5823773151 1.0704204836 0.4502438480 0.6688009554 -0.4940235596 0.325463487856 +1403715299112143104.0000000000 0.4315734186 -0.5712672261 1.0747142184 0.4531949050 0.6712804808 -0.4931124374 0.31754845018 +1403715299162142976.0000000000 0.4279022998 -0.5592475043 1.0791800576 0.4562245898 0.6740739243 -0.4907037907 0.310955395691 +1403715299212143104.0000000000 0.4255673134 -0.5464115796 1.0834188532 0.4591826814 0.6775186295 -0.4868946046 0.305046579668 +1403715299262142976.0000000000 0.4246228688 -0.5329086247 1.0873058392 0.4618225848 0.6816537398 -0.4823767232 0.298966178822 +1403715299312143104.0000000000 0.4252003146 -0.5188547815 1.0913890235 0.4656884789 0.6854558307 -0.4766803897 0.293360445216 +1403715299362142976.0000000000 0.4273429226 -0.5044268357 1.0953360713 0.4691146593 0.6899298367 -0.4705046949 0.287321403614 +1403715299412143104.0000000000 0.4314105599 -0.4894025322 1.0997356046 0.4734272553 0.6941679155 -0.4635067519 0.281352145877 +1403715299462142976.0000000000 0.4374473879 -0.4741425832 1.1044092247 0.4779926046 0.6985957047 -0.4554418211 0.275789519413 +1403715299512143104.0000000000 0.4453824554 -0.4585202579 1.1094628715 0.4838450325 0.7024873184 -0.4463678163 0.270483501602 +1403715299562142976.0000000000 0.4545072716 -0.4426073701 1.1141928201 0.4895785246 0.7067648774 -0.4365610340 0.264973092868 +1403715299612143104.0000000000 0.4649886616 -0.4264408397 1.1185495916 0.4959116495 0.7106113528 -0.4257591901 0.260446257989 +1403715299662142976.0000000000 0.4760132738 -0.4100405229 1.1221165990 0.5013695063 0.7152337141 -0.4153547215 0.254066541951 +1403715299712143104.0000000000 0.4880470956 -0.3935771736 1.1255153344 0.5078049296 0.7190782329 -0.4047878316 0.247401414284 +1403715299762142976.0000000000 0.5010382226 -0.3772499532 1.1282538074 0.5120765081 0.7246600198 -0.3935367518 0.240362914336 +1403715299812143104.0000000000 0.5148332218 -0.3610349596 1.1308632535 0.5180235461 0.7290417313 -0.3821119258 0.232680544625 +1403715299862142976.0000000000 0.5292678915 -0.3453404030 1.1322061541 0.5227785278 0.7341799384 -0.3705951826 0.224369426374 +1403715299912143104.0000000000 0.5445277709 -0.3298755634 1.1335963481 0.5276822246 0.7390631130 -0.3578259339 0.217480541352 +1403715299962142976.0000000000 0.5604343924 -0.3145165552 1.1349070574 0.5325363525 0.7435931443 -0.3452045826 0.210494810402 +1403715300012143104.0000000000 0.5771176828 -0.2994723706 1.1358597856 0.5360198330 0.7481182730 -0.3338438314 0.203838378221 +1403715300062142976.0000000000 0.5948805589 -0.2845191726 1.1373680676 0.5417860836 0.7501092644 -0.3219652154 0.200355511967 +1403715300112143104.0000000000 0.6131748003 -0.2702616788 1.1387444903 0.5473920009 0.7510535435 -0.3120915422 0.197178704153 +1403715300162142976.0000000000 0.6319931373 -0.2568482190 1.1394472931 0.5510953551 0.7524614353 -0.3018940262 0.197371971015 +1403715300212143104.0000000000 0.6510831099 -0.2440709369 1.1397180953 0.5531666147 0.7542448993 -0.2916205591 0.200196847879 +1403715300262142976.0000000000 0.6697352396 -0.2315736004 1.1404935470 0.5567497056 0.7541522349 -0.2833778187 0.202438098761 +1403715300312143104.0000000000 0.6872230049 -0.2194970091 1.1418478169 0.5608014604 0.7531194567 -0.2792977124 0.200762530719 +1403715300362142976.0000000000 0.7038047689 -0.2079327387 1.1434948880 0.5649333761 0.7514647942 -0.2772652264 0.198179055153 +1403715300412143104.0000000000 0.7194615743 -0.1969947285 1.1456824827 0.5683244355 0.7499963636 -0.2770298508 0.194337985123 +1403715300462142976.0000000000 0.7342882534 -0.1872534022 1.1477421001 0.5709611796 0.7485601084 -0.2778121820 0.191001275007 +1403715300512143104.0000000000 0.7482412903 -0.1788766302 1.1496433283 0.5720139050 0.7480692628 -0.2779213584 0.189610624915 +1403715300562142976.0000000000 0.7613670289 -0.1718386574 1.1513588514 0.5722708013 0.7478077419 -0.2794431109 0.187619985127 +1403715300612143104.0000000000 0.7737781721 -0.1662096659 1.1528116572 0.5713782790 0.7481922024 -0.2810670335 0.186377608947 +1403715300662142976.0000000000 0.7857047141 -0.1619551659 1.1540864215 0.5705489564 0.7483627609 -0.2827331823 0.185712180758 +1403715300712143104.0000000000 0.7971048730 -0.1589839515 1.1557124673 0.5697213703 0.7483709452 -0.2850980154 0.184601219558 +1403715300762142976.0000000000 0.8080484004 -0.1575134829 1.1575024253 0.5694053134 0.7478134815 -0.2869740491 0.184928313503 +1403715300812143104.0000000000 0.8186188489 -0.1575058344 1.1589401247 0.5691133372 0.7472851082 -0.2876714949 0.186869172403 +1403715300862142976.0000000000 0.8289377036 -0.1587952619 1.1601525535 0.5684234641 0.7470382191 -0.2873568296 0.190406714947 +1403715300912143104.0000000000 0.8385764546 -0.1614978985 1.1607590918 0.5671067918 0.7472718915 -0.2865129021 0.194640601862 +1403715300962142976.0000000000 0.8474533322 -0.1654583492 1.1612236718 0.5657690531 0.7475397670 -0.2856390764 0.198746052308 +1403715301012143104.0000000000 0.8554099166 -0.1703138451 1.1614982089 0.5647320256 0.7476048062 -0.2851390993 0.202139771416 +1403715301062142976.0000000000 0.8623517125 -0.1758769691 1.1614812625 0.5642952498 0.7471462919 -0.2845276926 0.205881717697 +1403715301112143104.0000000000 0.8682535223 -0.1822934073 1.1614811545 0.5647474607 0.7459519809 -0.2835654372 0.210253634045 +1403715301162142976.0000000000 0.8728616401 -0.1893167543 1.1611331782 0.5651339734 0.7449247354 -0.2819609442 0.214962221579 +1403715301212143104.0000000000 0.8759189032 -0.1973204775 1.1604720289 0.5655365956 0.7438228631 -0.2802458758 0.219904880741 +1403715301262142976.0000000000 0.8769824969 -0.2061239323 1.1593166529 0.5652803937 0.7434920066 -0.2784778827 0.2238923434 +1403715301312143104.0000000000 0.8757565311 -0.2154081870 1.1577725099 0.5655457663 0.7430239279 -0.2768850215 0.226733574163 +1403715301362142976.0000000000 0.8719825161 -0.2253519579 1.1557351959 0.5656048061 0.7428050064 -0.2763035779 0.228009339031 +1403715301412143104.0000000000 0.8657228819 -0.2357759883 1.1530098528 0.5650364703 0.7432750279 -0.2768518104 0.227220367328 +1403715301462142976.0000000000 0.8570390027 -0.2466123159 1.1500373331 0.5649014041 0.7436535400 -0.2797589173 0.222712290481 +1403715301512143104.0000000000 0.8463008815 -0.2582119651 1.1460559512 0.5625368327 0.7457421260 -0.2841790788 0.216016769266 +1403715301562142976.0000000000 0.8340447944 -0.2704715854 1.1409667420 0.5583239732 0.7490204278 -0.2887604669 0.209428108079 +1403715301612143104.0000000000 0.8207356077 -0.2831553962 1.1354868838 0.5536211163 0.7523739078 -0.2932639487 0.20355200503 +1403715301662142976.0000000000 0.8069254136 -0.2961330760 1.1297523543 0.5501977562 0.7545549334 -0.2974800255 0.198582265001 +1403715301712143104.0000000000 0.7930824073 -0.3096503990 1.1234771540 0.5475547925 0.7559904783 -0.3000822190 0.196501419405 +1403715301762142976.0000000000 0.7793323208 -0.3237184960 1.1164893334 0.5453416588 0.7569843079 -0.3011717387 0.197161904376 +1403715301812143104.0000000000 0.7658145417 -0.3380669525 1.1094719042 0.5443556749 0.7572013021 -0.2998158611 0.20108092088 +1403715301862142976.0000000000 0.7520351923 -0.3522179299 1.1024510646 0.5434113042 0.7573148615 -0.2982334306 0.205511984895 +1403715301912143104.0000000000 0.7376578151 -0.3662577297 1.0957041858 0.5421935754 0.7575535986 -0.2974963057 0.208889014043 +1403715301962142976.0000000000 0.7225287806 -0.3801955630 1.0897859302 0.5412888658 0.7576432375 -0.2986090776 0.209322018144 +1403715302012143104.0000000000 0.7069947055 -0.3938921328 1.0847249175 0.5405891601 0.7575317714 -0.2983633091 0.211868617287 +1403715302062142976.0000000000 0.6906410499 -0.4074144599 1.0801097527 0.5395307334 0.7576734426 -0.2983427998 0.214077359735 +1403715302112143104.0000000000 0.6734506858 -0.4206971116 1.0757295824 0.5374291043 0.7586102612 -0.2988082249 0.215392837061 +1403715302162142976.0000000000 0.6552373086 -0.4337461054 1.0716332188 0.5339987718 0.7604339259 -0.2996184702 0.216366190297 +1403715302212143104.0000000000 0.6362702221 -0.4463900664 1.0681207981 0.5309548659 0.7618305373 -0.3008000679 0.217302742461 +1403715302262142976.0000000000 0.6166098670 -0.4581317537 1.0648647150 0.5273444574 0.7635242270 -0.3023869470 0.217946581076 +1403715302312143104.0000000000 0.5967465322 -0.4686524692 1.0624435141 0.5243159902 0.7647875727 -0.3032543485 0.219612183337 +1403715302362142976.0000000000 0.5763807697 -0.4778133893 1.0609596562 0.5223682152 0.7651114185 -0.3044353083 0.221483877753 +1403715302412143104.0000000000 0.5554391808 -0.4857043898 1.0601189096 0.5213496960 0.7648376638 -0.3053522502 0.223557253809 +1403715302462142976.0000000000 0.5338229689 -0.4922908570 1.0602338768 0.5218203827 0.7635152642 -0.3082120703 0.223054363988 +1403715302512143104.0000000000 0.5112363057 -0.4976375964 1.0613887620 0.5231339641 0.7616685002 -0.3133704786 0.219068241985 +1403715302562142976.0000000000 0.4884266894 -0.5021172262 1.0627012428 0.5231812051 0.7606788999 -0.3183776354 0.21513883708 +1403715302612143104.0000000000 0.4653280970 -0.5059656866 1.0639434385 0.5237535790 0.7594662640 -0.3228582964 0.211318960116 +1403715302662142976.0000000000 0.4422051487 -0.5095982239 1.0646574486 0.5228292667 0.7593161758 -0.3258048314 0.209618021321 +1403715302712143104.0000000000 0.4193765211 -0.5125102317 1.0653120237 0.5225761341 0.7588039258 -0.3294977083 0.206305711334 +1403715302762142976.0000000000 0.3969883159 -0.5150468979 1.0648532717 0.5213227005 0.7591418521 -0.3321122351 0.204028805956 +1403715302812143104.0000000000 0.3752239808 -0.5170603636 1.0629913427 0.5189462958 0.7603810406 -0.3348128919 0.201036669629 +1403715302862142976.0000000000 0.3547203815 -0.5183793847 1.0600633267 0.5156875296 0.7624383680 -0.3360967233 0.199482077637 +1403715302912143104.0000000000 0.3351095060 -0.5185837339 1.0567873808 0.5134327420 0.7645721199 -0.3364862096 0.19645183551 +1403715302962142976.0000000000 0.3164157153 -0.5179438740 1.0537254827 0.5118850939 0.7671880344 -0.3348080040 0.193131486179 +1403715303012143104.0000000000 0.2989442032 -0.5164349376 1.0504085433 0.5105990563 0.7705269674 -0.3308751661 0.189995843796 +1403715303062142976.0000000000 0.2827229118 -0.5138085066 1.0470653571 0.5104456865 0.7738011081 -0.3259104396 0.185632517486 +1403715303112143104.0000000000 0.2678011914 -0.5101230997 1.0433377722 0.5108048868 0.7776777865 -0.3186735893 0.180949638035 +1403715303162142976.0000000000 0.2541439527 -0.5049708176 1.0395678074 0.5124268012 0.7814058230 -0.3093923413 0.176352182751 +1403715303212143104.0000000000 0.2416588721 -0.4983226677 1.0363543102 0.5161249713 0.7843373316 -0.2984176870 0.171396757132 +1403715303262142976.0000000000 0.2303401929 -0.4902713539 1.0342498096 0.5226332273 0.7857859193 -0.2855131961 0.166964707915 +1403715303312143104.0000000000 0.2199331639 -0.4810998620 1.0323775594 0.5295430019 0.7871182710 -0.2709233394 0.163185724775 +1403715303362142976.0000000000 0.2101016968 -0.4710584388 1.0305043930 0.5359606365 0.7886952649 -0.2554313621 0.159564390091 +1403715303412143104.0000000000 0.2007669599 -0.4604046914 1.0288920340 0.5416591065 0.7903623271 -0.2402277198 0.155638834861 +1403715303462142976.0000000000 0.1912635942 -0.4490004311 1.0271903373 0.5460608227 0.7926000400 -0.2256110679 0.150673158054 +1403715303512143104.0000000000 0.1810716091 -0.4370632605 1.0254960481 0.5497446733 0.7950268813 -0.2122567068 0.143736364844 +1403715303562142976.0000000000 0.1706710627 -0.4246314078 1.0239379943 0.5534558317 0.7970619179 -0.1980236695 0.138439761717 +1403715303612143104.0000000000 0.1592834604 -0.4117619739 1.0229261118 0.5572758252 0.7987950073 -0.1867506007 0.128430541552 +1403715303662142976.0000000000 0.1474851464 -0.3983560823 1.0224023616 0.5625664481 0.7991901167 -0.1758441883 0.117868444975 +1403715303712143104.0000000000 0.1351757335 -0.3849235306 1.0217327896 0.5666474775 0.8001047825 -0.1652854168 0.10688173021 +1403715303762142976.0000000000 0.1224595561 -0.3717279359 1.0212045095 0.5711164823 0.8003876877 -0.1550961077 0.0956593457116 +1403715303812143104.0000000000 0.1095504583 -0.3588903245 1.0203460027 0.5751497161 0.8006464151 -0.1440813058 0.0860738013221 +1403715303862142976.0000000000 0.0965250712 -0.3464838194 1.0198577864 0.5799004975 0.7999460968 -0.1343814043 0.0757845194885 +1403715303912143104.0000000000 0.0835667775 -0.3347680701 1.0191928179 0.5836010064 0.7994234073 -0.1257828191 0.0671622181696 +1403715303962142976.0000000000 0.0711036971 -0.3235086883 1.0183876622 0.5863808779 0.7990565237 -0.1183411820 0.0605103510314 +1403715304012143104.0000000000 0.0590008035 -0.3131597475 1.0171664340 0.5881046650 0.7990792964 -0.1122949722 0.0547267777588 +1403715304062142976.0000000000 0.0473255125 -0.3035785788 1.0155952664 0.5894628270 0.7990392043 -0.1074590773 0.050224220271 +1403715304112143104.0000000000 0.0361084633 -0.2950426600 1.0139805173 0.5909046614 0.7986152201 -0.1047128352 0.0456139622996 +1403715304162142976.0000000000 0.0256072137 -0.2875791185 1.0123526147 0.5924764103 0.7979246219 -0.1024150536 0.0424164796747 +1403715304212143104.0000000000 0.0157703032 -0.2814947785 1.0099798730 0.5922857531 0.7983806252 -0.1008727426 0.0401329514859 +1403715304262142976.0000000000 0.0065173170 -0.2764139389 1.0070252938 0.5911665623 0.7993799495 -0.1002086907 0.0383667859803 +1403715304312143104.0000000000 -0.0021557085 -0.2721351191 1.0037605633 0.5894357053 0.8007491387 -0.0998955450 0.0372457545273 +1403715304362142976.0000000000 -0.0101600462 -0.2685031368 0.9999470873 0.5877716392 0.8019384687 -0.1003002052 0.0368654495442 +1403715304412143104.0000000000 -0.0174863747 -0.2658398766 0.9955298642 0.5858792525 0.8032274798 -0.1009800787 0.0370694050948 +1403715304462142976.0000000000 -0.0239578971 -0.2637681024 0.9907398872 0.5844905428 0.8040617431 -0.1018462994 0.0385077900249 +1403715304512143104.0000000000 -0.0295573369 -0.2622121842 0.9846625931 0.5844801162 0.8039126858 -0.1014367096 0.0426377918265 +1403715304562142976.0000000000 -0.0348464706 -0.2610491813 0.9755503027 0.5838784301 0.8041216818 -0.1016053150 0.046375204838 +1403715304612143104.0000000000 -0.0399136325 -0.2601516002 0.9639054880 0.5836097684 0.8040587452 -0.1019815336 0.0498892707311 +1403715304662142976.0000000000 -0.0450742052 -0.2598008805 0.9510757932 0.5844644438 0.8031249753 -0.1033757338 0.0520100536194 +1403715304712143104.0000000000 -0.0502984690 -0.2601078375 0.9374495035 0.5845704286 0.8027314251 -0.1046165607 0.0543603568058 +1403715304762142976.0000000000 -0.0554447895 -0.2609016988 0.9236224064 0.5834436923 0.8032378737 -0.1054360250 0.0573203340484 +1403715304812143104.0000000000 -0.0608310122 -0.2625544659 0.9116133418 0.5827890244 0.8034391518 -0.1065570448 0.0590599578316 +1403715304862142976.0000000000 -0.0662962563 -0.2646535225 0.9024618920 0.5814576648 0.8041431979 -0.1076013605 0.0606848293541 +1403715304912143104.0000000000 -0.0717120227 -0.2666691550 0.8965306693 0.5803857756 0.8046938955 -0.1082220093 0.0625146601186 +1403715304962142976.0000000000 -0.0772483031 -0.2689096789 0.8942213114 0.5790308498 0.8055048088 -0.1091564868 0.0630090418062 +1403715305012143104.0000000000 -0.0830298070 -0.2714103321 0.8949320852 0.5785898622 0.8057230500 -0.1095646389 0.0635588537754 +1403715305062142976.0000000000 -0.0892376971 -0.2741601641 0.8979712571 0.5776289391 0.8063390404 -0.1106095102 0.0626713408457 +1403715305112143104.0000000000 -0.0956596721 -0.2769429803 0.9030141444 0.5772534209 0.8065744203 -0.1111505663 0.0621429335597 +1403715305162142976.0000000000 -0.1023414737 -0.2797277246 0.9085421107 0.5762481808 0.8073069820 -0.1113390368 0.0616205301172 +1403715305212143104.0000000000 -0.1089567228 -0.2824567753 0.9135216624 0.5748322428 0.8083647955 -0.1118825446 0.0599712126936 +1403715305262142976.0000000000 -0.1153120056 -0.2847993816 0.9179818845 0.5740494117 0.8089701148 -0.1122306145 0.0586422665759 +1403715305312143104.0000000000 -0.1213932625 -0.2872480586 0.9217958377 0.5734668270 0.8095150828 -0.1113615708 0.0584784533337 +1403715305362142976.0000000000 -0.1276232156 -0.2895700617 0.9253218316 0.5724811812 0.8103544065 -0.1112904226 0.0566169137054 +1403715305412143104.0000000000 -0.1336286976 -0.2916579816 0.9288774165 0.5719828109 0.8109225340 -0.1097268413 0.0565714431039 +1403715305462142976.0000000000 -0.1396285235 -0.2935225701 0.9338726590 0.5726697165 0.8107331668 -0.1080006136 0.0556506563907 +1403715305512143104.0000000000 -0.1454120031 -0.2955412319 0.9418285024 0.5738945510 0.8101710979 -0.1066857060 0.053721471353 +1403715305562142976.0000000000 -0.1509416329 -0.2975573445 0.9529061788 0.5745445088 0.8100816680 -0.1044752396 0.0524521017202 +1403715305612143104.0000000000 -0.1562248044 -0.2997084530 0.9670251386 0.5743775367 0.8105907037 -0.1022244002 0.0508264527206 +1403715305662142976.0000000000 -0.1614047200 -0.3015038378 0.9849225540 0.5754528258 0.8102064939 -0.0999677730 0.0492536995934 +1403715305712143104.0000000000 -0.1665816209 -0.3031136155 1.0053670792 0.5757576124 0.8102423980 -0.0997811765 0.0453226772017 +1403715305762142976.0000000000 -0.1711883750 -0.3048261676 1.0270124372 0.5763815388 0.8100850939 -0.0981784458 0.0436744221184 +1403715305812143104.0000000000 -0.1752741856 -0.3065721400 1.0484597892 0.5764244196 0.8102707045 -0.0971883139 0.0418414340017 +1403715305862142976.0000000000 -0.1786570794 -0.3082030436 1.0690596384 0.5760205063 0.8107596884 -0.0956142959 0.0415573140956 +1403715305912143104.0000000000 -0.1816835772 -0.3098798555 1.0888872063 0.5750803250 0.8115634478 -0.0945791780 0.0412573529669 +1403715305962142976.0000000000 -0.1841371668 -0.3109189557 1.1082452089 0.5748014928 0.8118545245 -0.0937501906 0.0413083124718 +1403715306012143104.0000000000 -0.1863141656 -0.3116741579 1.1265225783 0.5743444106 0.8122324646 -0.0933258440 0.0411971881994 +1403715306062142976.0000000000 -0.1880069537 -0.3124145154 1.1434532556 0.5731750783 0.8130984276 -0.0926956494 0.0418185761116 +1403715306112143104.0000000000 -0.1894430906 -0.3129779536 1.1593862844 0.5714783357 0.8142894652 -0.0929033297 0.0414022948915 +1403715306162142976.0000000000 -0.1907309274 -0.3130606449 1.1751154188 0.5710620474 0.8144789441 -0.0952491271 0.0379445850454 +1403715306212143104.0000000000 -0.1912513779 -0.3124447884 1.1907506415 0.5728361892 0.8129220922 -0.0992364228 0.0341833980464 +1403715306262142976.0000000000 -0.1905859933 -0.3116183976 1.2059189506 0.5756699871 0.8104120107 -0.1043390275 0.0308189258103 +1403715306312143104.0000000000 -0.1886459423 -0.3108074938 1.2205105170 0.5794408626 0.8069265995 -0.1111821840 0.0275003970024 +1403715306362142976.0000000000 -0.1851983727 -0.3101366562 1.2349753502 0.5831950156 0.8032426291 -0.1184118129 0.0257583988874 +1403715306412143104.0000000000 -0.1797537034 -0.3098923523 1.2494962596 0.5881945224 0.7984211533 -0.1260557541 0.0257062741129 +1403715306462142976.0000000000 -0.1721258602 -0.3103854066 1.2636422937 0.5916955533 0.7945047763 -0.1336795843 0.0280767055996 +1403715306512143104.0000000000 -0.1623330804 -0.3122097886 1.2769023659 0.5942008767 0.7911835212 -0.1409010156 0.0331791758588 +1403715306562142976.0000000000 -0.1503928290 -0.3154262844 1.2897858799 0.5961854075 0.7880341326 -0.1481443281 0.0402296381946 +1403715306612143104.0000000000 -0.1363198617 -0.3200137191 1.3029922627 0.5988639490 0.7839924546 -0.1561743688 0.048242805657 +1403715306662142976.0000000000 -0.1203960620 -0.3263309992 1.3162405672 0.6011747709 0.7799534026 -0.1639371053 0.0581911511122 +1403715306712143104.0000000000 -0.1030017024 -0.3349051541 1.3289685141 0.6023080967 0.7765873604 -0.1707824239 0.0705010072505 +1403715306762142976.0000000000 -0.0845377580 -0.3460055320 1.3409339813 0.6022202402 0.7737816304 -0.1773513383 0.0844942222474 +1403715306812143104.0000000000 -0.0654871329 -0.3594817908 1.3534287066 0.6040390404 0.7690132590 -0.1845556591 0.0984614337695 +1403715306862142976.0000000000 -0.0462693960 -0.3752786174 1.3656277958 0.6055226001 0.7640536211 -0.1917629690 0.113099109161 +1403715306912143104.0000000000 -0.0272681477 -0.3934976390 1.3763955344 0.6048714651 0.7603006797 -0.1983944386 0.12927889916 +1403715306962142976.0000000000 -0.0089753776 -0.4138135471 1.3863779301 0.6014316720 0.7583411134 -0.2044781417 0.146244279073 +1403715307012143104.0000000000 0.0082565999 -0.4360875808 1.3947907887 0.5963438120 0.7571429895 -0.2100184834 0.164319164995 +1403715307062142976.0000000000 0.0234745990 -0.4605661498 1.4003616960 0.5900089157 0.7565315545 -0.2166384142 0.180602557845 +1403715307112143104.0000000000 0.0362378842 -0.4867911555 1.4020992244 0.5817139186 0.7572862150 -0.2249019396 0.193766929722 +1403715307162142976.0000000000 0.0465421070 -0.5140306426 1.3997017520 0.5715307670 0.7592279659 -0.2340877016 0.205252103772 +1403715307212143104.0000000000 0.0543000466 -0.5417547679 1.3944469740 0.5618628387 0.7605607156 -0.2435340635 0.215751496389 +1403715307262142976.0000000000 0.0594535690 -0.5695402527 1.3863168262 0.5520851338 0.7618311320 -0.2526691969 0.225773355931 +1403715307312143104.0000000000 0.0620099115 -0.5968420391 1.3759122545 0.5436877263 0.7620034334 -0.2630298658 0.233601612693 +1403715307362142976.0000000000 0.0618571057 -0.6231999343 1.3640296871 0.5359459396 0.7618147402 -0.2753993756 0.237813867112 +1403715307412143104.0000000000 0.0591606709 -0.6480268434 1.3520000987 0.5295387223 0.7607525019 -0.2908584564 0.237161824061 +1403715307462142976.0000000000 0.0545947103 -0.6716309732 1.3400569885 0.5245053941 0.7586352134 -0.3061694246 0.235853742777 +1403715307512143104.0000000000 0.0488044876 -0.6942981680 1.3281716520 0.5199875761 0.7561323356 -0.3203652936 0.235038061686 +1403715307562142976.0000000000 0.0423444109 -0.7157313751 1.3164582454 0.5162523216 0.7529069147 -0.3340567436 0.234565151332 +1403715307612143104.0000000000 0.0357724605 -0.7359011525 1.3047657187 0.5129030662 0.7492786555 -0.3466333606 0.235281224169 +1403715307662142976.0000000000 0.0294697476 -0.7553081486 1.2931177568 0.5094378858 0.7453815187 -0.3585115084 0.237379296441 +1403715307712143104.0000000000 0.0235195972 -0.7741617331 1.2805988092 0.5046934769 0.7419190944 -0.3695536193 0.241393194126 +1403715307762142976.0000000000 0.0180066918 -0.7926982807 1.2675711456 0.4999626500 0.7380780273 -0.3796258290 0.247310339824 +1403715307812143104.0000000000 0.0132377213 -0.8104807570 1.2540930800 0.4948095443 0.7340862467 -0.3894719856 0.254150486391 +1403715307862142976.0000000000 0.0088629645 -0.8274737125 1.2405143061 0.4899273451 0.7297056687 -0.3990390422 0.261282751887 +1403715307912143104.0000000000 0.0049304458 -0.8435334781 1.2268254184 0.4845220495 0.7255728920 -0.4081849713 0.268639891252 +1403715307962142976.0000000000 0.0015657124 -0.8585712201 1.2131699306 0.4795502231 0.7209922512 -0.4168605617 0.276458006518 +1403715308012143104.0000000000 -0.0011504484 -0.8725474485 1.1995587286 0.4750704189 0.7158323748 -0.4255783828 0.28420969071 +1403715308062142976.0000000000 -0.0032909902 -0.8853344399 1.1862331494 0.4706136702 0.7105707383 -0.4343772081 0.291424845257 +1403715308112143104.0000000000 -0.0048990995 -0.8968882863 1.1731662543 0.4662887287 0.7052163961 -0.4429810640 0.298349514973 +1403715308162142976.0000000000 -0.0060472788 -0.9072184403 1.1603766153 0.4620166655 0.7004597144 -0.4507714293 0.304469879965 +1403715308212143104.0000000000 -0.0067436714 -0.9162464139 1.1477994556 0.4587009954 0.6957990856 -0.4574103272 0.310214154976 +1403715308262142976.0000000000 -0.0071188496 -0.9240006284 1.1350635457 0.4551635824 0.6913050916 -0.4644507058 0.314974483785 +1403715308312143104.0000000000 -0.0071358746 -0.9305248579 1.1222485858 0.4514218591 0.6870254042 -0.4707909430 0.320265962938 +1403715308362142976.0000000000 -0.0067897878 -0.9354738294 1.1098820053 0.4490006638 0.6822942286 -0.4769763980 0.32460207219 +1403715308412143104.0000000000 -0.0063913091 -0.9389593459 1.0975246586 0.4467948865 0.6782012712 -0.4831586527 0.327070453497 +1403715308462142976.0000000000 -0.0056747870 -0.9409618162 1.0853819736 0.4459634150 0.6741957699 -0.4885442916 0.328483137372 +1403715308512143104.0000000000 -0.0045091218 -0.9414694569 1.0742301049 0.4464839236 0.6702397813 -0.4933967902 0.32861885054 +1403715308562142976.0000000000 -0.0027801408 -0.9406367334 1.0652831943 0.4473478755 0.6670230452 -0.4977163274 0.327473041536 +1403715308612143104.0000000000 -0.0003152682 -0.9391406321 1.0589446685 0.4482149983 0.6645511696 -0.5012133436 0.325975831222 +1403715308662142976.0000000000 0.0031284590 -0.9373630595 1.0552543784 0.4490718902 0.6627185401 -0.5034001047 0.325156744703 +1403715308712143104.0000000000 0.0075078605 -0.9352144644 1.0540578189 0.4494459717 0.6615527149 -0.5056522125 0.323515322504 +1403715308762142976.0000000000 0.0130057297 -0.9328774652 1.0556327868 0.4499356650 0.6608076913 -0.5066996993 0.322717379675 +1403715308812143104.0000000000 0.0194924541 -0.9304131447 1.0593660684 0.4495831365 0.6610039101 -0.5073908417 0.321719393136 +1403715308862142976.0000000000 0.0270330588 -0.9278280638 1.0646372224 0.4497782836 0.6609910274 -0.5085020738 0.319712367973 +1403715308912143104.0000000000 0.0354503664 -0.9252252378 1.0699558225 0.4505273961 0.6609963925 -0.5093595752 0.317272213623 +1403715308962142976.0000000000 0.0452969135 -0.9224921493 1.0753468077 0.4524502112 0.6604863314 -0.5093118026 0.31567087322 +1403715309012143104.0000000000 0.0564099459 -0.9196379939 1.0807003560 0.4555624435 0.6596632423 -0.5085443169 0.31414955764 +1403715309062142976.0000000000 0.0687716427 -0.9168412364 1.0860756431 0.4600762029 0.6580250971 -0.5076634196 0.312427130053 +1403715309112143104.0000000000 0.0818673396 -0.9144801118 1.0909634680 0.4643267244 0.6567258263 -0.5070155603 0.30991467142 +1403715309162142976.0000000000 0.0958034730 -0.9127066092 1.0954149779 0.4686863826 0.6556708273 -0.5053738776 0.308263012455 +1403715309212143104.0000000000 0.1105174813 -0.9114517980 1.1003089585 0.4753175028 0.6530291318 -0.5036134349 0.306593758525 +1403715309262142976.0000000000 0.1261179723 -0.9110947539 1.1056632198 0.4838618278 0.6489633365 -0.5007028690 0.306628368579 +1403715309312143104.0000000000 0.1419069203 -0.9122173631 1.1104694810 0.4910482151 0.6460670721 -0.4969145256 0.307481614109 +1403715309362142976.0000000000 0.1575916281 -0.9149795190 1.1137730465 0.4932520820 0.6468567910 -0.4926993960 0.309072775784 +1403715309412143104.0000000000 0.1730292240 -0.9192162391 1.1161818875 0.4925110551 0.6499016475 -0.4880547377 0.311228665369 +1403715309462142976.0000000000 0.1881501587 -0.9246816563 1.1185269647 0.4903257813 0.6537084714 -0.4837315931 0.313447935777 +1403715309512143104.0000000000 0.2029524422 -0.9311418946 1.1213246558 0.4885989622 0.6570902432 -0.4795559260 0.315483090407 +1403715309562142976.0000000000 0.2174360401 -0.9379231501 1.1242509069 0.4869326177 0.6602707360 -0.4761539469 0.316570055122 +1403715309612143104.0000000000 0.2315863029 -0.9447551394 1.1279343123 0.4861772113 0.6624527950 -0.4733855807 0.317323345485 +1403715309662142976.0000000000 0.2450756510 -0.9519414589 1.1313712948 0.4859175710 0.6643098969 -0.4710431747 0.317324443825 +1403715309712143104.0000000000 0.2579559774 -0.9590924060 1.1346354990 0.4861363842 0.6656525411 -0.4699588944 0.315779587848 +1403715309762142976.0000000000 0.2699625967 -0.9663955030 1.1382630759 0.4865690747 0.6667023418 -0.4694503762 0.313647680296 +1403715309812143104.0000000000 0.2812235159 -0.9738894019 1.1423456034 0.4877886838 0.6673132599 -0.4697457504 0.309990553198 +1403715309862142976.0000000000 0.2922343371 -0.9815674768 1.1463372693 0.4895916426 0.6669160815 -0.4718101260 0.304824816527 +1403715309912143104.0000000000 0.3032571658 -0.9893683251 1.1500832083 0.4915953498 0.6664534933 -0.4743517592 0.298603686843 +1403715309962142976.0000000000 0.3143830639 -0.9982726671 1.1530263675 0.4947408093 0.6648745357 -0.4758806329 0.294467326963 +1403715310012143104.0000000000 0.3259966935 -1.0080298847 1.1552462698 0.4989751485 0.6624237018 -0.4761609024 0.292385764979 +1403715310062142976.0000000000 0.3386750475 -1.0185908521 1.1571749852 0.5040001380 0.6585255865 -0.4758141263 0.293136197095 +1403715310112143104.0000000000 0.3518915609 -1.0309053906 1.1586006869 0.5079878875 0.6542945985 -0.4756053507 0.296051405719 +1403715310162142976.0000000000 0.3649976710 -1.0450557363 1.1597008949 0.5107450956 0.6499589335 -0.4755406228 0.300921830718 +1403715310212143104.0000000000 0.3779911057 -1.0612150078 1.1608027774 0.5108532434 0.6466823567 -0.4757617707 0.307378643943 +1403715310262142976.0000000000 0.3904697071 -1.0794149626 1.1617791921 0.5084152030 0.6444516689 -0.4757913445 0.315940855818 +1403715310312143104.0000000000 0.4017941162 -1.0993764843 1.1628266294 0.5042061002 0.6427804070 -0.4759379445 0.325718636193 +1403715310362142976.0000000000 0.4115196331 -1.1203295519 1.1646306645 0.4997015204 0.6404893499 -0.4780626124 0.333957964127 +1403715310412143104.0000000000 0.4194562509 -1.1419923936 1.1667016811 0.4943487514 0.6380417886 -0.4818519825 0.341087459292 +1403715310462142976.0000000000 0.4258053245 -1.1640228907 1.1689240633 0.4887096321 0.6352588737 -0.4871754292 0.346798442897 +1403715310512143104.0000000000 0.4304721797 -1.1862117339 1.1708437413 0.4819280263 0.6338836258 -0.4931075564 0.350402431792 +1403715310562142976.0000000000 0.4337494822 -1.2081738326 1.1727741441 0.4749005104 0.6332761053 -0.4992622916 0.352374862543 +1403715310612143104.0000000000 0.4356262069 -1.2300149575 1.1750777392 0.4676814413 0.6334961498 -0.5051562753 0.353233400507 +1403715310662142976.0000000000 0.4367547260 -1.2513525912 1.1775360674 0.4609014761 0.6340331190 -0.5106401197 0.353296619718 +1403715310712143104.0000000000 0.4372337260 -1.2721009380 1.1797365326 0.4554121347 0.6342166589 -0.5153967933 0.353178655311 +1403715310762142976.0000000000 0.4374294545 -1.2921393143 1.1820414879 0.4511813754 0.6341408400 -0.5192971185 0.353031534305 +1403715310812143104.0000000000 0.4378311092 -1.3113572015 1.1843780063 0.4486798098 0.6334803763 -0.5224697672 0.352724231487 +1403715310862142976.0000000000 0.4382189653 -1.3299414585 1.1866075235 0.4473662274 0.6322123944 -0.5249247791 0.353022553487 +1403715310912143104.0000000000 0.4389470904 -1.3478531648 1.1888952780 0.4467122682 0.6308472705 -0.5268332500 0.353449568512 +1403715310962142976.0000000000 0.4397807637 -1.3652399959 1.1915988367 0.4460153750 0.6295225782 -0.5294817981 0.352733092083 +1403715311012143104.0000000000 0.4404159231 -1.3821737001 1.1937159676 0.4456562009 0.6281188089 -0.5328715777 0.350578371005 +1403715311062142976.0000000000 0.4414479341 -1.3985231711 1.1953806201 0.4459377718 0.6262052415 -0.5370488951 0.347253485894 +1403715311112143104.0000000000 0.4431256786 -1.4146650727 1.1966363036 0.4458154743 0.6249167512 -0.5401921195 0.344847924461 +1403715311162142976.0000000000 0.4457043010 -1.4306594539 1.1976436744 0.4463120403 0.6233552874 -0.5430236994 0.342577013577 +1403715311212143104.0000000000 0.4490966026 -1.4467220213 1.1987621282 0.4477891542 0.6211142123 -0.5458742002 0.340181372521 +1403715311262142976.0000000000 0.4533039999 -1.4630220821 1.1991479149 0.4480475761 0.6199773723 -0.5477429189 0.338908722556 +1403715311312143104.0000000000 0.4584479490 -1.4796086307 1.1998849748 0.4488034330 0.6186633826 -0.5498423454 0.336904278267 +1403715311362142976.0000000000 0.4646389200 -1.4967283194 1.2007289165 0.4485930904 0.6181094996 -0.5516067731 0.335313068013 +1403715311412143104.0000000000 0.4723486765 -1.5144464472 1.2022033624 0.4470163312 0.6185835638 -0.5519262060 0.336018209876 +1403715311462142976.0000000000 0.4812196121 -1.5328093143 1.2039034136 0.4443510452 0.6200644230 -0.5509542656 0.338410486315 +1403715311512143104.0000000000 0.4912091156 -1.5519458904 1.2055342620 0.4409797366 0.6218180214 -0.5494121840 0.342089859826 +1403715311562142976.0000000000 0.5021308238 -1.5710919415 1.2075473581 0.4388538325 0.6227785792 -0.5479607522 0.345388432094 +1403715311612143104.0000000000 0.5141307330 -1.5901255349 1.2101377966 0.4377723427 0.6230346092 -0.5467630862 0.348185840016 +1403715311662142976.0000000000 0.5269488114 -1.6088292568 1.2127062977 0.4365874426 0.6232113761 -0.5459921995 0.350558844964 +1403715311712143104.0000000000 0.5404463360 -1.6270435424 1.2153629076 0.4372677908 0.6220726592 -0.5464906864 0.350956429512 +1403715311762142976.0000000000 0.5546414633 -1.6448721387 1.2180089862 0.4381448536 0.6208560532 -0.5471445815 0.350998084711 +1403715311812143104.0000000000 0.5698805024 -1.6625667462 1.2206423385 0.4390534267 0.6192319627 -0.5483501333 0.350850390158 +1403715311862142976.0000000000 0.5859389792 -1.6802395884 1.2235007641 0.4408543666 0.6166365019 -0.5504076095 0.349940445453 +1403715311912143104.0000000000 0.6027178791 -1.6976863204 1.2264818071 0.4417614797 0.6146919646 -0.5512640612 0.350868235242 +1403715311962142976.0000000000 0.6200673127 -1.7152486297 1.2290672383 0.4406191471 0.6140332832 -0.5518227504 0.352575589817 +1403715312012143104.0000000000 0.6384733164 -1.7327398429 1.2312866211 0.4382338111 0.6143083762 -0.5516517360 0.355326199318 +1403715312062142976.0000000000 0.6575970837 -1.7501178922 1.2333216972 0.4354247797 0.6149400426 -0.5512387302 0.358315318598 +1403715312112143104.0000000000 0.6773558558 -1.7672501637 1.2356302297 0.4342903627 0.6143574287 -0.5509342059 0.361148627959 +1403715312162142976.0000000000 0.6972361668 -1.7839726718 1.2380375860 0.4328131640 0.6140631891 -0.5505177240 0.364045876776 +1403715312212143104.0000000000 0.7175080537 -1.8000077469 1.2407108454 0.4315241173 0.6136993695 -0.5506912535 0.36592234614 +1403715312262142976.0000000000 0.7380578953 -1.8155110308 1.2436304083 0.4307323599 0.6129233795 -0.5515592163 0.366847374259 +1403715312312143104.0000000000 0.7587232397 -1.8303960237 1.2468037037 0.4314444918 0.6112114871 -0.5531736886 0.366435586137 +1403715312362142976.0000000000 0.7795360146 -1.8448087277 1.2494826394 0.4319821204 0.6096974305 -0.5551471602 0.365338365622 +1403715312412143104.0000000000 0.8007606053 -1.8590768396 1.2520055963 0.4329647438 0.6079717210 -0.5566920005 0.364699785732 +1403715312462142976.0000000000 0.8224837592 -1.8731904572 1.2542718505 0.4343755824 0.6059854020 -0.5580971145 0.364180115964 +1403715312512143104.0000000000 0.8443655686 -1.8871853833 1.2560292607 0.4364117730 0.6039898796 -0.5583426880 0.364684017254 +1403715312562142976.0000000000 0.8665998848 -1.9013509817 1.2566375931 0.4367722439 0.6034213878 -0.5575924166 0.36633773035 +1403715312612143104.0000000000 0.8889626748 -1.9157073854 1.2565891138 0.4376430660 0.6027595848 -0.5554059788 0.369693965818 +1403715312662142976.0000000000 0.9114214095 -1.9300925097 1.2559098282 0.4388052472 0.6021910587 -0.5521408559 0.374107416437 +1403715312712143104.0000000000 0.9336137059 -1.9442034621 1.2546360394 0.4406289628 0.6013196802 -0.5490395907 0.377910422308 +1403715312762142976.0000000000 0.9552427857 -1.9580849378 1.2523260370 0.4414967475 0.6014995281 -0.5456298835 0.381532396877 +1403715312812143104.0000000000 0.9763587637 -1.9715030953 1.2494204955 0.4417250784 0.6025727639 -0.5416249434 0.385262819397 +1403715312862142976.0000000000 0.9965918475 -1.9840465296 1.2472101157 0.4439049919 0.6027038286 -0.5368714762 0.389185651377 +1403715312912143104.0000000000 1.0155816973 -1.9958612898 1.2463836371 0.4467049618 0.6026537341 -0.5324545773 0.392116407418 +1403715312962142976.0000000000 1.0330296867 -2.0068954223 1.2481461576 0.4492218534 0.6030064637 -0.5281231492 0.394548945611 +1403715313012143104.0000000000 1.0482211944 -2.0173219213 1.2526056370 0.4513009737 0.6036494797 -0.5245348737 0.395977149655 +1403715313062142976.0000000000 1.0616411469 -2.0268436198 1.2593336098 0.4520549043 0.6052788192 -0.5214946618 0.396644970033 +1403715313112143104.0000000000 1.0727417528 -2.0355491673 1.2682800471 0.4516519401 0.6077224916 -0.5192997159 0.396247023069 +1403715313162142976.0000000000 1.0822772710 -2.0432562093 1.2793110363 0.4521692933 0.6093804323 -0.5175177278 0.395441298243 +1403715313212143104.0000000000 1.0902048013 -2.0497559480 1.2909675437 0.4533332947 0.6104885918 -0.5173631761 0.392591323305 +1403715313262142976.0000000000 1.0960781566 -2.0553583871 1.3022263125 0.4541654055 0.6118065710 -0.5182853475 0.388338515493 +1403715313312143104.0000000000 1.0998708619 -2.0603886451 1.3123324623 0.4545634259 0.6132906509 -0.5195748424 0.38378203772 +1403715313362142976.0000000000 1.1026729886 -2.0648097610 1.3218286030 0.4540054479 0.6150360669 -0.5209797578 0.379723296246 +1403715313412143104.0000000000 1.1044921806 -2.0688700487 1.3309508840 0.4525765701 0.6171210719 -0.5221667935 0.376401209574 +1403715313462142976.0000000000 1.1056970909 -2.0729279049 1.3395384886 0.4512325129 0.6178150255 -0.5242158673 0.374020772252 +1403715313512143104.0000000000 1.1062342419 -2.0772503357 1.3481357959 0.4491755837 0.6175318408 -0.5259159578 0.374577263004 +1403715313562142976.0000000000 1.1063121415 -2.0815418440 1.3567669743 0.4464323931 0.6167775093 -0.5283258213 0.375706599544 +1403715313612143104.0000000000 1.1060734925 -2.0854532983 1.3653980146 0.4425518510 0.6164464573 -0.5303121325 0.37803527146 +1403715313662142976.0000000000 1.1054014027 -2.0889063461 1.3740326585 0.4393220307 0.6157263380 -0.5316974691 0.381018413471 +1403715313712143104.0000000000 1.1039732724 -2.0917767441 1.3832552533 0.4369992528 0.6147884835 -0.5329402686 0.383459833199 +1403715313762142976.0000000000 1.1020310571 -2.0939300612 1.3931051715 0.4356147515 0.6134957097 -0.5350775957 0.384128583968 +1403715313812143104.0000000000 1.0996496845 -2.0950323774 1.4034572392 0.4348493584 0.6119573071 -0.5367994184 0.385046327314 +1403715313862142976.0000000000 1.0968894305 -2.0953909831 1.4137102514 0.4339167520 0.6106300053 -0.5384412042 0.385912319801 +1403715313912143104.0000000000 1.0938658406 -2.0948028573 1.4242639937 0.4345692075 0.6086639941 -0.5404388823 0.385491323824 +1403715313962142976.0000000000 1.0902437957 -2.0934600435 1.4345253851 0.4363239646 0.6062845050 -0.5427070703 0.384069697811 +1403715314012143104.0000000000 1.0863248196 -2.0918667655 1.4431177555 0.4362270925 0.6045623056 -0.5455667792 0.382841000749 +1403715314062142976.0000000000 1.0821516153 -2.0905924084 1.4504541212 0.4337255233 0.6031468286 -0.5483325552 0.383962866058 +1403715314112143104.0000000000 1.0778878073 -2.0896017706 1.4566156770 0.4288640464 0.6012726933 -0.5514215262 0.387918907022 +1403715314162142976.0000000000 1.0736711053 -2.0885938136 1.4620340339 0.4233093834 0.5976880707 -0.5560415200 0.39293251854 +1403715314212143104.0000000000 1.0693057923 -2.0874613866 1.4663905524 0.4159484202 0.5939835395 -0.5615991890 0.39846808825 +1403715314262142976.0000000000 1.0650808106 -2.0857743150 1.4708931156 0.4092037414 0.5889205919 -0.5673755278 0.404734289185 +1403715314312143104.0000000000 1.0606049594 -2.0832890283 1.4745332678 0.4018834493 0.5837172803 -0.5745883300 0.409404544343 +1403715314362142976.0000000000 1.0562892526 -2.0797675570 1.4776673670 0.3951947888 0.5779515361 -0.5814477678 0.414380977076 +1403715314412143104.0000000000 1.0519021534 -2.0747852094 1.4800461005 0.3905562499 0.5715910391 -0.5883859714 0.41779354751 +1403715314462142976.0000000000 1.0475737924 -2.0684922052 1.4816356620 0.3853023770 0.5668041618 -0.5945327581 0.420482960385 +1403715314512143104.0000000000 1.0440407892 -2.0608271749 1.4836983743 0.3818782259 0.5617604203 -0.5999801592 0.422632297965 +1403715314562142976.0000000000 1.0411925226 -2.0520341025 1.4857041399 0.3796567780 0.5569017668 -0.6057966170 0.42276661644 +1403715314612143104.0000000000 1.0386629706 -2.0423249768 1.4873028906 0.3787670364 0.5520928564 -0.6105074815 0.423095290777 +1403715314662142976.0000000000 1.0362797795 -2.0319115122 1.4883887063 0.3780556195 0.5480422414 -0.6137467932 0.424309467411 +1403715314712143104.0000000000 1.0341560289 -2.0206545298 1.4888138545 0.3771254266 0.5449807968 -0.6163227546 0.425345278364 +1403715314762142976.0000000000 1.0322953883 -2.0088035706 1.4889808214 0.3761082984 0.5426292400 -0.6177936266 0.427114844941 +1403715314812143104.0000000000 1.0309063365 -1.9963708377 1.4895103966 0.3763111788 0.5401404262 -0.6182200874 0.429467274956 +1403715314862142976.0000000000 1.0296837766 -1.9835153237 1.4898669614 0.3751403650 0.5390784129 -0.6183410841 0.431646238194 +1403715314912143104.0000000000 1.0285473600 -1.9699023798 1.4902158154 0.3749936768 0.5377851040 -0.6185875845 0.433031551395 +1403715314962142976.0000000000 1.0273464457 -1.9555032875 1.4907516786 0.3758418410 0.5363794264 -0.6188450151 0.433671383406 +1403715315012143104.0000000000 1.0265822351 -1.9401690208 1.4911089838 0.3773238514 0.5351270911 -0.6189967972 0.433714966866 +1403715315062142976.0000000000 1.0263056648 -1.9240671670 1.4914129558 0.3803453669 0.5327708969 -0.6189349048 0.434064692055 +1403715315112143104.0000000000 1.0262044350 -1.9076397197 1.4907242084 0.3815958614 0.5320136424 -0.6187585272 0.434147403332 +1403715315162142976.0000000000 1.0259726938 -1.8909268258 1.4899166503 0.3821679705 0.5318177217 -0.6192348379 0.433204072884 +1403715315212143104.0000000000 1.0255373768 -1.8740181270 1.4891365311 0.3825695487 0.5319930793 -0.6194696998 0.432297577007 +1403715315262142976.0000000000 1.0249828150 -1.8571254428 1.4886712063 0.3826034532 0.5318429949 -0.6196178574 0.432239906903 +1403715315312143104.0000000000 1.0241273213 -1.8405726388 1.4879981197 0.3815984304 0.5308379228 -0.6207107407 0.432795464409 +1403715315362142976.0000000000 1.0234778421 -1.8242797984 1.4879436970 0.3800101455 0.5285293063 -0.6223416690 0.434672185324 +1403715315412143104.0000000000 1.0227199289 -1.8079044976 1.4880607972 0.3782479529 0.5252116855 -0.6252090441 0.436113314206 +1403715315462142976.0000000000 1.0220686493 -1.7914830090 1.4880867423 0.3761338374 0.5208775213 -0.6289185842 0.437802876476 +1403715315512143104.0000000000 1.0212054329 -1.7752094132 1.4884897146 0.3740031826 0.5158576713 -0.6328164833 0.439949748137 +1403715315562142976.0000000000 1.0203492419 -1.7590501133 1.4891747765 0.3720614602 0.5105773493 -0.6367010872 0.442145638656 +1403715315612143104.0000000000 1.0185899995 -1.7430493053 1.4898529680 0.3696382155 0.5050785246 -0.6408867509 0.444440599141 +1403715315662142976.0000000000 1.0167031047 -1.7274250049 1.4909654214 0.3670350026 0.4990234300 -0.6451161630 0.447309802557 +1403715315712143104.0000000000 1.0147270824 -1.7118991602 1.4923007736 0.3667056601 0.4906011997 -0.6507972159 0.448665137384 +1403715315762142976.0000000000 1.0123299695 -1.6967321453 1.4937861473 0.3665315989 0.4814523791 -0.6572395965 0.44932650316 +1403715315812143104.0000000000 1.0093901480 -1.6824057352 1.4948472115 0.3653676936 0.4723932247 -0.6640606731 0.449860547329 +1403715315862142976.0000000000 1.0061892073 -1.6694094746 1.4955640629 0.3621539328 0.4641354874 -0.6704229569 0.451614699965 +1403715315912143104.0000000000 1.0024167664 -1.6576066474 1.4958634055 0.3569851566 0.4569105773 -0.6762685312 0.454373410349 +1403715315962142976.0000000000 0.9980457081 -1.6466919170 1.4959200129 0.3509909298 0.4498467999 -0.6812120601 0.458686552015 +1403715316012143104.0000000000 0.9928816322 -1.6367166168 1.4948482780 0.3440667674 0.4431419912 -0.6865682818 0.462457813903 +1403715316062142976.0000000000 0.9872359624 -1.6276836540 1.4929094764 0.3361534442 0.4369622872 -0.6908862531 0.467697559057 +1403715316112143104.0000000000 0.9814722047 -1.6195276679 1.4899139833 0.3270800088 0.4313440238 -0.6951207030 0.473041445564 +1403715316162142976.0000000000 0.9755335928 -1.6122581513 1.4855742792 0.3172784970 0.4258217417 -0.6994785209 0.478267705795 +1403715316212143104.0000000000 0.9693734447 -1.6055837533 1.4803598999 0.3068703474 0.4204357773 -0.7042006781 0.482872397292 +1403715316262142976.0000000000 0.9629854511 -1.5994187839 1.4742947316 0.2941267079 0.4160736354 -0.7098019679 0.486367531823 +1403715316312143104.0000000000 0.9570031326 -1.5934792213 1.4680459728 0.2815343294 0.4110668121 -0.7163033218 0.488540733762 +1403715316362142976.0000000000 0.9515336070 -1.5872419303 1.4603401467 0.2683816268 0.4074760672 -0.7226743295 0.48956753421 +1403715316412143104.0000000000 0.9471301650 -1.5804246353 1.4524565713 0.2568357242 0.4040207947 -0.7283103098 0.490272068237 +1403715316462142976.0000000000 0.9445176174 -1.5729388930 1.4447743578 0.2480402504 0.3999039927 -0.7326469380 0.491712614334 +1403715316512143104.0000000000 0.9441389984 -1.5647310767 1.4370981986 0.2430340378 0.3948406388 -0.7361896049 0.493011350805 +1403715316562142976.0000000000 0.9457882219 -1.5561835447 1.4294106763 0.2400840856 0.3892989502 -0.7383823820 0.495577861814 +1403715316612143104.0000000000 0.9494278501 -1.5472191854 1.4215733052 0.2394948936 0.3833564369 -0.7398640348 0.498278283927 +1403715316662142976.0000000000 0.9548151457 -1.5380067151 1.4135376946 0.2399833334 0.3776998885 -0.7400255111 0.502108590719 +1403715316712143104.0000000000 0.9617034550 -1.5285110606 1.4048945726 0.2407854427 0.3715398790 -0.7405590718 0.505522254729 +1403715316762142976.0000000000 0.9695771527 -1.5189536073 1.3955387280 0.2405536653 0.3652424146 -0.7412424675 0.50920675275 +1403715316812143104.0000000000 0.9783362339 -1.5093412200 1.3854687884 0.2392258761 0.3590222094 -0.7423286101 0.512661943199 +1403715316862142976.0000000000 0.9879433958 -1.4997506997 1.3749387167 0.2368833267 0.3520641014 -0.7438278348 0.516388720118 +1403715316912143104.0000000000 0.9985248807 -1.4901355609 1.3641788973 0.2342205994 0.3440130906 -0.7458730026 0.520066503768 +1403715316962142976.0000000000 1.0096192624 -1.4805450969 1.3535986225 0.2299414313 0.3355302840 -0.7473870086 0.525318023695 +1403715317012143104.0000000000 1.0206899576 -1.4706425394 1.3434043691 0.2264136971 0.3251700330 -0.7491570606 0.530815397303 +1403715317062142976.0000000000 1.0317869400 -1.4599488374 1.3327597747 0.2220579009 0.3145187772 -0.7527443879 0.53398887058 +1403715317112143104.0000000000 1.0426186934 -1.4488802293 1.3220462216 0.2157568637 0.3041497730 -0.7574158431 0.535969338607 +1403715317162142976.0000000000 1.0533243407 -1.4375720765 1.3116635049 0.2084296825 0.2936265152 -0.7627377588 0.537188652397 +1403715317212143104.0000000000 1.0639114060 -1.4260438856 1.3015924832 0.2004022856 0.2828963975 -0.7681168504 0.538335449664 +1403715317262142976.0000000000 1.0746272461 -1.4145275566 1.2920056580 0.1912634411 0.2726272877 -0.7726886216 0.5404118357 +1403715317312143104.0000000000 1.0855554959 -1.4029494756 1.2828268679 0.1824680800 0.2615606546 -0.7771406781 0.542534598179 +1403715317362142976.0000000000 1.0966341372 -1.3909181456 1.2742812954 0.1746936601 0.2493050169 -0.7817991375 0.544168395227 +1403715317412143104.0000000000 1.1078985056 -1.3785506130 1.2663975091 0.1682579331 0.2358252560 -0.7861533316 0.54592916742 +1403715317462142976.0000000000 1.1192559543 -1.3661770612 1.2587545054 0.1613584138 0.2229897808 -0.7904315090 0.547226689287 +1403715317512143104.0000000000 1.1306698430 -1.3538621726 1.2515065339 0.1543018144 0.2104860109 -0.7941280809 0.548859891424 +1403715317562142976.0000000000 1.1420674111 -1.3419096169 1.2444367580 0.1467760395 0.1984203265 -0.7969317872 0.551349158661 +1403715317612143104.0000000000 1.1536227803 -1.3301816614 1.2376263481 0.1397542156 0.1863285255 -0.7995833882 0.553549315911 +1403715317662142976.0000000000 1.1652100625 -1.3186746901 1.2312054324 0.1338991314 0.1736616914 -0.8020858134 0.555491662839 +1403715317712143104.0000000000 1.1765060172 -1.3074417055 1.2249340150 0.1275490014 0.1614758021 -0.8044396842 0.557255428009 +1403715317762142976.0000000000 1.1875346623 -1.2964105894 1.2189633582 0.1225640196 0.1485999136 -0.8069482045 0.558328507209 +1403715317812143104.0000000000 1.1983105727 -1.2855981593 1.2135433140 0.1206202464 0.1338955945 -0.8096112883 0.55861640488 +1403715317862142976.0000000000 1.2083399589 -1.2753601004 1.2081311569 0.1182824755 0.1192536272 -0.8125952709 0.558101025059 +1403715317912143104.0000000000 1.2173194293 -1.2657072471 1.2027310249 0.1139496724 0.1067741112 -0.8146593198 0.558520325576 +1403715317962142976.0000000000 1.2249123275 -1.2566548284 1.1972489226 0.1082282407 0.0956234000 -0.8164565137 0.55905417854 +1403715318012143104.0000000000 1.2312693618 -1.2480648857 1.1915580251 0.1021993870 0.0852181683 -0.8180413939 0.559554668433 +1403715318062142976.0000000000 1.2366457958 -1.2398994175 1.1860846159 0.0978969730 0.0756862726 -0.8186651109 0.560780890427 +1403715318112143104.0000000000 1.2408408705 -1.2324283430 1.1807326060 0.0948353588 0.0672803320 -0.8193927494 0.561315538612 +1403715318162142976.0000000000 1.2436367404 -1.2257294116 1.1754924715 0.0911792839 0.0608508188 -0.8197011951 0.562204114825 +1403715318212143104.0000000000 1.2450802780 -1.2198307310 1.1699147003 0.0870138767 0.0563669617 -0.8203072912 0.562447596545 +1403715318262142976.0000000000 1.2452806937 -1.2144841319 1.1644445247 0.0840253457 0.0523243362 -0.8205643794 0.562917404614 +1403715318312143104.0000000000 1.2438146847 -1.2099687645 1.1586407142 0.0800536398 0.0492059594 -0.8210766705 0.563030451611 +1403715318362142976.0000000000 1.2408491341 -1.2063167515 1.1531087249 0.0757725429 0.0460193947 -0.8213134125 0.563546817426 +1403715318412143104.0000000000 1.2364446620 -1.2031475078 1.1474327142 0.0698458696 0.0437974606 -0.8218438796 0.563716218104 +1403715318462142976.0000000000 1.2305122392 -1.2004805282 1.1412739849 0.0612470903 0.0424692631 -0.8224880963 0.56387807826 +1403715318512143104.0000000000 1.2237077002 -1.1982288682 1.1348107672 0.0518015998 0.0414217771 -0.8234075932 0.563560791829 +1403715318562142976.0000000000 1.2164519581 -1.1964644338 1.1282675394 0.0431138807 0.0390462048 -0.8251792502 0.561868127015 +1403715318612143104.0000000000 1.2090725201 -1.1952932370 1.1214997207 0.0349849251 0.0357325870 -0.8283054626 0.558040587957 +1403715318662142976.0000000000 1.2018167386 -1.1949144511 1.1146246663 0.0276086632 0.0311393699 -0.8321178819 0.553035199575 +1403715318712143104.0000000000 1.1949129452 -1.1954296539 1.1074488875 0.0211805403 0.0256050990 -0.8367474461 0.546579797521 +1403715318762142976.0000000000 1.1885201585 -1.1977164846 1.1008058437 0.0165023687 0.0179997885 -0.8398581852 0.542256312216 +1403715318812143104.0000000000 1.1821734877 -1.2021627216 1.0940366486 0.0097526752 0.0110985403 -0.8423724819 0.538693149622 +1403715318862142976.0000000000 1.1763153764 -1.2090263882 1.0880068145 0.0040177728 0.0033544006 -0.8429505483 0.537965592375 +1403715318912143104.0000000000 1.1709174227 -1.2180613198 1.0822196676 0.0017787199 0.0035641600 0.8424327443 -0.538786789282 +1403715318962142976.0000000000 1.1660832446 -1.2295363533 1.0768562036 0.0072905112 0.0098329205 0.8411740816 -0.540625865629 +1403715319012143104.0000000000 1.1616399771 -1.2430052531 1.0717660902 0.0125822187 0.0169720710 0.8393723522 -0.543146104645 +1403715319062142976.0000000000 1.1574692940 -1.2583168371 1.0668097897 0.0189950808 0.0238696829 0.8371516412 -0.546119542574 +1403715319112143104.0000000000 1.1537637939 -1.2748455865 1.0621012730 0.0263251139 0.0302467702 0.8342213390 -0.549969889077 +1403715319162142976.0000000000 1.1505722813 -1.2927071091 1.0578089915 0.0341390744 0.0366392854 0.8312217362 -0.553680875199 +1403715319212143104.0000000000 1.1481753706 -1.3119148917 1.0540210771 0.0414423094 0.0440366044 0.8285100292 -0.556699599356 +1403715319262142976.0000000000 1.1466522824 -1.3321905944 1.0503866508 0.0486858694 0.0518674130 0.8266622482 -0.558183648019 +1403715319312143104.0000000000 1.1460494223 -1.3534673611 1.0471084198 0.0563607684 0.0594064703 0.8248242497 -0.559427646888 +1403715319362142976.0000000000 1.1464007418 -1.3754997262 1.0439059438 0.0641597170 0.0673406253 0.8230895389 -0.56024314523 +1403715319412143104.0000000000 1.1482132578 -1.3984197822 1.0409403557 0.0708610219 0.0757390369 0.8210301480 -0.561383834706 +1403715319462142976.0000000000 1.1513054876 -1.4218311214 1.0381157309 0.0754216307 0.0853706883 0.8188640801 -0.562570032504 +1403715319512143104.0000000000 1.1551297937 -1.4455031900 1.0351258286 0.0799422782 0.0955891639 0.8167189261 -0.563420038339 +1403715319562142976.0000000000 1.1598129016 -1.4697565787 1.0320481230 0.0852823309 0.1049334895 0.8149619624 -0.56351831082 +1403715319612143104.0000000000 1.1657226584 -1.4943817556 1.0303071714 0.0892345066 0.1140554079 0.8130266966 -0.563929213103 +1403715319662142976.0000000000 1.1729227544 -1.5191204922 1.0304126468 0.0939247334 0.1204081024 0.8118553660 -0.563534291828 +1403715319712143104.0000000000 1.1813732868 -1.5439241989 1.0334818029 0.0961675631 0.1260690447 0.8107302594 -0.563537791322 +1403715319762142976.0000000000 1.1908192565 -1.5690575690 1.0393092052 0.0983207959 0.1294301681 0.8105498998 -0.562663054223 +1403715319812143104.0000000000 1.2011705198 -1.5946977129 1.0485591179 0.0987774271 0.1321929564 0.8100596063 -0.562646848806 +1403715319862142976.0000000000 1.2120312068 -1.6207658775 1.0605994504 0.0995601468 0.1344255707 0.8096126581 -0.562623219282 +1403715319912143104.0000000000 1.2234568483 -1.6473682929 1.0751280372 0.0998541064 0.1373118396 0.8094546333 -0.562101247778 +1403715319962142976.0000000000 1.2354159486 -1.6739997327 1.0907021874 0.1012338905 0.1394587517 0.8088876777 -0.562142046886 +1403715320012143104.0000000000 1.2479106173 -1.7013046436 1.1059858013 0.1032697459 0.1425424212 0.8079658537 -0.562323925257 +1403715320062142976.0000000000 1.2609348192 -1.7291749447 1.1206573432 0.1060164122 0.1465137587 0.8070026167 -0.562175253333 +1403715320112143104.0000000000 1.2743360231 -1.7574259327 1.1345052983 0.1108624683 0.1507781671 0.8052210425 -0.562667335266 +1403715320162142976.0000000000 1.2883476191 -1.7857473197 1.1474427505 0.1163251204 0.1566810549 0.8035072990 -0.562401576973 +1403715320212143104.0000000000 1.3028669348 -1.8142524914 1.1602458991 0.1225882796 0.1643547224 0.8003964416 -0.563316230172 +1403715320262142976.0000000000 1.3180009675 -1.8428365460 1.1728463087 0.1301465616 0.1732432367 0.7955868182 -0.565765205776 +1403715320312143104.0000000000 1.3339649742 -1.8712931204 1.1852136151 0.1364344008 0.1848859303 0.7893351920 -0.569344185658 +1403715320362142976.0000000000 1.3507429704 -1.8992948152 1.1969758333 0.1416393818 0.1991738622 0.7831832769 -0.571744709546 +1403715320412143104.0000000000 1.3680492002 -1.9265175094 1.2084088090 0.1466151648 0.2148243581 0.7780006615 -0.571899868238 +1403715320462142976.0000000000 1.3857762247 -1.9526644890 1.2198467938 0.1525185450 0.2308722330 0.7729665652 -0.570928011726 +1403715320512143104.0000000000 1.4040001104 -1.9769846801 1.2307148945 0.1581013582 0.2472898851 0.7687016986 -0.568286346711 +1403715320562142976.0000000000 1.4224175579 -2.0004143460 1.2411459413 0.1634690363 0.2637328524 0.7640112417 -0.565693980254 +1403715320612143104.0000000000 1.4410182818 -2.0227193834 1.2520646221 0.1680094579 0.2801869804 0.7590409222 -0.563138487896 +1403715320662142976.0000000000 1.4594514956 -2.0436466278 1.2628786693 0.1720246050 0.2968006913 0.7533231909 -0.561089168452 +1403715320712143104.0000000000 1.4776960240 -2.0629241474 1.2729903363 0.1750497924 0.3124380623 0.7475914820 -0.55932727752 +1403715320762142976.0000000000 1.4958312736 -2.0807955948 1.2826467965 0.1760334987 0.3272347954 0.7413866444 -0.558816105302 +1403715320812143104.0000000000 1.5137510814 -2.0968254467 1.2917512733 0.1763458254 0.3400009839 0.7355765059 -0.558774269987 +1403715320862142976.0000000000 1.5311074501 -2.1106749689 1.2996608362 0.1756412292 0.3512096227 0.7316954566 -0.557156816621 +1403715320912143104.0000000000 1.5473006401 -2.1221365302 1.3067563721 0.1751649172 0.3603410515 0.7296195490 -0.554190303165 +1403715320962142976.0000000000 1.5617034330 -2.1313237469 1.3133268562 0.1764607679 0.3668000493 0.7285364503 -0.550957313983 +1403715321012143104.0000000000 1.5743505325 -2.1382513147 1.3192475447 0.1792446008 0.3710212348 0.7285922836 -0.547145228161 +1403715321062142976.0000000000 1.5850594928 -2.1431684872 1.3247822430 0.1828422964 0.3735403951 0.7288196989 -0.543928409197 +1403715321112143104.0000000000 1.5939564741 -2.1465360282 1.3301537040 0.1864265315 0.3750643867 0.7290897070 -0.541294793311 +1403715321162142976.0000000000 1.6009714594 -2.1484654080 1.3350862099 0.1895831284 0.3759895556 0.7294155711 -0.539113175751 +1403715321212143104.0000000000 1.6062925062 -2.1489944465 1.3394020436 0.1923169699 0.3763575528 0.7303465220 -0.536621965084 +1403715321262142976.0000000000 1.6103725203 -2.1481837101 1.3436454670 0.1940369101 0.3766871255 0.7309275068 -0.534978005905 +1403715321312143104.0000000000 1.6129501293 -2.1461478724 1.3478473219 0.1940506176 0.3772481925 0.7312151223 -0.534184054324 +1403715321362142976.0000000000 1.6139597250 -2.1428399190 1.3519311460 0.1936397337 0.3776950666 0.7313362630 -0.533851440586 +1403715321412143104.0000000000 1.6133599316 -2.1382083944 1.3561288456 0.1930333132 0.3779520468 0.7306558158 -0.534820034291 +1403715321462142976.0000000000 1.6110633295 -2.1323540050 1.3602203344 0.1929532230 0.3774603885 0.7299030166 -0.536222244162 +1403715321512143104.0000000000 1.6072730727 -2.1252440689 1.3639632208 0.1930029344 0.3760281911 0.7304092519 -0.536521193969 +1403715321562142976.0000000000 1.6020363434 -2.1170504930 1.3676023196 0.1922193942 0.3745188045 0.7314826132 -0.536395894998 +1403715321612143104.0000000000 1.5951612502 -2.1075802652 1.3710177843 0.1931508465 0.3713848035 0.7331441958 -0.535971702935 +1403715321662142976.0000000000 1.5863611068 -2.0972001651 1.3748786789 0.1951255398 0.3690198036 0.7334911335 -0.536415105453 +1403715321712143104.0000000000 1.5756136962 -2.0861566409 1.3796348946 0.1975532873 0.3679972663 0.7310575457 -0.539542005307 +1403715321762142976.0000000000 1.5635138925 -2.0740122307 1.3845612446 0.1998711911 0.3683492581 0.7286260673 -0.541732761642 +1403715321812143104.0000000000 1.5504080028 -2.0606489694 1.3899911735 0.2002726987 0.3711905234 0.7242136774 -0.545548339681 +1403715321862142976.0000000000 1.5362844541 -2.0459274880 1.3961996188 0.2005104409 0.3743861036 0.7182279131 -0.551161748875 +1403715321912143104.0000000000 1.5210849847 -2.0292302551 1.4019496712 0.2020992767 0.3771086563 0.7133215108 -0.555083206254 +1403715321962142976.0000000000 1.5050862919 -2.0098314282 1.4068283350 0.2039982637 0.3807856307 0.7105132132 -0.555479959739 +1403715322012143104.0000000000 1.4885414511 -1.9878258566 1.4109463275 0.2062104826 0.3851047735 0.7101578125 -0.552129904682 +1403715322062142976.0000000000 1.4713593483 -1.9636974410 1.4153422866 0.2063748493 0.3904551148 0.7107799626 -0.547490702786 +1403715322112143104.0000000000 1.4531378166 -1.9373159627 1.4199189143 0.2090858664 0.3938352392 0.7125618777 -0.541694079032 +1403715322162142976.0000000000 1.4339893871 -1.9090036814 1.4239150364 0.2157543661 0.3936087664 0.7159771807 -0.534695118002 +1403715322212143104.0000000000 1.4135216196 -1.8793989306 1.4280100729 0.2239774391 0.3922123949 0.7189235776 -0.528348780245 +1403715322262142976.0000000000 1.3920227084 -1.8487742967 1.4320000256 0.2320766354 0.3923970706 0.7207456917 -0.522197876492 +1403715322312143104.0000000000 1.3700610540 -1.8176554627 1.4357745443 0.2390075330 0.3941281100 0.7223618327 -0.515491818337 +1403715322362142976.0000000000 1.3473155030 -1.7865005891 1.4384515399 0.2457280343 0.3973302986 0.7229679687 -0.508982989102 +1403715322412143104.0000000000 1.3237712804 -1.7556210404 1.4381949348 0.2528162694 0.4018127803 0.7226505713 -0.502400811481 +1403715322462142976.0000000000 1.3001146686 -1.7252349379 1.4349549021 0.2586935741 0.4074245711 0.7218154060 -0.496049768848 +1403715322512143104.0000000000 1.2765401654 -1.6957787993 1.4287228412 0.2636342354 0.4130589011 0.7205580933 -0.490586759204 +1403715322562142976.0000000000 1.2530910873 -1.6675162820 1.4196585314 0.2664288705 0.4185766129 0.7194956701 -0.48593750295 +1403715322612143104.0000000000 1.2295010943 -1.6404630609 1.4088809758 0.2696523946 0.4225189818 0.7187161619 -0.481884192153 +1403715322662142976.0000000000 1.2054371334 -1.6151036787 1.3975062216 0.2715951776 0.4260174229 0.7180951660 -0.4786277755 +1403715322712143104.0000000000 1.1807020356 -1.5914036709 1.3860683267 0.2734760741 0.4285250721 0.7170798907 -0.476837005511 +1403715322762142976.0000000000 1.1549069659 -1.5694573389 1.3747652153 0.2754745778 0.4300975581 0.7156115039 -0.47647667629 +1403715322812143104.0000000000 1.1282508219 -1.5489024451 1.3640920846 0.2770251683 0.4311708504 0.7150182849 -0.475497219913 +1403715322862142976.0000000000 1.1007844092 -1.5300713011 1.3555422822 0.2783655373 0.4315438754 0.7150564774 -0.474317135916 +1403715322912143104.0000000000 1.0726708943 -1.5127484882 1.3501236496 0.2808553581 0.4307950943 0.7146522864 -0.474139182177 +1403715322962142976.0000000000 1.0440614288 -1.4971430617 1.3476798945 0.2827832493 0.4302657068 0.7140982966 -0.474308631888 +1403715323012143104.0000000000 1.0151867117 -1.4833668619 1.3481808268 0.2841331024 0.4294839284 0.7139757081 -0.47439500798 +1403715323062142976.0000000000 0.9859762810 -1.4714062839 1.3513910946 0.2845412856 0.4289129316 0.7140502609 -0.474554716397 +1403715323112143104.0000000000 0.9560603668 -1.4612861081 1.3560583887 0.2853284967 0.4282042112 0.7141849405 -0.474519412903 +1403715323162142976.0000000000 0.9257870937 -1.4531836463 1.3591831511 0.2859507777 0.4272436550 0.7147315331 -0.474187565817 +1403715323212143104.0000000000 0.8953586337 -1.4468499428 1.3596753616 0.2874206228 0.4254812266 0.7152678487 -0.474074905452 +1403715323262142976.0000000000 0.8648641603 -1.4421678733 1.3571203848 0.2888789045 0.4240547926 0.7151726261 -0.474609972919 +1403715323312143104.0000000000 0.8344395435 -1.4393297441 1.3516335166 0.2894249218 0.4231030750 0.7154165571 -0.474759046584 +1403715323362142976.0000000000 0.8039640270 -1.4384218741 1.3451415672 0.2890355481 0.4230859947 0.7148862061 -0.475809211006 +1403715323412143104.0000000000 0.7732347319 -1.4396503339 1.3403826527 0.2892412574 0.4228539191 0.7147073478 -0.476159075462 +1403715323462142976.0000000000 0.7423114885 -1.4429866912 1.3375154556 0.2886652072 0.4231683070 0.7149620960 -0.475846806746 +1403715323512143104.0000000000 0.7109617815 -1.4486060313 1.3373173321 0.2886329719 0.4232318976 0.7149122422 -0.475884706992 +1403715323562142976.0000000000 0.6796537689 -1.4559643602 1.3397918285 0.2883946603 0.4236355619 0.7149889279 -0.475554690448 +1403715323612143104.0000000000 0.6478814799 -1.4652288128 1.3468178017 0.2906108888 0.4225205900 0.7111753933 -0.480885872356 +1403715323662142976.0000000000 0.6155848563 -1.4762186678 1.3560078307 0.2941194944 0.4207460455 0.7050941050 -0.489191977847 +1403715323712143104.0000000000 0.5838334858 -1.4881639312 1.3654768754 0.2989062095 0.4183968362 0.6987123453 -0.497393429738 +1403715323762142976.0000000000 0.5532958028 -1.5008589113 1.3747048493 0.3041534258 0.4153949810 0.6918370198 -0.506260053084 +1403715323812143104.0000000000 0.5248343628 -1.5140331334 1.3831673196 0.3081373903 0.4128867436 0.6857658089 -0.514102267021 +1403715323862142976.0000000000 0.4984917193 -1.5273773630 1.3912071185 0.3116791110 0.4107774939 0.6803215949 -0.520845955927 +1403715323912143104.0000000000 0.4744686136 -1.5407477637 1.3993006715 0.3155275115 0.4081146155 0.6750493756 -0.527440224715 +1403715323962142976.0000000000 0.4535664131 -1.5542251460 1.4081163471 0.3194574929 0.4047784321 0.6683785233 -0.536070406573 +1403715324012143104.0000000000 0.4361815041 -1.5670281167 1.4169014709 0.3216384831 0.4026101512 0.6630307466 -0.542995378806 +1403715324062142976.0000000000 0.4227068889 -1.5788867548 1.4245471155 0.3214430644 0.4019845931 0.6606908768 -0.546415875075 +1403715324112143104.0000000000 0.4132802506 -1.5894505904 1.4308380965 0.3179706936 0.4036778115 0.6615987894 -0.546100635757 +1403715324162142976.0000000000 0.4075228816 -1.5988470318 1.4366543372 0.3132090987 0.4063249683 0.6641896591 -0.543739070983 +1403715324212143104.0000000000 0.4047111641 -1.6075399455 1.4423245909 0.3080633869 0.4093220590 0.6664704743 -0.541635955746 +1403715324262142976.0000000000 0.4046910378 -1.6154314901 1.4484710357 0.3025280978 0.4123972147 0.6682021383 -0.540288061826 +1403715324312143104.0000000000 0.4070653838 -1.6223142390 1.4546161976 0.2959671410 0.4158971430 0.6693295513 -0.539843467689 +1403715324362142976.0000000000 0.4115721118 -1.6279158669 1.4617845061 0.2871774148 0.4212567229 0.6702242436 -0.539324919831 +1403715324412143104.0000000000 0.4180982915 -1.6317428427 1.4682849651 0.2772991477 0.4269708810 0.6737980359 -0.535534551862 +1403715324462142976.0000000000 0.4259718907 -1.6336053837 1.4746369744 0.2681145613 0.4324820862 0.6788064526 -0.529429529816 +1403715324512143104.0000000000 0.4338069036 -1.6340706753 1.4808784707 0.2610229505 0.4368353153 0.6832512340 -0.523650339316 +1403715324562142976.0000000000 0.4408033538 -1.6333422764 1.4875750694 0.2562687319 0.4398846413 0.6873126303 -0.518101522491 +1403715324612143104.0000000000 0.4464719871 -1.6317110220 1.4951033216 0.2541011116 0.4415360676 0.6898712682 -0.514350230306 +1403715324662142976.0000000000 0.4508195756 -1.6290666753 1.5025584257 0.2542964467 0.4416402395 0.6916491970 -0.511770069853 +1403715324712143104.0000000000 0.4540262433 -1.6252744948 1.5102633209 0.2556498903 0.4410976694 0.6925252493 -0.510377075054 +1403715324762142976.0000000000 0.4561455554 -1.6205365259 1.5174112914 0.2586006579 0.4394004805 0.6934395768 -0.509111452265 +1403715324812143104.0000000000 0.4574302084 -1.6152191741 1.5239234161 0.2642774310 0.4356945568 0.6949738001 -0.507286023677 +1403715324862142976.0000000000 0.4580768898 -1.6096516502 1.5296983239 0.2712777879 0.4309214145 0.6961682289 -0.506028549972 +1403715324912143104.0000000000 0.4582738824 -1.6043593156 1.5353397070 0.2780239265 0.4260381701 0.6961213993 -0.506566058212 +1403715324962142976.0000000000 0.4585616632 -1.5994980228 1.5407910348 0.2826697899 0.4224193084 0.6946822328 -0.508995396161 +1403715325012143104.0000000000 0.4592042049 -1.5949160158 1.5457731016 0.2860254131 0.4194222326 0.6929336731 -0.511974001751 +1403715325062142976.0000000000 0.4605755157 -1.5905394725 1.5503589457 0.2879834705 0.4175175973 0.6911834785 -0.514791196233 +1403715325112143104.0000000000 0.4630134698 -1.5861170559 1.5545207487 0.2885994803 0.4161823387 0.6890479861 -0.518377732731 +1403715325162142976.0000000000 0.4663692491 -1.5814759663 1.5576163596 0.2888830104 0.4150862416 0.6881909627 -0.520233810122 +1403715325212143104.0000000000 0.4706958271 -1.5765279694 1.5605065845 0.2889314022 0.4141753951 0.6873979720 -0.521978366347 +1403715325262142976.0000000000 0.4762824643 -1.5714191189 1.5622491918 0.2875477802 0.4141436432 0.6874586764 -0.522687177165 +1403715325312143104.0000000000 0.4831134198 -1.5660702565 1.5636271843 0.2855014032 0.4144819730 0.6882607125 -0.522485248088 +1403715325362142976.0000000000 0.4909653784 -1.5600099039 1.5646660418 0.2829845252 0.4153533632 0.6899993202 -0.52086685458 +1403715325412143104.0000000000 0.4996479578 -1.5535263105 1.5654626296 0.2787026868 0.4172234932 0.6919731731 -0.519059242111 +1403715325462142976.0000000000 0.5089338188 -1.5466011037 1.5657565153 0.2741605197 0.4196499596 0.6943396304 -0.51635491522 +1403715325512143104.0000000000 0.5180434673 -1.5396021288 1.5655354494 0.2699182563 0.4219796150 0.6963607053 -0.513964111148 +1403715325562142976.0000000000 0.5269848994 -1.5327132958 1.5655810107 0.2657207323 0.4246319296 0.6969257379 -0.513200479957 +1403715325612143104.0000000000 0.5351056660 -1.5258839957 1.5668750565 0.2601898449 0.4284283808 0.6955734639 -0.514711495318 +1403715325662142976.0000000000 0.5423296019 -1.5183387802 1.5674798108 0.2548435622 0.4321751368 0.6939327033 -0.516465694115 +1403715325712143104.0000000000 0.5486312120 -1.5098383810 1.5677599676 0.2507212500 0.4351236200 0.6930453511 -0.517198638258 +1403715325762142976.0000000000 0.5535752029 -1.5001016365 1.5679372498 0.2475254293 0.4375967956 0.6929350693 -0.516798989944 +1403715325812143104.0000000000 0.5574413807 -1.4888727599 1.5680112686 0.2464081633 0.4387007436 0.6937787020 -0.515262833191 +1403715325862142976.0000000000 0.5600904936 -1.4767155275 1.5676686765 0.2464703675 0.4390903117 0.6947251707 -0.513623396375 +1403715325912143104.0000000000 0.5616576259 -1.4634842101 1.5668992742 0.2470623301 0.4392669161 0.6957475698 -0.511800840704 +1403715325962142976.0000000000 0.5619848869 -1.4493951683 1.5658162890 0.2480492892 0.4390123588 0.6971101907 -0.509683314406 +1403715326012143104.0000000000 0.5605543321 -1.4345638253 1.5643443942 0.2506445065 0.4381793624 0.6979109815 -0.508031927719 +1403715326062142976.0000000000 0.5574685004 -1.4190653829 1.5624629041 0.2547951855 0.4364965046 0.6985350082 -0.506556075074 +1403715326112143104.0000000000 0.5530903845 -1.4030785109 1.5595670189 0.2603279918 0.4340337355 0.6994491764 -0.504593799749 +1403715326162142976.0000000000 0.5477061833 -1.3869780377 1.5564555746 0.2662959720 0.4312333961 0.7000762610 -0.503008391821 +1403715326212143104.0000000000 0.5416793220 -1.3708329651 1.5524493080 0.2713599809 0.4289893870 0.7004558934 -0.501690550046 +1403715326262142976.0000000000 0.5350459799 -1.3550139144 1.5478696575 0.2765868170 0.4265757655 0.7002068490 -0.501241675727 +1403715326312143104.0000000000 0.5284556252 -1.3393595761 1.5433246348 0.2809504273 0.4247134487 0.6986186780 -0.502610472105 +1403715326362142976.0000000000 0.5217192356 -1.3241774383 1.5389932097 0.2859855496 0.4225103563 0.6955571031 -0.505863203371 +1403715326412143104.0000000000 0.5150919009 -1.3097610710 1.5350108181 0.2901522754 0.4208584202 0.6915882072 -0.510289720636 +1403715326462142976.0000000000 0.5086061261 -1.2960186703 1.5311190602 0.2930322463 0.4199704818 0.6881734382 -0.513978808972 +1403715326512143104.0000000000 0.5031326108 -1.2821618916 1.5272267316 0.2961598271 0.4187816065 0.6849132190 -0.517498990629 +1403715326562142976.0000000000 0.4995978506 -1.2678524722 1.5223332026 0.2985681403 0.4181362999 0.6824794190 -0.519847038061 +1403715326612143104.0000000000 0.4975844400 -1.2531602030 1.5169926466 0.3012773733 0.4171259415 0.6808098856 -0.521282833943 +1403715326662142976.0000000000 0.4971649839 -1.2380114598 1.5120721978 0.3022818026 0.4174815932 0.6797529288 -0.521795732932 +1403715326712143104.0000000000 0.4979625879 -1.2223551764 1.5069671397 0.3027110712 0.4183984687 0.6795494430 -0.521077041575 +1403715326762142976.0000000000 0.5002068478 -1.2065818430 1.5013397487 0.3002463134 0.4212349355 0.6803801468 -0.519130172714 +1403715326812143104.0000000000 0.5038379767 -1.1903705113 1.4956865737 0.2961158123 0.4250247339 0.6818885948 -0.516427483319 +1403715326862142976.0000000000 0.5087229069 -1.1739865472 1.4899345669 0.2917515818 0.4292769747 0.6832079313 -0.513643082394 +1403715326912143104.0000000000 0.5145000788 -1.1570995769 1.4839740837 0.2880454896 0.4326726601 0.6854054329 -0.509944661355 +1403715326962142976.0000000000 0.5208906639 -1.1398508086 1.4785672297 0.2846241354 0.4362401361 0.6861082874 -0.507877015832 +1403715327012143104.0000000000 0.5272960362 -1.1223609634 1.4735275932 0.2808173429 0.4398294565 0.6861770593 -0.506806385602 +1403715327062142976.0000000000 0.5334970427 -1.1043756363 1.4691172248 0.2774675515 0.4429292570 0.6858189386 -0.506436387526 +1403715327112143104.0000000000 0.5390919259 -1.0857505526 1.4647288372 0.2745203458 0.4457589209 0.6857876441 -0.505601494645 +1403715327162142976.0000000000 0.5441398023 -1.0663782967 1.4601942825 0.2720390061 0.4479411989 0.6863459587 -0.504254584987 +1403715327212143104.0000000000 0.5484487433 -1.0463376228 1.4554838088 0.2695170919 0.4501850648 0.6867945457 -0.502998207331 +1403715327262142976.0000000000 0.5518551095 -1.0253571666 1.4513878118 0.2673389977 0.4524039149 0.6871554741 -0.501675106564 +1403715327312143104.0000000000 0.5539943586 -1.0038778688 1.4481961594 0.2653522198 0.4545052897 0.6870855719 -0.500925701029 +1403715327362142976.0000000000 0.5546965454 -0.9817550404 1.4451526083 0.2636078757 0.4564746928 0.6870934572 -0.500044321853 +1403715327412143104.0000000000 0.5540812959 -0.9588594093 1.4418549894 0.2621244748 0.4584674515 0.6867426783 -0.499482581711 +1403715327462142976.0000000000 0.5521475236 -0.9353347746 1.4384136300 0.2616135890 0.4584584258 0.6875015311 -0.498714193347 +1403715327512143104.0000000000 0.5489309683 -0.9109501382 1.4352641340 0.2605012157 0.4577275256 0.6882492195 -0.498936509802 +1403715327562142976.0000000000 0.5441406628 -0.8853870430 1.4317697174 0.2614400851 0.4542133434 0.6906850079 -0.498290618394 +1403715327612143104.0000000000 0.5377113576 -0.8593885033 1.4281093006 0.2629288297 0.4491693877 0.6939183433 -0.497586800957 +1403715327662142976.0000000000 0.5303067658 -0.8332508087 1.4243842343 0.2632908332 0.4434382612 0.6975903790 -0.497401355928 +1403715327712143104.0000000000 0.5219197013 -0.8069933676 1.4206525426 0.2631652940 0.4364818825 0.7018055142 -0.497691284394 +1403715327762142976.0000000000 0.5128617353 -0.7810820164 1.4172077873 0.2610381714 0.4293093188 0.7059444433 -0.499194375745 +1403715327812143104.0000000000 0.5030649324 -0.7552542589 1.4132681359 0.2580844875 0.4214866210 0.7108122739 -0.500487099611 +1403715327862142976.0000000000 0.4926957850 -0.7298457404 1.4091575806 0.2538577618 0.4132333432 0.7155208291 -0.50281645153 +1403715327912143104.0000000000 0.4816735842 -0.7051123277 1.4048467752 0.2502178255 0.4040172152 0.7198332729 -0.505965600522 +1403715327962142976.0000000000 0.4698021936 -0.6808534237 1.4002449275 0.2471475886 0.3943788050 0.7237873866 -0.509426389813 +1403715328012143104.0000000000 0.4571595528 -0.6568169538 1.3957807471 0.2456563901 0.3852811543 0.7268214754 -0.512778619965 +1403715328062142976.0000000000 0.4439343452 -0.6329719133 1.3914541175 0.2441589913 0.3780840266 0.7288792388 -0.515920450303 +1403715328112143104.0000000000 0.4299820801 -0.6095998332 1.3876082140 0.2442656857 0.3715469386 0.7296764902 -0.519479900354 +1403715328162142976.0000000000 0.4158234023 -0.5866813335 1.3845392838 0.2453408024 0.3661480765 0.7297787855 -0.522653232069 +1403715328212143104.0000000000 0.4017768421 -0.5642291526 1.3821023931 0.2478764863 0.3613725930 0.7290405620 -0.525801250953 +1403715328262142976.0000000000 0.3885263142 -0.5419999466 1.3801608318 0.2502645969 0.3579931897 0.7276771572 -0.528861477636 +1403715328312143104.0000000000 0.3761007070 -0.5197589126 1.3783287493 0.2534740400 0.3555104958 0.7262533322 -0.530960729205 +1403715328362142976.0000000000 0.3647408171 -0.4977851454 1.3765009671 0.2567900316 0.3543763128 0.7249835970 -0.531860031037 +1403715328412143104.0000000000 0.3548894516 -0.4759063983 1.3750118671 0.2599552232 0.3541390912 0.7236195520 -0.532337796866 +1403715328462142976.0000000000 0.3467840511 -0.4541440529 1.3735205286 0.2625146420 0.3547609906 0.7228556039 -0.531705255026 +1403715328512143104.0000000000 0.3403007120 -0.4327329533 1.3720446887 0.2641420049 0.3562597767 0.7223755546 -0.530548330355 +1403715328562142976.0000000000 0.3355722764 -0.4115210762 1.3700440521 0.2642519494 0.3585924301 0.7234881646 -0.527396674317 +1403715328612143104.0000000000 0.3325317495 -0.3908059953 1.3675394047 0.2631137011 0.3598998024 0.7262809963 -0.523220055922 +1403715328662142976.0000000000 0.3309774461 -0.3709390398 1.3650756493 0.2607390492 0.3604134212 0.7299435120 -0.518941020962 +1403715328712143104.0000000000 0.3307758098 -0.3522100488 1.3630253517 0.2576570263 0.3594966353 0.7327777278 -0.517118775111 +1403715328762142976.0000000000 0.3320212774 -0.3348947789 1.3607553184 0.2518821536 0.3578812108 0.7364903822 -0.515808430095 +1403715328812143104.0000000000 0.3344257460 -0.3189590854 1.3585795606 0.2456222555 0.3537689575 0.7400122330 -0.516622809492 +1403715328862142976.0000000000 0.3376698789 -0.3044253009 1.3566505452 0.2385812506 0.3477250650 0.7431598550 -0.519499466754 +1403715328912143104.0000000000 0.3414692607 -0.2911061320 1.3546293616 0.2306918794 0.3397723101 0.7468171689 -0.52306801694 +1403715328962142976.0000000000 0.3462205628 -0.2787490620 1.3524973513 0.2223877770 0.3295629984 0.7508965928 -0.527338803442 +1403715329012143104.0000000000 0.3516202973 -0.2673239778 1.3504623964 0.2132236989 0.3178964921 0.7550359648 -0.532351543947 +1403715329062142976.0000000000 0.3578013421 -0.2564373503 1.3479561175 0.2031883862 0.3055084022 0.7598044230 -0.536727430449 +1403715329112143104.0000000000 0.3643914143 -0.2462934523 1.3455950766 0.1916784885 0.2929004835 0.7641459834 -0.541802159358 +1403715329162142976.0000000000 0.3710248766 -0.2368102134 1.3427026633 0.1803085018 0.2795203191 0.7690804836 -0.545776918875 +1403715329212143104.0000000000 0.3775608972 -0.2277216725 1.3390784318 0.1696962294 0.2661252192 0.7740938362 -0.548779819476 +1403715329262142976.0000000000 0.3839444575 -0.2189259885 1.3349562297 0.1598025508 0.2534782407 0.7790945092 -0.550657490647 +1403715329312143104.0000000000 0.3897761008 -0.2106242177 1.3310345423 0.1510698387 0.2427164077 0.7828279598 -0.552672628828 +1403715329362142976.0000000000 0.3952682594 -0.2027265371 1.3266651432 0.1435392674 0.2339285511 0.7858512247 -0.554176654443 +1403715329412143104.0000000000 0.4005018748 -0.1951206289 1.3212084680 0.1372451795 0.2266476974 0.7877880040 -0.556043741769 +1403715329462142976.0000000000 0.4053577992 -0.1877049146 1.3144412372 0.1320176588 0.2208634910 0.7900206260 -0.556469286253 +1403715329512143104.0000000000 0.4097748214 -0.1808818691 1.3077986913 0.1286740924 0.2158855998 0.7915906714 -0.556974500971 +1403715329562142976.0000000000 0.4140099678 -0.1745785771 1.3009207536 0.1248763387 0.2126449217 0.7933084922 -0.556641422732 +1403715329612143104.0000000000 0.4178206130 -0.1684468041 1.2946588552 0.1232577770 0.2095695971 0.7948138853 -0.556020676028 +1403715329662142976.0000000000 0.4208884674 -0.1630799341 1.2893529953 0.1222863122 0.2077027722 0.7950677240 -0.556572484482 +1403715329712143104.0000000000 0.4235918274 -0.1583750543 1.2837057685 0.1223245079 0.2063219101 0.7946188082 -0.557717611194 +1403715329762142976.0000000000 0.4265148464 -0.1539925127 1.2772478400 0.1221163356 0.2059578241 0.7936203906 -0.559317129037 +1403715329812143104.0000000000 0.4292804957 -0.1500171232 1.2699152815 0.1220481355 0.2058647583 0.7927873173 -0.560546361535 +1403715329862142976.0000000000 0.4320532409 -0.1464344133 1.2620398561 0.1217577453 0.2064680002 0.7922888728 -0.561092112173 +1403715329912143104.0000000000 0.4344218885 -0.1434683443 1.2536122091 0.1221681987 0.2069672613 0.7916517721 -0.561717861256 +1403715329962142976.0000000000 0.4366259788 -0.1409841186 1.2450173365 0.1217738037 0.2076664289 0.7913868690 -0.561918693983 +1403715330012143104.0000000000 0.4391119646 -0.1384545527 1.2357590687 0.1202511333 0.2074810913 0.7911533495 -0.562643438835 +1403715330062142976.0000000000 0.4418105491 -0.1361314652 1.2257672460 0.1181309849 0.2064060108 0.7909123124 -0.563825631981 +1403715330112143104.0000000000 0.4443422401 -0.1334962791 1.2143420273 0.1164711479 0.2049755535 0.7916968579 -0.563591677842 +1403715330162142976.0000000000 0.4463368567 -0.1308628550 1.2021923399 0.1166857183 0.2022922833 0.7929517492 -0.562751986909 +1403715330212143104.0000000000 0.4479565154 -0.1285746381 1.1905027523 0.1171275901 0.1999570764 0.7946407290 -0.561109977704 +1403715330262142976.0000000000 0.4493641738 -0.1269892216 1.1792428376 0.1174645570 0.1984058863 0.7966890908 -0.558680297373 +1403715330312143104.0000000000 0.4505610058 -0.1257689856 1.1687030589 0.1182666347 0.1970638365 0.7981942300 -0.556834642186 +1403715330362142976.0000000000 0.4517260916 -0.1251041080 1.1586351108 0.1186400322 0.1965604798 0.7993218847 -0.555313465655 +1403715330412143104.0000000000 0.4528917805 -0.1252555663 1.1497200685 0.1180938070 0.1966819491 0.7994403754 -0.555216309034 +1403715330462142976.0000000000 0.4540344347 -0.1256600576 1.1433305505 0.1173648777 0.1970365037 0.7984857279 -0.55661714318 +1403715330512143104.0000000000 0.4549160872 -0.1264295357 1.1394499038 0.1158843341 0.1980657057 0.7978801293 -0.557429902787 +1403715330562142976.0000000000 0.4552739654 -0.1278798157 1.1383940102 0.1161759473 0.1977206335 0.7977771236 -0.557639095993 +1403715330612143104.0000000000 0.4552724030 -0.1300509040 1.1410998292 0.1155301682 0.1984201945 0.7962054552 -0.559766987053 +1403715330662142976.0000000000 0.4552239227 -0.1322546531 1.1475744103 0.1142456884 0.1998501653 0.7932571950 -0.563693938867 +1403715330712143104.0000000000 0.4553557204 -0.1340534385 1.1566505170 0.1116762699 0.2017502790 0.7906620871 -0.567167259033 +1403715330762142976.0000000000 0.4556796077 -0.1355990746 1.1669653560 0.1065203174 0.2036816005 0.7888938602 -0.569924297476 +1403715330812143104.0000000000 0.4562927952 -0.1367561542 1.1774196412 0.0997806133 0.2039713444 0.7880717988 -0.572173365228 +1403715330862142976.0000000000 0.4569582896 -0.1372045370 1.1873629551 0.0941932297 0.2008628597 0.7889754761 -0.572974209806 +1403715330912143104.0000000000 0.4576192343 -0.1372679068 1.1966337978 0.0867398797 0.1962577634 0.7903826658 -0.573806871001 +1403715330962142976.0000000000 0.4576892032 -0.1371128753 1.2057027050 0.0790439618 0.1896543557 0.7917177013 -0.575296757252 +1403715331012143104.0000000000 0.4571274329 -0.1361121188 1.2147495864 0.0706355562 0.1816393714 0.7935408310 -0.576463968015 +1403715331062142976.0000000000 0.4557655857 -0.1340760009 1.2241467195 0.0609982884 0.1730257337 0.7956797562 -0.577265129612 +1403715331112143104.0000000000 0.4531348710 -0.1310465095 1.2343662115 0.0523802244 0.1628376187 0.7980931092 -0.577743551347 +1403715331162142976.0000000000 0.4488756290 -0.1273548612 1.2452545514 0.0462882374 0.1504852592 0.8017895887 -0.576493747805 +1403715331212143104.0000000000 0.4426959790 -0.1234299773 1.2574974856 0.0414311107 0.1388021610 0.8045016450 -0.576016081635 +1403715331262142976.0000000000 0.4347705026 -0.1192176501 1.2709320334 0.0386285701 0.1276250190 0.8067951390 -0.57558777933 +1403715331312143104.0000000000 0.4253643271 -0.1146707745 1.2854098899 0.0382511628 0.1168220131 0.8091583642 -0.574588728984 +1403715331362142976.0000000000 0.4148562963 -0.1101823101 1.3015675914 0.0393364763 0.1068009919 0.8109129924 -0.57399155783 +1403715331412143104.0000000000 0.4034500470 -0.1057079568 1.3193802861 0.0395344402 0.0993181083 0.8120665766 -0.573690523282 +1403715331462142976.0000000000 0.3915254676 -0.1014441727 1.3381367716 0.0385130453 0.0945489802 0.8123033732 -0.57423032455 +1403715331512143104.0000000000 0.3792777612 -0.0973975009 1.3570230982 0.0378141248 0.0904197058 0.8128241239 -0.574204939412 +1403715331562142976.0000000000 0.3668272183 -0.0935410111 1.3759370338 0.0365193707 0.0875130116 0.8127051648 -0.574907056376 +1403715331612143104.0000000000 0.3542489824 -0.0897030864 1.3940141525 0.0344310292 0.0860875388 0.8131111526 -0.574677033999 +1403715331662142976.0000000000 0.3412197835 -0.0860051870 1.4116260991 0.0344724021 0.0842196274 0.8127575997 -0.57545094662 +1403715331712143104.0000000000 0.3277662850 -0.0824253139 1.4284215861 0.0372066450 0.0816585736 0.8122740085 -0.576331916507 +1403715331762142976.0000000000 0.3142415883 -0.0790274334 1.4443543832 0.0403052962 0.0795230677 0.8124862824 -0.576122908546 +1403715331812143104.0000000000 0.3007186616 -0.0757400925 1.4593574448 0.0425079637 0.0788966906 0.8122456496 -0.576389963365 +1403715331862142976.0000000000 0.2875728368 -0.0727371178 1.4738974156 0.0432208563 0.0797612946 0.8117847091 -0.576867124699 +1403715331912143104.0000000000 0.2747037122 -0.0698061980 1.4870123791 0.0442815977 0.0809539558 0.8118432515 -0.576538057821 +1403715331962142976.0000000000 0.2623964578 -0.0668408571 1.4980183245 0.0430049949 0.0836010616 0.8131740475 -0.574377403325 +1403715332012143104.0000000000 0.2506193791 -0.0642226769 1.5063708486 0.0409892382 0.0874492780 0.8135948316 -0.573355000142 +1403715332062142976.0000000000 0.2386856591 -0.0618737467 1.5113165033 0.0410965408 0.0906601917 0.8148842143 -0.571012715429 +1403715332112143104.0000000000 0.2267063700 -0.0599097137 1.5133571306 0.0417891713 0.0935987563 0.8160918025 -0.568759270621 +1403715332162142976.0000000000 0.2148845057 -0.0585066576 1.5138732362 0.0395594887 0.0987370892 0.8171648020 -0.566504828281 +1403715332212143104.0000000000 0.2030614689 -0.0583160186 1.5143030732 0.0349731979 0.1044155975 0.8173287498 -0.565551034978 +1403715332262142976.0000000000 0.1911257743 -0.0589206123 1.5156042057 0.0297948862 0.1088747407 0.8162695376 -0.566535610115 +1403715332312143104.0000000000 0.1786460329 -0.0598658358 1.5174450611 0.0254184755 0.1115959702 0.8150325265 -0.567998434218 +1403715332362142976.0000000000 0.1654798678 -0.0609758161 1.5192858207 0.0216300246 0.1119735865 0.8153602236 -0.567610573974 +1403715332412143104.0000000000 0.1512703153 -0.0624648992 1.5210994278 0.0195151323 0.1101364790 0.8163322299 -0.566648750202 +1403715332462142976.0000000000 0.1357046056 -0.0647056417 1.5231829616 0.0189126275 0.1074741907 0.8179618160 -0.564827476698 +1403715332512143104.0000000000 0.1190948582 -0.0677827937 1.5254890602 0.0173090196 0.1053065239 0.8199085961 -0.562459623396 +1403715332562142976.0000000000 0.1013875154 -0.0721299159 1.5272123136 0.0174924104 0.1026495038 0.8215631712 -0.560527475372 +1403715332612143104.0000000000 0.0825582622 -0.0779640397 1.5295586922 0.0171461973 0.1009062058 0.8215098216 -0.560932757673 +1403715332662142976.0000000000 0.0626831797 -0.0849679399 1.5325708628 0.0167391868 0.0993584875 0.8207007083 -0.562403803346 +1403715332712143104.0000000000 0.0414944322 -0.0927440295 1.5359033056 0.0167761049 0.0972175587 0.8197337985 -0.564184197038 +1403715332762142976.0000000000 0.0193422802 -0.1012723039 1.5391714965 0.0168650228 0.0945887579 0.8198706143 -0.564429547101 +1403715332812143104.0000000000 -0.0036019846 -0.1109367102 1.5423639397 0.0175274082 0.0907045711 0.8198657051 -0.565053711069 +1403715332862142976.0000000000 -0.0272387090 -0.1218956561 1.5453427123 0.0179343394 0.0860775009 0.8201563982 -0.565342821468 +1403715332912143104.0000000000 -0.0511131061 -0.1341395104 1.5495226504 0.0174833030 0.0811866053 0.8165525286 -0.571266170262 +1403715332962142976.0000000000 -0.0754220338 -0.1472670203 1.5546245674 0.0167001981 0.0756640911 0.8104705777 -0.580631975805 +1403715333012143104.0000000000 -0.0998152538 -0.1601747174 1.5603263079 0.0149831710 0.0697908999 0.8039838400 -0.590351352884 +1403715333062142976.0000000000 -0.1246568709 -0.1722551720 1.5654469664 0.0126990411 0.0644975197 0.7984722449 -0.598432016498 +1403715333112143104.0000000000 -0.1499146787 -0.1828224764 1.5694143062 0.0111591008 0.0599216381 0.7944358623 -0.604281831979 +1403715333162142976.0000000000 -0.1753056316 -0.1921135225 1.5722555544 0.0103957285 0.0557625162 0.7918995009 -0.608011226096 +1403715333212143104.0000000000 -0.2008366737 -0.1996086118 1.5736467917 0.0099143177 0.0525966391 0.7907991409 -0.609731103519 +1403715333262142976.0000000000 -0.2262659469 -0.2051175863 1.5736515221 0.0092612833 0.0502137153 0.7916850220 -0.608791949202 +1403715333312143104.0000000000 -0.2515954430 -0.2090639200 1.5725881185 0.0084352303 0.0484843114 0.7937412445 -0.606261457749 +1403715333362142976.0000000000 -0.2768624679 -0.2116066000 1.5706028364 0.0086675701 0.0469292778 0.7961895032 -0.603162325701 +1403715333412143104.0000000000 -0.3017422325 -0.2126089918 1.5679727800 0.0086366476 0.0458935794 0.7988729473 -0.599684251679 +1403715333462142976.0000000000 -0.3263046425 -0.2121488064 1.5649381265 0.0084608958 0.0453753258 0.8009384754 -0.596964866316 +1403715333512143104.0000000000 -0.3506274056 -0.2105073151 1.5620860786 0.0081114479 0.0454966856 0.8015761133 -0.596104009911 +1403715333562142976.0000000000 -0.3748115720 -0.2081141241 1.5592671311 0.0072960806 0.0460375324 0.8012875890 -0.596460822346 +1403715333612143104.0000000000 -0.3988750118 -0.2048999112 1.5558873708 0.0075172451 0.0458238655 0.8005957267 -0.597402834612 +1403715333662142976.0000000000 -0.4226517971 -0.2004593300 1.5515451968 0.0069130313 0.0458453748 0.8022052805 -0.595245411183 +1403715333712143104.0000000000 -0.4462397841 -0.1948080354 1.5465356429 0.0061969017 0.0458587162 0.8053349193 -0.591011204854 +1403715333762142976.0000000000 -0.4697415725 -0.1882810487 1.5410969411 0.0052985253 0.0460782441 0.8099446484 -0.584669468678 +1403715333812143104.0000000000 -0.4930510568 -0.1811687895 1.5358102425 0.0038219249 0.0456489259 0.8141706592 -0.578815779146 +1403715333862142976.0000000000 -0.5161460451 -0.1738347796 1.5311525626 0.0013949439 0.0436853646 0.8174846563 -0.57428954355 +1403715333912143104.0000000000 -0.5392223849 -0.1667833111 1.5273393216 0.0015967074 -0.0408299912 -0.8198603500 0.57110364111 +1403715333962142976.0000000000 -0.5621820436 -0.1604664220 1.5245931075 0.0039763960 -0.0362646986 -0.8210478191 0.569692494794 +1403715334012143104.0000000000 -0.5848937246 -0.1548004240 1.5230011618 0.0081404307 -0.0317596851 -0.8214010703 0.569407883245 +1403715334062142976.0000000000 -0.6073884721 -0.1501081152 1.5220931415 0.0129188106 -0.0270838013 -0.8219212502 0.568810188408 +1403715334112143104.0000000000 -0.6300838822 -0.1460593313 1.5219467073 0.0172054850 -0.0227031466 -0.8221885443 0.568502010537 +1403715334162142976.0000000000 -0.6531866402 -0.1426286866 1.5222299148 0.0206272985 -0.0180570626 -0.8227934270 0.567678988085 +1403715334212143104.0000000000 -0.6766458446 -0.1399135647 1.5229553365 0.0240793755 -0.0145851164 -0.8233746327 0.566799499241 +1403715334262142976.0000000000 -0.7002660707 -0.1379649954 1.5238588117 0.0267928330 -0.0115841745 -0.8240534886 0.565759488582 +1403715334312143104.0000000000 -0.7242668401 -0.1368320485 1.5248976701 0.0287779733 -0.0089322095 -0.8239904646 0.565801871788 +1403715334362142976.0000000000 -0.7486070364 -0.1363811224 1.5257286066 0.0301593750 -0.0065396623 -0.8242422161 0.565395803029 +1403715334412143104.0000000000 -0.7732853507 -0.1370240513 1.5265657020 0.0310042504 -0.0047286069 -0.8241286650 0.56553365974 +1403715334462142976.0000000000 -0.7979651150 -0.1385286018 1.5276857812 0.0320951005 -0.0033978488 -0.8240173565 0.565644548642 +1403715334512143104.0000000000 -0.8228524775 -0.1407494176 1.5287692143 0.0325603302 -0.0023794778 -0.8237457881 0.566018585829 +1403715334562142976.0000000000 -0.8480444461 -0.1436073133 1.5299374320 0.0325912667 -0.0011534065 -0.8229313435 0.567204092827 +1403715334612143104.0000000000 -0.8732672836 -0.1468257446 1.5305418397 0.0319112409 0.0007679979 -0.8227902469 0.567448052637 +1403715334662142976.0000000000 -0.8986272471 -0.1504574333 1.5307207226 0.0303055957 0.0027759274 -0.8228532447 0.567438457258 +1403715334712143104.0000000000 -0.9238865573 -0.1546261538 1.5309062736 0.0296521127 0.0035851761 -0.8225022596 0.567977052135 +1403715334762142976.0000000000 -0.9489624523 -0.1594249888 1.5308633371 0.0288574984 0.0042542407 -0.8222187295 0.56842370381 +1403715334812143104.0000000000 -0.9737265721 -0.1648006189 1.5308008221 0.0278260972 0.0047419581 -0.8223176331 0.568328190826 +1403715334862142976.0000000000 -0.9983114288 -0.1706840193 1.5305675272 0.0267584541 0.0051462505 -0.8220893243 0.568706114026 +1403715334912143104.0000000000 -1.0228118190 -0.1769925213 1.5302099215 0.0260415213 0.0053003753 -0.8220491340 0.568796067511 +1403715334962142976.0000000000 -1.0470713522 -0.1837397670 1.5294070646 0.0249788866 0.0054091961 -0.8225307353 0.568146094978 +1403715335012143104.0000000000 -1.0709105841 -0.1906786806 1.5286826741 0.0247594677 0.0055849288 -0.8224230414 0.568309878791 +1403715335062142976.0000000000 -1.0941693002 -0.1978666954 1.5276973632 0.0249295353 0.0064682595 -0.8228091046 0.567733967006 +1403715335112143104.0000000000 -1.1169395028 -0.2056140368 1.5268261813 0.0250314547 0.0073639581 -0.8230137340 0.567421881904 +1403715335162142976.0000000000 -1.1394193275 -0.2138567332 1.5258458501 0.0246176844 0.0084822047 -0.8230720639 0.567339756608 +1403715335212143104.0000000000 -1.1611944747 -0.2226002784 1.5248765823 0.0247741299 0.0088234335 -0.8233621795 0.566906615659 +1403715335262142976.0000000000 -1.1823884837 -0.2315254935 1.5237320415 0.0248153108 0.0104583282 -0.8235895849 0.566546573027 +1403715335312143104.0000000000 -1.2028560921 -0.2407271549 1.5226567048 0.0258866740 0.0126270133 -0.8236152132 0.566417177733 +1403715335362142976.0000000000 -1.2226503281 -0.2503554129 1.5217601903 0.0278678520 0.0155998150 -0.8234581778 0.566477411687 +1403715335412143104.0000000000 -1.2418289658 -0.2602790635 1.5208205102 0.0303120585 0.0194341271 -0.8231416293 0.566693349166 +1403715335462142976.0000000000 -1.2603603422 -0.2705538185 1.5196458864 0.0332037282 0.0231848638 -0.8230153441 0.56657366499 +1403715335512143104.0000000000 -1.2784922303 -0.2814904706 1.5186639738 0.0373993698 0.0254021300 -0.8230571830 0.566156243886 +1403715335562142976.0000000000 -1.2964436928 -0.2929417535 1.5180509802 0.0419124810 0.0267550079 -0.8226992519 0.566298026153 +1403715335612143104.0000000000 -1.3140110335 -0.3046535439 1.5171941459 0.0459122751 0.0286206137 -0.8225349995 0.566135229459 +1403715335662142976.0000000000 -1.3311287971 -0.3165752709 1.5163455150 0.0503415462 0.0314446523 -0.8222418517 0.566034716127 +1403715335712143104.0000000000 -1.3479600303 -0.3289252867 1.5151129490 0.0533718630 0.0365374437 -0.8223579563 0.565282098689 +1403715335762142976.0000000000 -1.3644674649 -0.3417610100 1.5139475116 0.0570757425 0.0419534968 -0.8218052081 0.565348090672 +1403715335812143104.0000000000 -1.3809162964 -0.3549824548 1.5123288861 0.0602267312 0.0471370990 -0.8213260884 0.565309022809 +1403715335862142976.0000000000 -1.3973538778 -0.3686963883 1.5106530776 0.0631688809 0.0517717605 -0.8207217028 0.565460223056 +1403715335912143104.0000000000 -1.4137661262 -0.3827003602 1.5088020176 0.0655890546 0.0562335718 -0.8202408439 0.565456292976 +1403715335962142976.0000000000 -1.4301108564 -0.3971300442 1.5074895591 0.0689169443 0.0595536337 -0.8186057433 0.567087697369 +1403715336012143104.0000000000 -1.4465623496 -0.4117941197 1.5059642687 0.0703018703 0.0637704136 -0.8169773645 0.568804858686 +1403715336062142976.0000000000 -1.4627954915 -0.4267277089 1.5048939858 0.0723399617 0.0663923898 -0.8147721672 0.571406419358 +1403715336112143104.0000000000 -1.4788670756 -0.4417430070 1.5038671652 0.0745241602 0.0681470020 -0.8124207713 0.574260068302 +1403715336162142976.0000000000 -1.4948892523 -0.4567213402 1.5024880932 0.0752205466 0.0702773637 -0.8099920218 0.57733515923 +1403715336212143104.0000000000 -1.5105287081 -0.4714611259 1.5012428267 0.0769967757 0.0711908560 -0.8078360542 0.580003679371 +1403715336262142976.0000000000 -1.5260595738 -0.4851792156 1.4993952184 0.0790108715 0.0718899048 -0.8074627351 0.580166403024 +1403715336312143104.0000000000 -1.5417875233 -0.4983085097 1.4971088732 0.0794926693 0.0733058519 -0.8086894934 0.578211441279 +1403715336362142976.0000000000 -1.5575980838 -0.5109314708 1.4946115729 0.0802312153 0.0749199532 -0.8108730022 0.574834695345 +1403715336412143104.0000000000 -1.5733873618 -0.5232913645 1.4924582263 0.0799944453 0.0765159714 -0.8127186376 0.572044238569 +1403715336462142976.0000000000 -1.5890960512 -0.5356099449 1.4908010760 0.0785435158 0.0788432992 -0.8141111314 0.569945362285 +1403715336512143104.0000000000 -1.6042441051 -0.5479309628 1.4895854643 0.0788396968 0.0794653113 -0.8151768025 0.568292483758 +1403715336562142976.0000000000 -1.6191931789 -0.5605280368 1.4888843299 0.0788453289 0.0796726104 -0.8154925858 0.567809414974 +1403715336612143104.0000000000 -1.6337561803 -0.5732075496 1.4884304335 0.0794095124 0.0794436157 -0.8155173404 0.567727319058 +1403715336662142976.0000000000 -1.6480582127 -0.5860634622 1.4878536546 0.0791325443 0.0793651794 -0.8157968933 0.567375217654 +1403715336712143104.0000000000 -1.6620124769 -0.5989206624 1.4873666433 0.0787239055 0.0791658464 -0.8159205368 0.567282110689 +1403715336762142976.0000000000 -1.6757201753 -0.6121079024 1.4872938737 0.0784287571 0.0787961239 -0.8160565625 0.567178796925 +1403715336812143104.0000000000 -1.6891308782 -0.6256181277 1.4876494621 0.0774775993 0.0790896045 -0.8159767277 0.567383499834 +1403715336862142976.0000000000 -1.7021256944 -0.6393112802 1.4886568545 0.0768616573 0.0790749323 -0.8157036407 0.567861788826 +1403715336912143104.0000000000 -1.7145436039 -0.6532590108 1.4903891753 0.0768062589 0.0789656173 -0.8155893326 0.568048651534 +1403715336962142976.0000000000 -1.7266151931 -0.6673918025 1.4929794974 0.0758434071 0.0792904229 -0.8151284578 0.568793814797 +1403715337012143104.0000000000 -1.7380697478 -0.6814149004 1.4962230274 0.0756273319 0.0798342751 -0.8150057828 0.568922287531 +1403715337062142976.0000000000 -1.7487494092 -0.6949864453 1.5002374351 0.0756803373 0.0816978283 -0.8150434080 0.568596688701 +1403715337112143104.0000000000 -1.7585717080 -0.7079393141 1.5046042920 0.0774795071 0.0840253931 -0.8158543476 0.566849488642 +1403715337162142976.0000000000 -1.7674853666 -0.7205300975 1.5090815794 0.0788965781 0.0887197302 -0.8164903179 0.565020088262 +1403715337212143104.0000000000 -1.7753963080 -0.7331477724 1.5137824164 0.0825468211 0.0931517260 -0.8170813550 0.562927026856 +1403715337262142976.0000000000 -1.7822873568 -0.7460533181 1.5186870642 0.0882141894 0.0975491040 -0.8175561002 0.560628622287 +1403715337312143104.0000000000 -1.7884372102 -0.7591845927 1.5235929993 0.0947390193 0.1026034018 -0.8180270085 0.557968523814 +1403715337362142976.0000000000 -1.7942585454 -0.7729565715 1.5282515761 0.1014033269 0.1069311134 -0.8185364769 0.555230707191 +1403715337412143104.0000000000 -1.8000241637 -0.7875337780 1.5328024378 0.1079592360 0.1104402973 -0.8188388245 0.552856874436 +1403715337462142976.0000000000 -1.8058173779 -0.8030583851 1.5374443434 0.1144551299 0.1130324998 -0.8180233956 0.552233104254 +1403715337512143104.0000000000 -1.8116651963 -0.8193003628 1.5420883410 0.1221863892 0.1136849160 -0.8173965178 0.551370255652 +1403715337562142976.0000000000 -1.8179797661 -0.8365689679 1.5462123678 0.1275513410 0.1148788259 -0.8159743658 0.552013899317 +1403715337612143104.0000000000 -1.8248471019 -0.8548779909 1.5499219421 0.1291918251 0.1181018720 -0.8146839778 0.552857519161 +1403715337662142976.0000000000 -1.8321810666 -0.8739861754 1.5535107812 0.1294585034 0.1213478848 -0.8128569076 0.554778184944 +1403715337712143104.0000000000 -1.8397768922 -0.8935533093 1.5563707080 0.1290274967 0.1243862648 -0.8117751849 0.555788639069 +1403715337762142976.0000000000 -1.8475703857 -0.9136290111 1.5594281574 0.1287582395 0.1265013049 -0.8110873354 0.556377632522 +1403715337812143104.0000000000 -1.8555511308 -0.9342813276 1.5624960340 0.1282738645 0.1276848182 -0.8103663105 0.557269096235 +1403715337862142976.0000000000 -1.8637192964 -0.9553462894 1.5655625673 0.1271946164 0.1281992484 -0.8097383332 0.558310230983 +1403715337912143104.0000000000 -1.8717713908 -0.9768082996 1.5685975876 0.1249688639 0.1289688064 -0.8094109594 0.559109764512 +1403715337962142976.0000000000 -1.8797254735 -0.9985854645 1.5717930895 0.1228295029 0.1290409176 -0.8092570529 0.559789582983 +1403715338012143104.0000000000 -1.8875678751 -1.0202118566 1.5752594846 0.1218512484 0.1276148257 -0.8090853869 0.560577885933 +1403715338062142976.0000000000 -1.8954704881 -1.0418152198 1.5787458083 0.1215330120 0.1252706760 -0.8091703804 0.561052831958 +1403715338112143104.0000000000 -1.9033367739 -1.0632577088 1.5823424911 0.1215128790 0.1226756235 -0.8092218204 0.561556192151 +1403715338162142976.0000000000 -1.9111490262 -1.0845169942 1.5854869840 0.1217803894 0.1216126211 -0.8091887875 0.561777013879 +1403715338212143104.0000000000 -1.9187217395 -1.1056176895 1.5880533065 0.1228590073 0.1209541150 -0.8091660005 0.561717144127 +1403715338262142976.0000000000 -1.9258711260 -1.1265270862 1.5904526586 0.1250471908 0.1208632762 -0.8089301040 0.561593585568 +1403715338312143104.0000000000 -1.9328944241 -1.1473599475 1.5926709684 0.1278527504 0.1216012804 -0.8090359128 0.560649350894 +1403715338362142976.0000000000 -1.9397926823 -1.1679687045 1.5953009154 0.1320813234 0.1228834663 -0.8091453168 0.559229857917 +1403715338412143104.0000000000 -1.9468901066 -1.1886490451 1.5982833632 0.1364893438 0.1261339675 -0.8083400477 0.558611894413 +1403715338462142976.0000000000 -1.9545706776 -1.2093649122 1.6014325943 0.1410694675 0.1305454083 -0.8074889662 0.557690659028 +1403715338512143104.0000000000 -1.9624853665 -1.2301888099 1.6046451803 0.1460484588 0.1361482135 -0.8067242578 0.556173968808 +1403715338562142976.0000000000 -1.9708372049 -1.2515095828 1.6082748721 0.1500657925 0.1436909683 -0.8048601784 0.555907597305 +1403715338612143104.0000000000 -1.9797146798 -1.2729220771 1.6125253483 0.1540294714 0.1522608081 -0.8027159810 0.555642530918 +1403715338662142976.0000000000 -1.9889544613 -1.2945897434 1.6170865987 0.1585621274 0.1615524793 -0.8001843875 0.555395169442 +1403715338712143104.0000000000 -1.9987727752 -1.3163105754 1.6217535112 0.1630104851 0.1711158558 -0.7976753131 0.554852269093 +1403715338762142976.0000000000 -2.0090140447 -1.3378421730 1.6263619033 0.1681070992 0.1798897402 -0.7957313074 0.55334561624 +1403715338812143104.0000000000 -2.0199056895 -1.3592873162 1.6303381036 0.1711010928 0.1885409466 -0.7942479816 0.551676418893 +1403715338862142976.0000000000 -2.0308595560 -1.3810348364 1.6343848886 0.1745374929 0.1950909942 -0.7927909336 0.550416844826 +1403715338912143104.0000000000 -2.0420453959 -1.4030204964 1.6377891861 0.1773796677 0.2006430646 -0.7921153231 0.548481657854 +1403715338962142976.0000000000 -2.0537652420 -1.4248528159 1.6402514355 0.1784239439 0.2066223947 -0.7915480763 0.546739174646 +1403715339012143104.0000000000 -2.0654828042 -1.4466350266 1.6420600359 0.1796694562 0.2111726035 -0.7916416886 0.544452435892 +1403715339062142976.0000000000 -2.0771779053 -1.4685933380 1.6432665288 0.1805073488 0.2150678365 -0.7919833763 0.542148738227 +1403715339112143104.0000000000 -2.0888440393 -1.4909820003 1.6436114945 0.1798491045 0.2191851443 -0.7917975225 0.540988775747 +1403715339162142976.0000000000 -2.0999531294 -1.5136771567 1.6433708515 0.1787218590 0.2231249429 -0.7910585109 0.540832866285 +1403715339212143104.0000000000 -2.1105967942 -1.5366508457 1.6424905141 0.1768078061 0.2267449839 -0.7903949313 0.540926579598 +1403715339262142976.0000000000 -2.1204115216 -1.5595712287 1.6414948757 0.1767091613 0.2285501474 -0.7897024161 0.54121049178 +1403715339312143104.0000000000 -2.1294132285 -1.5827347941 1.6409022290 0.1789204168 0.2281910620 -0.7887541908 0.542017665885 +1403715339362142976.0000000000 -2.1377597510 -1.6062393651 1.6400565872 0.1809689161 0.2272631727 -0.7876292203 0.543361678009 +1403715339412143104.0000000000 -2.1457933020 -1.6294853138 1.6387641413 0.1831060073 0.2257266644 -0.7871380183 0.543997613302 +1403715339462142976.0000000000 -2.1538011750 -1.6525665915 1.6368953006 0.1842580886 0.2242673171 -0.7869646123 0.544462878704 +1403715339512143104.0000000000 -2.1616743216 -1.6758248871 1.6346975201 0.1847881125 0.2225817027 -0.7864040816 0.545783253225 +1403715339562142976.0000000000 -2.1695458734 -1.6985711097 1.6318187756 0.1854839196 0.2206456539 -0.7870607453 0.545386646505 +1403715339612143104.0000000000 -2.1773667205 -1.7211121473 1.6276026013 0.1840212669 0.2198757097 -0.7890051837 0.543379853916 +1403715339662142976.0000000000 -2.1852953542 -1.7434094802 1.6227459028 0.1804255193 0.2199762858 -0.7901585110 0.542868854425 +1403715339712143104.0000000000 -2.1930262670 -1.7657682841 1.6172847839 0.1748204257 0.2215937713 -0.7908833155 0.542989503154 +1403715339762142976.0000000000 -2.2002597511 -1.7883156666 1.6115982190 0.1684476478 0.2232672025 -0.7902038796 0.545302645189 +1403715339812143104.0000000000 -2.2066830663 -1.8103435113 1.6051887753 0.1614777932 0.2253635315 -0.7894240250 0.547673177771 +1403715339862142976.0000000000 -2.2120063660 -1.8317521708 1.5986388868 0.1555051893 0.2274526130 -0.7881781460 0.550325953482 +1403715339912143104.0000000000 -2.2158652215 -1.8520378020 1.5920983504 0.1512782146 0.2306389976 -0.7865104522 0.552559375251 +1403715339962142976.0000000000 -2.2178412017 -1.8711902091 1.5852691325 0.1484340736 0.2352914590 -0.7850362348 0.553464872587 +1403715340012143104.0000000000 -2.2180057914 -1.8890611594 1.5792618605 0.1462850290 0.2414776308 -0.7829321815 0.554352273645 +1403715340062142976.0000000000 -2.2155063927 -1.9052625463 1.5741976748 0.1475525193 0.2477240356 -0.7810570218 0.553905212909 +1403715340112143104.0000000000 -2.2107605620 -1.9194852104 1.5706327378 0.1517777684 0.2538653982 -0.7792441862 0.552534493855 +1403715340162142976.0000000000 -2.2040716088 -1.9318417193 1.5690588873 0.1579760528 0.2600742788 -0.7765975469 0.551635011956 +1403715340212143104.0000000000 -2.1953280989 -1.9420190320 1.5690504881 0.1676447784 0.2658047810 -0.7744576568 0.549052260207 +1403715340262142976.0000000000 -2.1847109348 -1.9507085971 1.5707562076 0.1788994020 0.2716553894 -0.7718764936 0.546264617233 +1403715340312143104.0000000000 -2.1723484516 -1.9581817393 1.5744205482 0.1907835661 0.2790510458 -0.7687275541 0.542945754555 +1403715340362142976.0000000000 -2.1586983064 -1.9645515427 1.5802047497 0.2045119410 0.2866648714 -0.7654557296 0.5385867094 +1403715340412143104.0000000000 -2.1446635565 -1.9699776689 1.5872957285 0.2165767505 0.2961649016 -0.7615888130 0.534194105309 +1403715340462142976.0000000000 -2.1301277633 -1.9746060542 1.5952901771 0.2266425738 0.3058627614 -0.7582563000 0.529271667928 +1403715340512143104.0000000000 -2.1149770153 -1.9789522380 1.6032481892 0.2351456047 0.3144539998 -0.7553916416 0.524603368661 +1403715340562142976.0000000000 -2.0994798082 -1.9830860488 1.6105446631 0.2435019110 0.3211865406 -0.7540925830 0.518546431646 +1403715340612143104.0000000000 -2.0840036377 -1.9873581307 1.6171896365 0.2502994966 0.3270998447 -0.7520301425 0.514593546824 +1403715340662142976.0000000000 -2.0683530635 -1.9921789002 1.6229925083 0.2559070432 0.3319139455 -0.7504613757 0.511030763942 +1403715340712143104.0000000000 -2.0525004377 -1.9975387346 1.6281810320 0.2599430904 0.3357421766 -0.7493158811 0.50816581051 +1403715340762142976.0000000000 -2.0363466594 -2.0033616372 1.6327788490 0.2626895500 0.3386762993 -0.7489523385 0.505334502335 +1403715340812143104.0000000000 -2.0199434148 -2.0098902754 1.6373247667 0.2646932940 0.3407626816 -0.7486902006 0.503270541944 +1403715340862142976.0000000000 -2.0035282801 -2.0170131516 1.6421538750 0.2683688155 0.3397874516 -0.7496672559 0.500521400111 +1403715340912143104.0000000000 -1.9868185696 -2.0248801805 1.6467426139 0.2720825816 0.3378142209 -0.7509589701 0.497908873352 +1403715340962142976.0000000000 -1.9700802816 -2.0336403662 1.6508429119 0.2737655210 0.3362857521 -0.7521785320 0.496177174431 +1403715341012143104.0000000000 -1.9533333099 -2.0436252946 1.6549600035 0.2750194800 0.3342011116 -0.7538662477 0.494327404848 +1403715341062142976.0000000000 -1.9366481455 -2.0552919215 1.6591992232 0.2745488217 0.3324349495 -0.7543851172 0.494987922855 +1403715341112143104.0000000000 -1.9201611170 -2.0685539999 1.6631020013 0.2717132260 0.3318494803 -0.7536965003 0.497985371961 +1403715341162142976.0000000000 -1.9037627002 -2.0830714201 1.6670238401 0.2669827546 0.3324762442 -0.7520905752 0.502533105896 +1403715341212143104.0000000000 -1.8870375805 -2.0984529190 1.6720218045 0.2665836109 0.3291393378 -0.7504168233 0.507420009553 +1403715341262142976.0000000000 -1.8704297430 -2.1147625679 1.6771858111 0.2658412751 0.3257813373 -0.7495497027 0.511243757773 +1403715341312143104.0000000000 -1.8541851207 -2.1317286499 1.6821501772 0.2636959522 0.3232300337 -0.7483637781 0.515692200547 +1403715341362142976.0000000000 -1.8390043718 -2.1485868466 1.6872956329 0.2608030743 0.3211812897 -0.7467756889 0.520721044341 +1403715341412143104.0000000000 -1.8240733673 -2.1651221471 1.6926084613 0.2585595399 0.3185975571 -0.7460235053 0.524491649598 +1403715341462142976.0000000000 -1.8098911471 -2.1811128639 1.6972830766 0.2541573083 0.3179766735 -0.7459801913 0.527075376007 +1403715341512143104.0000000000 -1.7962184306 -2.1967860650 1.7024358712 0.2508327329 0.3167801540 -0.7469967890 0.527947981649 +1403715341562142976.0000000000 -1.7831501304 -2.2121828313 1.7071950353 0.2453960388 0.3174806449 -0.7470337910 0.53002579118 +1403715341612143104.0000000000 -1.7702914279 -2.2271780305 1.7118078538 0.2412657667 0.3179765331 -0.7455580663 0.53368991377 +1403715341662142976.0000000000 -1.7577418868 -2.2415492794 1.7161481822 0.2369998687 0.3184299131 -0.7436590534 0.53796344202 +1403715341712143104.0000000000 -1.7453188656 -2.2549367709 1.7201767357 0.2322047556 0.3196769367 -0.7414014358 0.54241268297 +1403715341762142976.0000000000 -1.7328324189 -2.2670518759 1.7234265509 0.2277129169 0.3212381598 -0.7411624940 0.543719624112 +1403715341812143104.0000000000 -1.7204865134 -2.2772535089 1.7258619997 0.2239361447 0.3228297465 -0.7412607835 0.54421136408 +1403715341862142976.0000000000 -1.7074921689 -2.2859219261 1.7279154960 0.2198445720 0.3250779589 -0.7408821148 0.54505630602 +1403715341912143104.0000000000 -1.6933998527 -2.2920659306 1.7303790907 0.2220723810 0.3240708734 -0.7430185917 0.541835121612 +1403715341962142976.0000000000 -1.6787714730 -2.2966388681 1.7331323703 0.2263074700 0.3221381373 -0.7455172981 0.537787976609 +1403715342012143104.0000000000 -1.6643165846 -2.2998417346 1.7356546377 0.2309279082 0.3200209408 -0.7486432723 0.532721455902 +1403715342062142976.0000000000 -1.6497889080 -2.3022653642 1.7379423886 0.2343441134 0.3191734300 -0.7518104424 0.527249672194 +1403715342112143104.0000000000 -1.6355880451 -2.3037543585 1.7400631550 0.2364749742 0.3194576671 -0.7546489156 0.522045400093 +1403715342162142976.0000000000 -1.6215887956 -2.3044848376 1.7423095381 0.2403806500 0.3182977240 -0.7582403313 0.515727934023 +1403715342212143104.0000000000 -1.6073333478 -2.3054601159 1.7442099147 0.2427936598 0.3185099704 -0.7602506664 0.511489551939 +1403715342262142976.0000000000 -1.5926341638 -2.3073384657 1.7460072515 0.2453233340 0.3186586948 -0.7613886573 0.508488358328 +1403715342312143104.0000000000 -1.5774109622 -2.3103033407 1.7469865451 0.2480438184 0.3193251483 -0.7615279700 0.506538117816 +1403715342362142976.0000000000 -1.5622001675 -2.3135544275 1.7471535431 0.2496962301 0.3225531473 -0.7608751806 0.504658517631 +1403715342412143104.0000000000 -1.5468367309 -2.3170417398 1.7469227144 0.2510321006 0.3280012313 -0.7588363188 0.503552894879 +1403715342462142976.0000000000 -1.5309358175 -2.3208692977 1.7464245419 0.2536979575 0.3342256276 -0.7575737368 0.50001260939 +1403715342512143104.0000000000 -1.5145076208 -2.3254519721 1.7457643563 0.2554331274 0.3424905161 -0.7547877492 0.497744530357 +1403715342562142976.0000000000 -1.4975054007 -2.3308831643 1.7449865527 0.2560818801 0.3521931449 -0.7506050113 0.496964964929 +1403715342612143104.0000000000 -1.4798499587 -2.3372400500 1.7446624538 0.2557718466 0.3630975874 -0.7445622145 0.498365341124 +1403715342662142976.0000000000 -1.4610953234 -2.3438850667 1.7445952721 0.2556732599 0.3741967033 -0.7367260835 0.501839306202 +1403715342712143104.0000000000 -1.4409145541 -2.3500813688 1.7446113972 0.2573787221 0.3842824206 -0.7294597439 0.503956046297 +1403715342762142976.0000000000 -1.4198172158 -2.3554036772 1.7445720887 0.2612241737 0.3919958716 -0.7243611355 0.503390616743 +1403715342812143104.0000000000 -1.3978790105 -2.3595391045 1.7450947240 0.2683855244 0.3962310520 -0.7216908826 0.500132416178 +1403715342862142976.0000000000 -1.3751971242 -2.3631208716 1.7463446613 0.2754098158 0.3991129057 -0.7187272827 0.498286478776 +1403715342912143104.0000000000 -1.3518230523 -2.3661674616 1.7472540595 0.2818901128 0.4008478640 -0.7172009736 0.495461116202 +1403715342962142976.0000000000 -1.3277924221 -2.3692307815 1.7480860173 0.2878678634 0.4016354513 -0.7149534554 0.494633818164 +1403715343012143104.0000000000 -1.3032860397 -2.3724229444 1.7483388309 0.2926843572 0.4020828253 -0.7129475341 0.494339035762 +1403715343062142976.0000000000 -1.2784775256 -2.3756379197 1.7479922041 0.2971854113 0.4020552338 -0.7117482614 0.493403316542 +1403715343112143104.0000000000 -1.2535653952 -2.3789185043 1.7466186016 0.2986799395 0.4036218292 -0.7101326981 0.493549656806 +1403715343162142976.0000000000 -1.2286742280 -2.3820733998 1.7446936616 0.3004451506 0.4047589060 -0.7095673995 0.492358654976 +1403715343212143104.0000000000 -1.2036125651 -2.3852990508 1.7427290669 0.3026188191 0.4052845440 -0.7083274551 0.492380447547 +1403715343262142976.0000000000 -1.1787259084 -2.3884965879 1.7395712332 0.3026845448 0.4069029793 -0.7086491981 0.490538832193 +1403715343312143104.0000000000 -1.1540738778 -2.3916739437 1.7359792928 0.3025587511 0.4080891496 -0.7093544192 0.488607977974 +1403715343362142976.0000000000 -1.1295076892 -2.3949011465 1.7319299387 0.3017568369 0.4092255750 -0.7107414534 0.486131491072 +1403715343412143104.0000000000 -1.1049546935 -2.3981981152 1.7274945869 0.2990312734 0.4114820618 -0.7117145811 0.484484432471 +1403715343462142976.0000000000 -1.0803699108 -2.4016003862 1.7231549615 0.2967513728 0.4128312113 -0.7121386458 0.48411523715 +1403715343512143104.0000000000 -1.0551200482 -2.4050818432 1.7190062926 0.2960444534 0.4126099535 -0.7130605230 0.483379145615 +1403715343562142976.0000000000 -1.0293375762 -2.4085792266 1.7147665120 0.2943742809 0.4128346229 -0.7134823414 0.483584848096 +1403715343612143104.0000000000 -1.0027342232 -2.4119639035 1.7109323313 0.2934233577 0.4123699367 -0.7139570194 0.483858598116 +1403715343662142976.0000000000 -0.9755262113 -2.4153922300 1.7071145585 0.2918337211 0.4122372275 -0.7137685669 0.485209213027 +1403715343712143104.0000000000 -0.9476528211 -2.4190558900 1.7039536466 0.2902791819 0.4120712817 -0.7131431093 0.487198276823 +1403715343762142976.0000000000 -0.9190646118 -2.4227930949 1.7014311454 0.2881241408 0.4121052446 -0.7114649045 0.490888415535 +1403715343812143104.0000000000 -0.8898012897 -2.4261652965 1.6996915097 0.2879572657 0.4108177591 -0.7095114525 0.494876631808 +1403715343862142976.0000000000 -0.8600109882 -2.4288418104 1.6978451932 0.2875522917 0.4100185520 -0.7091115162 0.496345972276 +1403715343912143104.0000000000 -0.8300227181 -2.4306205847 1.6964930493 0.2883199012 0.4091128928 -0.7085003476 0.497519379435 +1403715343962142976.0000000000 -0.7994852713 -2.4314169003 1.6958626141 0.2909477797 0.4086965493 -0.7076046060 0.497606512889 +1403715344012143104.0000000000 -0.7687161314 -2.4313343379 1.6952147140 0.2930499494 0.4100371003 -0.7063614221 0.497036059965 +1403715344062142976.0000000000 -0.7379281704 -2.4301403128 1.6946974316 0.2971417432 0.4120076321 -0.7036173997 0.496869248838 +1403715344112143104.0000000000 -0.7072264461 -2.4280032005 1.6944934853 0.3018994962 0.4152633240 -0.7003244902 0.49594220873 +1403715344162142976.0000000000 -0.6764767594 -2.4249202988 1.6937873913 0.3071415371 0.4197565498 -0.6964459863 0.494400144813 +1403715344212143104.0000000000 -0.6461357094 -2.4213132958 1.6924061663 0.3103402055 0.4264287455 -0.6913157603 0.493892702358 +1403715344262142976.0000000000 -0.6160113151 -2.4171663504 1.6910003049 0.3127371765 0.4329326938 -0.6851392131 0.495327164454 +1403715344312143104.0000000000 -0.5866205436 -2.4120857383 1.6894046151 0.3140292002 0.4395681998 -0.6783204423 0.498043006891 +1403715344362142976.0000000000 -0.5578652266 -2.4058610056 1.6877694215 0.3158062100 0.4449126091 -0.6718932277 0.50087792782 +1403715344412143104.0000000000 -0.5294792931 -2.3984362682 1.6860892261 0.3177418898 0.4496568287 -0.6652208838 0.504311415312 +1403715344462142976.0000000000 -0.5018357347 -2.3893961551 1.6840714544 0.3198103925 0.4534783193 -0.6602764022 0.50607687109 +1403715344512143104.0000000000 -0.4753626540 -2.3786243729 1.6816783594 0.3206022627 0.4574853668 -0.6553264069 0.508398100659 +1403715344562142976.0000000000 -0.4498562187 -2.3656306626 1.6789052358 0.3223372144 0.4605330838 -0.6522987329 0.508443076485 +1403715344612143104.0000000000 -0.4253694392 -2.3504429550 1.6753323644 0.3234483932 0.4636073725 -0.6515150650 0.505942151987 +1403715344662142976.0000000000 -0.4019902347 -2.3331455648 1.6706315986 0.3214255998 0.4683156331 -0.6516746150 0.502679070405 +1403715344712143104.0000000000 -0.3793162769 -2.3135615034 1.6656823368 0.3199852722 0.4720565514 -0.6527089653 0.498741460478 +1403715344762142976.0000000000 -0.3570012055 -2.2916378062 1.6605816762 0.3184704724 0.4754187654 -0.6540853155 0.494697842917 +1403715344812143104.0000000000 -0.3349252638 -2.2676829152 1.6558328335 0.3179896090 0.4777171916 -0.6546404622 0.49205158131 +1403715344862142976.0000000000 -0.3131348563 -2.2419142741 1.6511474612 0.3177267365 0.4792906572 -0.6549974042 0.49021279804 +1403715344912143104.0000000000 -0.2914028188 -2.2141444436 1.6465007825 0.3180324145 0.4803477887 -0.6554313012 0.488396554751 +1403715344962142976.0000000000 -0.2694750113 -2.1843970429 1.6421229718 0.3205892821 0.4794640943 -0.6557502103 0.487163582619 +1403715345012143104.0000000000 -0.2472078124 -2.1526401814 1.6388090467 0.3269520517 0.4756326513 -0.6567567492 0.485331339625 +1403715345062142976.0000000000 -0.2248815145 -2.1194471940 1.6358026987 0.3328222195 0.4718317462 -0.6572178062 0.48442639137 +1403715345112143104.0000000000 -0.2030739573 -2.0851981636 1.6330856614 0.3380015941 0.4683032354 -0.6573726223 0.484053961332 +1403715345162142976.0000000000 -0.1820187908 -2.0500345081 1.6297850742 0.3412268082 0.4659443159 -0.6582162357 0.482919814139 +1403715345212143104.0000000000 -0.1618184385 -2.0144574633 1.6262956024 0.3431508069 0.4644292698 -0.6597458617 0.480924500352 +1403715345262142976.0000000000 -0.1425743282 -1.9785376885 1.6224215774 0.3426715402 0.4646943016 -0.6607011942 0.479697147852 +1403715345312143104.0000000000 -0.1243734593 -1.9422964934 1.6185243041 0.3435143733 0.4638351410 -0.6619457452 0.478207766316 +1403715345362142976.0000000000 -0.1070088968 -1.9055247156 1.6144143302 0.3433907828 0.4638561272 -0.6627519797 0.47715833541 +1403715345412143104.0000000000 -0.0902339610 -1.8682691985 1.6102969477 0.3432747775 0.4639207866 -0.6636016235 0.475996655666 +1403715345462142976.0000000000 -0.0740854815 -1.8305181809 1.6062376484 0.3438687380 0.4637319737 -0.6643428573 0.474716247335 +1403715345512143104.0000000000 -0.0586587682 -1.7925199708 1.6018091096 0.3429991709 0.4644525816 -0.6641311708 0.474937002305 +1403715345562142976.0000000000 -0.0437862314 -1.7540530116 1.5978642055 0.3438592948 0.4641618564 -0.6640197681 0.474754993689 +1403715345612143104.0000000000 -0.0294709339 -1.7152366929 1.5937468990 0.3447651869 0.4638602035 -0.6642340690 0.474092585006 +1403715345662142976.0000000000 -0.0158831735 -1.6760992068 1.5893990303 0.3454450188 0.4637706203 -0.6642205101 0.473704195368 +1403715345712143104.0000000000 -0.0031509876 -1.6368100676 1.5848642931 0.3462031286 0.4635436552 -0.6644737672 0.473017215493 +1403715345762142976.0000000000 0.0089567928 -1.5973863950 1.5800978122 0.3469362657 0.4631814692 -0.6647240938 0.472482839057 +1403715345812143104.0000000000 0.0204777236 -1.5580764523 1.5751681459 0.3473105560 0.4631317936 -0.6651423160 0.47166727566 +1403715345862142976.0000000000 0.0311933758 -1.5186534978 1.5699537483 0.3470980792 0.4635363428 -0.6662868101 0.469807267889 +1403715345912143104.0000000000 0.0409716125 -1.4793383174 1.5639411677 0.3438467466 0.4659451953 -0.6692224367 0.465624118902 +1403715345962142976.0000000000 0.0506830162 -1.4398052713 1.5578601721 0.3394219943 0.4693100525 -0.6731613784 0.459776623039 +1403715346012143104.0000000000 0.0604062838 -1.4003543865 1.5528603445 0.3362248058 0.4715188104 -0.6766852623 0.454664653527 +1403715346062142976.0000000000 0.0705104209 -1.3612549237 1.5484526192 0.3335431546 0.4731872977 -0.6805942316 0.449037010968 +1403715346112143104.0000000000 0.0816398114 -1.3229997052 1.5449969882 0.3313173298 0.4741817608 -0.6829631300 0.446028976485 +1403715346162142976.0000000000 0.0938164192 -1.2852733933 1.5425195589 0.3304197162 0.4744587108 -0.6840731896 0.444697216257 +1403715346212143104.0000000000 0.1073751738 -1.2483640952 1.5414359995 0.3316710236 0.4730145968 -0.6835005007 0.446182237313 +1403715346262142976.0000000000 0.1220920323 -1.2121308888 1.5407651700 0.3333135170 0.4711529845 -0.6821435801 0.448995657823 +1403715346312143104.0000000000 0.1373120671 -1.1763556802 1.5400906107 0.3350305875 0.4686596322 -0.6814027381 0.451445415468 +1403715346362142976.0000000000 0.1531140943 -1.1408641655 1.5396188811 0.3363203886 0.4667832966 -0.6803547736 0.454003669864 +1403715346412143104.0000000000 0.1693594153 -1.1059308250 1.5397109504 0.3380766941 0.4641081706 -0.6794141197 0.456841557685 +1403715346462142976.0000000000 0.1855966406 -1.0716764658 1.5401545948 0.3394745732 0.4614537286 -0.6785127331 0.45982381577 +1403715346512143104.0000000000 0.2017633931 -1.0377745468 1.5410100166 0.3414202993 0.4583253889 -0.6782282375 0.461926915179 +1403715346562142976.0000000000 0.2176900032 -1.0043437012 1.5417281774 0.3425487423 0.4555570929 -0.6788209018 0.462958181151 +1403715346612143104.0000000000 0.2331842963 -0.9715843950 1.5427387059 0.3441839784 0.4518737932 -0.6798958015 0.463777061863 +1403715346662142976.0000000000 0.2478404577 -0.9395903235 1.5436119222 0.3441428096 0.4490834095 -0.6812827526 0.464482108358 +1403715346712143104.0000000000 0.2617007412 -0.9082765001 1.5449412900 0.3443968773 0.4460419537 -0.6820391706 0.466111506251 +1403715346762142976.0000000000 0.2746388901 -0.8774793041 1.5461627245 0.3442117386 0.4434881888 -0.6833559337 0.466756010446 +1403715346812143104.0000000000 0.2867046696 -0.8474152984 1.5471827583 0.3430389812 0.4415216298 -0.6851243061 0.46689141449 +1403715346862142976.0000000000 0.2981022866 -0.8181325102 1.5478357158 0.3401559196 0.4410234447 -0.6868132228 0.466990223143 +1403715346912143104.0000000000 0.3089506895 -0.7892450729 1.5485744183 0.3391338556 0.4392278990 -0.6899858440 0.464743602247 +1403715346962142976.0000000000 0.3193296798 -0.7611831633 1.5491987170 0.3376932780 0.4377602807 -0.6936286309 0.461745069308 +1403715347012143104.0000000000 0.3294709244 -0.7341653974 1.5500987462 0.3362646049 0.4366655520 -0.6968553096 0.458957502106 +1403715347062142976.0000000000 0.3390661400 -0.7084647343 1.5512690924 0.3342617488 0.4362997891 -0.6996800398 0.456464039291 +1403715347112143104.0000000000 0.3485473873 -0.6840108843 1.5530028444 0.3314109722 0.4382523251 -0.6995598938 0.456856237784 +1403715347162142976.0000000000 0.3577669554 -0.6601505621 1.5544951792 0.3289271525 0.4419440376 -0.6980890041 0.457344660302 +1403715347212143104.0000000000 0.3672501175 -0.6372032546 1.5568235366 0.3274948665 0.4470872506 -0.6946009843 0.45868243411 +1403715347262142976.0000000000 0.3772037239 -0.6146536562 1.5596227044 0.3283356497 0.4525416244 -0.6900390175 0.459617159875 +1403715347312143104.0000000000 0.3878093819 -0.5925224121 1.5632731663 0.3302204482 0.4591534664 -0.6842043925 0.460431210065 +1403715347362142976.0000000000 0.3978974610 -0.5705698013 1.5667588996 0.3330679555 0.4665907289 -0.6772645106 0.46116332406 +1403715347412143104.0000000000 0.4080990089 -0.5486199696 1.5704752584 0.3356280295 0.4753200192 -0.6688954146 0.462605263223 +1403715347462142976.0000000000 0.4181208925 -0.5258376876 1.5744016811 0.3390399748 0.4840176453 -0.6613735018 0.461913309639 +1403715347512143104.0000000000 0.4281891897 -0.5026484520 1.5785805550 0.3417029368 0.4922670763 -0.6539388505 0.461818371656 +1403715347562142976.0000000000 0.4385911124 -0.4790505154 1.5830681359 0.3444637360 0.4990217260 -0.6471319066 0.462106423824 +1403715347612143104.0000000000 0.4488657943 -0.4545727392 1.5877712688 0.3472574530 0.5046479813 -0.6412779562 0.462066293126 +1403715347662142976.0000000000 0.4592401143 -0.4291244009 1.5926167945 0.3513125643 0.5082147179 -0.6368072670 0.461274091293 +1403715347712143104.0000000000 0.4692552872 -0.4028193762 1.5975911553 0.3572666918 0.5092696444 -0.6348976466 0.45815927207 +1403715347762142976.0000000000 0.4790508031 -0.3756201605 1.6023327282 0.3632455785 0.5096504697 -0.6345509260 0.453491092276 +1403715347812143104.0000000000 0.4887204363 -0.3477584418 1.6068474739 0.3686540092 0.5109684328 -0.6333760568 0.449266349521 +1403715347862142976.0000000000 0.4979148957 -0.3193425606 1.6107381967 0.3753427264 0.5123351631 -0.6323490837 0.443582184847 +1403715347912143104.0000000000 0.5062838510 -0.2906870359 1.6144822889 0.3823656331 0.5145521028 -0.6304841574 0.437632703843 +1403715347962142976.0000000000 0.5138785552 -0.2622303991 1.6185219060 0.3912370020 0.5162167244 -0.6290812644 0.429779786015 +1403715348012143104.0000000000 0.5209032731 -0.2342976810 1.6227306627 0.4008601563 0.5185156334 -0.6266958373 0.421550709349 +1403715348062142976.0000000000 0.5273406205 -0.2073825356 1.6260484038 0.4087879533 0.5232083874 -0.6231647095 0.413293040691 +1403715348112143104.0000000000 0.5331485730 -0.1816761895 1.6299306387 0.4163576232 0.5294479476 -0.6171653422 0.406740876705 +1403715348162142976.0000000000 0.5380855941 -0.1573994379 1.6329799549 0.4223906785 0.5377146337 -0.6108214738 0.399181931669 +1403715348212143104.0000000000 0.5423923954 -0.1347616807 1.6360744832 0.4285676599 0.5465375532 -0.6031666534 0.392194405899 +1403715348262142976.0000000000 0.5464000480 -0.1139234535 1.6385638161 0.4325100045 0.5572342426 -0.5951095495 0.385058072022 +1403715348312143104.0000000000 0.5503202425 -0.0951240174 1.6407113367 0.4360740905 0.5674354087 -0.5866994269 0.378998980183 +1403715348362142976.0000000000 0.5543965798 -0.0779188110 1.6414899576 0.4391968195 0.5765933533 -0.5797073980 0.372270857485 +1403715348412143104.0000000000 0.5590037700 -0.0625152571 1.6406799978 0.4409020586 0.5848153965 -0.5732525063 0.367393373257 +1403715348462142976.0000000000 0.5638636587 -0.0487972437 1.6373520653 0.4421590419 0.5914513472 -0.5688939358 0.361994993534 +1403715348512143104.0000000000 0.5693334039 -0.0365581623 1.6307693758 0.4429481246 0.5968966083 -0.5647593708 0.358550207162 +1403715348562142976.0000000000 0.5758766091 -0.0253058343 1.6213138499 0.4442793440 0.6004674654 -0.5617984919 0.355580007796 +1403715348612143104.0000000000 0.5838319612 -0.0151848515 1.6096924736 0.4473850343 0.6018602272 -0.5590153646 0.353712764959 +1403715348662142976.0000000000 0.5921357612 -0.0061050916 1.5957183722 0.4521749968 0.6010575189 -0.5575405368 0.351306392012 +1403715348712143104.0000000000 0.6010045598 0.0012900192 1.5795973799 0.4560770751 0.6004069579 -0.5563715852 0.349221771448 +1403715348762142976.0000000000 0.6108433806 0.0071093367 1.5625071086 0.4589872429 0.6004066290 -0.5557903505 0.346323081815 +1403715348812143104.0000000000 0.6209884984 0.0114437051 1.5453612586 0.4617195631 0.6012740099 -0.5538745433 0.344249328814 +1403715348862142976.0000000000 0.6314221239 0.0141762140 1.5287229973 0.4649885370 0.6026455201 -0.5507260053 0.34249803607 +1403715348912143104.0000000000 0.6418888669 0.0148357002 1.5125203221 0.4674579392 0.6044073747 -0.5478687260 0.340609247674 +1403715348962142976.0000000000 0.6524312420 0.0135205336 1.4969765656 0.4688273652 0.6068121737 -0.5452999452 0.3385673598 +1403715349012143104.0000000000 0.6636388075 0.0102396019 1.4821236793 0.4699901421 0.6091603767 -0.5414831842 0.338864077498 +1403715349062142976.0000000000 0.6754129056 0.0052525811 1.4675399860 0.4705746442 0.6116751924 -0.5377068667 0.339535401152 +1403715349112143104.0000000000 0.6873676999 -0.0012726434 1.4534672642 0.4707747023 0.6150365134 -0.5324751930 0.341425593079 +1403715349162142976.0000000000 0.6990136745 -0.0091878104 1.4400519502 0.4721063138 0.6175666349 -0.5278624539 0.342181691087 +1403715349212143104.0000000000 0.7108803039 -0.0184052553 1.4272078641 0.4737757372 0.6196002792 -0.5230366637 0.343605432625 +1403715349262142976.0000000000 0.7225641849 -0.0286850497 1.4149123134 0.4759782834 0.6209912462 -0.5190192367 0.344141798931 +1403715349312143104.0000000000 0.7340330738 -0.0402444028 1.4035923254 0.4793781783 0.6209221750 -0.5158610482 0.344295793865 +1403715349362142976.0000000000 0.7452092227 -0.0531546244 1.3918433718 0.4804848111 0.6222686095 -0.5125395334 0.345281552623 +1403715349412143104.0000000000 0.7558362176 -0.0672869978 1.3798719533 0.4811728194 0.6232240395 -0.5090519079 0.347750872753 +1403715349462142976.0000000000 0.7657752120 -0.0825271066 1.3674357169 0.4804993726 0.6244560792 -0.5068248015 0.349719285638 +1403715349512143104.0000000000 0.7750367342 -0.0983251015 1.3549598985 0.4792974846 0.6257646114 -0.5045858833 0.352257943455 +1403715349562142976.0000000000 0.7831761516 -0.1144821396 1.3415901926 0.4769985143 0.6286058452 -0.5029819259 0.352613514985 +1403715349612143104.0000000000 0.7900782591 -0.1307858475 1.3281789491 0.4757079979 0.6318139287 -0.5007641848 0.351778753582 +1403715349662142976.0000000000 0.7958169468 -0.1471472956 1.3150879336 0.4756289202 0.6350556471 -0.4984092892 0.349384652972 +1403715349712143104.0000000000 0.8003276063 -0.1633351304 1.3022008775 0.4761660236 0.6389603712 -0.4959179935 0.345052033218 +1403715349762142976.0000000000 0.8041611210 -0.1794978263 1.2904222670 0.4779195426 0.6429275931 -0.4923950621 0.340270662394 +1403715349812143104.0000000000 0.8071239841 -0.1955951114 1.2796938062 0.4807902454 0.6468828959 -0.4891732318 0.333305877854 +1403715349862142976.0000000000 0.8096109243 -0.2116946671 1.2695926518 0.4844666538 0.6508505493 -0.4845583019 0.326938642288 +1403715349912143104.0000000000 0.8119350905 -0.2279837008 1.2599181158 0.4877732730 0.6556296075 -0.4782813759 0.321673712719 +1403715349962142976.0000000000 0.8136569522 -0.2444639949 1.2507210430 0.4911413193 0.6607420397 -0.4716810980 0.3157801502 +1403715350012143104.0000000000 0.8151256857 -0.2617595893 1.2414920402 0.4933312831 0.6663143972 -0.4645866445 0.311140834554 +1403715350062142976.0000000000 0.8165917062 -0.2797536816 1.2325418025 0.4950872331 0.6711592239 -0.4579314803 0.307786755907 +1403715350112143104.0000000000 0.8175967444 -0.2983775217 1.2225806553 0.4931009883 0.6777622142 -0.4529443106 0.30386057294 +1403715350162142976.0000000000 0.8186848702 -0.3172707080 1.2126836186 0.4915445452 0.6830070143 -0.4497908555 0.299288430663 +1403715350212143104.0000000000 0.8204937985 -0.3364676562 1.2028818552 0.4886411339 0.6882726747 -0.4466579464 0.296660153143 +1403715350262142976.0000000000 0.8225527092 -0.3559606628 1.1925569229 0.4829566638 0.6947460155 -0.4441457631 0.29464449092 +1403715350312143104.0000000000 0.8253174475 -0.3749547904 1.1822439377 0.4776132434 0.7002265952 -0.4417462156 0.293987391255 +1403715350362142976.0000000000 0.8286613631 -0.3931769021 1.1719009911 0.4726509863 0.7046690609 -0.4403901421 0.29342645155 +1403715350412143104.0000000000 0.8328343072 -0.4102551552 1.1616490103 0.4675815825 0.7086075306 -0.4385777830 0.294775099992 +1403715350462142976.0000000000 0.8377548543 -0.4255913643 1.1514984900 0.4633457761 0.7115507710 -0.4371266993 0.296523929617 +1403715350512143104.0000000000 0.8434655937 -0.4388185932 1.1415498621 0.4601546379 0.7134254052 -0.4357481058 0.299007506204 +1403715350562142976.0000000000 0.8499538569 -0.4498167411 1.1318625509 0.4577471153 0.7145222634 -0.4354947345 0.300449412943 +1403715350612143104.0000000000 0.8573382364 -0.4581154858 1.1227264017 0.4573358548 0.7139868170 -0.4364341521 0.300985002805 +1403715350662142976.0000000000 0.8653845438 -0.4639214398 1.1141691538 0.4579065548 0.7128527796 -0.4380336211 0.300481361337 +1403715350712143104.0000000000 0.8740654869 -0.4673280734 1.1060614292 0.4596782376 0.7109855961 -0.4402485036 0.298959286545 +1403715350762142976.0000000000 0.8835861894 -0.4687468887 1.0983088483 0.4613753627 0.7092563398 -0.4424479805 0.297200275613 +1403715350812143104.0000000000 0.8940849158 -0.4683342869 1.0911383051 0.4635035493 0.7075753470 -0.4434497772 0.296401557289 +1403715350862142976.0000000000 0.9055521528 -0.4666117650 1.0843243334 0.4647985222 0.7066379361 -0.4423241897 0.298285890058 +1403715350912143104.0000000000 0.9175504338 -0.4634059226 1.0778498830 0.4648811146 0.7067696002 -0.4400937289 0.30113085396 +1403715350962142976.0000000000 0.9299877015 -0.4584997304 1.0720634824 0.4655021209 0.7064991745 -0.4378604448 0.304047566546 +1403715351012143104.0000000000 0.9424915661 -0.4518394109 1.0667194901 0.4656795834 0.7066857651 -0.4363346146 0.30553209166 +1403715351062142976.0000000000 0.9548667945 -0.4431180726 1.0620451360 0.4657140537 0.7071530306 -0.4352679770 0.305919596923 +1403715351112143104.0000000000 0.9673446984 -0.4323086489 1.0584310058 0.4659558885 0.7071939791 -0.4345211183 0.306517835832 +1403715351162142976.0000000000 0.9796673113 -0.4193939591 1.0555654671 0.4667973982 0.7069857724 -0.4351329785 0.304845202887 +1403715351212143104.0000000000 0.9920605998 -0.4048278892 1.0529408244 0.4674819289 0.7070069738 -0.4357972261 0.302791285845 +1403715351262142976.0000000000 1.0046991285 -0.3886696485 1.0507543843 0.4679585130 0.7070576271 -0.4361179678 0.301472154881 +1403715351312143104.0000000000 1.0178728247 -0.3704651798 1.0500615346 0.4722168883 0.7044896858 -0.4357928055 0.30131399502 +1403715351362142976.0000000000 1.0311222172 -0.3510541415 1.0493769424 0.4750826386 0.7026435538 -0.4348792928 0.302437635665 +1403715351412143104.0000000000 1.0441790147 -0.3304059530 1.0491522940 0.4785246910 0.7002867337 -0.4342081004 0.303440169086 +1403715351462142976.0000000000 1.0570419327 -0.3088452362 1.0490051548 0.4802444813 0.6989782132 -0.4330786331 0.305348314464 +1403715351512143104.0000000000 1.0694159365 -0.2862279910 1.0490774147 0.4814188103 0.6979042013 -0.4324402924 0.306856722928 +1403715351562142976.0000000000 1.0814965556 -0.2624976216 1.0502481247 0.4848092381 0.6951889145 -0.4308035636 0.309968813637 +1403715351612143104.0000000000 1.0929160732 -0.2378539151 1.0523033843 0.4895887465 0.6913497296 -0.4281715500 0.31465462739 +1403715351662142976.0000000000 1.1027788872 -0.2123293278 1.0539741018 0.4919483154 0.6899189109 -0.4262917608 0.316660837567 +1403715351712143104.0000000000 1.1111314324 -0.1857787876 1.0556456505 0.4923119890 0.6908520750 -0.4244246162 0.316569204346 +1403715351762142976.0000000000 1.1178057730 -0.1582039508 1.0576386750 0.4920164403 0.6932399914 -0.4227775094 0.314002092948 +1403715351812143104.0000000000 1.1229179201 -0.1293985128 1.0603515546 0.4939288763 0.6951815072 -0.4211322533 0.308876289746 +1403715351862142976.0000000000 1.1267681089 -0.0996197809 1.0635436607 0.4962852998 0.6976838001 -0.4192736077 0.301907035592 +1403715351912143104.0000000000 1.1295868791 -0.0691985244 1.0666267835 0.4991982065 0.7004111326 -0.4163678513 0.294725649289 +1403715351962142976.0000000000 1.1318245404 -0.0381203246 1.0702399652 0.5028315244 0.7031057262 -0.4137555874 0.285673082 +1403715352012143104.0000000000 1.1334641485 -0.0068733487 1.0747171296 0.5065220535 0.7061853403 -0.4098588348 0.277044058008 +1403715352062142976.0000000000 1.1346483642 0.0241825524 1.0798123805 0.5097928034 0.7096023473 -0.4055275603 0.2685576367 +1403715352112143104.0000000000 1.1361599884 0.0548939167 1.0859265772 0.5119773465 0.7131634570 -0.4004102375 0.262580886765 +1403715352162142976.0000000000 1.1376003247 0.0853752385 1.0923580444 0.5150405256 0.7154197872 -0.3965338518 0.256259028111 +1403715352212143104.0000000000 1.1391383650 0.1153905999 1.0988549922 0.5181727263 0.7168314651 -0.3934916142 0.250627264925 +1403715352262142976.0000000000 1.1410549513 0.1447179436 1.1048467006 0.5192423400 0.7189225058 -0.3908645495 0.246500967671 +1403715352312143104.0000000000 1.1435337392 0.1736481995 1.1101983095 0.5192220624 0.7213479918 -0.3888347250 0.242637757292 +1403715352362142976.0000000000 1.1467014169 0.2020498885 1.1152195413 0.5197840359 0.7228270149 -0.3870414412 0.23988452505 +1403715352412143104.0000000000 1.1502840366 0.2300269529 1.1199207163 0.5220567535 0.7224456302 -0.3878135159 0.234797219897 +1403715352462142976.0000000000 1.1542034036 0.2574090263 1.1245153230 0.5258792678 0.7204995316 -0.3907993446 0.227172385744 +1403715352512143104.0000000000 1.1593500464 0.2839079116 1.1288066779 0.5299759588 0.7181608533 -0.3927796189 0.221573109458 +1403715352562142976.0000000000 1.1657000447 0.3089916021 1.1320342926 0.5319393188 0.7175069040 -0.3920876813 0.220208206061 +1403715352612143104.0000000000 1.1734133180 0.3325715066 1.1342483979 0.5318144202 0.7184080521 -0.3885870804 0.223748461619 +1403715352662142976.0000000000 1.1817853660 0.3549030127 1.1357217381 0.5310950466 0.7196313820 -0.3853255855 0.227140746414 +1403715352712143104.0000000000 1.1910513805 0.3764090718 1.1374409187 0.5317559793 0.7195043356 -0.3823860629 0.23093286548 +1403715352762142976.0000000000 1.2006318793 0.3969517995 1.1387844399 0.5321209742 0.7195433657 -0.3785272158 0.236266291836 +1403715352812143104.0000000000 1.2100979316 0.4165913963 1.1401788229 0.5337202852 0.7185730633 -0.3755002046 0.240405919692 +1403715352862142976.0000000000 1.2192792501 0.4353700616 1.1411755084 0.5343383298 0.7183522782 -0.3728036290 0.243864732724 +1403715352912143104.0000000000 1.2279977089 0.4532791098 1.1420924809 0.5335951803 0.7189751792 -0.3706869326 0.246864483468 +1403715352962142976.0000000000 1.2357672387 0.4705254051 1.1435975730 0.5347489193 0.7182358908 -0.3705581787 0.246713264044 +1403715353012143104.0000000000 1.2428217366 0.4872180712 1.1455291619 0.5364491083 0.7171143738 -0.3715810250 0.244738372507 +1403715353062142976.0000000000 1.2494617224 0.5029480175 1.1475424859 0.5366080905 0.7171948466 -0.3715334200 0.24422577088 +1403715353112143104.0000000000 1.2555704896 0.5177799875 1.1502042856 0.5356058639 0.7183585259 -0.3707857450 0.244142003862 +1403715353162142976.0000000000 1.2612257448 0.5316313726 1.1546484404 0.5342296305 0.7199118140 -0.3701208999 0.243590232568 +1403715353212143104.0000000000 1.2663874842 0.5446163028 1.1617591417 0.5334653630 0.7210229826 -0.3692179343 0.243348889651 +1403715353262142976.0000000000 1.2709711614 0.5567122420 1.1719845554 0.5332663632 0.7219355744 -0.3682384172 0.242562322761 +1403715353312143104.0000000000 1.2750358278 0.5678774485 1.1849890885 0.5327674741 0.7230651267 -0.3675960304 0.241264998492 +1403715353362142976.0000000000 1.2786726169 0.5782798840 1.1990201145 0.5319234726 0.7246265390 -0.3666223041 0.239920579276 +1403715353412143104.0000000000 1.2821169127 0.5881771276 1.2114683876 0.5307204939 0.7266236846 -0.3644812684 0.239806553886 +1403715353462142976.0000000000 1.2853941211 0.5981254654 1.2211907537 0.5304268025 0.7279262661 -0.3623730864 0.239700864747 +1403715353512143104.0000000000 1.2883987280 0.6078559645 1.2273439668 0.5297327448 0.7293689542 -0.3609255433 0.239033261152 +1403715353562142976.0000000000 1.2910562518 0.6171047404 1.2295694263 0.5289755195 0.7307235934 -0.3593421779 0.238958425375 +1403715353612143104.0000000000 1.2931783580 0.6261939887 1.2281858971 0.5289470714 0.7316661317 -0.3581681685 0.237897521047 +1403715353662142976.0000000000 1.2951306794 0.6349183753 1.2238878157 0.5287439464 0.7326883203 -0.3560443283 0.238390647192 +1403715353712143104.0000000000 1.2967051528 0.6433794318 1.2179152975 0.5286074169 0.7335539093 -0.3542506230 0.238703492007 +1403715353762142976.0000000000 1.2977824791 0.6516604245 1.2110928994 0.5287410535 0.7343169070 -0.3524663724 0.23870281703 +1403715353812143104.0000000000 1.2984175095 0.6601576127 1.2036274707 0.5290095746 0.7349451795 -0.3503092992 0.239348799843 +1403715353862142976.0000000000 1.2985129455 0.6687711341 1.1956927396 0.5292999455 0.7353947213 -0.3492242987 0.23891119832 +1403715353912143104.0000000000 1.2981158392 0.6774275155 1.1875416837 0.5302055967 0.7354660936 -0.3478938414 0.238624234916 +1403715353962142976.0000000000 1.2969467008 0.6859641841 1.1786270258 0.5299928543 0.7362428790 -0.3472457601 0.237643387496 +1403715354012143104.0000000000 1.2953041950 0.6944618912 1.1690592974 0.5298950025 0.7369195226 -0.3469048298 0.236258211745 +1403715354062142976.0000000000 1.2930338694 0.7032215902 1.1591086875 0.5294172748 0.7377840303 -0.3486360393 0.232045223735 +1403715354112143104.0000000000 1.2902345001 0.7120577957 1.1499548955 0.5309844326 0.7370896643 -0.3523860501 0.224896489228 +1403715354162142976.0000000000 1.2874455713 0.7204403270 1.1407860703 0.5325481664 0.7362367650 -0.3561353445 0.217980486963 +1403715354212143104.0000000000 1.2849317932 0.7280539867 1.1313494657 0.5333291812 0.7359289736 -0.3590513688 0.212251371845 +1403715354262142976.0000000000 1.2833675628 0.7347437381 1.1220107462 0.5326656450 0.7366542697 -0.3603311605 0.209211023457 +1403715354312143104.0000000000 1.2826502920 0.7405914651 1.1130031238 0.5317309019 0.7376778410 -0.3596363643 0.209177762631 +1403715354362142976.0000000000 1.2827469536 0.7455678893 1.1036022744 0.5291380358 0.7398666108 -0.3579049168 0.21098437809 +1403715354412143104.0000000000 1.2837473866 0.7500806331 1.0942934645 0.5260938219 0.7423594069 -0.3553658471 0.214109589301 +1403715354462142976.0000000000 1.2855860777 0.7545352851 1.0852934175 0.5234616466 0.7445701018 -0.3528904521 0.216959896896 +1403715354512143104.0000000000 1.2879759471 0.7590683077 1.0765837857 0.5217206293 0.7460716665 -0.3507268367 0.219488813931 +1403715354562142976.0000000000 1.2906378884 0.7638931073 1.0685484265 0.5210678899 0.7466457990 -0.3498145963 0.220540366236 +1403715354612143104.0000000000 1.2935230363 0.7690560474 1.0629989763 0.5217210764 0.7461756888 -0.3496286137 0.220881851404 +1403715354662142976.0000000000 1.2969510281 0.7745140383 1.0597891294 0.5216963553 0.7460695745 -0.3497452728 0.221113877809 +1403715354712143104.0000000000 1.3011947518 0.7803482384 1.0597478990 0.5219886709 0.7457003201 -0.3501997282 0.220950244276 +1403715354762142976.0000000000 1.3061528581 0.7862126965 1.0632434403 0.5220864227 0.7453935025 -0.3506494408 0.221041315826 +1403715354812143104.0000000000 1.3113751824 0.7922728440 1.0699308187 0.5219486047 0.7453920940 -0.3515550173 0.219930330048 +1403715354862142976.0000000000 1.3170447557 0.7982606700 1.0793007703 0.5219188869 0.7453240509 -0.3513069578 0.220626734693 +1403715354912143104.0000000000 1.3229267837 0.8046297242 1.0919243177 0.5239380036 0.7440350288 -0.3527879619 0.217810693611 +1403715354962142976.0000000000 1.3291611451 0.8110374962 1.1061981177 0.5259434169 0.7428876160 -0.3536373800 0.215504328767 +1403715355012143104.0000000000 1.3358155791 0.8171882768 1.1217543116 0.5284629874 0.7415104997 -0.3538127722 0.213788615296 +1403715355062142976.0000000000 1.3430576622 0.8229707159 1.1363890651 0.5290434742 0.7415830141 -0.3529078860 0.2135969557 +1403715355112143104.0000000000 1.3505674729 0.8284242762 1.1500644006 0.5284284097 0.7429475719 -0.3508008511 0.213848273428 +1403715355162142976.0000000000 1.3580464817 0.8338218586 1.1631190780 0.5286815627 0.7447154015 -0.3472512926 0.212864547965 +1403715355212143104.0000000000 1.3654513895 0.8391303914 1.1755906317 0.5289226489 0.7473533317 -0.3432372385 0.209504241476 +1403715355262142976.0000000000 1.3731443606 0.8442607225 1.1874214723 0.5300044147 0.7501818323 -0.3369893121 0.206786707386 +1403715355312143104.0000000000 1.3809314094 0.8494091150 1.1982231562 0.5303698019 0.7542806442 -0.3290824747 0.203649963944 +1403715355362142976.0000000000 1.3887603971 0.8547496868 1.2086288591 0.5314669473 0.7582879584 -0.3204979427 0.199557823111 +1403715355412143104.0000000000 1.3965706690 0.8603651797 1.2193989524 0.5344188839 0.7613024153 -0.3114760025 0.194416534378 +1403715355462142976.0000000000 1.4044363298 0.8660303389 1.2300072190 0.5380117600 0.7641163710 -0.3024987709 0.187520695584 +1403715355512143104.0000000000 1.4125727520 0.8717349147 1.2407882087 0.5424686905 0.7662825929 -0.2928275513 0.181082116358 +1403715355562142976.0000000000 1.4206528409 0.8770541108 1.2511600519 0.5461116827 0.7689308013 -0.2829152934 0.174546239238 +1403715355612143104.0000000000 1.4286267006 0.8822282733 1.2609588533 0.5492017867 0.7718552917 -0.2731599637 0.16733332096 +1403715355662142976.0000000000 1.4371324007 0.8870563115 1.2697010065 0.5512639278 0.7749773247 -0.2629720226 0.162369773586 +1403715355712143104.0000000000 1.4458897776 0.8916154872 1.2780874488 0.5530335428 0.7775895090 -0.2541602178 0.15783231509 +1403715355762142976.0000000000 1.4548958772 0.8957505177 1.2858822695 0.5540954534 0.7799721165 -0.2465643120 0.154362450316 +1403715355812143104.0000000000 1.4639184304 0.8995371343 1.2931767985 0.5540010790 0.7824154306 -0.2405317763 0.151833339562 +1403715355862142976.0000000000 1.4728815248 0.9034298463 1.3003592399 0.5534683885 0.7846128536 -0.2360465942 0.149457078392 +1403715355912143104.0000000000 1.4821019259 0.9076701676 1.3077249526 0.5532419253 0.7861918877 -0.2322571982 0.147926609266 +1403715355962142976.0000000000 1.4916200446 0.9119942131 1.3146106059 0.5521382146 0.7879590773 -0.2288940029 0.147889891142 +1403715356012143104.0000000000 1.5008685108 0.9164590708 1.3214501320 0.5514547443 0.7890083724 -0.2262006613 0.148985617126 +1403715356062142976.0000000000 1.5099805340 0.9211889268 1.3280350390 0.5496620218 0.7905129039 -0.2235488971 0.151614317471 +1403715356112143104.0000000000 1.5186689165 0.9262893072 1.3344308889 0.5472779076 0.7919768921 -0.2214023018 0.155693657434 +1403715356162142976.0000000000 1.5266895311 0.9320397682 1.3406524944 0.5449896117 0.7930161146 -0.2202753312 0.159970446122 +1403715356212143104.0000000000 1.5337527848 0.9384541891 1.3470377054 0.5437881853 0.7929277552 -0.2204658525 0.164179147067 +1403715356262142976.0000000000 1.5399744755 0.9458501231 1.3529788082 0.5426769458 0.7926309528 -0.2217583450 0.167514601297 +1403715356312143104.0000000000 1.5449905638 0.9539116062 1.3581821158 0.5405560811 0.7929094029 -0.2238586296 0.17023840915 +1403715356362142976.0000000000 1.5488182815 0.9632606263 1.3626316030 0.5375858140 0.7937153639 -0.2275126795 0.171042083568 +1403715356412143104.0000000000 1.5514845150 0.9738558662 1.3663215157 0.5345837431 0.7946076412 -0.2315382866 0.170906231426 +1403715356462142976.0000000000 1.5531612718 0.9857128502 1.3693912831 0.5326136908 0.7947381972 -0.2367297814 0.169330637886 +1403715356512143104.0000000000 1.5538832324 0.9988824645 1.3720328935 0.5323908915 0.7937016077 -0.2440259784 0.164465857875 +1403715356562142976.0000000000 1.5543065885 1.0131349002 1.3739005250 0.5330005100 0.7925093483 -0.2490615972 0.16064778265 +1403715356612143104.0000000000 1.5544226067 1.0285445554 1.3751798006 0.5339678310 0.7916747510 -0.2521834437 0.156629993197 +1403715356662142976.0000000000 1.5544642706 1.0450587772 1.3760723666 0.5359658339 0.7907824596 -0.2531790763 0.152656744914 +1403715356712143104.0000000000 1.5547729207 1.0626429253 1.3765458733 0.5373579994 0.7909933298 -0.2518438718 0.148830765856 +1403715356762142976.0000000000 1.5553222471 1.0811900064 1.3768474745 0.5393478108 0.7913332016 -0.2490112951 0.144530543258 +1403715356812143104.0000000000 1.5560979188 1.1001181567 1.3767891640 0.5420812217 0.7917518478 -0.2444800546 0.139665541746 +1403715356862142976.0000000000 1.5571930685 1.1191886465 1.3761632809 0.5429316936 0.7940255390 -0.2380298666 0.134500565519 +1403715356912143104.0000000000 1.5587838193 1.1391204294 1.3760719353 0.5448322316 0.7958502835 -0.2314625102 0.127299929797 +1403715356962142976.0000000000 1.5614338218 1.1596195670 1.3779195030 0.5481001386 0.7971105199 -0.2236409911 0.119104006016 +1403715357012143104.0000000000 1.5650584592 1.1804550312 1.3812403732 0.5518838043 0.7982893142 -0.2131987052 0.112715346826 +1403715357062142976.0000000000 1.5694056069 1.2011983176 1.3859904277 0.5549820104 0.7999923340 -0.2025056335 0.104874696758 +1403715357112143104.0000000000 1.5743457200 1.2220027181 1.3919427408 0.5588919649 0.8009445301 -0.1910883634 0.0980452372442 +1403715357162142976.0000000000 1.5798227089 1.2426170099 1.3981745203 0.5616057531 0.8025029147 -0.1793154204 0.091836975309 +1403715357212143104.0000000000 1.5862573785 1.2632687378 1.4051222573 0.5636019871 0.8041034398 -0.1681753818 0.0865303362815 +1403715357262142976.0000000000 1.5939066888 1.2841151367 1.4125547252 0.5661280957 0.8047495482 -0.1576793067 0.0837518961984 +1403715357312143104.0000000000 1.6027920440 1.3052421238 1.4202707648 0.5675438422 0.8055690196 -0.1485866965 0.0829128184357 +1403715357362142976.0000000000 1.6124859091 1.3267492890 1.4289127100 0.5683844104 0.8063391788 -0.1409753549 0.0829592674517 +1403715357412143104.0000000000 1.6219747646 1.3481255420 1.4376451317 0.5689429060 0.8069321557 -0.1357787151 0.082028083162 +1403715357462142976.0000000000 1.6313497380 1.3692757297 1.4458210266 0.5692427475 0.8074717874 -0.1307821235 0.0827529048061 +1403715357512143104.0000000000 1.6403075461 1.3902509329 1.4531451828 0.5678307018 0.8090315075 -0.1272461627 0.0827328716583 +1403715357562142976.0000000000 1.6489226342 1.4113565882 1.4592472996 0.5662984185 0.8105338747 -0.1244507012 0.082782619792 +1403715357612143104.0000000000 1.6571082410 1.4326265621 1.4648225696 0.5647637743 0.8119773858 -0.1217059259 0.0832001912306 +1403715357662142976.0000000000 1.6649212949 1.4544224570 1.4698601031 0.5644990419 0.8124212180 -0.1191198490 0.084398209917 +1403715357712143104.0000000000 1.6723808659 1.4766022475 1.4754502306 0.5664725260 0.8112300563 -0.1164729382 0.0863060121486 +1403715357762142976.0000000000 1.6791589599 1.4987520053 1.4801073573 0.5668657019 0.8110733750 -0.1139189086 0.0885761742176 +1403715357812143104.0000000000 1.6850198061 1.5210383784 1.4839827956 0.5673911102 0.8107747920 -0.1104058396 0.0923153037111 +1403715357862142976.0000000000 1.6896556732 1.5434863887 1.4864203726 0.5667805744 0.8111788615 -0.1069405282 0.096500562063 +1403715357912143104.0000000000 1.6928135666 1.5664078048 1.4880287853 0.5658337517 0.8118017833 -0.1048856168 0.0990405848347 +1403715357962142976.0000000000 1.6945402649 1.5899000251 1.4890464591 0.5639586255 0.8130611187 -0.1041156157 0.100210900594 +1403715358012143104.0000000000 1.6948131935 1.6139305286 1.4893028561 0.5620406922 0.8143864691 -0.1035558747 0.100802381132 +1403715358062142976.0000000000 1.6935787046 1.6385768450 1.4889862600 0.5601254996 0.8156702573 -0.1033042236 0.101339495622 +1403715358112143104.0000000000 1.6905550009 1.6640267323 1.4885662666 0.5591652884 0.8163663706 -0.1048915364 0.0993875988815 +1403715358162142976.0000000000 1.6860538441 1.6905202080 1.4880838666 0.5592788532 0.8163061169 -0.1076761238 0.0962150723684 +1403715358212143104.0000000000 1.6801409455 1.7180828443 1.4871385428 0.5581231196 0.8171044953 -0.1118041374 0.0913162740622 +1403715358262142976.0000000000 1.6731942777 1.7465098135 1.4863801818 0.5580116122 0.8171827644 -0.1147932879 0.0875092638184 +1403715358312143104.0000000000 1.6658310196 1.7757247440 1.4848834803 0.5566800778 0.8180975419 -0.1164810288 0.0851814113331 +1403715358362142976.0000000000 1.6582905805 1.8062323119 1.4829944323 0.5553736630 0.8191660048 -0.1156186334 0.0846137262189 +1403715358412143104.0000000000 1.6501810352 1.8375477834 1.4809594766 0.5550519507 0.8197935616 -0.1115149757 0.0861409224612 +1403715358462142976.0000000000 1.6409883647 1.8695849534 1.4787385600 0.5562680422 0.8196264894 -0.1063675116 0.0863958073992 +1403715358512143104.0000000000 1.6307055106 1.9030041921 1.4765792838 0.5594227651 0.8182768450 -0.0999734476 0.0864551013738 +1403715358562142976.0000000000 1.6194671622 1.9371953914 1.4741582005 0.5626214541 0.8169056371 -0.0938162048 0.0855616689577 +1403715358612143104.0000000000 1.6069795844 1.9717948679 1.4712673219 0.5659354836 0.8154356694 -0.0883549206 0.0835170974965 +1403715358662142976.0000000000 1.5930028857 2.0069495646 1.4688854530 0.5703067202 0.8132514790 -0.0846675808 0.078763428121 +1403715358712143104.0000000000 1.5775633558 2.0422931541 1.4673188679 0.5759057851 0.8102378452 -0.0837549477 0.0695145278214 +1403715358762142976.0000000000 1.5614014329 2.0774525874 1.4657193851 0.5804343246 0.8078350757 -0.0826728654 0.0605283631921 +1403715358812143104.0000000000 1.5450074852 2.1121515380 1.4637316430 0.5842476441 0.8057655507 -0.0810547810 0.0531666263756 +1403715358862142976.0000000000 1.5284446528 2.1461468096 1.4613519411 0.5872975186 0.8041375341 -0.0793708842 0.0463110537724 +1403715358912143104.0000000000 1.5122499355 2.1793587025 1.4584566592 0.5906497116 0.8021468040 -0.0771594197 0.0417114716539 +1403715358962142976.0000000000 1.4960446440 2.2114523038 1.4546878381 0.5922679509 0.8013662103 -0.0746400230 0.0382065210806 +1403715359012143104.0000000000 1.4800237276 2.2425406515 1.4504500310 0.5921263523 0.8018085007 -0.0730820001 0.0338900040946 +1403715359062142976.0000000000 1.4645317435 2.2727006578 1.4453530205 0.5906624151 0.8031772401 -0.0710817342 0.0311708114368 +1403715359112143104.0000000000 1.4496270706 2.3016256942 1.4405835554 0.5904199205 0.8035725373 -0.0692391823 0.0296888948454 +1403715359162142976.0000000000 1.4351302645 2.3295691132 1.4358282997 0.5913409806 0.8030727185 -0.0674528240 0.028985686733 +1403715359212143104.0000000000 1.4209438773 2.3567252752 1.4309919797 0.5929822043 0.8019687368 -0.0663728551 0.0285113078911 +1403715359262142976.0000000000 1.4072946605 2.3825116115 1.4261800503 0.5941961313 0.8011460562 -0.0650272140 0.0294519199471 +1403715359312143104.0000000000 1.3941373146 2.4068255440 1.4213733839 0.5943106384 0.8010982910 -0.0635190880 0.0316499417546 +1403715359362142976.0000000000 1.3809101882 2.4295847618 1.4163679663 0.5936434295 0.8016018830 -0.0621271177 0.0340898965587 +1403715359412143104.0000000000 1.3677349187 2.4511148793 1.4116731399 0.5931198640 0.8019413729 -0.0601346618 0.0385056335502 +1403715359462142976.0000000000 1.3542278847 2.4716969460 1.4073642491 0.5927409856 0.8021315592 -0.0581149687 0.0431941681708 +1403715359512143104.0000000000 1.3399736289 2.4912362585 1.4043790986 0.5926422957 0.8020899864 -0.0566587239 0.0470802729282 +1403715359562142976.0000000000 1.3249468814 2.5098101307 1.4025154121 0.5932458571 0.8015007883 -0.0563011990 0.0498599484727 +1403715359612143104.0000000000 1.3087528299 2.5272611571 1.4015342575 0.5940540289 0.8008174830 -0.0569342325 0.0504941867389 +1403715359662142976.0000000000 1.2914352676 2.5435662931 1.4009896852 0.5939249024 0.8008514088 -0.0584485953 0.049739250661 +1403715359712143104.0000000000 1.2732776152 2.5587588485 1.4011429420 0.5933343293 0.8012306519 -0.0605757083 0.0481082087887 +1403715359762142976.0000000000 1.2543665518 2.5728787585 1.4017175374 0.5921437979 0.8020590262 -0.0626574323 0.0462718848523 +1403715359812143104.0000000000 1.2348764623 2.5858387470 1.4030002316 0.5920944316 0.8020247283 -0.0647777524 0.0445461800699 +1403715359862142976.0000000000 1.2150397322 2.5976658686 1.4044523153 0.5908121776 0.8029357149 -0.0658709964 0.0435456127828 +1403715359912143104.0000000000 1.1947872681 2.6083052108 1.4061873646 0.5885158943 0.8045886228 -0.0677643999 0.0411603720583 +1403715359962142976.0000000000 1.1743179867 2.6181139848 1.4083947075 0.5867192321 0.8058465169 -0.0706754302 0.037106839065 +1403715360012143104.0000000000 1.1540836200 2.6271706122 1.4105416393 0.5847482896 0.8072754077 -0.0712795063 0.0359873024007 +1403715360062142976.0000000000 1.1340251190 2.6357262438 1.4123770650 0.5830670607 0.8085076049 -0.0711605140 0.0358390417676 +1403715360112143104.0000000000 1.1140309456 2.6439643318 1.4141452236 0.5819095935 0.8093832346 -0.0705843027 0.0360258343197 +1403715360162142976.0000000000 1.0941370065 2.6521180478 1.4159819915 0.5811567046 0.8099773833 -0.0696460882 0.0366462223736 +1403715360212143104.0000000000 1.0744444039 2.6599873354 1.4178699753 0.5806117446 0.8104054333 -0.0689836869 0.0370713717059 +1403715360262142976.0000000000 1.0550982957 2.6674151117 1.4199956525 0.5802117056 0.8106453086 -0.0693388242 0.0374257641081 +1403715360312143104.0000000000 1.0360395160 2.6746919599 1.4221879585 0.5800638018 0.8105406496 -0.0718471369 0.037253591092 +1403715360362142976.0000000000 1.0174403725 2.6819098703 1.4247470549 0.5799475905 0.8101779617 -0.0777385698 0.0350596266331 +1403715360412143104.0000000000 0.9994375664 2.6888444508 1.4278188188 0.5801046508 0.8093502385 -0.0861184187 0.0318497010743 +1403715360462142976.0000000000 0.9824747373 2.6953397822 1.4311416182 0.5799089032 0.8084909488 -0.0957947568 0.0295197267529 +1403715360512143104.0000000000 0.9669622270 2.7017329155 1.4343463171 0.5797234213 0.8073437070 -0.1063317195 0.0284685606132 +1403715360562142976.0000000000 0.9532156920 2.7078492301 1.4369253040 0.5795416493 0.8059993692 -0.1166602058 0.0297806990111 +1403715360612143104.0000000000 0.9414623966 2.7136306838 1.4395624293 0.5788403784 0.8048729728 -0.1262597057 0.0343773276358 +1403715360662142976.0000000000 0.9318729285 2.7190608900 1.4428011532 0.5785892858 0.8032735265 -0.1350156020 0.0419150003185 +1403715360712143104.0000000000 0.9243430502 2.7233424665 1.4465182154 0.5778226992 0.8018009668 -0.1438089974 0.0505480978695 +1403715360762142976.0000000000 0.9189346006 2.7269499357 1.4503751298 0.5759914911 0.8009300817 -0.1510987330 0.0625618036359 +1403715360812143104.0000000000 0.9150700607 2.7300766331 1.4538971714 0.5736223330 0.8000079368 -0.1590669541 0.0751160713673 +1403715360862142976.0000000000 0.9121811229 2.7328980459 1.4578319853 0.5711475160 0.7987956779 -0.1672050611 0.0880820497952 +1403715360912143104.0000000000 0.9102326763 2.7353323595 1.4618454431 0.5692046096 0.7968091438 -0.1758012384 0.100971408557 +1403715360962142976.0000000000 0.9088001953 2.7376931818 1.4661066652 0.5663404815 0.7950770028 -0.1855417282 0.112628974171 +1403715361012143104.0000000000 0.9077415583 2.7399340639 1.4708574205 0.5636756834 0.7928904806 -0.1959527839 0.123275773496 +1403715361062142976.0000000000 0.9068070414 2.7419918252 1.4755948137 0.5607712647 0.7905455814 -0.2068091548 0.13342880449 +1403715361112143104.0000000000 0.9056654936 2.7440412885 1.4802787254 0.5576011560 0.7880748620 -0.2184486453 0.142475092585 +1403715361162142976.0000000000 0.9043562391 2.7461442293 1.4849533720 0.5543104903 0.7854685149 -0.2300552148 0.151174371253 +1403715361212143104.0000000000 0.9033376888 2.7482975607 1.4895952531 0.5505588203 0.7828696485 -0.2412731378 0.1605844691 +1403715361262142976.0000000000 0.9022973436 2.7507573064 1.4943005713 0.5471555107 0.7798566972 -0.2523333546 0.169623869597 +1403715361312143104.0000000000 0.9010945921 2.7533615206 1.4986775231 0.5434122287 0.7768830855 -0.2629439346 0.178931015798 +1403715361362142976.0000000000 0.8998734805 2.7562025864 1.5028901508 0.5400629984 0.7733209070 -0.2733206273 0.188686425653 +1403715361412143104.0000000000 0.8983376137 2.7592923768 1.5062340775 0.5365237190 0.7697215867 -0.2838864684 0.197685231942 +1403715361462142976.0000000000 0.8963467409 2.7629751270 1.5088856094 0.5334096574 0.7659047610 -0.2941627434 0.205748183391 +1403715361512143104.0000000000 0.8937926606 2.7672631679 1.5109641435 0.5308777272 0.7622453567 -0.3029279183 0.213038802254 +1403715361562142976.0000000000 0.8906442491 2.7721556091 1.5122610305 0.5280424221 0.7594667192 -0.3103379742 0.219252924016 +1403715361612143104.0000000000 0.8867937058 2.7775953324 1.5129023552 0.5248235990 0.7575580751 -0.3158866397 0.225569465255 +1403715361662142976.0000000000 0.8823439532 2.7839093916 1.5131345781 0.5224565804 0.7556926096 -0.3210228748 0.230026335973 +1403715361712143104.0000000000 0.8774990030 2.7911728862 1.5126570295 0.5197724359 0.7539953860 -0.3271477821 0.233027683759 +1403715361762142976.0000000000 0.8724864306 2.7992482255 1.5113998572 0.5163380689 0.7525112782 -0.3343199156 0.235269991355 +1403715361812143104.0000000000 0.8675062297 2.8082006283 1.5095018889 0.5127306679 0.7509382184 -0.3419449948 0.237218622431 +1403715361862142976.0000000000 0.8628004493 2.8180016338 1.5070714982 0.5087992590 0.7490743053 -0.3500636449 0.239721596318 +1403715361912143104.0000000000 0.8586967891 2.8285067477 1.5040904136 0.5047347012 0.7466056502 -0.3579294823 0.244355008337 +1403715361962142976.0000000000 0.8549375590 2.8400575498 1.5014330055 0.5026894253 0.7423222212 -0.3662908563 0.249182804929 +1403715362012143104.0000000000 0.8516697532 2.8522448145 1.4984507260 0.5004924266 0.7375430511 -0.3750602567 0.254690758685 +1403715362062142976.0000000000 0.8488371800 2.8651420583 1.4948794718 0.4974502163 0.7328693625 -0.3834518619 0.261553913246 +1403715362112143104.0000000000 0.8465215402 2.8787449749 1.4909035513 0.4943601869 0.7275282802 -0.3925930329 0.268665810371 +1403715362162142976.0000000000 0.8446001385 2.8929611489 1.4859829773 0.4898620227 0.7226037652 -0.4017709567 0.276512378789 +1403715362212143104.0000000000 0.8433413432 2.9078076905 1.4809529489 0.4854927544 0.7168642545 -0.4113572620 0.284934429474 +1403715362262142976.0000000000 0.8425530082 2.9233769630 1.4756357165 0.4812664630 0.7104445101 -0.4210409362 0.293897464661 +1403715362312143104.0000000000 0.8420916076 2.9398351957 1.4697267611 0.4759062698 0.7043909494 -0.4310802580 0.302516815856 +1403715362362142976.0000000000 0.8419824265 2.9572867385 1.4638635754 0.4706041164 0.6977905879 -0.4415299120 0.31092024357 +1403715362412143104.0000000000 0.8417425015 2.9756758971 1.4580194405 0.4654221215 0.6907477357 -0.4521351784 0.319098096049 +1403715362462142976.0000000000 0.8413624680 2.9952104827 1.4521747183 0.4606383554 0.6830094648 -0.4631140021 0.326857457472 +1403715362512143104.0000000000 0.8409751675 3.0156214089 1.4461752746 0.4556259980 0.6750260559 -0.4739251617 0.334872684439 +1403715362562142976.0000000000 0.8406514161 3.0369940302 1.4400073824 0.4492399631 0.6678996609 -0.4844525559 0.342635695122 +1403715362612143104.0000000000 0.8405885537 3.0596120240 1.4343434340 0.4440153955 0.6599986373 -0.4950944593 0.34947618478 +1403715362662142976.0000000000 0.8407878307 3.0833495355 1.4292354686 0.4389220467 0.6519696616 -0.5053502430 0.35623605825 +1403715362712143104.0000000000 0.8413873018 3.1081776259 1.4246840093 0.4345027036 0.6433786516 -0.5158855209 0.362123515649 +1403715362762142976.0000000000 0.8423802714 3.1341556740 1.4207525118 0.4315623625 0.6337551547 -0.5275531766 0.365781324095 +1403715362812143104.0000000000 0.8435661774 3.1610178369 1.4177627866 0.4300151542 0.6230881239 -0.5400103853 0.367745755536 +1403715362862142976.0000000000 0.8449551136 3.1883962266 1.4156605438 0.4312855920 0.6104171965 -0.5535573544 0.367366084206 +1403715362912143104.0000000000 0.8469862953 3.2156585851 1.4149319876 0.4358418069 0.5953241754 -0.5665393604 0.366966209105 +1403715362962142976.0000000000 0.8497851920 3.2417032025 1.4149235831 0.4395668636 0.5810469515 -0.5770169654 0.369075648461 +1403715363012143104.0000000000 0.8530180801 3.2661506951 1.4153350053 0.4425794422 0.5679050188 -0.5866492930 0.370742409154 +1403715363062142976.0000000000 0.8563012445 3.2885111397 1.4159975804 0.4432262575 0.5568632479 -0.5954573071 0.37267197801 +1403715363112143104.0000000000 0.8593730695 3.3083847304 1.4169977754 0.4418789626 0.5477821353 -0.6031986968 0.375271963875 +1403715363162142976.0000000000 0.8619803850 3.3255349824 1.4178130793 0.4377905758 0.5411891114 -0.6107901247 0.377344909909 +1403715363212143104.0000000000 0.8644658878 3.3397629309 1.4192927212 0.4332012098 0.5349855059 -0.6175948045 0.380399628968 +1403715363262142976.0000000000 0.8670688985 3.3511479752 1.4214415842 0.4282338035 0.5291624359 -0.6236115733 0.384332579589 +1403715363312143104.0000000000 0.8696937494 3.3599658880 1.4243063375 0.4234104240 0.5233461776 -0.6296033093 0.387855725878 +1403715363362142976.0000000000 0.8720835360 3.3661315890 1.4277468484 0.4186279829 0.5172514585 -0.6351375501 0.392175768002 +1403715363412143104.0000000000 0.8743420542 3.3699345712 1.4318716006 0.4142277560 0.5110757220 -0.6399486093 0.397092873205 +1403715363462142976.0000000000 0.8765073783 3.3709848441 1.4362835745 0.4091597544 0.5048788031 -0.6447575871 0.402459120118 +1403715363512143104.0000000000 0.8784975049 3.3695041452 1.4410999990 0.4037139943 0.4988005487 -0.6493441615 0.408123980428 +1403715363562142976.0000000000 0.8801760361 3.3656657862 1.4459639607 0.3960880624 0.4941781865 -0.6529040640 0.415473765758 +1403715363612143104.0000000000 0.8818202671 3.3595634584 1.4506106415 0.3863768043 0.4908484655 -0.6553770624 0.424572320099 +1403715363662142976.0000000000 0.8834035482 3.3518171462 1.4556475814 0.3778137514 0.4864885360 -0.6586095481 0.432225793676 +1403715363712143104.0000000000 0.8849825922 3.3425826444 1.4609812147 0.3695283815 0.4811989036 -0.6618941391 0.440218739959 +1403715363762142976.0000000000 0.8863726514 3.3324737508 1.4664255714 0.3623672258 0.4743011647 -0.6662045383 0.447101679671 +1403715363812143104.0000000000 0.8875036432 3.3217088221 1.4718114404 0.3553160127 0.4664277684 -0.6710602842 0.453733140682 +1403715363862142976.0000000000 0.8884535693 3.3104064632 1.4769573022 0.3485703884 0.4573022352 -0.6771230512 0.459214245692 +1403715363912143104.0000000000 0.8891166907 3.2985577163 1.4821115303 0.3413443602 0.4477654504 -0.6827061227 0.465727902492 +1403715363962142976.0000000000 0.8894493551 3.2858428521 1.4873039607 0.3335060848 0.4373532720 -0.6878831645 0.473616468164 +1403715364012143104.0000000000 0.8892763347 3.2728975365 1.4922708271 0.3260385123 0.4259965729 -0.6944628452 0.47952806479 +1403715364062142976.0000000000 0.8886255145 3.2596509484 1.4971508139 0.3181001895 0.4148249392 -0.7003549759 0.48604058161 +1403715364112143104.0000000000 0.8871733400 3.2466845216 1.5023809069 0.3115814052 0.4040313669 -0.7058643668 0.491356467555 +1403715364162142976.0000000000 0.8848384241 3.2340964546 1.5077478984 0.3055202773 0.3944796772 -0.7103603715 0.496418459567 +1403715364212143104.0000000000 0.8819176495 3.2221120775 1.5126730006 0.2996689070 0.3870404776 -0.7148830856 0.499339953096 +1403715364262142976.0000000000 0.8788345619 3.2105850440 1.5180576633 0.2955983406 0.3802282157 -0.7193662165 0.500560058 +1403715364312143104.0000000000 0.8749806849 3.1992997625 1.5238387041 0.2928894559 0.3744076081 -0.7237842501 0.500171039712 +1403715364362142976.0000000000 0.8703371259 3.1884949508 1.5299090361 0.2909437738 0.3699745645 -0.7278958402 0.498636328242 +1403715364412143104.0000000000 0.8654054407 3.1777118061 1.5368056456 0.2905520059 0.3659508208 -0.7312804512 0.496878687708 +1403715364462142976.0000000000 0.8603239695 3.1662907639 1.5440786663 0.2900364622 0.3631106232 -0.7330474734 0.496659770421 +1403715364512143104.0000000000 0.8548519558 3.1542651031 1.5513679727 0.2908522486 0.3609199430 -0.7348050043 0.495180138815 +1403715364562142976.0000000000 0.8484841710 3.1416701943 1.5591684787 0.2918414541 0.3595624681 -0.7353203821 0.494820505707 +1403715364612143104.0000000000 0.8415549921 3.1280725812 1.5672770148 0.2920365231 0.3590685793 -0.7354397477 0.49488665579 +1403715364662142976.0000000000 0.8341606637 3.1132790268 1.5756558221 0.2921258268 0.3577284848 -0.7351725127 0.496199767272 +1403715364712143104.0000000000 0.8259349127 3.0973087110 1.5845424547 0.2896295868 0.3571033443 -0.7339172817 0.499957325691 +1403715364762142976.0000000000 0.8166052286 3.0804941115 1.5931781962 0.2839238033 0.3575697252 -0.7330075486 0.504213346986 +1403715364812143104.0000000000 0.8066722279 3.0632961072 1.6011273516 0.2761101945 0.3585351012 -0.7330759719 0.507755217628 +1403715364862142976.0000000000 0.7964048660 3.0461302899 1.6089900520 0.2682915481 0.3586484018 -0.7341086592 0.510367951143 +1403715364912143104.0000000000 0.7860839991 3.0293741088 1.6170169539 0.2617956617 0.3572260716 -0.7359587993 0.512071490076 +1403715364962142976.0000000000 0.7758451762 3.0128932117 1.6249633947 0.2543432730 0.3555403136 -0.7380595603 0.513973413983 +1403715365012143104.0000000000 0.7660266366 2.9967754505 1.6333910567 0.2497530716 0.3514306253 -0.7409764355 0.514853222678 +1403715365062142976.0000000000 0.7563135999 2.9806871772 1.6415669375 0.2437173696 0.3478292554 -0.7437484400 0.516192707078 +1403715365112143104.0000000000 0.7470594556 2.9649876191 1.6501913089 0.2392933067 0.3425404800 -0.7458322086 0.518786130823 +1403715365162142976.0000000000 0.7383951685 2.9498685944 1.6591916689 0.2361433399 0.3357676502 -0.7470185978 0.522933669383 +1403715365212143104.0000000000 0.7302266931 2.9354316266 1.6680867705 0.2327932852 0.3292159774 -0.7483884548 0.526629706047 +1403715365262142976.0000000000 0.7223532851 2.9218983978 1.6764331866 0.2291499213 0.3237905238 -0.7494883521 0.530016245272 +1403715365312143104.0000000000 0.7146832243 2.9092981644 1.6842497060 0.2257252078 0.3191441287 -0.7505187654 0.532838379272 +1403715365362142976.0000000000 0.7073942155 2.8978109891 1.6916443239 0.2231944348 0.3143125834 -0.7519378897 0.534772151711 +1403715365412143104.0000000000 0.7004242703 2.8871616192 1.6989237487 0.2216396376 0.3077645471 -0.7538530915 0.536528071027 +1403715365462142976.0000000000 0.6931972050 2.8772102580 1.7054574184 0.2181557387 0.3015688282 -0.7562102958 0.538154535403 +1403715365512143104.0000000000 0.6860613788 2.8680543911 1.7117390664 0.2151571165 0.2939949205 -0.7585915170 0.540197475282 +1403715365562142976.0000000000 0.6788734110 2.8595601505 1.7174705338 0.2103553674 0.2863717380 -0.7614361086 0.542177922491 +1403715365612143104.0000000000 0.6716104214 2.8518109232 1.7233623479 0.2074215243 0.2760295248 -0.7650736611 0.543549727051 +1403715365662142976.0000000000 0.6641613411 2.8445049977 1.7292638820 0.2050546196 0.2640620424 -0.7690832141 0.544733742851 +1403715365712143104.0000000000 0.6564301427 2.8373897877 1.7347849402 0.2021379194 0.2515832754 -0.7732593897 0.545816849623 +1403715365762142976.0000000000 0.6480343862 2.8301896433 1.7398193481 0.1983827430 0.2390077202 -0.7775396715 0.546764717368 +1403715365812143104.0000000000 0.6387729908 2.8232800844 1.7444475629 0.1936133931 0.2272011915 -0.7816578011 0.547635421264 +1403715365862142976.0000000000 0.6287394162 2.8167064760 1.7489421242 0.1885207068 0.2168685894 -0.7847819588 0.549131346082 +1403715365912143104.0000000000 0.6179461126 2.8105201168 1.7529796222 0.1833461952 0.2076759267 -0.7878687539 0.550016098721 +1403715365962142976.0000000000 0.6065921233 2.8044440906 1.7567673258 0.1794150097 0.1992876356 -0.7907800184 0.550237816847 +1403715366012143104.0000000000 0.5946861861 2.7984307881 1.7604321056 0.1785979953 0.1903528432 -0.7928939704 0.550624829571 +1403715366062142976.0000000000 0.5818670177 2.7923882590 1.7633415051 0.1777512765 0.1827813501 -0.7952304767 0.550094492558 +1403715366112143104.0000000000 0.5679958958 2.7860434979 1.7661504481 0.1784991721 0.1752867125 -0.7971029689 0.549581177789 +1403715366162142976.0000000000 0.5525848093 2.7794273376 1.7686333279 0.1773327895 0.1703991920 -0.7979775554 0.550226333634 +1403715366212143104.0000000000 0.5354266502 2.7728419007 1.7705089040 0.1764963452 0.1668397554 -0.7985221423 0.550795719328 +1403715366262142976.0000000000 0.5167548309 2.7659148175 1.7721642224 0.1753839902 0.1643588916 -0.7986531949 0.551706158237 +1403715366312143104.0000000000 0.4966822370 2.7585554152 1.7737839962 0.1728671398 0.1639748013 -0.7987457642 0.552480244645 +1403715366362142976.0000000000 0.4753820786 2.7507085853 1.7756036451 0.1707398088 0.1640184483 -0.7985706881 0.553381172833 +1403715366412143104.0000000000 0.4525808278 2.7429292285 1.7768691313 0.1672420229 0.1661722754 -0.7993789036 0.55263934819 +1403715366462142976.0000000000 0.4282568263 2.7350237089 1.7779131744 0.1618111341 0.1697814264 -0.7995047921 0.552976953932 +1403715366512143104.0000000000 0.4033987073 2.7269876392 1.7791215626 0.1568001581 0.1737232328 -0.7996139975 0.553038338421 +1403715366562142976.0000000000 0.3782241411 2.7191497947 1.7801598093 0.1539204228 0.1768797515 -0.7999894739 0.552303266814 +1403715366612143104.0000000000 0.3527196326 2.7112282069 1.7808195996 0.1512226024 0.1800588714 -0.8009049356 0.550692120343 +1403715366662142976.0000000000 0.3275639912 2.7031251715 1.7814402647 0.1493321897 0.1829220224 -0.8015119624 0.549379654593 +1403715366712143104.0000000000 0.3027899767 2.6949066662 1.7819652402 0.1482867308 0.1857939390 -0.8024187296 0.547371756738 +1403715366762142976.0000000000 0.2781779052 2.6865003591 1.7826477069 0.1480000167 0.1878872956 -0.8035368312 0.545089827625 +1403715366812143104.0000000000 0.2536587043 2.6779892163 1.7829720500 0.1471984384 0.1904686289 -0.8050428303 0.54218111596 +1403715366862142976.0000000000 0.2296360795 2.6689884169 1.7836863385 0.1472525870 0.1926790249 -0.8061955413 0.539666765824 +1403715366912143104.0000000000 0.2063620748 2.6592948718 1.7849287157 0.1477895162 0.1943195648 -0.8067171113 0.538150228098 +1403715366962142976.0000000000 0.1838055993 2.6492332950 1.7866148530 0.1496590063 0.1948458860 -0.8077095658 0.535950109425 +1403715367012143104.0000000000 0.1618789762 2.6384362293 1.7887254147 0.1513745707 0.1955836137 -0.8081415242 0.534546598757 +1403715367062142976.0000000000 0.1407392243 2.6268166175 1.7914004929 0.1534850987 0.1957953493 -0.8083705519 0.533519968269 +1403715367112143104.0000000000 0.1201660700 2.6143412347 1.7943835995 0.1550425648 0.1965194250 -0.8084309746 0.532711252093 +1403715367162142976.0000000000 0.1002704037 2.6010702419 1.7975342841 0.1567437143 0.1972928505 -0.8088530106 0.53128499551 +1403715367212143104.0000000000 0.0809227997 2.5866997734 1.8010538098 0.1576258408 0.1985305526 -0.8082886557 0.531421831596 +1403715367262142976.0000000000 0.0621788769 2.5715890275 1.8046054443 0.1605075349 0.1982638571 -0.8084975539 0.530339966043 +1403715367312143104.0000000000 0.0434646062 2.5555373053 1.8075750873 0.1615413136 0.1992464229 -0.8090654680 0.528789500154 +1403715367362142976.0000000000 0.0253822793 2.5381011058 1.8106284780 0.1629671306 0.1997473213 -0.8099223246 0.526847748451 +1403715367412143104.0000000000 0.0075534135 2.5195052434 1.8133891578 0.1641433478 0.2003673369 -0.8102904971 0.525679752254 +1403715367462142976.0000000000 -0.0099019647 2.4997131988 1.8160910605 0.1650532796 0.2011992813 -0.8102651704 0.525115813693 +1403715367512143104.0000000000 -0.0272488036 2.4787332686 1.8190220937 0.1654694099 0.2022189107 -0.8108161654 0.52374090213 +1403715367562142976.0000000000 -0.0441469707 2.4563293043 1.8222403254 0.1660267374 0.2033973787 -0.8107748241 0.523171877435 +1403715367612143104.0000000000 -0.0606269600 2.4325656646 1.8258334288 0.1669468034 0.2041139590 -0.8102198122 0.523459752555 +1403715367662142976.0000000000 -0.0765781184 2.4076781428 1.8295345900 0.1682814050 0.2045485831 -0.8098933013 0.523368021956 +1403715367712143104.0000000000 -0.0920933354 2.3813231310 1.8333681205 0.1683245468 0.2056979825 -0.8088609130 0.524499008948 +1403715367762142976.0000000000 -0.1070794159 2.3537903835 1.8374443230 0.1688863706 0.2064673706 -0.8082327376 0.524984247866 +1403715367812143104.0000000000 -0.1216539180 2.3250660818 1.8415072446 0.1684673235 0.2077635125 -0.8072690733 0.526089086671 +1403715367862142976.0000000000 -0.1360137541 2.2954309729 1.8456458868 0.1675808547 0.2092192265 -0.8057198105 0.528166223291 +1403715367912143104.0000000000 -0.1500616427 2.2645973417 1.8496891669 0.1660957611 0.2106311204 -0.8033820401 0.531623952582 +1403715367962142976.0000000000 -0.1633697658 2.2329378073 1.8541478412 0.1665409277 0.2102635734 -0.8005273579 0.535919115513 +1403715368012143104.0000000000 -0.1763398153 2.2007495999 1.8581278032 0.1673450254 0.2093356039 -0.7982673154 0.539391824662 +1403715368062142976.0000000000 -0.1890588367 2.1681577609 1.8618070481 0.1690537137 0.2076427438 -0.7963188003 0.542385196333 +1403715368112143104.0000000000 -0.2019379791 2.1355056777 1.8646519497 0.1699944705 0.2063907764 -0.7949653658 0.544550084513 +1403715368162142976.0000000000 -0.2149652879 2.1028515416 1.8668345773 0.1711066333 0.2048096339 -0.7940409100 0.54614518876 +1403715368212143104.0000000000 -0.2282767729 2.0704798140 1.8682808405 0.1723768413 0.2032025779 -0.7937909363 0.546709142339 +1403715368262142976.0000000000 -0.2419685883 2.0384013638 1.8693060198 0.1750599519 0.2006433193 -0.7940672624 0.546400452483 +1403715368312143104.0000000000 -0.2562588328 2.0062490319 1.8700626791 0.1776094345 0.1981137562 -0.7946383609 0.545669958658 +1403715368362142976.0000000000 -0.2712156000 1.9739334783 1.8707435031 0.1816431264 0.1944728226 -0.7950546493 0.54504513626 +1403715368412143104.0000000000 -0.2872718168 1.9414035119 1.8709563980 0.1846858679 0.1916287088 -0.7953077204 0.544660626453 +1403715368462142976.0000000000 -0.3041215919 1.9082913598 1.8711864810 0.1873835903 0.1888572322 -0.7945913642 0.545751683299 +1403715368512143104.0000000000 -0.3221899269 1.8747381776 1.8709902501 0.1883004588 0.1871924755 -0.7939728671 0.546908585273 +1403715368562142976.0000000000 -0.3418603998 1.8410363615 1.8701258335 0.1861804223 0.1876593670 -0.7929881744 0.548899414861 +1403715368612143104.0000000000 -0.3629122827 1.8071884964 1.8686538834 0.1813133462 0.1900181079 -0.7920569010 0.551057578417 +1403715368662142976.0000000000 -0.3851799688 1.7734892615 1.8668856267 0.1758378721 0.1929114115 -0.7915684359 0.552526597857 +1403715368712143104.0000000000 -0.4081801108 1.7402821759 1.8649758631 0.1722793389 0.1945545569 -0.7915743707 0.553062717494 +1403715368762142976.0000000000 -0.4319472587 1.7070535096 1.8630734740 0.1683064258 0.1962126158 -0.7914977896 0.553809358521 +1403715368812143104.0000000000 -0.4561369140 1.6742841285 1.8613543704 0.1651412411 0.1974073066 -0.7913376802 0.55456595793 +1403715368862142976.0000000000 -0.4803729231 1.6421491069 1.8596119844 0.1633200155 0.1976487290 -0.7920620073 0.553984953882 +1403715368912143104.0000000000 -0.5046295140 1.6104557581 1.8578637061 0.1622287976 0.1988442811 -0.7925426576 0.553189755005 +1403715368962142976.0000000000 -0.5288990025 1.5798686918 1.8559723120 0.1623443685 0.2011569481 -0.7932453295 0.551309382704 +1403715369012143104.0000000000 -0.5529321360 1.5500840168 1.8538360573 0.1637509754 0.2045072854 -0.7941785375 0.548309072323 +1403715369062142976.0000000000 -0.5768959160 1.5206824923 1.8519324423 0.1661151834 0.2092038837 -0.7949503602 0.544695700083 +1403715369112143104.0000000000 -0.6005313664 1.4915852519 1.8505217974 0.1694352645 0.2152479535 -0.7948773028 0.541414890037 +1403715369162142976.0000000000 -0.6236094799 1.4624824437 1.8489280982 0.1730477506 0.2227351097 -0.7940270955 0.538483536011 +1403715369212143104.0000000000 -0.6460746830 1.4331858342 1.8477489071 0.1776800607 0.2309686995 -0.7926316023 0.535554291359 +1403715369262142976.0000000000 -0.6680699261 1.4037708173 1.8467440315 0.1820596498 0.2406248731 -0.7900309467 0.533671301136 +1403715369312143104.0000000000 -0.6895980780 1.3747656105 1.8456943958 0.1875187500 0.2506240555 -0.7876693452 0.530661194927 +1403715369362142976.0000000000 -0.7103282099 1.3454862367 1.8452916499 0.1938226822 0.2608280802 -0.7843265350 0.528425365499 +1403715369412143104.0000000000 -0.7303396771 1.3161793480 1.8448659540 0.1999974527 0.2718525743 -0.7809491007 0.525562269267 +1403715369462142976.0000000000 -0.7493495410 1.2867891007 1.8447306322 0.2070252820 0.2825931501 -0.7773431196 0.522512505677 +1403715369512143104.0000000000 -0.7677283195 1.2573942599 1.8447507045 0.2144347756 0.2934600965 -0.7733353381 0.519472187596 +1403715369562142976.0000000000 -0.7855475240 1.2280555906 1.8447396588 0.2219895581 0.3042398285 -0.7690641487 0.516429180091 +1403715369612143104.0000000000 -0.8027239285 1.1988621000 1.8446470286 0.2294748097 0.3152320417 -0.7644053444 0.513473018831 +1403715369662142976.0000000000 -0.8191767356 1.1694471925 1.8446871293 0.2360919816 0.3256546741 -0.7599389678 0.510590221918 +1403715369712143104.0000000000 -0.8350471415 1.1393420695 1.8446955191 0.2418323029 0.3346769650 -0.7556708955 0.508399413884 +1403715369762142976.0000000000 -0.8503066430 1.1089549883 1.8444556913 0.2459707022 0.3432909293 -0.7516594740 0.506614041051 +1403715369812143104.0000000000 -0.8647128614 1.0782928152 1.8440723647 0.2495085252 0.3501947462 -0.7486229922 0.504651118249 +1403715369862142976.0000000000 -0.8782997330 1.0474087404 1.8431484153 0.2509474613 0.3567555712 -0.7456647357 0.503721089479 +1403715369912143104.0000000000 -0.8908476173 1.0165441384 1.8415614372 0.2511412267 0.3625063946 -0.7440003008 0.501976842695 +1403715369962142976.0000000000 -0.9023816943 0.9857447197 1.8395343107 0.2505703789 0.3675592597 -0.7432467768 0.499698813958 +1403715370012143104.0000000000 -0.9126492082 0.9549811383 1.8371522379 0.2486274668 0.3722105912 -0.7422542315 0.498700625938 +1403715370062142976.0000000000 -0.9213946891 0.9244805744 1.8342889011 0.2459017588 0.3764625801 -0.7409348960 0.498822343904 +1403715370112143104.0000000000 -0.9283358940 0.8942109381 1.8316544112 0.2442806409 0.3789750286 -0.7394158604 0.499969080666 +1403715370162142976.0000000000 -0.9332925123 0.8643232091 1.8293985137 0.2440421177 0.3801240428 -0.7365884657 0.503375197056 +1403715370212143104.0000000000 -0.9361229321 0.8354945573 1.8279711177 0.2486386339 0.3769081117 -0.7353123644 0.505405611118 +1403715370262142976.0000000000 -0.9377455601 0.8074719284 1.8270218710 0.2537494061 0.3726832439 -0.7345580536 0.507092599526 +1403715370312143104.0000000000 -0.9383141734 0.7801148545 1.8259248281 0.2582140799 0.3687617361 -0.7343240072 0.508043820383 +1403715370362142976.0000000000 -0.9382662210 0.7536081434 1.8251044656 0.2631112754 0.3640617783 -0.7349350034 0.50803741909 +1403715370412143104.0000000000 -0.9376658757 0.7275623344 1.8245632068 0.2680182132 0.3591719144 -0.7360092717 0.507397403741 +1403715370462142976.0000000000 -0.9369549008 0.7019383958 1.8239168707 0.2712483050 0.3552825886 -0.7372827220 0.506569666538 +1403715370512143104.0000000000 -0.9361957929 0.6762648492 1.8233965294 0.2734118098 0.3517421722 -0.7383487726 0.50632451715 +1403715370562142976.0000000000 -0.9357494488 0.6506021324 1.8226448418 0.2747529207 0.3491637096 -0.7394789661 0.505733521947 +1403715370612143104.0000000000 -0.9356446346 0.6247164426 1.8221605953 0.2751459583 0.3471965470 -0.7398003997 0.506403621619 +1403715370662142976.0000000000 -0.9360810407 0.5986631810 1.8214272948 0.2751720509 0.3455885690 -0.7409326032 0.505833728475 +1403715370712143104.0000000000 -0.9368197948 0.5722259056 1.8206864242 0.2744912633 0.3448365703 -0.7413594890 0.506091290464 +1403715370762142976.0000000000 -0.9376360471 0.5454823859 1.8199849022 0.2720917615 0.3454424760 -0.7410992390 0.507353414353 +1403715370812143104.0000000000 -0.9387886374 0.5187309909 1.8193729899 0.2690018009 0.3467146458 -0.7410528380 0.508200429723 +1403715370862142976.0000000000 -0.9401441757 0.4920709945 1.8187668140 0.2657486103 0.3480099647 -0.7414705963 0.508417245338 +1403715370912143104.0000000000 -0.9414093178 0.4656660066 1.8181354782 0.2636593601 0.3485933316 -0.7421033350 0.508182123989 +1403715370962142976.0000000000 -0.9425355893 0.4395841237 1.8168348034 0.2611534136 0.3493597874 -0.7440163705 0.506148470305 +1403715371012143104.0000000000 -0.9433047698 0.4135652706 1.8150409880 0.2581777566 0.3505708611 -0.7470010032 0.502427923695 +1403715371062142976.0000000000 -0.9438932324 0.3875577680 1.8127284199 0.2542807377 0.3523641337 -0.7511554967 0.496936860639 +1403715371112143104.0000000000 -0.9434279588 0.3614146835 1.8102652355 0.2501062439 0.3544374330 -0.7548377256 0.491976605934 +1403715371162142976.0000000000 -0.9416456755 0.3350889353 1.8078299943 0.2469455413 0.3560275219 -0.7580151753 0.487519535242 +1403715371212143104.0000000000 -0.9381627776 0.3080805241 1.8050636234 0.2438669645 0.3577251293 -0.7603518684 0.484176281704 +1403715371262142976.0000000000 -0.9327350431 0.2801787441 1.8022568740 0.2419189057 0.3586593893 -0.7616317593 0.482447664197 +1403715371312143104.0000000000 -0.9252790427 0.2513388518 1.7992676815 0.2408783675 0.3593500735 -0.7618538530 0.482103560944 +1403715371362142976.0000000000 -0.9160639943 0.2218729399 1.7962033606 0.2406433719 0.3595464290 -0.7618704195 0.482048334588 +1403715371412143104.0000000000 -0.9051582356 0.1917809893 1.7931325692 0.2412086382 0.3594314910 -0.7609606010 0.483287036771 +1403715371462142976.0000000000 -0.8924258925 0.1610368898 1.7907878417 0.2449884133 0.3570443295 -0.7589634288 0.486286477126 +1403715371512143104.0000000000 -0.8779815300 0.1297092122 1.7890127944 0.2511844186 0.3527483511 -0.7566259825 0.489889897057 +1403715371562142976.0000000000 -0.8625650451 0.0980499238 1.7873183835 0.2582271169 0.3482598621 -0.7543761395 0.492900055576 +1403715371612143104.0000000000 -0.8464655436 0.0656996074 1.7852821849 0.2642793321 0.3444165933 -0.7522860887 0.495579746979 +1403715371662142976.0000000000 -0.8301846480 0.0327614536 1.7831982391 0.2702874131 0.3404623316 -0.7507629334 0.497378259421 +1403715371712143104.0000000000 -0.8141004018 -0.0007555177 1.7807750458 0.2759192181 0.3369335688 -0.7501709039 0.497582124141 +1403715371762142976.0000000000 -0.7984505754 -0.0351616216 1.7780077752 0.2796114649 0.3350346997 -0.7497196114 0.497483349438 +1403715371812143104.0000000000 -0.7833491839 -0.0707514879 1.7748556465 0.2810616609 0.3345758815 -0.7490598061 0.497968602673 +1403715371862142976.0000000000 -0.7693278095 -0.1067781038 1.7702995762 0.2782370124 0.3377464954 -0.7489450597 0.49758694451 +1403715371912143104.0000000000 -0.7561782165 -0.1434860418 1.7655331448 0.2739628127 0.3417920240 -0.7482724630 0.498207698296 +1403715371962142976.0000000000 -0.7432358962 -0.1808059627 1.7606830935 0.2694597832 0.3459634744 -0.7473771886 0.499127275919 +1403715372012143104.0000000000 -0.7302542266 -0.2182870720 1.7561717904 0.2664774260 0.3489423778 -0.7471263209 0.499030318698 +1403715372062142976.0000000000 -0.7168778960 -0.2561563760 1.7523877687 0.2652978280 0.3504390288 -0.7457594987 0.500651894718 +1403715372112143104.0000000000 -0.7032507591 -0.2940099504 1.7491584475 0.2654532833 0.3508715264 -0.7447982237 0.501696454356 +1403715372162142976.0000000000 -0.6893042474 -0.3319031694 1.7465129579 0.2663480352 0.3513145298 -0.7437983206 0.502395146832 +1403715372212143104.0000000000 -0.6751726539 -0.3695516880 1.7451660952 0.2694104639 0.3518319643 -0.7425764193 0.502207658533 +1403715372262142976.0000000000 -0.6606812601 -0.4072440206 1.7445775588 0.2709186885 0.3545262190 -0.7408072729 0.50211433826 +1403715372312143104.0000000000 -0.6461757603 -0.4447041742 1.7448892353 0.2734430597 0.3580787923 -0.7386134390 0.501456537849 +1403715372362142976.0000000000 -0.6317095524 -0.4818581959 1.7461450599 0.2764029942 0.3627405319 -0.7360544153 0.50024452926 +1403715372412143104.0000000000 -0.6171733797 -0.5188140091 1.7486791886 0.2796165753 0.3686936453 -0.7320896405 0.499924319225 +1403715372462142976.0000000000 -0.6026562997 -0.5556506961 1.7523087623 0.2830426396 0.3736642295 -0.7289975752 0.498823057982 +1403715372512143104.0000000000 -0.5881979582 -0.5922511755 1.7568420392 0.2855147804 0.3787092462 -0.7260458106 0.497913745467 +1403715372562142976.0000000000 -0.5736358751 -0.6288201979 1.7628269976 0.2882725631 0.3829170414 -0.7227890842 0.497844763494 +1403715372612143104.0000000000 -0.5590850466 -0.6651680866 1.7693718431 0.2908250323 0.3864031078 -0.7202790494 0.497304262775 +1403715372662142976.0000000000 -0.5444914486 -0.7014057630 1.7758915595 0.2926017715 0.3896967702 -0.7180603781 0.496900315973 +1403715372712143104.0000000000 -0.5300267636 -0.7372562190 1.7823349271 0.2947473039 0.3918644681 -0.7166420145 0.495974282128 +1403715372762142976.0000000000 -0.5157718628 -0.7726742053 1.7878357368 0.2954145580 0.3942608347 -0.7154615726 0.495382045707 +1403715372812143104.0000000000 -0.5016061410 -0.8077186716 1.7931635460 0.2968938662 0.3954889867 -0.7144620242 0.494961119315 +1403715372862142976.0000000000 -0.4875026867 -0.8425185886 1.7980613360 0.2980796448 0.3963814036 -0.7141840336 0.493934686421 +1403715372912143104.0000000000 -0.4732471821 -0.8770564871 1.8027457273 0.2999959286 0.3962890245 -0.7142957634 0.492685512483 +1403715372962142976.0000000000 -0.4590169019 -0.9113795676 1.8073104324 0.3022317731 0.3954879786 -0.7145995751 0.491520763916 +1403715373012143104.0000000000 -0.4449146071 -0.9455206043 1.8116487259 0.3038734178 0.3948567145 -0.7152521769 0.490064734842 +1403715373062142976.0000000000 -0.4308736678 -0.9796074351 1.8155740301 0.3054188780 0.3939925143 -0.7157371288 0.489090554086 +1403715373112143104.0000000000 -0.4170866398 -1.0137349871 1.8189845895 0.3065729844 0.3929905171 -0.7162673572 0.488397923555 +1403715373162142976.0000000000 -0.4036743318 -1.0479792555 1.8220608014 0.3072183764 0.3922873609 -0.7167238428 0.487887721602 +1403715373212143104.0000000000 -0.3905594597 -1.0825301166 1.8248110447 0.3074066760 0.3915807757 -0.7170880830 0.487801509688 +1403715373262142976.0000000000 -0.3780223898 -1.1171189850 1.8273316593 0.3062960819 0.3916094546 -0.7174140947 0.487997707039 +1403715373312143104.0000000000 -0.3657174927 -1.1519791140 1.8300142545 0.3035981799 0.3926570194 -0.7166183495 0.490006889122 +1403715373362142976.0000000000 -0.3536070543 -1.1866064368 1.8327315752 0.3021028321 0.3926686507 -0.7165637336 0.491000636677 +1403715373412143104.0000000000 -0.3416548320 -1.2211281067 1.8353897418 0.3009556904 0.3926037525 -0.7165820907 0.491729674974 +1403715373462142976.0000000000 -0.3297287653 -1.2553415516 1.8377718765 0.2996717477 0.3928456391 -0.7162612289 0.492786971671 +1403715373512143104.0000000000 -0.3179673471 -1.2889186927 1.8395301167 0.2989903519 0.3939342469 -0.7156976655 0.493150514761 +1403715373562142976.0000000000 -0.3061837441 -1.3221785711 1.8410114932 0.2978335637 0.3969501099 -0.7136517605 0.494395533225 +1403715373612143104.0000000000 -0.2944548894 -1.3547718914 1.8417936414 0.2954764247 0.4025980285 -0.7107757511 0.495385043623 +1403715373662142976.0000000000 -0.2827433708 -1.3863200827 1.8425878400 0.2948816385 0.4089061775 -0.7069812235 0.496002123873 +1403715373712143104.0000000000 -0.2710979470 -1.4164521392 1.8431754822 0.2950086772 0.4166518542 -0.7019145146 0.496676078512 +1403715373762142976.0000000000 -0.2591322870 -1.4449233996 1.8440290348 0.2972451287 0.4243364636 -0.6970023507 0.49575359015 +1403715373812143104.0000000000 -0.2465239897 -1.4716562736 1.8446486898 0.3019858407 0.4316827469 -0.6920542653 0.49347284823 +1403715373862142976.0000000000 -0.2333362466 -1.4967887751 1.8454243398 0.3083714479 0.4392267455 -0.6873040214 0.489489630488 +1403715373912143104.0000000000 -0.2198082185 -1.5205137158 1.8466070075 0.3157614512 0.4469727095 -0.6822296081 0.484843134135 +1403715373962142976.0000000000 -0.2061846932 -1.5429640076 1.8481540375 0.3240612410 0.4547337351 -0.6767758851 0.479766551201 +1403715374012143104.0000000000 -0.1928431099 -1.5640814618 1.8491708708 0.3317313832 0.4634813008 -0.6706745649 0.474694640043 +1403715374062142976.0000000000 -0.1796382521 -1.5837310939 1.8496065983 0.3398931653 0.4722391528 -0.6642876083 0.469238523771 +1403715374112143104.0000000000 -0.1662018416 -1.6021798424 1.8499323015 0.3482328197 0.4810649084 -0.6574502986 0.463755929363 +1403715374162142976.0000000000 -0.1529614400 -1.6196702926 1.8500441183 0.3549060193 0.4908705051 -0.6500105549 0.458883583548 +1403715374212143104.0000000000 -0.1396939901 -1.6361229081 1.8503760787 0.3623500048 0.5001416832 -0.6428764776 0.453067992005 +1403715374262142976.0000000000 -0.1269193375 -1.6518506142 1.8507129416 0.3695659541 0.5093035519 -0.6354278727 0.447506777732 +1403715374312143104.0000000000 -0.1142738184 -1.6667554691 1.8509244674 0.3763769423 0.5183631429 -0.6288442376 0.440675588439 +1403715374362142976.0000000000 -0.1020935205 -1.6815219262 1.8512965856 0.3815953531 0.5275148975 -0.6220104540 0.434989671748 +1403715374412143104.0000000000 -0.0900253197 -1.6959129832 1.8518135736 0.3854399100 0.5359604510 -0.6163572157 0.429285747922 +1403715374462142976.0000000000 -0.0776034839 -1.7098472688 1.8525453264 0.3882335026 0.5433172797 -0.6117411576 0.42409177913 +1403715374512143104.0000000000 -0.0648971839 -1.7233906686 1.8528444406 0.3886511438 0.5504299859 -0.6090162438 0.418421239728 +1403715374562142976.0000000000 -0.0516609679 -1.7365528404 1.8534472409 0.3890459978 0.5559228182 -0.6068031158 0.413984311861 +1403715374612143104.0000000000 -0.0381687314 -1.7493201845 1.8540172703 0.3883262031 0.5608528641 -0.6053270573 0.410153603584 +1403715374662142976.0000000000 -0.0236067374 -1.7613228883 1.8549342103 0.3882862661 0.5638609473 -0.6046996078 0.406980333696 +1403715374712143104.0000000000 -0.0078229451 -1.7727415612 1.8558911526 0.3878093704 0.5663120064 -0.6039828560 0.405091734498 +1403715374762142976.0000000000 0.0090312522 -1.7836776399 1.8569905454 0.3870344284 0.5679504710 -0.6035389443 0.404199649211 +1403715374812143104.0000000000 0.0271987763 -1.7939279207 1.8582180950 0.3862759159 0.5689251268 -0.6031770130 0.404094800577 +1403715374862142976.0000000000 0.0468418031 -1.8034899225 1.8594132329 0.3857810483 0.5690209397 -0.6033450721 0.404181737498 +1403715374912143104.0000000000 0.0678095709 -1.8123478269 1.8605954846 0.3849122205 0.5689962990 -0.6027664807 0.405904377926 +1403715374962142976.0000000000 0.0898917998 -1.8201871908 1.8622263213 0.3862115328 0.5672042643 -0.6012960138 0.409344693734 +1403715375012143104.0000000000 0.1129116604 -1.8270222893 1.8634938550 0.3873790774 0.5651059147 -0.6003680553 0.412493580339 +1403715375062142976.0000000000 0.1369150729 -1.8329602054 1.8646241054 0.3876230665 0.5634217857 -0.5990737311 0.416431164106 +1403715375112143104.0000000000 0.1613941170 -1.8375780002 1.8652783094 0.3877040651 0.5616225536 -0.5990078396 0.418873815432 +1403715375162142976.0000000000 0.1863330376 -1.8410783319 1.8657039999 0.3880559625 0.5593802400 -0.5993544596 0.421046967477 +1403715375212143104.0000000000 0.2116103601 -1.8433328538 1.8658714960 0.3882587235 0.5569989531 -0.6001507403 0.422878728201 +1403715375262142976.0000000000 0.2368329373 -1.8441976471 1.8653943905 0.3882470191 0.5548101747 -0.6019552652 0.423201820645 +1403715375312143104.0000000000 0.2620405464 -1.8440734006 1.8644291567 0.3875208654 0.5528985756 -0.6035830138 0.424049866712 +1403715375362142976.0000000000 0.2870878151 -1.8429617522 1.8634703998 0.3887721954 0.5496384256 -0.6060676958 0.423598547465 +1403715375412143104.0000000000 0.3125176083 -1.8414286003 1.8615227348 0.3860992385 0.5489963482 -0.6078436421 0.424330642836 +1403715375462142976.0000000000 0.3383761620 -1.8387624865 1.8601520767 0.3865986916 0.5463282914 -0.6099794316 0.424254572948 +1403715375512143104.0000000000 0.3642372527 -1.8354780292 1.8582179936 0.3859282899 0.5447049615 -0.6119597878 0.424100316084 +1403715375562142976.0000000000 0.3904802252 -1.8314261853 1.8560500436 0.3861451085 0.5423409912 -0.6145558811 0.423177590893 +1403715375612143104.0000000000 0.4165264268 -1.8269085332 1.8532930813 0.3860208698 0.5403510821 -0.6164892369 0.42302436912 +1403715375662142976.0000000000 0.4426287231 -1.8221917674 1.8500923644 0.3860840190 0.5383570228 -0.6178581459 0.423511697292 +1403715375712143104.0000000000 0.4689777773 -1.8172145155 1.8466810982 0.3857875947 0.5367920567 -0.6182645490 0.425171926569 +1403715375762142976.0000000000 0.4957009373 -1.8116715096 1.8432199430 0.3860540712 0.5352864819 -0.6187040443 0.426187683983 +1403715375812143104.0000000000 0.5224075387 -1.8058891264 1.8397290121 0.3859265633 0.5340790657 -0.6189720590 0.427426987323 +1403715375862142976.0000000000 0.5492559598 -1.7998318322 1.8364605820 0.3852695211 0.5335187292 -0.6182253352 0.429793667393 +1403715375912143104.0000000000 0.5760854312 -1.7933602497 1.8328174566 0.3836600744 0.5339839894 -0.6173215433 0.431949254587 +1403715375962142976.0000000000 0.6026670448 -1.7862080463 1.8298351156 0.3837003151 0.5334404688 -0.6163134765 0.434019623022 +1403715376012143104.0000000000 0.6288827735 -1.7785625570 1.8267545752 0.3832392068 0.5336632452 -0.6151623881 0.435782614906 +1403715376062142976.0000000000 0.6547920154 -1.7700247423 1.8234624809 0.3844335422 0.5327736490 -0.6152710108 0.435665782176 +1403715376112143104.0000000000 0.6801770711 -1.7608113045 1.8197009468 0.3864130492 0.5317993806 -0.6156412726 0.434580484744 +1403715376162142976.0000000000 0.7050382572 -1.7511914438 1.8156456529 0.3892231086 0.5304750891 -0.6161532207 0.432962770074 +1403715376212143104.0000000000 0.7296936336 -1.7413187192 1.8114003295 0.3920675927 0.5288333499 -0.6168908092 0.431351388491 +1403715376262142976.0000000000 0.7537583722 -1.7311449894 1.8067020806 0.3946358932 0.5275798812 -0.6173983510 0.429815375418 +1403715376312143104.0000000000 0.7775936433 -1.7211100398 1.8024271451 0.3983750306 0.5253339459 -0.6146453855 0.433050378534 +1403715376362142976.0000000000 0.8008252923 -1.7111939727 1.7983206128 0.4034347154 0.5218894170 -0.6110830979 0.43754921355 +1403715376412143104.0000000000 0.8228108927 -1.7013543925 1.7935549480 0.4054411149 0.5208245482 -0.6069214908 0.442725192856 +1403715376462142976.0000000000 0.8428057017 -1.6914242122 1.7875967457 0.4031930294 0.5229452394 -0.6049807302 0.444929178362 +1403715376512143104.0000000000 0.8611123062 -1.6811037378 1.7808871610 0.3994795865 0.5265057198 -0.6046431540 0.444538461024 +1403715376562142976.0000000000 0.8781721662 -1.6701977339 1.7740530224 0.3958058961 0.5303562802 -0.6050826294 0.442645366266 +1403715376612143104.0000000000 0.8941043849 -1.6585930636 1.7672032030 0.3929406985 0.5335635932 -0.6053850331 0.4409268206 +1403715376662142976.0000000000 0.9091860975 -1.6463300354 1.7603141701 0.3905401857 0.5366286856 -0.6061810728 0.438237976595 +1403715376712143104.0000000000 0.9237370152 -1.6334222918 1.7541907602 0.3902150244 0.5380849603 -0.6060731510 0.436889168768 +1403715376762142976.0000000000 0.9376914596 -1.6198910580 1.7482189016 0.3898004864 0.5396131068 -0.6048661756 0.437047120328 +1403715376812143104.0000000000 0.9511123910 -1.6057172126 1.7426805064 0.3910140400 0.5399549067 -0.6030914583 0.437992479576 +1403715376862142976.0000000000 0.9638592612 -1.5908396912 1.7379639546 0.3940108074 0.5391741934 -0.6010154882 0.439120775873 +1403715376912143104.0000000000 0.9757264024 -1.5752799118 1.7340532028 0.3986426374 0.5372253104 -0.5975278916 0.442078536347 +1403715376962142976.0000000000 0.9865029445 -1.5590117692 1.7305474691 0.4031309545 0.5353238844 -0.5927180034 0.44676519649 +1403715377012143104.0000000000 0.9955014389 -1.5417083978 1.7266984905 0.4081238097 0.5333771465 -0.5903668931 0.447672544477 +1403715377062142976.0000000000 1.0026091971 -1.5237295812 1.7217484896 0.4089221962 0.5347533292 -0.5889742340 0.447136294697 +1403715377112143104.0000000000 1.0079103049 -1.5050670420 1.7159357801 0.4064842915 0.5383457055 -0.5897800700 0.443975101908 +1403715377162142976.0000000000 1.0116532899 -1.4859661519 1.7102566820 0.4034207222 0.5424008998 -0.5899780011 0.441564200269 +1403715377212143104.0000000000 1.0143308253 -1.4659475306 1.7047462275 0.4007698641 0.5459495840 -0.5903313352 0.439125816214 +1403715377262142976.0000000000 1.0161526534 -1.4449681035 1.6996742729 0.3997360368 0.5484438985 -0.5904486724 0.436796012353 +1403715377312143104.0000000000 1.0170152641 -1.4229534189 1.6953402760 0.4003014347 0.5495803817 -0.5907398112 0.434449813932 +1403715377362142976.0000000000 1.0170000321 -1.4002894707 1.6913615554 0.4013960625 0.5500248099 -0.5902739079 0.433509657537 +1403715377412143104.0000000000 1.0162318819 -1.3768589590 1.6877401176 0.4044371468 0.5492368003 -0.5894505039 0.432802073684 +1403715377462142976.0000000000 1.0145625142 -1.3530845305 1.6839108460 0.4061065178 0.5490024782 -0.5882334681 0.43319183062 +1403715377512143104.0000000000 1.0117932758 -1.3287063751 1.6799675133 0.4076032772 0.5489642323 -0.5874426382 0.432907596227 +1403715377562142976.0000000000 1.0081111451 -1.3037071755 1.6759398956 0.4089269028 0.5488201025 -0.5873852458 0.431918807457 +1403715377612143104.0000000000 1.0033429761 -1.2783323198 1.6715784777 0.4089667304 0.5493297404 -0.5874527144 0.431140763558 +1403715377662142976.0000000000 0.9976243237 -1.2523043326 1.6670893234 0.4081011068 0.5505573214 -0.5881439199 0.429449475404 +1403715377712143104.0000000000 0.9911972726 -1.2259332842 1.6624762286 0.4071926421 0.5514341142 -0.5891464624 0.427809555428 +1403715377762142976.0000000000 0.9842215530 -1.1990866079 1.6580940178 0.4068514325 0.5518419820 -0.5893720573 0.427297223032 +1403715377812143104.0000000000 0.9764275214 -1.1716354074 1.6541079996 0.4065140907 0.5522030088 -0.5898654524 0.426470255856 +1403715377862142976.0000000000 0.9678816674 -1.1437074747 1.6501678739 0.4062433678 0.5524503659 -0.5903775664 0.425698541679 +1403715377912143104.0000000000 0.9587320150 -1.1154133450 1.6457313814 0.4062205065 0.5525802225 -0.5905058734 0.42537373126 +1403715377962142976.0000000000 0.9491093546 -1.0866906361 1.6410915340 0.4067672408 0.5523798022 -0.5905668395 0.425026792142 +1403715378012143104.0000000000 0.9389553133 -1.0574183256 1.6366930297 0.4081974587 0.5514491739 -0.5915041053 0.423558185716 +1403715378062142976.0000000000 0.9283849048 -1.0276854002 1.6325028236 0.4108508584 0.5499195644 -0.5923559924 0.421787177503 +1403715378112143104.0000000000 0.9170467143 -0.9978475380 1.6279449450 0.4131479710 0.5486788280 -0.5932265863 0.419931559916 +1403715378162142976.0000000000 0.9051005545 -0.9679653706 1.6233683905 0.4158952438 0.5472608021 -0.5939374134 0.418061131528 +1403715378212143104.0000000000 0.8927206392 -0.9385480864 1.6189482978 0.4188410623 0.5453980262 -0.5948566025 0.416243654561 +1403715378262142976.0000000000 0.8796838500 -0.9096091251 1.6141185177 0.4199685282 0.5450559808 -0.5967179429 0.41287783872 +1403715378312143104.0000000000 0.8662726973 -0.8812743583 1.6091610010 0.4211436503 0.5445608924 -0.5990478103 0.408941537535 +1403715378362142976.0000000000 0.8524851115 -0.8539911010 1.6038717677 0.4211510709 0.5448145893 -0.6016766652 0.404714750496 +1403715378412143104.0000000000 0.8382619396 -0.8278765992 1.5985261227 0.4194686930 0.5462784061 -0.6040015548 0.401008778427 +1403715378462142976.0000000000 0.8241344084 -0.8031910987 1.5933864944 0.4168970315 0.5480271720 -0.6050492867 0.399722959776 +1403715378512143104.0000000000 0.8101162081 -0.7796541642 1.5885690848 0.4133882220 0.5506473865 -0.6051158708 0.399665380765 +1403715378562142976.0000000000 0.7963261582 -0.7572518862 1.5844921538 0.4097584032 0.5532218464 -0.6042400201 0.40117033508 +1403715378612143104.0000000000 0.7828831088 -0.7353787154 1.5814771199 0.4076291314 0.5546725131 -0.6040534666 0.401617111108 +1403715378662142976.0000000000 0.7697210434 -0.7137755117 1.5785470578 0.4050153981 0.5565239076 -0.6039932326 0.401790794499 +1403715378712143104.0000000000 0.7574784170 -0.6925380347 1.5762132126 0.4027439147 0.5582172434 -0.6041506305 0.401488311201 +1403715378762142976.0000000000 0.7456542723 -0.6718413425 1.5745023321 0.4007014444 0.5596568109 -0.6049063545 0.400388447312 +1403715378812143104.0000000000 0.7346327320 -0.6515240949 1.5731986399 0.3985603155 0.5612252165 -0.6062278065 0.398326220467 +1403715378862142976.0000000000 0.7245849108 -0.6315263435 1.5727084991 0.3972105278 0.5622101810 -0.6074938457 0.396351783741 +1403715378912143104.0000000000 0.7160874299 -0.6119055662 1.5728605332 0.3963760808 0.5629081288 -0.6084119501 0.39478518229 +1403715378962142976.0000000000 0.7088939779 -0.5926252381 1.5738584553 0.3959825280 0.5630844163 -0.6091102077 0.393850901229 +1403715379012143104.0000000000 0.7030912045 -0.5736636945 1.5757684047 0.3961432196 0.5629149370 -0.6093496041 0.393561155696 +1403715379062142976.0000000000 0.6986633880 -0.5551797858 1.5780727291 0.3954931042 0.5631143666 -0.6088041262 0.394772023462 +1403715379112143104.0000000000 0.6953713965 -0.5370124921 1.5809828226 0.3954659068 0.5632855687 -0.6073806305 0.396742806265 +1403715379162142976.0000000000 0.6933565500 -0.5192951449 1.5842802899 0.3947228828 0.5635501684 -0.6044893088 0.401494369987 +1403715379212143104.0000000000 0.6920941900 -0.5015602736 1.5875331042 0.3933137183 0.5643148461 -0.6022376481 0.405170197148 +1403715379262142976.0000000000 0.6911773698 -0.4835367965 1.5908270789 0.3918277872 0.5651896517 -0.6000958482 0.408554299489 +1403715379312143104.0000000000 0.6909105258 -0.4653825748 1.5943501365 0.3902932982 0.5659439090 -0.5985292526 0.41126799905 +1403715379362142976.0000000000 0.6913422327 -0.4465591863 1.5979878147 0.3891621767 0.5666970841 -0.5967446731 0.413887678268 +1403715379412143104.0000000000 0.6922551158 -0.4270005881 1.6015897782 0.3876710764 0.5674613415 -0.5957595436 0.415655300312 +1403715379462142976.0000000000 0.6936219822 -0.4065588040 1.6049064390 0.3858525033 0.5686171371 -0.5953777895 0.416314406288 +1403715379512143104.0000000000 0.6955691149 -0.3852822186 1.6082393238 0.3841578351 0.5696192089 -0.5950735445 0.41694626894 +1403715379562142976.0000000000 0.6981814022 -0.3629112307 1.6115917260 0.3833325391 0.5700853501 -0.5957791783 0.416060126405 +1403715379612143104.0000000000 0.7017343991 -0.3396710797 1.6151696329 0.3819765332 0.5710846992 -0.5958014266 0.41590486231 +1403715379662142976.0000000000 0.7057807306 -0.3154713351 1.6186144224 0.3800782683 0.5722178682 -0.5967493377 0.414725751794 +1403715379712143104.0000000000 0.7108962285 -0.2902677852 1.6224737102 0.3796501612 0.5725875437 -0.5959945599 0.415691886501 +1403715379762142976.0000000000 0.7168612671 -0.2639572236 1.6266413162 0.3795593275 0.5725557176 -0.5956941387 0.416248916344 +1403715379812143104.0000000000 0.7237694623 -0.2365670952 1.6315077421 0.3808441294 0.5717491385 -0.5942479242 0.418246430179 +1403715379862142976.0000000000 0.7315424040 -0.2082041509 1.6363928229 0.3820752653 0.5708892653 -0.5921183389 0.421307264499 +1403715379912143104.0000000000 0.7399603731 -0.1786658589 1.6414066718 0.3841226459 0.5695058197 -0.5898734034 0.424455277064 +1403715379962142976.0000000000 0.7488040559 -0.1480210725 1.6461299436 0.3855051700 0.5682820373 -0.5883722246 0.426918511422 +1403715380012143104.0000000000 0.7578065810 -0.1160391979 1.6504228307 0.3856205852 0.5678342052 -0.5870119971 0.429276128888 +1403715380062142976.0000000000 0.7669886941 -0.0826110901 1.6548453071 0.3879241247 0.5658125937 -0.5865306757 0.430526130087 +1403715380112143104.0000000000 0.7757893743 -0.0477531446 1.6589374500 0.3916977586 0.5627527435 -0.5877743149 0.429422368164 +1403715380162142976.0000000000 0.7840138062 -0.0117111821 1.6629462511 0.3966425429 0.5589889030 -0.5897034140 0.427148666133 +1403715380212143104.0000000000 0.7918281009 0.0246016517 1.6665468774 0.3996107397 0.5567248408 -0.5907862406 0.425840728795 +1403715380262142976.0000000000 0.7990761741 0.0613901626 1.6698928143 0.4022414593 0.5547452786 -0.5926219201 0.423389589138 +1403715380312143104.0000000000 0.8057962261 0.0981708254 1.6728411766 0.4035501188 0.5535168309 -0.5944050853 0.42124697515 +1403715380362142976.0000000000 0.8122608158 0.1346268120 1.6753853057 0.4034408243 0.5527242634 -0.5963014921 0.419709328546 +1403715380412143104.0000000000 0.8187803474 0.1707513696 1.6777789977 0.4020404418 0.5530915114 -0.5975937339 0.418730214284 +1403715380462142976.0000000000 0.8255445282 0.2065247097 1.6803142713 0.4007251922 0.5536982361 -0.5972958066 0.419613277995 +1403715380512143104.0000000000 0.8318998405 0.2419741625 1.6827736659 0.3999277626 0.5542662879 -0.5965454860 0.420690087802 +1403715380562142976.0000000000 0.8376291073 0.2773610491 1.6851296250 0.3989204648 0.5551344533 -0.5957175447 0.421673817633 +1403715380612143104.0000000000 0.8427918028 0.3129875361 1.6879047713 0.3983530468 0.5560571339 -0.5950597409 0.42192323795 +1403715380662142976.0000000000 0.8478043192 0.3488908157 1.6911267672 0.3983211330 0.5564632498 -0.5946196779 0.422038345764 +1403715380712143104.0000000000 0.8525874243 0.3850411526 1.6945744786 0.3988743567 0.5564981914 -0.5940706395 0.42224292277 +1403715380762142976.0000000000 0.8573076394 0.4214710344 1.6982323997 0.3991069273 0.5566303348 -0.5933130053 0.422913713036 +1403715380812143104.0000000000 0.8616997548 0.4581849537 1.7023746415 0.3997428909 0.5565535273 -0.5926753801 0.42330802761 +1403715380862142976.0000000000 0.8658131481 0.4949138057 1.7061364994 0.4002025649 0.5564892169 -0.5919036709 0.42403738389 +1403715380912143104.0000000000 0.8693607375 0.5315362812 1.7090432682 0.3999500383 0.5567988590 -0.5913136032 0.424691911963 +1403715380962142976.0000000000 0.8724451605 0.5685393676 1.7119425570 0.3999786868 0.5569054838 -0.5906370529 0.425465867065 +1403715381012143104.0000000000 0.8749981704 0.6058314394 1.7146486206 0.3992558098 0.5574357069 -0.5900594279 0.42625122007 +1403715381062142976.0000000000 0.8771409564 0.6432645059 1.7174784781 0.3993624549 0.5567520934 -0.5899356064 0.427215070412 +1403715381112143104.0000000000 0.8786826669 0.6811562872 1.7200083105 0.4000053626 0.5557173879 -0.5911132561 0.426332045726 +1403715381162142976.0000000000 0.8799925659 0.7190963210 1.7229011755 0.4015035328 0.5537395751 -0.5924421252 0.425652116699 +1403715381212143104.0000000000 0.8808069750 0.7571210771 1.7254537126 0.4028316323 0.5518506127 -0.5935729151 0.425274936745 +1403715381262142976.0000000000 0.8811407422 0.7949727586 1.7273727462 0.4040929085 0.5497849147 -0.5947277273 0.425140446493 +1403715381312143104.0000000000 0.8808109486 0.8325299086 1.7288968866 0.4048768370 0.5481424081 -0.5955356689 0.425384431319 +1403715381362142976.0000000000 0.8801194871 0.8695352772 1.7300089618 0.4056627689 0.5461278040 -0.5973509869 0.424680983875 +1403715381412143104.0000000000 0.8790743274 0.9060000637 1.7311318436 0.4068267710 0.5436502164 -0.5987331303 0.424800022803 +1403715381462142976.0000000000 0.8776433449 0.9417424854 1.7318806457 0.4070075985 0.5417810655 -0.5997830385 0.425533075687 +1403715381512143104.0000000000 0.8755656866 0.9767538089 1.7325318967 0.4082128619 0.5391835092 -0.5997848566 0.427669882721 +1403715381562142976.0000000000 0.8722762894 1.0110890604 1.7318828445 0.4062088570 0.5394160647 -0.5990000717 0.430376100309 +1403715381612143104.0000000000 0.8681582782 1.0449915543 1.7307380659 0.4041868905 0.5397404938 -0.5989364311 0.431958688252 +1403715381662142976.0000000000 0.8630959612 1.0785816440 1.7285580210 0.4006062867 0.5414020381 -0.5992186434 0.432822658433 +1403715381712143104.0000000000 0.8573708729 1.1121136145 1.7260153210 0.3958687483 0.5441243304 -0.6002641919 0.432318802617 +1403715381762142976.0000000000 0.8514204774 1.1457156085 1.7238515667 0.3915985846 0.5469412997 -0.6012096009 0.431338357862 +1403715381812143104.0000000000 0.8451288615 1.1793727482 1.7219318786 0.3876019170 0.5497345894 -0.6023100455 0.429859563401 +1403715381862142976.0000000000 0.8388652096 1.2132874097 1.7195964561 0.3831232561 0.5524427740 -0.6041736782 0.427782326197 +1403715381912143104.0000000000 0.8332871858 1.2472437801 1.7171823764 0.3783587813 0.5539422803 -0.6066030919 0.426644197814 +1403715381962142976.0000000000 0.8282979162 1.2813991752 1.7148324063 0.3731048720 0.5539026509 -0.6096144300 0.427030273537 +1403715382012143104.0000000000 0.8241572425 1.3160163522 1.7130564697 0.3693991012 0.5512536578 -0.6138260790 0.427646177952 +1403715382062142976.0000000000 0.8213085714 1.3508079794 1.7113812644 0.3651032817 0.5475381060 -0.6187522834 0.429007258674 +1403715382112143104.0000000000 0.8195697345 1.3862149836 1.7099336552 0.3620605423 0.5419316386 -0.6243964805 0.430524445172 +1403715382162142976.0000000000 0.8185655725 1.4218988421 1.7088215545 0.3592044712 0.5352305707 -0.6304549545 0.432466107808 +1403715382212143104.0000000000 0.8187610895 1.4576557534 1.7085089258 0.3564984393 0.5274891038 -0.6369455198 0.434700486399 +1403715382262142976.0000000000 0.8198661180 1.4933831971 1.7082455029 0.3527025844 0.5198289430 -0.6430388498 0.43804085961 +1403715382312143104.0000000000 0.8220150900 1.5289834209 1.7081029761 0.3490832330 0.5114519671 -0.6494708437 0.441299677056 +1403715382362142976.0000000000 0.8251326909 1.5644032497 1.7077534858 0.3446021763 0.5032198561 -0.6555230944 0.445318525613 +1403715382412143104.0000000000 0.8292483942 1.5994853392 1.7071617617 0.3401871589 0.4943084164 -0.6613347100 0.450075868809 +1403715382462142976.0000000000 0.8341221597 1.6346004288 1.7063282847 0.3353043406 0.4865807014 -0.6673828513 0.453222186114 +1403715382512143104.0000000000 0.8400132848 1.6699313184 1.7055558425 0.3314913687 0.4790692725 -0.6726309250 0.456260609098 +1403715382562142976.0000000000 0.8468257704 1.7053865272 1.7048045422 0.3278231706 0.4723577178 -0.6776011565 0.458548610208 +1403715382612143104.0000000000 0.8543408886 1.7404447056 1.7039779624 0.3249466372 0.4654803933 -0.6825111984 0.460343513552 +1403715382662142976.0000000000 0.8626864668 1.7750010876 1.7025289232 0.3205062102 0.4593181846 -0.6872153454 0.462642025219 +1403715382712143104.0000000000 0.8719077356 1.8091894068 1.7009999472 0.3171326588 0.4522406193 -0.6920818904 0.464680488017 +1403715382762142976.0000000000 0.8821071461 1.8427744076 1.6988398843 0.3114655223 0.4466127085 -0.6967786587 0.466932348182 +1403715382812143104.0000000000 0.8932729265 1.8758183004 1.6969067385 0.3067439703 0.4403152612 -0.7005686474 0.470355373966 +1403715382862142976.0000000000 0.9051267552 1.9084728006 1.6947805925 0.3019587388 0.4338092947 -0.7050041462 0.47286316173 +1403715382912143104.0000000000 0.9179151031 1.9406996600 1.6926156526 0.2970718579 0.4275078597 -0.7089853363 0.475736412326 +1403715382962142976.0000000000 0.9318071892 1.9725240248 1.6904146376 0.2927589929 0.4209261095 -0.7136021994 0.477373316543 +1403715383012143104.0000000000 0.9467350037 2.0037897029 1.6883743649 0.2890559002 0.4140204469 -0.7180090978 0.479058129675 +1403715383062142976.0000000000 0.9623770243 2.0347707200 1.6860044789 0.2863848038 0.4076380418 -0.7225506759 0.47930730422 +1403715383112143104.0000000000 0.9788536724 2.0653122557 1.6835620718 0.2850442947 0.4018768678 -0.7264787603 0.479033760756 +1403715383162142976.0000000000 0.9959646901 2.0952523923 1.6807981901 0.2837508394 0.3976569599 -0.7293797153 0.478915059523 +1403715383212143104.0000000000 1.0141761931 2.1245547524 1.6780403996 0.2831520765 0.3937736232 -0.7327245754 0.477369806129 +1403715383262142976.0000000000 1.0337365722 2.1527458584 1.6751382043 0.2816117912 0.3919411443 -0.7340774454 0.477710417039 +1403715383312143104.0000000000 1.0542451803 2.1800345992 1.6721512312 0.2818029560 0.3895365430 -0.7356941272 0.477077066035 +1403715383362142976.0000000000 1.0755656464 2.2062621354 1.6693091780 0.2829051969 0.3872287489 -0.7367304861 0.476704034423 +1403715383412143104.0000000000 1.0973065464 2.2311566015 1.6660306610 0.2834145439 0.3859848457 -0.7367332110 0.477405562411 +1403715383462142976.0000000000 1.1196440421 2.2546034996 1.6627272368 0.2845004973 0.3841927504 -0.7365976237 0.478413355104 +1403715383512143104.0000000000 1.1426484696 2.2765081053 1.6598545766 0.2857730187 0.3810328866 -0.7361204314 0.480910003694 +1403715383562142976.0000000000 1.1661324703 2.2969001711 1.6567250564 0.2854771723 0.3778969183 -0.7355882179 0.484362134136 +1403715383612143104.0000000000 1.1899711993 2.3157882653 1.6532662135 0.2842697346 0.3737789556 -0.7350251681 0.489099184761 +1403715383662142976.0000000000 1.2136206867 2.3334829518 1.6491605848 0.2816864423 0.3687543824 -0.7362236201 0.492592869282 +1403715383712143104.0000000000 1.2368183391 2.3498520189 1.6450182630 0.2780929799 0.3628749231 -0.7381865798 0.496051064024 +1403715383762142976.0000000000 1.2598265261 2.3649093846 1.6407121906 0.2738776455 0.3555366703 -0.7406855073 0.499969689697 +1403715383812143104.0000000000 1.2825851157 2.3789686020 1.6364042066 0.2690359487 0.3470928959 -0.7440465205 0.503528504936 +1403715383862142976.0000000000 1.3050465987 2.3921732750 1.6321832160 0.2628069705 0.3382746986 -0.7482041981 0.506648993395 +1403715383912143104.0000000000 1.3270684184 2.4044353821 1.6281797544 0.2563376563 0.3280375473 -0.7526748033 0.510061774643 +1403715383962142976.0000000000 1.3486068053 2.4158273250 1.6238180627 0.2478818592 0.3179137307 -0.7573012182 0.513790140581 +1403715384012143104.0000000000 1.3700312683 2.4265853720 1.6201131107 0.2404924550 0.3064257842 -0.7619680382 0.517369622803 +1403715384062142976.0000000000 1.3906430779 2.4367807087 1.6162303667 0.2321657550 0.2952131029 -0.7669968073 0.520253960736 +1403715384112143104.0000000000 1.4105066833 2.4466162972 1.6129791558 0.2240327188 0.2833310922 -0.7716792293 0.523492120482 +1403715384162142976.0000000000 1.4298341026 2.4558206103 1.6100538721 0.2162083983 0.2714818450 -0.7760395718 0.526606228032 +1403715384212143104.0000000000 1.4487843513 2.4643818576 1.6074386775 0.2085483881 0.2596679856 -0.7806848516 0.528782818941 +1403715384262142976.0000000000 1.4674043029 2.4722247625 1.6053624488 0.2016179491 0.2473895779 -0.7847651833 0.531311778948 +1403715384312143104.0000000000 1.4855769291 2.4795928729 1.6037563189 0.1951605023 0.2348253891 -0.7888728424 0.533337654357 +1403715384362142976.0000000000 1.5030534980 2.4863389671 1.6024171987 0.1883800853 0.2224272857 -0.7925148457 0.53568578981 +1403715384412143104.0000000000 1.5198556046 2.4925603377 1.6011597269 0.1812878657 0.2107134176 -0.7958598982 0.537904812982 +1403715384462142976.0000000000 1.5358895816 2.4984121942 1.5998447884 0.1745812858 0.1988751719 -0.7995557842 0.539148020972 +1403715384512143104.0000000000 1.5511016385 2.5037204000 1.5985119303 0.1681282028 0.1871355919 -0.8035598422 0.539448568141 +1403715384562142976.0000000000 1.5655446126 2.5079551335 1.5967941127 0.1602254456 0.1767031521 -0.8078146454 0.539016976875 +1403715384612143104.0000000000 1.5795384929 2.5110316957 1.5957636169 0.1533632416 0.1655962426 -0.8117854000 0.538574103515 +1403715384662142976.0000000000 1.5925434611 2.5133090292 1.5946705601 0.1457067774 0.1550755417 -0.8156865231 0.537937363828 +1403715384712143104.0000000000 1.6046549603 2.5142214186 1.5935772633 0.1369323318 0.1457142078 -0.8191320856 0.537623969386 +1403715384762142976.0000000000 1.6162299123 2.5139736730 1.5935166651 0.1302782800 0.1352191767 -0.8217880098 0.537966365926 +1403715384812143104.0000000000 1.6269785447 2.5125513332 1.5935168413 0.1230750689 0.1254113709 -0.8243982497 0.53804464627 +1403715384862142976.0000000000 1.6372799587 2.5099210909 1.5938381139 0.1165529300 0.1157701500 -0.8266441852 0.538211926561 +1403715384912143104.0000000000 1.6472810047 2.5058863985 1.5947524091 0.1110838213 0.1065287999 -0.8279579371 0.539256575195 +1403715384962142976.0000000000 1.6567150176 2.5007014727 1.5962858399 0.1069202409 0.0989014192 -0.8280723391 0.541371196659 +1403715385012143104.0000000000 1.6656034812 2.4943071911 1.5979392018 0.1021463079 0.0936490703 -0.8277926009 0.543650065149 +1403715385062142976.0000000000 1.6736560238 2.4868362164 1.5995226563 0.0967894423 0.0899608665 -0.8276582148 0.545454604775 +1403715385112143104.0000000000 1.6809702305 2.4781886178 1.6015514555 0.0906112186 0.0869160033 -0.8274322957 0.547349076448 +1403715385162142976.0000000000 1.6879136399 2.4686030495 1.6039018554 0.0842367491 0.0834360660 -0.8273192349 0.549076931304 +1403715385212143104.0000000000 1.6945238998 2.4583685991 1.6064953635 0.0778333228 0.0798007800 -0.8272847119 0.550612218185 +1403715385262142976.0000000000 1.7011684834 2.4474991812 1.6094032618 0.0723581383 0.0767404437 -0.8274078854 0.55160800871 +1403715385312143104.0000000000 1.7081436047 2.4360091058 1.6123606364 0.0682067986 0.0738166095 -0.8279323823 0.551748956538 +1403715385362142976.0000000000 1.7155302647 2.4236875829 1.6156140461 0.0659266878 0.0709028423 -0.8279700665 0.552351362665 +1403715385412143104.0000000000 1.7228846599 2.4108266126 1.6187198066 0.0636925024 0.0689712812 -0.8285956314 0.551919837643 +1403715385462142976.0000000000 1.7303069301 2.3976357595 1.6225479866 0.0639921141 0.0662100691 -0.8284041322 0.552510479329 +1403715385512143104.0000000000 1.7378871728 2.3839073938 1.6268111053 0.0658159725 0.0633951647 -0.8275009982 0.553977805431 +1403715385562142976.0000000000 1.7454405192 2.3695756177 1.6314382176 0.0694278509 0.0596196407 -0.8268078506 0.554990135244 +1403715385612143104.0000000000 1.7528467897 2.3548197367 1.6365284301 0.0746225821 0.0557167563 -0.8261106671 0.555759191584 +1403715385662142976.0000000000 1.7596653584 2.3397406474 1.6412967174 0.0792655709 0.0525584035 -0.8266608256 0.554604780766 +1403715385712143104.0000000000 1.7655442747 2.3241399588 1.6463187351 0.0832370872 0.0505166650 -0.8264448035 0.55453461629 +1403715385762142976.0000000000 1.7701795889 2.3079488240 1.6512487739 0.0856952402 0.0497520099 -0.8257015231 0.555335986586 +1403715385812143104.0000000000 1.7733602688 2.2911228543 1.6570108627 0.0884261419 0.0487902545 -0.8242480901 0.557149364628 +1403715385862142976.0000000000 1.7747561901 2.2736311730 1.6632350742 0.0896755949 0.0489024022 -0.8226245967 0.559334976188 +1403715385912143104.0000000000 1.7744081567 2.2555566628 1.6699245631 0.0894916428 0.0498887733 -0.8202652883 0.562731919332 +1403715385962142976.0000000000 1.7723658010 2.2370887124 1.6764044240 0.0863330595 0.0528442554 -0.8172466203 0.567328872149 +1403715386012143104.0000000000 1.7688247420 2.2187896720 1.6824028051 0.0819067421 0.0564611376 -0.8146438744 0.571365717736 +1403715386062142976.0000000000 1.7641309444 2.2012303735 1.6881623157 0.0779109087 0.0596498073 -0.8130523285 0.573862093088 +1403715386112143104.0000000000 1.7584614253 2.1844804831 1.6937193236 0.0746584890 0.0621947298 -0.8119918490 0.575523381577 +1403715386162142976.0000000000 1.7519275821 2.1687224467 1.6988568968 0.0718586045 0.0640202670 -0.8118669168 0.575855759561 +1403715386212143104.0000000000 1.7449245959 2.1537990929 1.7032137564 0.0693304328 0.0655455128 -0.8123977323 0.57524516639 +1403715386262142976.0000000000 1.7376026416 2.1394046089 1.7066106497 0.0680687795 0.0659275205 -0.8133225916 0.574044044722 +1403715386312143104.0000000000 1.7300876258 2.1257379729 1.7098610486 0.0681866079 0.0650831356 -0.8139782385 0.573196475303 +1403715386362142976.0000000000 1.7220834848 2.1123261018 1.7131191211 0.0683051306 0.0643682733 -0.8135844448 0.573821823987 +1403715386412143104.0000000000 1.7136225137 2.0996346886 1.7161020202 0.0685463503 0.0633900147 -0.8124512169 0.575505103435 +1403715386462142976.0000000000 1.7048327904 2.0874577345 1.7185042654 0.0688653477 0.0622731747 -0.8112389557 0.577296260506 +1403715386512143104.0000000000 1.6955813996 2.0759779533 1.7204799251 0.0697796104 0.0609679089 -0.8098362612 0.579291765925 +1403715386562142976.0000000000 1.6858984107 2.0655016204 1.7220170970 0.0723596064 0.0586385941 -0.8089756983 0.580417024317 +1403715386612143104.0000000000 1.6756046850 2.0561304048 1.7225794037 0.0740611342 0.0571536889 -0.8085784176 0.58090390494 +1403715386662142976.0000000000 1.6646265257 2.0477146620 1.7229844559 0.0780049280 0.0540958544 -0.8077425818 0.581842582928 +1403715386712143104.0000000000 1.6526597964 2.0403289495 1.7226245767 0.0812126907 0.0519747263 -0.8076625849 0.581708067325 +1403715386762142976.0000000000 1.6397163951 2.0341656256 1.7217290079 0.0841857612 0.0500122829 -0.8085455142 0.580228989881 +1403715386812143104.0000000000 1.6253757132 2.0290968937 1.7195619793 0.0883635013 0.0475048099 -0.8116647753 0.575443721989 +1403715386862142976.0000000000 1.6094514913 2.0244689580 1.7174162365 0.0930188076 0.0450461420 -0.8144279269 0.570986425807 +1403715386912143104.0000000000 1.5914222161 2.0202109806 1.7149735330 0.0969334090 0.0427070022 -0.8170367364 0.566772438906 +1403715386962142976.0000000000 1.5714529237 2.0158660527 1.7121007864 0.0997395060 0.0412663584 -0.8191153686 0.56338187008 +1403715387012143104.0000000000 1.5492200653 2.0111285816 1.7087218325 0.1013360886 0.0405121274 -0.8207790403 0.560724113655 +1403715387062142976.0000000000 1.5245870572 2.0059773080 1.7045946303 0.1007114500 0.0412894235 -0.8218103238 0.559267537922 +1403715387112143104.0000000000 1.4979845055 1.9999742398 1.6999734445 0.0978541809 0.0439372613 -0.8219919584 0.559306084923 +1403715387162142976.0000000000 1.4693927719 1.9933356530 1.6950507818 0.0935632850 0.0473922263 -0.8221465854 0.559530947067 +1403715387212143104.0000000000 1.4392677156 1.9863163197 1.6899128137 0.0886593377 0.0518951373 -0.8216882721 0.560602176247 +1403715387262142976.0000000000 1.4079002017 1.9790078883 1.6846849829 0.0853022167 0.0552082750 -0.8214542187 0.561149307061 +1403715387312143104.0000000000 1.3755632446 1.9712817107 1.6794243431 0.0823038992 0.0582627108 -0.8206817078 0.562417157642 +1403715387362142976.0000000000 1.3427032979 1.9630803311 1.6739789668 0.0803546226 0.0607618633 -0.8200298501 0.563384571606 +1403715387412143104.0000000000 1.3093015184 1.9547365922 1.6683007569 0.0783836854 0.0632342734 -0.8196435655 0.563951992687 +1403715387462142976.0000000000 1.2755511806 1.9463511077 1.6627079320 0.0773124356 0.0651887759 -0.8196808676 0.563823098159 +1403715387512143104.0000000000 1.2412909820 1.9378645601 1.6574295049 0.0761983653 0.0674170733 -0.8209967867 0.561794467466 +1403715387562142976.0000000000 1.2067955700 1.9291369193 1.6535867277 0.0759160323 0.0689006374 -0.8223811502 0.559623714696 +1403715387612143104.0000000000 1.1719545650 1.9203559403 1.6518135279 0.0771257965 0.0694671450 -0.8244422952 0.556345961757 +1403715387662142976.0000000000 1.1369472718 1.9109119866 1.6527678618 0.0777544983 0.0704337200 -0.8263502146 0.553297977439 +1403715387712143104.0000000000 1.1019682817 1.9004637943 1.6568632068 0.0779147496 0.0722720582 -0.8277301782 0.550970773729 +1403715387762142976.0000000000 1.0670758850 1.8890823083 1.6643021754 0.0787930278 0.0737904835 -0.8289563716 0.548796826953 +1403715387812143104.0000000000 1.0319218223 1.8764680373 1.6746106227 0.0796863510 0.0752812290 -0.8295733699 0.547531593577 +1403715387862142976.0000000000 0.9968725096 1.8623926183 1.6865709709 0.0808886053 0.0764269300 -0.8303665375 0.54599209825 +1403715387912143104.0000000000 0.9618810734 1.8472491714 1.6978216419 0.0822151568 0.0774826850 -0.8307145103 0.545115129079 +1403715387962142976.0000000000 0.9268113215 1.8313990768 1.7062257136 0.0830681607 0.0786545721 -0.8307958322 0.544693881161 +1403715388012143104.0000000000 0.8919249311 1.8143055672 1.7113682641 0.0842797468 0.0792732139 -0.8305123461 0.544850369253 +1403715388062142976.0000000000 0.8569290871 1.7962535466 1.7132613133 0.0843306697 0.0808456770 -0.8300239847 0.545355388252 +1403715388112143104.0000000000 0.8219186901 1.7775796934 1.7118109598 0.0847416019 0.0816334053 -0.8291021493 0.546575222681 +1403715388162142976.0000000000 0.7870588842 1.7580659904 1.7068707807 0.0852353366 0.0825232423 -0.8280208764 0.548002080435 +1403715388212143104.0000000000 0.7524176025 1.7375521821 1.6988704835 0.0851438351 0.0835640729 -0.8262270619 0.550560092305 +1403715388262142976.0000000000 0.7179888261 1.7162705864 1.6885160580 0.0850950851 0.0844703651 -0.8240845759 0.55363182326 +1403715388312143104.0000000000 0.6833606155 1.6943012979 1.6766166539 0.0847543842 0.0856276374 -0.8222783764 0.556186006419 +1403715388362142976.0000000000 0.6487076867 1.6716345345 1.6642127681 0.0838315014 0.0867862972 -0.8206241098 0.558584361052 +1403715388412143104.0000000000 0.6141942607 1.6486403975 1.6515600890 0.0838812538 0.0874017603 -0.8196991319 0.559837655678 +1403715388462142976.0000000000 0.5796008668 1.6251914386 1.6386858960 0.0826153941 0.0885424192 -0.8186644459 0.561358585724 +1403715388512143104.0000000000 0.5453027360 1.6016364502 1.6252905039 0.0822674959 0.0888500237 -0.8185593392 0.561514328141 +1403715388562142976.0000000000 0.5114254455 1.5779210536 1.6123626381 0.0832040272 0.0885219237 -0.8181032153 0.562092597324 +1403715388612143104.0000000000 0.4773979932 1.5541629832 1.5997057612 0.0835203466 0.0882496488 -0.8177973744 0.562533381794 +1403715388662142976.0000000000 0.4435341530 1.5304969027 1.5872281202 0.0836598676 0.0884092883 -0.8172687336 0.563255396244 +1403715388712143104.0000000000 0.4098971430 1.5068040283 1.5752272189 0.0840617274 0.0885464400 -0.8166054387 0.564135366314 +1403715388762142976.0000000000 0.3762744950 1.4829590658 1.5636870045 0.0836428760 0.0890983280 -0.8163010392 0.564551123099 +1403715388812143104.0000000000 0.3429218088 1.4591821669 1.5528843898 0.0838640608 0.0892784127 -0.8160884236 0.564797193054 +1403715388862142976.0000000000 0.3097705994 1.4353887968 1.5428101117 0.0838317318 0.0901138233 -0.8158696874 0.564985303164 +1403715388912143104.0000000000 0.2765004337 1.4116542657 1.5345115740 0.0824795890 0.0916570858 -0.8151515424 0.565971782886 +1403715388962142976.0000000000 0.2435146922 1.3880860181 1.5287313089 0.0826236687 0.0924955535 -0.8145591677 0.566666801776 +1403715389012143104.0000000000 0.2106190988 1.3642149703 1.5254353791 0.0822726530 0.0935841031 -0.8141742121 0.567092213507 +1403715389062142976.0000000000 0.1781367808 1.3401294730 1.5254421322 0.0824358559 0.0945585552 -0.8134675638 0.567920357001 +1403715389112143104.0000000000 0.1458930396 1.3161378199 1.5286386092 0.0819205055 0.0959270485 -0.8132171523 0.56812401408 +1403715389162142976.0000000000 0.1139764099 1.2922101402 1.5343830979 0.0811625590 0.0975670603 -0.8129653177 0.568313909667 +1403715389212143104.0000000000 0.0825631140 1.2683333714 1.5407826826 0.0805009095 0.0990765035 -0.8124894291 0.568827194879 +1403715389262142976.0000000000 0.0515532562 1.2447443357 1.5470109223 0.0787579608 0.1013735133 -0.8121129298 0.569203991198 +1403715389312143104.0000000000 0.0211038779 1.2219414398 1.5530982303 0.0777085163 0.1030544787 -0.8118738456 0.569387407439 +1403715389362142976.0000000000 -0.0086625859 1.1995269757 1.5587417869 0.0768949302 0.1049571152 -0.8116497234 0.569469841346 +1403715389412143104.0000000000 -0.0377632324 1.1772305822 1.5638157860 0.0758695012 0.1065750352 -0.8114039609 0.569657083615 +1403715389462142976.0000000000 -0.0660233213 1.1552255328 1.5682798456 0.0758094996 0.1075308964 -0.8115214956 0.569317914882 +1403715389512143104.0000000000 -0.0934661321 1.1334996807 1.5725235061 0.0765027037 0.1078937663 -0.8116631899 0.568954424919 +1403715389562142976.0000000000 -0.1201474919 1.1120046297 1.5764868284 0.0781525228 0.1072481087 -0.8117660792 0.56870542377 +1403715389612143104.0000000000 -0.1459548231 1.0908272804 1.5803879168 0.0813828920 0.1063718886 -0.8116508436 0.56858135238 +1403715389662142976.0000000000 -0.1708045671 1.0699579736 1.5834968336 0.0850474622 0.1069812231 -0.8115669485 0.568050204853 +1403715389712143104.0000000000 -0.1950082181 1.0492988534 1.5861389993 0.0891535447 0.1088350288 -0.8113475968 0.567381405386 +1403715389762142976.0000000000 -0.2187694436 1.0288415673 1.5881731497 0.0936408795 0.1119138456 -0.8110772031 0.56644544965 +1403715389812143104.0000000000 -0.2421401541 1.0086384050 1.5897631898 0.0985576346 0.1165058469 -0.8103433263 0.565735339033 +1403715389862142976.0000000000 -0.2653026684 0.9887763073 1.5903894037 0.1034406405 0.1222290050 -0.8104106962 0.563555328065 +1403715389912143104.0000000000 -0.2883474917 0.9690618981 1.5903688269 0.1079188795 0.1293672541 -0.8108165085 0.560530301246 +1403715389962142976.0000000000 -0.3112900400 0.9491882301 1.5898484887 0.1122381593 0.1370047600 -0.8113957331 0.557018182461 +1403715390012143104.0000000000 -0.3341108603 0.9291827837 1.5884715214 0.1158463231 0.1457476564 -0.8123345292 0.552675187413 +1403715390062142976.0000000000 -0.3567121399 0.9088021938 1.5862043756 0.1196066085 0.1548172153 -0.8129672724 0.548461578479 +1403715390112143104.0000000000 -0.3787972681 0.8879135986 1.5837895302 0.1234992430 0.1642570974 -0.8130077895 0.54478057706 +1403715390162142976.0000000000 -0.4001095035 0.8660712827 1.5810240240 0.1267586525 0.1744352093 -0.8125082703 0.541604018211 +1403715390212143104.0000000000 -0.4203752594 0.8433206194 1.5778847350 0.1303781219 0.1846773967 -0.8114621074 0.538910987697 +1403715390262142976.0000000000 -0.4393862911 0.8198549647 1.5739732725 0.1337980832 0.1951201633 -0.8105855762 0.535702546635 +1403715390312143104.0000000000 -0.4566934213 0.7951819184 1.5700528881 0.1380701477 0.2051242365 -0.8078657658 0.53498933293 +1403715390362142976.0000000000 -0.4728428608 0.7698558298 1.5660610760 0.1428423502 0.2148934811 -0.8051547058 0.533987597746 +1403715390412143104.0000000000 -0.4877395196 0.7437536162 1.5620058962 0.1465827531 0.2253545863 -0.8018356569 0.533655681318 +1403715390462142976.0000000000 -0.5012911095 0.7170271585 1.5577508907 0.1495872210 0.2365485426 -0.7979470516 0.533806100631 +1403715390512143104.0000000000 -0.5131596727 0.6901109034 1.5535251891 0.1532475286 0.2471863092 -0.7941521337 0.533607076478 +1403715390562142976.0000000000 -0.5233721019 0.6629330505 1.5493447221 0.1567653702 0.2578912752 -0.7897187130 0.5340983648 +1403715390612143104.0000000000 -0.5319594762 0.6359628546 1.5452891408 0.1607300677 0.2681610614 -0.7848438590 0.535047294585 +1403715390662142976.0000000000 -0.5387666641 0.6092529136 1.5411899439 0.1661107221 0.2771055309 -0.7808618321 0.534672378131 +1403715390712143104.0000000000 -0.5436334246 0.5831659907 1.5373576290 0.1736932145 0.2841985870 -0.7778791349 0.532884492088 +1403715390762142976.0000000000 -0.5464649435 0.5578230319 1.5338387258 0.1839185178 0.2889706806 -0.7762437850 0.529259398464 +1403715390812143104.0000000000 -0.5479572142 0.5323506472 1.5300974527 0.1919134160 0.2943303254 -0.7748515553 0.525494022373 +1403715390862142976.0000000000 -0.5481811845 0.5064768054 1.5262140206 0.1988927819 0.2981736154 -0.7740785237 0.521858788874 +1403715390912143104.0000000000 -0.5472402339 0.4802724592 1.5220561347 0.2031699154 0.3021014163 -0.7733545916 0.519017721712 +1403715390962142976.0000000000 -0.5450170034 0.4536767793 1.5181572207 0.2072866475 0.3047415853 -0.7732434530 0.516003269681 +1403715391012143104.0000000000 -0.5418545360 0.4266930684 1.5140971875 0.2108798501 0.3071480974 -0.7733570243 0.512941174109 +1403715391062142976.0000000000 -0.5375941561 0.3994097098 1.5099718196 0.2152916718 0.3097293816 -0.7730856616 0.509956631584 +1403715391112143104.0000000000 -0.5324167929 0.3716607137 1.5058065877 0.2201915664 0.3126143759 -0.7726397419 0.506769923381 +1403715391162142976.0000000000 -0.5258999828 0.3433355062 1.5023016405 0.2268138335 0.3149454499 -0.7714890560 0.50415224388 +1403715391212143104.0000000000 -0.5184723985 0.3141568801 1.4988724315 0.2326685647 0.3178695392 -0.7699556170 0.50198868805 +1403715391262142976.0000000000 -0.5101598625 0.2837384010 1.4961371597 0.2387379072 0.3194707995 -0.7678973356 0.501274677088 +1403715391312143104.0000000000 -0.5014022592 0.2520713837 1.4936658238 0.2433849030 0.3207931896 -0.7660414061 0.501035011392 +1403715391362142976.0000000000 -0.4922566686 0.2191112659 1.4908833890 0.2461031722 0.3225603262 -0.7643024168 0.501228371324 +1403715391412143104.0000000000 -0.4829084648 0.1850927207 1.4878252468 0.2475612986 0.3243972478 -0.7629496104 0.501385800563 +1403715391462142976.0000000000 -0.4733561011 0.1502211729 1.4846168642 0.2485350551 0.3254850264 -0.7627249478 0.500540186131 +1403715391512143104.0000000000 -0.4632236024 0.1140570350 1.4813638397 0.2486565866 0.3265945608 -0.7625148685 0.500076964265 +1403715391562142976.0000000000 -0.4525553283 0.0771752764 1.4784687975 0.2501127203 0.3268729509 -0.7622299763 0.499603006724 +1403715391612143104.0000000000 -0.4414759090 0.0397755946 1.4761171491 0.2536182882 0.3267410700 -0.7624265503 0.497618119155 +1403715391662142976.0000000000 -0.4302104456 0.0011565074 1.4746769390 0.2571237883 0.3274175449 -0.7617127953 0.496466238818 +1403715391712143104.0000000000 -0.4188522598 -0.0386096259 1.4754226603 0.2598594190 0.3297472845 -0.7599225036 0.496243487824 +1403715391762142976.0000000000 -0.4075195603 -0.0793133654 1.4791133875 0.2628406933 0.3330907282 -0.7574910775 0.496157841996 +1403715391812143104.0000000000 -0.3958703147 -0.1214407833 1.4857776555 0.2640701379 0.3386870409 -0.7540792491 0.496913007109 +1403715391862142976.0000000000 -0.3839783789 -0.1647168252 1.4948940883 0.2639916659 0.3461571790 -0.7502805664 0.497556709777 +1403715391912143104.0000000000 -0.3721430300 -0.2086230678 1.5067567074 0.2643135502 0.3531412827 -0.7469577078 0.497477400787 +1403715391962142976.0000000000 -0.3602166317 -0.2531367826 1.5200754087 0.2640005573 0.3596876019 -0.7446764497 0.496372360259 +1403715392012143104.0000000000 -0.3477885663 -0.2977817375 1.5332593014 0.2630457666 0.3654494650 -0.7444440583 0.493007765984 +1403715392062142976.0000000000 -0.3346126701 -0.3428469207 1.5463424201 0.2629199882 0.3700691018 -0.7437484583 0.49067318088 +1403715392112143104.0000000000 -0.3205280827 -0.3883615835 1.5591227983 0.2631702721 0.3730978243 -0.7438081595 0.488148382465 +1403715392162142976.0000000000 -0.3054524042 -0.4342590890 1.5715667627 0.2635761862 0.3758182624 -0.7434085464 0.486448312655 +1403715392212143104.0000000000 -0.2893610382 -0.4805167260 1.5841930202 0.2655872294 0.3782003652 -0.7420816632 0.485533430881 +1403715392262142976.0000000000 -0.2721124067 -0.5269433664 1.5970243303 0.2684598165 0.3814489403 -0.7392722289 0.485698058861 +1403715392312143104.0000000000 -0.2537440080 -0.5732061925 1.6093398692 0.2727887750 0.3850642851 -0.7357985645 0.485707991551 +1403715392362142976.0000000000 -0.2340918950 -0.6197826911 1.6219263050 0.2780826025 0.3896963990 -0.7299144879 0.487884846191 +1403715392412143104.0000000000 -0.2138294379 -0.6662335953 1.6350822751 0.2863334116 0.3931197166 -0.7221851186 0.491852335814 +1403715392462142976.0000000000 -0.1932651675 -0.7126696924 1.6482618338 0.2952997157 0.3966477163 -0.7129763315 0.497125152996 +1403715392512143104.0000000000 -0.1733012422 -0.7584360603 1.6602002344 0.3025073743 0.4021623229 -0.7042079895 0.500845147823 +1403715392562142976.0000000000 -0.1540773063 -0.8031518229 1.6705081343 0.3084061790 0.4091129821 -0.6974323384 0.501099121899 +1403715392612143104.0000000000 -0.1355571491 -0.8467373740 1.6792810845 0.3125701310 0.4175210415 -0.6923183798 0.49866958402 +1403715392662142976.0000000000 -0.1180000768 -0.8893014150 1.6875639191 0.3180504997 0.4254807950 -0.6866095481 0.496364081243 +1403715392712143104.0000000000 -0.1014984349 -0.9311521686 1.6952465546 0.3240684964 0.4330787011 -0.6806273263 0.494134486743 +1403715392762142976.0000000000 -0.0860286977 -0.9719799669 1.7016775923 0.3292512859 0.4413138316 -0.6752941336 0.490727547502 +1403715392812143104.0000000000 -0.0712587251 -1.0117777778 1.7069677133 0.3324374498 0.4513758935 -0.6712991686 0.484873768056 +1403715392862142976.0000000000 -0.0573361192 -1.0503396110 1.7117426441 0.3350311961 0.4619380244 -0.6683534309 0.477148876857 +1403715392912143104.0000000000 -0.0439356655 -1.0879133441 1.7163046858 0.3379822556 0.4724401048 -0.6644993587 0.470115884207 +1403715392962142976.0000000000 -0.0310781259 -1.1243069413 1.7203208283 0.3404618426 0.4835615888 -0.6599887587 0.463323604004 +1403715393012143104.0000000000 -0.0178858092 -1.1599313901 1.7247203260 0.3440660647 0.4939343119 -0.6545752814 0.457360513827 +1403715393062142976.0000000000 -0.0045038429 -1.1946805414 1.7296491310 0.3492920649 0.5031878957 -0.6491723079 0.450968191397 +1403715393112143104.0000000000 0.0092563027 -1.2286073268 1.7339967053 0.3537925574 0.5132526168 -0.6420463438 0.446294824255 +1403715393162142976.0000000000 0.0231799833 -1.2615681404 1.7374403973 0.3580276239 0.5236470712 -0.6332350069 0.443422362199 +1403715393212143104.0000000000 0.0372014250 -1.2931816850 1.7399171497 0.3625740500 0.5341858165 -0.6235366247 0.440894147689 +1403715393262142976.0000000000 0.0514836697 -1.3232217034 1.7422692877 0.3689320288 0.5434956814 -0.6135224919 0.438282733394 +1403715393312143104.0000000000 0.0657432487 -1.3514389858 1.7445396943 0.3757135086 0.5527058534 -0.6030262712 0.435562757131 +1403715393362142976.0000000000 0.0797921928 -1.3781922675 1.7466134592 0.3824496423 0.5619099390 -0.5927655153 0.431993675168 +1403715393412143104.0000000000 0.0935399467 -1.4034913140 1.7484618711 0.3883393775 0.5715839243 -0.5821470923 0.428472995973 +1403715393462142976.0000000000 0.1069401158 -1.4270741995 1.7495027625 0.3939463236 0.5812985620 -0.5713647683 0.424782976953 +1403715393512143104.0000000000 0.1198386777 -1.4488301608 1.7501114409 0.4005204300 0.5901245031 -0.5604043215 0.421050415588 +1403715393562142976.0000000000 0.1319561023 -1.4684730113 1.7503182571 0.4066270771 0.5991808968 -0.5490634865 0.417331955347 +1403715393612143104.0000000000 0.1431611639 -1.4858578632 1.7503937137 0.4135907171 0.6076706131 -0.5385133809 0.411925336978 +1403715393662142976.0000000000 0.1529789098 -1.5008835722 1.7502915716 0.4220236176 0.6150053687 -0.5297971783 0.403707087409 +1403715393712143104.0000000000 0.1621062675 -1.5137903127 1.7498798194 0.4300265224 0.6225202073 -0.5224982368 0.393117506678 +1403715393762142976.0000000000 0.1700786122 -1.5246411002 1.7492187515 0.4377764065 0.6298525955 -0.5158748303 0.381458628603 +1403715393812143104.0000000000 0.1774425124 -1.5339226881 1.7480257134 0.4442618986 0.6377686340 -0.5089969493 0.369871113397 +1403715393862142976.0000000000 0.1841457321 -1.5421864886 1.7471663633 0.4508890730 0.6450790872 -0.5022220225 0.358252781165 +1403715393912143104.0000000000 0.1905192608 -1.5497126467 1.7459393956 0.4561098294 0.6529729195 -0.4934231212 0.34946217735 +1403715393962142976.0000000000 0.1963820866 -1.5561969340 1.7448928097 0.4619376420 0.6600503817 -0.4855643124 0.339373550829 +1403715394012143104.0000000000 0.2018460693 -1.5620674108 1.7438248980 0.4683806975 0.6664458378 -0.4768578655 0.330266624964 +1403715394062142976.0000000000 0.2071474629 -1.5672541156 1.7427408841 0.4743964378 0.6730110993 -0.4673833618 0.321802537504 +1403715394112143104.0000000000 0.2122957588 -1.5719373213 1.7414015920 0.4798336755 0.6799598449 -0.4574061837 0.313358957612 +1403715394162142976.0000000000 0.2173346198 -1.5761162550 1.7398554877 0.4848894201 0.6870900884 -0.4458559706 0.306597316022 +1403715394212143104.0000000000 0.2218185534 -1.5796872553 1.7381181136 0.4899757573 0.6942455645 -0.4344570293 0.298653550274 +1403715394262142976.0000000000 0.2257774606 -1.5827930009 1.7361040147 0.4949547084 0.7013456205 -0.4225943823 0.290771637686 +1403715394312143104.0000000000 0.2294105391 -1.5852525815 1.7345698969 0.5011672178 0.7073056731 -0.4106352888 0.28271675599 +1403715394362142976.0000000000 0.2330222633 -1.5872347059 1.7330857677 0.5070169133 0.7133379424 -0.3968512629 0.276752424936 +1403715394412143104.0000000000 0.2360986487 -1.5888329942 1.7319908264 0.5129914459 0.7190702839 -0.3829910293 0.270361932806 +1403715394462142976.0000000000 0.2389371723 -1.5898277231 1.7313519488 0.5193168585 0.7240774729 -0.3683825076 0.265171909989 +1403715394512143104.0000000000 0.2408833618 -1.5903689033 1.7306252006 0.5248514314 0.7292812574 -0.3539889731 0.259560454415 +1403715394562142976.0000000000 0.2416356867 -1.5905050899 1.7299424670 0.5299248771 0.7346398480 -0.3402943427 0.252356253517 +1403715394612143104.0000000000 0.2411041111 -1.5902624142 1.7292179533 0.5349829909 0.7398056995 -0.3274465775 0.243432670931 +1403715394662142976.0000000000 0.2387956280 -1.5898565006 1.7282995265 0.5396676466 0.7450917988 -0.3152249097 0.232873997938 +1403715394712143104.0000000000 0.2351375569 -1.5890667699 1.7271059123 0.5432380917 0.7508748928 -0.3029979553 0.221971867936 +1403715394762142976.0000000000 0.2299403048 -1.5881892888 1.7255742073 0.5455325126 0.7573737143 -0.2908017838 0.210270438183 +1403715394812143104.0000000000 0.2237998063 -1.5872945218 1.7240868310 0.5474296457 0.7638526977 -0.2781876021 0.198649181252 +1403715394862142976.0000000000 0.2169357035 -1.5864473974 1.7227359735 0.5495605673 0.7700206017 -0.2647744999 0.186938278585 +1403715394912143104.0000000000 0.2094170641 -1.5855211475 1.7211825560 0.5512827885 0.7763454353 -0.2502446808 0.175364340745 +1403715394962142976.0000000000 0.2014128818 -1.5841356696 1.7199969151 0.5536451912 0.7819571706 -0.2350319199 0.163645904641 +1403715395012143104.0000000000 0.1930751564 -1.5826416647 1.7185986230 0.5555004973 0.7875204257 -0.2189407023 0.152629438354 +1403715395062142976.0000000000 0.1839904470 -1.5808159374 1.7171326846 0.5578727454 0.7923377328 -0.2025958201 0.141187289694 +1403715395112143104.0000000000 0.1745442844 -1.5784266996 1.7156853176 0.5604196276 0.7964184325 -0.1864833763 0.129890229463 +1403715395162142976.0000000000 0.1648727676 -1.5755175015 1.7140889523 0.5622799956 0.8002729315 -0.1707949558 0.119304336518 +1403715395212143104.0000000000 0.1548370401 -1.5721764342 1.7125385128 0.5635749586 0.8038745991 -0.1569318587 0.107430380577 +1403715395262142976.0000000000 0.1444559287 -1.5684328601 1.7106808959 0.5650837014 0.8067132608 -0.1427217746 0.0975941610001 +1403715395312143104.0000000000 0.1336733411 -1.5639984311 1.7083514320 0.5665483473 0.8090425405 -0.1288737505 0.0886831114404 +1403715395362142976.0000000000 0.1226385571 -1.5592284925 1.7054779610 0.5675086940 0.8111988038 -0.1159763463 0.0802488011342 +1403715395412143104.0000000000 0.1112174533 -1.5542468115 1.7020189265 0.5681985589 0.8131358429 -0.1040476728 0.0716559859462 +1403715395462142976.0000000000 0.0994715692 -1.5488624406 1.6979762635 0.5682235241 0.8151653780 -0.0931525648 0.0628492867129 +1403715395512143104.0000000000 0.0875619332 -1.5430290888 1.6932231419 0.5685291976 0.8166836872 -0.0827237611 0.0543974799147 +1403715395562142976.0000000000 0.0753620082 -1.5366888741 1.6879295839 0.5689469757 0.8178463078 -0.0729165099 0.0459340637123 +1403715395612143104.0000000000 0.0629270273 -1.5299643814 1.6820033932 0.5695982060 0.8185355132 -0.0643984915 0.0375543823157 +1403715395662142976.0000000000 0.0504107954 -1.5226597701 1.6756130190 0.5702796301 0.8190034792 -0.0554509663 0.0306534635699 +1403715395712143104.0000000000 0.0377609002 -1.5149742094 1.6682483756 0.5697251863 0.8201607122 -0.0460115006 0.0251507470302 +1403715395762142976.0000000000 0.0250200772 -1.5063896251 1.6606522828 0.5705244388 0.8202168844 -0.0368138709 0.0197703390423 +1403715395812143104.0000000000 0.0121907282 -1.4970556316 1.6524970133 0.5708735815 0.8204089728 -0.0278572518 0.0160138909735 +1403715395862142976.0000000000 -0.0010686387 -1.4871922490 1.6446239028 0.5710589251 0.8205491535 -0.0221954872 0.00990712470367 +1403715395912143104.0000000000 -0.0144741988 -1.4767012031 1.6366382078 0.5710687724 0.8206851332 -0.0184539749 0.00397746325661 +1403715395962142976.0000000000 -0.0280527655 -1.4654788431 1.6289393951 0.5710522989 0.8207314165 -0.0170819776 -0.00272394542328 +1403715396012143104.0000000000 -0.0416573473 -1.4535385253 1.6214076288 0.5712142714 0.8205638313 -0.0171620982 -0.00973228180265 +1403715396062142976.0000000000 -0.0548164332 -1.4409464236 1.6146419852 0.5719761290 0.8198588071 -0.0193871927 -0.0172910670803 +1403715396112143104.0000000000 -0.0669741905 -1.4283988096 1.6082271354 0.5726361568 0.8191916356 -0.0217927053 -0.0231942669916 +1403715396162142976.0000000000 -0.0777480708 -1.4153908802 1.6022485525 0.5740769515 0.8179887721 -0.0241352748 -0.0273406446487 +1403715396212143104.0000000000 -0.0869093329 -1.4021564218 1.5965221475 0.5752177615 0.8170905331 -0.0255429947 -0.0288988403983 +1403715396262142976.0000000000 -0.0944971363 -1.3887236985 1.5909184489 0.5764701511 0.8162899844 -0.0252066272 -0.0267852971737 +1403715396312143104.0000000000 -0.1005289292 -1.3748086630 1.5851632425 0.5769800091 0.8161440106 -0.0230819295 -0.0216851938928 +1403715396362142976.0000000000 -0.1053898683 -1.3605484405 1.5795923596 0.5781628608 0.8155322177 -0.0200721155 -0.0152321507745 +1403715396412143104.0000000000 -0.1098207599 -1.3464020248 1.5742273519 0.5789118052 0.8151204572 -0.0180201498 -0.0107254974653 +1403715396462142976.0000000000 -0.1138343957 -1.3324514440 1.5684287785 0.5786994439 0.8153775494 -0.0152822610 -0.0057321953667 +1403715396512143104.0000000000 -0.1181181327 -1.3185452089 1.5630037179 0.5792653193 0.8150507893 -0.0117144635 -0.00258305074622 +1403715396562142976.0000000000 -0.1229919894 -1.3045543029 1.5578559342 0.5802462132 0.8143945883 -0.0085338211 -0.00172063615937 +1403715396612143104.0000000000 -0.1284914759 -1.2908801241 1.5524537053 0.5806698858 0.8141260546 -0.0043022741 -0.00165573089376 +1403715396662142976.0000000000 -0.1346749209 -1.2775710947 1.5470240236 0.5821047241 0.8131059750 0.0003890733 -0.00355137634284 +1403715396712143104.0000000000 -0.1413824658 -1.2649087816 1.5408751422 0.5829064235 0.8124988941 0.0047316107 -0.00657725911405 +1403715396762142976.0000000000 -0.1486225402 -1.2527115134 1.5342047940 0.5821301554 0.8129835425 0.0079578848 -0.0109047636507 +1403715396812143104.0000000000 -0.1563299068 -1.2408142277 1.5274131993 0.5809968610 0.8136801847 0.0106097434 -0.0159573774164 +1403715396862142976.0000000000 -0.1642719759 -1.2290558901 1.5201087895 0.5788257243 0.8150926183 0.0135651400 -0.0200197775575 +1403715396912143104.0000000000 -0.1724203025 -1.2174164963 1.5122983855 0.5765512371 0.8165612752 0.0162058331 -0.0235313792839 +1403715396962142976.0000000000 -0.1807280809 -1.2057883215 1.5033568520 0.5719560342 0.8196551325 0.0194168597 -0.0255879711799 +1403715397012143104.0000000000 -0.1890307992 -1.1937266378 1.4939866401 0.5671759212 0.8228312778 0.0212814731 -0.0284123498915 +1403715397062142976.0000000000 -0.1972417759 -1.1811365698 1.4841426906 0.5627006172 0.8257734333 0.0236659565 -0.0301027367848 +1403715397112143104.0000000000 -0.2055621599 -1.1676605388 1.4742947727 0.5594052187 0.8278802207 0.0249151167 -0.0325480943671 +1403715397162142976.0000000000 -0.2141672340 -1.1526553659 1.4644395210 0.5567513527 0.8295155765 0.0249337712 -0.0361959477189 +1403715397212143104.0000000000 -0.2230141183 -1.1362876792 1.4549400206 0.5548521999 0.8305929290 0.0233592684 -0.0413372379976 +1403715397262142976.0000000000 -0.2319091115 -1.1185643785 1.4456181253 0.5531457214 0.8314637735 0.0207453175 -0.0476176017927 +1403715397312143104.0000000000 -0.2403746729 -1.0989588198 1.4369303629 0.5530913596 0.8312183278 0.0175460763 -0.0534619002511 +1403715397362142976.0000000000 -0.2478237505 -1.0777872994 1.4280817151 0.5531757663 0.8309018492 0.0150661599 -0.0580663364615 +1403715397412143104.0000000000 -0.2543356493 -1.0550316637 1.4192919503 0.5532333011 0.8306667976 0.0132774317 -0.0612314930076 +1403715397462142976.0000000000 -0.2596671522 -1.0307747956 1.4107046937 0.5527378457 0.8308201466 0.0122757206 -0.0637813820735 +1403715397512143104.0000000000 -0.2636768842 -1.0049347509 1.4025702190 0.5525244976 0.8308846708 0.0118171341 -0.0648667760611 +1403715397562142976.0000000000 -0.2663218147 -0.9773771319 1.3947851699 0.5534428178 0.8301726625 0.0114020188 -0.0662147405417 +1403715397612143104.0000000000 -0.2673004451 -0.9481405183 1.3880181418 0.5550302628 0.8290249087 0.0109195261 -0.0673785726923 +1403715397662142976.0000000000 -0.2665879220 -0.9174274124 1.3824618766 0.5580511027 0.8270198779 0.0112171627 -0.0670168910902 +1403715397712143104.0000000000 -0.2644039082 -0.8855358096 1.3782025280 0.5627795632 0.8238630280 0.0118647769 -0.0662427467568 +1403715397762142976.0000000000 -0.2608673935 -0.8528581886 1.3746840308 0.5666101545 0.8213813411 0.0128582433 -0.0641894915826 +1403715397812143104.0000000000 -0.2562863687 -0.8197521707 1.3720807241 0.5703091861 0.8189205602 0.0132738213 -0.0627722387786 +1403715397862142976.0000000000 -0.2504249145 -0.7860875837 1.3701193373 0.5730560628 0.8171326916 0.0139806147 -0.06087245451 +1403715397912143104.0000000000 -0.2433719891 -0.7521189656 1.3685116168 0.5758298209 0.8153999364 0.0155135884 -0.0574655521936 +1403715397962142976.0000000000 -0.2354467492 -0.7179576233 1.3677468195 0.5808699739 0.8120229148 0.0167398334 -0.0541168848236 +1403715398012143104.0000000000 -0.2268853775 -0.6838641256 1.3668128436 0.5863362806 0.8083003685 0.0179863782 -0.050366362584 +1403715398062142976.0000000000 -0.2178969865 -0.6504510123 1.3655906046 0.5915212634 0.8046881650 0.0187864644 -0.0471870817109 +1403715398112143104.0000000000 -0.2085946871 -0.6179440384 1.3634873526 0.5957716461 0.8016846302 0.0192477172 -0.0445805435921 +1403715398162142976.0000000000 -0.1991678292 -0.5863816489 1.3608996001 0.5993706920 0.7991236493 0.0195803450 -0.0421043566979 +1403715398212143104.0000000000 -0.1896613600 -0.5564988717 1.3573908831 0.6008191604 0.7981423735 0.0196575649 -0.0399833500707 +1403715398262142976.0000000000 -0.1801316147 -0.5285192164 1.3528633112 0.6002836720 0.7986298570 0.0192128193 -0.0384802819156 +1403715398312143104.0000000000 -0.1704414879 -0.5022682717 1.3474654404 0.5985140997 0.8000581952 0.0190743135 -0.036385811442 +1403715398362142976.0000000000 -0.1606946109 -0.4775530659 1.3417058997 0.5971065462 0.8012121545 0.0187248057 -0.0342379553159 +1403715398412143104.0000000000 -0.1511985618 -0.4539813520 1.3362431428 0.5957754837 0.8022322051 0.0168594189 -0.034508288997 +1403715398462142976.0000000000 -0.1414602789 -0.4316160464 1.3301666266 0.5941924800 0.8035099964 0.0167074605 -0.0320599929484 +1403715398512143104.0000000000 -0.1317499671 -0.4104328523 1.3242135867 0.5931220018 0.8044021707 0.0162800862 -0.0296377712235 +1403715398562142976.0000000000 -0.1223169152 -0.3903501317 1.3186801614 0.5928342355 0.8047095958 0.0162128747 -0.0269662447355 +1403715398612143104.0000000000 -0.1132246579 -0.3713092953 1.3142385161 0.5948542914 0.8032918136 0.0153714796 -0.0251863424419 +1403715398662142976.0000000000 -0.1043678688 -0.3535287375 1.3100304557 0.5975698704 0.8013731552 0.0159768364 -0.021355485992 +1403715398712143104.0000000000 -0.0958520547 -0.3370824626 1.3060868671 0.6011636149 0.7987679172 0.0176171886 -0.0161789156854 +1403715398762142976.0000000000 -0.0879217958 -0.3222201461 1.3024163975 0.6044410943 0.7963441399 0.0194735239 -0.0103805669853 +1403715398812143104.0000000000 -0.0809709864 -0.3094293989 1.2989487634 0.6065930799 0.7947122156 0.0210713933 -0.00577287684191 +1403715398862142976.0000000000 -0.0754917487 -0.2986623024 1.2955779462 0.6078409689 0.7937340707 0.0226132882 -0.00205444468727 +1403715398912143104.0000000000 -0.0716859482 -0.2897882099 1.2924499997 0.6087579321 0.7930045060 0.0236120313 0.000324944482243 +1403715398962142976.0000000000 -0.0696918660 -0.2827940746 1.2897035208 0.6091302466 0.7927086288 0.0239279444 0.000908843727516 +1403715399012143104.0000000000 -0.0691467801 -0.2779383779 1.2875410008 0.6098645132 0.7921252238 0.0245127203 0.00142543584157 +1403715399062142976.0000000000 -0.0702416985 -0.2754247348 1.2858034152 0.6094860896 0.7924238907 0.0243120938 7.82475475027e-05 +1403715399112143104.0000000000 -0.0730253823 -0.2750954883 1.2838908926 0.6078016542 0.7937272982 0.0238263321 -0.00253599060034 +1403715399162142976.0000000000 -0.0774754482 -0.2765555062 1.2822374248 0.6068424384 0.7944746157 0.0225569323 -0.0065973336658 +1403715399212143104.0000000000 -0.0830658739 -0.2798787566 1.2809004897 0.6061642349 0.7949726516 0.0222590762 -0.00937747541908 +1403715399262142976.0000000000 -0.0896927457 -0.2854197889 1.2801370589 0.6063774246 0.7947859803 0.0218140105 -0.0120753216206 +1403715399312143104.0000000000 -0.0970486723 -0.2927902685 1.2788180352 0.6048781136 0.7958907656 0.0228433169 -0.0125912553983 +1403715399362142976.0000000000 -0.1051363336 -0.3018796955 1.2774107572 0.6024033975 0.7977361639 0.0238486150 -0.0125858266716 +1403715399412143104.0000000000 -0.1141178256 -0.3125026317 1.2757938316 0.5987999865 0.8004055074 0.0254593774 -0.011892016547 +1403715399462142976.0000000000 -0.1240307955 -0.3243346997 1.2745922937 0.5963013998 0.8022348058 0.0268689055 -0.0110462131035 +1403715399512143104.0000000000 -0.1347892558 -0.3370575557 1.2735826632 0.5949515819 0.8032047783 0.0286806629 -0.00849228566275 +1403715399562142976.0000000000 -0.1468316046 -0.3513580323 1.2718820011 0.5899099073 0.8068975273 0.0294455864 -0.0074591687532 +1403715399612143104.0000000000 -0.1605368665 -0.3665592966 1.2701965171 0.5828864754 0.8120319496 0.0271781266 -0.0104316402941 +1403715399662142976.0000000000 -0.1753970945 -0.3822070526 1.2688140562 0.5762678238 0.8167776425 0.0248785269 -0.0130666329317 +1403715399712143104.0000000000 -0.1914027133 -0.3975961043 1.2677895054 0.5703635467 0.8209407904 0.0224697905 -0.0153867419425 +1403715399762142976.0000000000 -0.2081068615 -0.4121307096 1.2677736820 0.5660098749 0.8239777934 0.0206379104 -0.0163552489655 +1403715399812143104.0000000000 -0.2253814239 -0.4258340982 1.2686552187 0.5631124501 0.8259908014 0.0189644420 -0.0168497634362 +1403715399862142976.0000000000 -0.2432617753 -0.4390278246 1.2699245411 0.5610326942 0.8274282197 0.0180290812 -0.0167275077258 +1403715399912143104.0000000000 -0.2617357534 -0.4513412854 1.2716839989 0.5592789546 0.8286442795 0.0173692510 -0.0159379489018 +1403715399962142976.0000000000 -0.2806901738 -0.4622528087 1.2738684031 0.5579726524 0.8295872891 0.0161016399 -0.013863120581 +1403715400012143104.0000000000 -0.3001407837 -0.4717947683 1.2768595771 0.5579008998 0.8297258009 0.0140869206 -0.0101607062021 +1403715400062142976.0000000000 -0.3203730056 -0.4798670005 1.2805803731 0.5589877903 0.8290805480 0.0110864970 -0.0059316785701 +1403715400112143104.0000000000 -0.3415410885 -0.4864065122 1.2844100924 0.5603135366 0.8282472269 0.0073967842 -0.00074791952283 +1403715400162142976.0000000000 -0.3635128282 -0.4919060512 1.2883774306 0.5612436706 0.8276374147 0.0019080552 0.00426747121119 +1403715400212143104.0000000000 -0.3864017306 -0.4962175739 1.2925270208 0.5622329206 0.8268999729 -0.0038913921 0.0107440665594 +1403715400262142976.0000000000 -0.4102678881 -0.4994499114 1.2966603467 0.5621642833 0.8267342800 -0.0084109172 0.0202732668127 +1403715400312143104.0000000000 -0.4354300164 -0.5016409296 1.3010004215 0.5617470746 0.8266694266 -0.0145213032 0.0291035225262 +1403715400362142976.0000000000 -0.4620926036 -0.5028671528 1.3049121446 0.5614220572 0.8263628458 -0.0212298075 0.0384579784928 +1403715400412143104.0000000000 -0.4903601130 -0.5033340145 1.3084475768 0.5601329870 0.8265552533 -0.0296449861 0.0466757414785 +1403715400462142976.0000000000 -0.5203840778 -0.5026987908 1.3121900753 0.5596152254 0.8260884935 -0.0406008154 0.0525373606333 +1403715400512143104.0000000000 -0.5520427275 -0.5009633030 1.3157997983 0.5585383778 0.8257850007 -0.0533745409 0.0571416793933 +1403715400562142976.0000000000 -0.5851451106 -0.4980935995 1.3187803861 0.5567578242 0.8256599029 -0.0668778490 0.0619177138256 +1403715400612143104.0000000000 -0.6193473147 -0.4942213787 1.3214205797 0.5550775908 0.8251157544 -0.0818796793 0.0660952206003 +1403715400662142976.0000000000 -0.6542601202 -0.4894379049 1.3232968841 0.5523412504 0.8248847299 -0.0970987648 0.0711066479158 +1403715400712143104.0000000000 -0.6896669235 -0.4833458562 1.3245670912 0.5498192206 0.8240958479 -0.1123234863 0.077125174551 +1403715400762142976.0000000000 -0.7254634491 -0.4759467442 1.3253723892 0.5470232728 0.8231212143 -0.1281539791 0.0825443106875 +1403715400812143104.0000000000 -0.7616228007 -0.4671316741 1.3260296632 0.5456794860 0.8208087573 -0.1446668865 0.0870538593184 +1403715400862142976.0000000000 -0.7977203739 -0.4569918338 1.3262271503 0.5447443171 0.8178546603 -0.1613695120 0.0912538449837 +1403715400912143104.0000000000 -0.8338401839 -0.4457287586 1.3253693988 0.5420104338 0.8161789930 -0.1763464534 0.0947547854313 +1403715400962142976.0000000000 -0.8697184218 -0.4331691070 1.3240041217 0.5392451295 0.8147770772 -0.1894588744 0.0972539955875 +1403715401012143104.0000000000 -0.9047834843 -0.4194755523 1.3227565650 0.5364815831 0.8135611193 -0.2010215165 0.0994794750248 +1403715401062142976.0000000000 -0.9386755555 -0.4046706284 1.3215470496 0.5328967294 0.8133926901 -0.2093672428 0.102853124573 +1403715401112143104.0000000000 -0.9711344291 -0.3887696422 1.3211129290 0.5309575329 0.8125338481 -0.2159391673 0.106033578984 +1403715401162142976.0000000000 -1.0021979386 -0.3714470826 1.3210167480 0.5284952823 0.8123274286 -0.2204379314 0.110562216794 +1403715401212143104.0000000000 -1.0317435523 -0.3527107728 1.3213492534 0.5261653423 0.8124934853 -0.2226600236 0.115874426938 +1403715401262142976.0000000000 -1.0597156663 -0.3320627271 1.3220693576 0.5240370346 0.8128784168 -0.2234515451 0.121174555084 +1403715401312143104.0000000000 -1.0867231033 -0.3094643519 1.3231477038 0.5225639412 0.8128873272 -0.2242407662 0.125925372118 +1403715401362142976.0000000000 -1.1129485365 -0.2843954577 1.3254130886 0.5235855537 0.8115019665 -0.2252798914 0.128731102881 +1403715401412143104.0000000000 -1.1383974208 -0.2568732773 1.3286863625 0.5252874444 0.8098730344 -0.2261263810 0.130558908783 +1403715401462142976.0000000000 -1.1626109650 -0.2275895532 1.3321971702 0.5272364320 0.8082423771 -0.2262963218 0.132498978559 +1403715401512143104.0000000000 -1.1856195836 -0.1966578808 1.3364527231 0.5304979294 0.8058478884 -0.2269522424 0.132942872484 +1403715401562142976.0000000000 -1.2076651251 -0.1649054109 1.3412688564 0.5335463285 0.8035428519 -0.2283982373 0.132217418271 +1403715401612143104.0000000000 -1.2284822349 -0.1322535715 1.3472500819 0.5388740411 0.7998082719 -0.2296552986 0.131072269399 +1403715401662142976.0000000000 -1.2480931783 -0.0990348194 1.3532768730 0.5429451642 0.7966771138 -0.2311141989 0.130775961383 +1403715401712143104.0000000000 -1.2664279556 -0.0646493101 1.3600232513 0.5489202100 0.7915514823 -0.2357565864 0.128653355197 +1403715401762142976.0000000000 -1.2834996144 -0.0297205251 1.3664790370 0.5540604033 0.7863433809 -0.2426416718 0.125722614817 +1403715401812143104.0000000000 -1.2987781592 0.0049544262 1.3724802006 0.5571220791 0.7824921611 -0.2475367016 0.126675128765 +1403715401862142976.0000000000 -1.3125665481 0.0385885465 1.3784591505 0.5588225257 0.7795069795 -0.2522173215 0.128345924853 +1403715401912143104.0000000000 -1.3252326333 0.0712554165 1.3835991245 0.5587402361 0.7785301651 -0.2531882789 0.132649259483 +1403715401962142976.0000000000 -1.3365495221 0.1030969820 1.3878796414 0.5578401676 0.7785714900 -0.2518746726 0.138563818024 +1403715402012143104.0000000000 -1.3472188297 0.1339432913 1.3916747253 0.5569865657 0.7788504019 -0.2497493421 0.144164084176 +1403715402062142976.0000000000 -1.3572355382 0.1646738110 1.3956974936 0.5558853920 0.7795593658 -0.2473421966 0.14866224761 +1403715402112143104.0000000000 -1.3666305542 0.1955612125 1.4000021303 0.5583556715 0.7778948722 -0.2449306515 0.152077243061 +1403715402162142976.0000000000 -1.3755059559 0.2257943449 1.4047177951 0.5647661100 0.7732440497 -0.2421175788 0.156562954589 +1403715402212143104.0000000000 -1.3843962042 0.2552597328 1.4089804468 0.5698321908 0.7690778438 -0.2412999302 0.159952768488 +1403715402262142976.0000000000 -1.3933677761 0.2833192226 1.4124188414 0.5725899125 0.7661746503 -0.2420124623 0.162933008939 +1403715402312143104.0000000000 -1.4024989128 0.3096007579 1.4141889492 0.5707530930 0.7663637328 -0.2427899900 0.167273897053 +1403715402362142976.0000000000 -1.4117066287 0.3344799616 1.4151057126 0.5660379031 0.7680522025 -0.2446831048 0.172705195846 +1403715402412143104.0000000000 -1.4208875050 0.3584468865 1.4160421647 0.5623341232 0.7682526276 -0.2475506968 0.179685521507 +1403715402462142976.0000000000 -1.4303121652 0.3815063602 1.4165012434 0.5587449092 0.7676658860 -0.2509140923 0.188508175499 +1403715402512143104.0000000000 -1.4404324103 0.4044048514 1.4171030626 0.5571532143 0.7654426224 -0.2532816354 0.198812224903 +1403715402562142976.0000000000 -1.4518660991 0.4271998376 1.4179251698 0.5556097285 0.7636278257 -0.2562728060 0.206142238191 +1403715402612143104.0000000000 -1.4645621380 0.4498953580 1.4191240990 0.5561254331 0.7606012404 -0.2587288263 0.212766656718 +1403715402662142976.0000000000 -1.4789129581 0.4724768324 1.4198158075 0.5559423391 0.7583710512 -0.2611891828 0.218132242138 +1403715402712143104.0000000000 -1.4953274049 0.4950629260 1.4204086362 0.5561259501 0.7562708684 -0.2642760794 0.221215856344 +1403715402762142976.0000000000 -1.5141702532 0.5174349353 1.4207977691 0.5544448950 0.7559478639 -0.2714412907 0.217837809241 +1403715402812143104.0000000000 -1.5348551404 0.5392063075 1.4212606897 0.5533154640 0.7554484179 -0.2785997156 0.213358580194 +1403715402862142976.0000000000 -1.5568761311 0.5604735338 1.4216040664 0.5521821590 0.7551920381 -0.2853188070 0.208261919923 +1403715402912143104.0000000000 -1.5796788210 0.5814200018 1.4216921475 0.5507508950 0.7551420010 -0.2919439460 0.202984586558 +1403715402962142976.0000000000 -1.6028973577 0.6021214269 1.4216648124 0.5477849511 0.7561809612 -0.2983428364 0.197771467185 +1403715403012143104.0000000000 -1.6260222780 0.6225927607 1.4217793901 0.5440875062 0.7578678976 -0.3048961944 0.191424517948 +1403715403062142976.0000000000 -1.6483442512 0.6423938654 1.4218123403 0.5385863395 0.7608507090 -0.3099629776 0.186959637263 +1403715403112143104.0000000000 -1.6694391888 0.6619503795 1.4223888973 0.5338917954 0.7633363471 -0.3145870775 0.182516143733 +1403715403162142976.0000000000 -1.6891095982 0.6811571997 1.4232647579 0.5296354060 0.7657663278 -0.3178810605 0.178996925062 +1403715403212143104.0000000000 -1.7068999669 0.7006425658 1.4254067369 0.5268831444 0.7671160817 -0.3205738543 0.176520461076 +1403715403262142976.0000000000 -1.7225988272 0.7203611532 1.4276097128 0.5238335634 0.7691965864 -0.3202921599 0.177053499508 +1403715403312143104.0000000000 -1.7364523114 0.7405250716 1.4299600291 0.5223469284 0.7703823092 -0.3187846871 0.179000299629 +1403715403362142976.0000000000 -1.7484817909 0.7609121229 1.4326374890 0.5218741146 0.7705130750 -0.3174042757 0.182240323698 +1403715403412143104.0000000000 -1.7584497756 0.7818532514 1.4355131754 0.5216806238 0.7698842145 -0.3170601456 0.186012061796 +1403715403462142976.0000000000 -1.7664627074 0.8034230147 1.4387499755 0.5216266732 0.7685094334 -0.3180572815 0.190101105339 +1403715403512143104.0000000000 -1.7725571329 0.8256628604 1.4421149330 0.5217741330 0.7660812008 -0.3208183389 0.194799746517 +1403715403562142976.0000000000 -1.7772349084 0.8485619059 1.4452075555 0.5214317447 0.7631791998 -0.3257508395 0.198878946097 +1403715403612143104.0000000000 -1.7807014569 0.8718802350 1.4475371445 0.5190277942 0.7609657853 -0.3320593536 0.203169407482 +1403715403662142976.0000000000 -1.7831079490 0.8954979930 1.4494385868 0.5161794277 0.7584526547 -0.3392609908 0.207870991797 +1403715403712143104.0000000000 -1.7844566224 0.9195177529 1.4506018159 0.5118622912 0.7564242184 -0.3480194473 0.211428146202 +1403715403762142976.0000000000 -1.7844189529 0.9440640796 1.4519313539 0.5078255465 0.7535825283 -0.3583242278 0.214080207194 +1403715403812143104.0000000000 -1.7825106652 0.9693785734 1.4536508844 0.5045121973 0.7497920338 -0.3688866803 0.217260134326 +1403715403862142976.0000000000 -1.7786233875 0.9951915870 1.4559628252 0.5017396238 0.7453490806 -0.3790167573 0.221491299395 +1403715403912143104.0000000000 -1.7727550169 1.0212410246 1.4582507478 0.4984575069 0.7410157700 -0.3887448425 0.226524148607 +1403715403962142976.0000000000 -1.7648005572 1.0477876388 1.4608487211 0.4956734755 0.7361806852 -0.3982460610 0.23183157516 +1403715404012143104.0000000000 -1.7550341297 1.0744276239 1.4637361808 0.4929398051 0.7312833916 -0.4065392407 0.238664609035 +1403715404062142976.0000000000 -1.7433779913 1.1009834020 1.4675653104 0.4918386013 0.7250499790 -0.4138689355 0.247204009785 +1403715404112143104.0000000000 -1.7301309033 1.1276184158 1.4714719959 0.4901107238 0.7193315222 -0.4200660639 0.256706333183 +1403715404162142976.0000000000 -1.7153382195 1.1543299456 1.4751887913 0.4876216015 0.7140143793 -0.4242705245 0.269078356555 +1403715404212143104.0000000000 -1.6995568392 1.1812968647 1.4786912486 0.4847202166 0.7090038652 -0.4288197143 0.280131189634 +1403715404262142976.0000000000 -1.6833992433 1.2088540313 1.4816462161 0.4818339684 0.7047513553 -0.4317761921 0.291085681468 +1403715404312143104.0000000000 -1.6669407952 1.2372472038 1.4836337823 0.4781173338 0.7016753361 -0.4343801675 0.300615049316 +1403715404362142976.0000000000 -1.6508278295 1.2666937639 1.4854041030 0.4753106931 0.6989988604 -0.4375926454 0.306582802599 +1403715404412143104.0000000000 -1.6348505304 1.2969820844 1.4867601278 0.4728552983 0.6967348976 -0.4396427394 0.312542174824 +1403715404462142976.0000000000 -1.6190960735 1.3284934519 1.4881332406 0.4721778778 0.6939655204 -0.4416168954 0.316913909277 +1403715404512143104.0000000000 -1.6036235794 1.3610374242 1.4888963759 0.4712876560 0.6920914010 -0.4423859530 0.321235282267 +1403715404562142976.0000000000 -1.5887147454 1.3945949995 1.4890442172 0.4711443021 0.6902955009 -0.4431709559 0.324213929234 +1403715404612143104.0000000000 -1.5747663417 1.4290850499 1.4881744143 0.4718407555 0.6882486203 -0.4443061933 0.325994086933 +1403715404662142976.0000000000 -1.5614207194 1.4649719417 1.4869461616 0.4745744928 0.6853980112 -0.4468752483 0.324516763182 +1403715404712143104.0000000000 -1.5487731246 1.5013671443 1.4852094983 0.4772399333 0.6828351549 -0.4488242368 0.323318730983 +1403715404762142976.0000000000 -1.5366534871 1.5384203432 1.4834545626 0.4810339004 0.6796019499 -0.4513275281 0.321015636261 +1403715404812143104.0000000000 -1.5248912746 1.5754373843 1.4809590028 0.4824737982 0.6774473157 -0.4542210611 0.319323340953 +1403715404862142976.0000000000 -1.5130174871 1.6123061284 1.4780547985 0.4827250200 0.6749149170 -0.4578610742 0.319107578317 +1403715404912143104.0000000000 -1.5013888366 1.6491095359 1.4749020571 0.4833228649 0.6712801560 -0.4618376974 0.320137316974 +1403715404962142976.0000000000 -1.4899304804 1.6855784541 1.4715884959 0.4840063889 0.6664078292 -0.4669609478 0.32184762526 +1403715405012143104.0000000000 -1.4783727419 1.7213708286 1.4681911678 0.4846593535 0.6604110775 -0.4730230594 0.32436353848 +1403715405062142976.0000000000 -1.4671631933 1.7563095688 1.4647384960 0.4844395507 0.6537105340 -0.4805940307 0.327124192206 +1403715405112143104.0000000000 -1.4566662939 1.7903112725 1.4612900173 0.4839111115 0.6459907656 -0.4901048315 0.329124932229 +1403715405162142976.0000000000 -1.4466324078 1.8227712242 1.4573746890 0.4809246381 0.6384941967 -0.5007944479 0.332026466156 +1403715405212143104.0000000000 -1.4370409146 1.8535401046 1.4533314953 0.4766428073 0.6305779417 -0.5123887202 0.335620161843 +1403715405262142976.0000000000 -1.4276803344 1.8828076387 1.4489426849 0.4714336039 0.6222508108 -0.5243229836 0.340058369272 +1403715405312143104.0000000000 -1.4183197879 1.9103049735 1.4443193529 0.4647103194 0.6143238561 -0.5355027047 0.346247559056 +1403715405362142976.0000000000 -1.4089206380 1.9362637939 1.4396490943 0.4572952307 0.6065393519 -0.5463162080 0.352887641443 +1403715405412143104.0000000000 -1.3996806097 1.9605902664 1.4348358745 0.4487831391 0.5992573101 -0.5566758954 0.359994885875 +1403715405462142976.0000000000 -1.3904624305 1.9837400597 1.4301092706 0.4406370502 0.5914448238 -0.5674992403 0.36602817191 +1403715405512143104.0000000000 -1.3811526836 2.0054742742 1.4256828598 0.4328564140 0.5829816487 -0.5779858012 0.372424671249 +1403715405562142976.0000000000 -1.3717846735 2.0259916559 1.4213863915 0.4247804793 0.5744501459 -0.5880877008 0.379106093811 +1403715405612143104.0000000000 -1.3624268757 2.0450505860 1.4168449992 0.4150096619 0.5671053511 -0.5968212609 0.387250414733 +1403715405662142976.0000000000 -1.3527880711 2.0631942053 1.4119358515 0.4037271346 0.5610041159 -0.6050637730 0.395191869017 +1403715405712143104.0000000000 -1.3426648026 2.0809374737 1.4072110167 0.3932656328 0.5545699636 -0.6132852649 0.402088897333 +1403715405762142976.0000000000 -1.3318886837 2.0982476123 1.4027098649 0.3831915780 0.5479133095 -0.6210265178 0.409000347343 +1403715405812143104.0000000000 -1.3207887061 2.1154053063 1.3979856566 0.3735872389 0.5408570733 -0.6295876847 0.414156429975 +1403715405862142976.0000000000 -1.3087653470 2.1322781831 1.3933602976 0.3643219755 0.5334590901 -0.6377999395 0.419406884183 +1403715405912143104.0000000000 -1.2959767564 2.1491866563 1.3887289232 0.3575761177 0.5235893770 -0.6461943265 0.424766261333 +1403715405962142976.0000000000 -1.2819291337 2.1657831640 1.3840779730 0.3523154837 0.5124058929 -0.6535432758 0.4315034037 +1403715406012143104.0000000000 -1.2667106050 2.1819302566 1.3795073876 0.3473474016 0.5004894801 -0.6598036034 0.439908249261 +1403715406062142976.0000000000 -1.2509337401 2.1980837936 1.3744601562 0.3427340528 0.4878316317 -0.6665898827 0.447450104972 +1403715406112143104.0000000000 -1.2348652874 2.2137265987 1.3685048780 0.3369727575 0.4760961897 -0.6730068878 0.454800514236 +1403715406162142976.0000000000 -1.2187167764 2.2293123929 1.3616273984 0.3313302594 0.4641268770 -0.6799458487 0.460955685579 +1403715406212143104.0000000000 -1.2023972513 2.2445752701 1.3542688444 0.3256350452 0.4521651153 -0.6870338000 0.466361537364 +1403715406262142976.0000000000 -1.1862514055 2.2595833777 1.3461741299 0.3188258633 0.4411246210 -0.6939332920 0.471397628119 +1403715406312143104.0000000000 -1.1699784742 2.2744329862 1.3378204111 0.3121802852 0.4301955695 -0.7010213998 0.475441098974 +1403715406362142976.0000000000 -1.1539754676 2.2892645005 1.3290453586 0.3062501373 0.4190075183 -0.7090039982 0.477448304592 +1403715406412143104.0000000000 -1.1377697849 2.3033745865 1.3198896307 0.2998892333 0.4081702432 -0.7168932627 0.479090336184 +1403715406462142976.0000000000 -1.1212924746 2.3167867650 1.3105729106 0.2950195427 0.3962970787 -0.7250698916 0.479776767973 +1403715406512143104.0000000000 -1.1049315483 2.3294810042 1.3008096067 0.2886158743 0.3856416700 -0.7324337496 0.48116751961 +1403715406562142976.0000000000 -1.0885453566 2.3414005425 1.2906834127 0.2826396688 0.3746469678 -0.7394986889 0.482593158136 +1403715406612143104.0000000000 -1.0723899957 2.3521726852 1.2805699312 0.2766596556 0.3638185109 -0.7455675477 0.484999544136 +1403715406662142976.0000000000 -1.0563496953 2.3616284210 1.2707544641 0.2704656756 0.3532623294 -0.7509215032 0.488027602724 +1403715406712143104.0000000000 -1.0403226519 2.3695651495 1.2606537365 0.2641921695 0.3430336407 -0.7557333171 0.49132226933 +1403715406762142976.0000000000 -1.0242705791 2.3759042218 1.2500575571 0.2566627749 0.3333937173 -0.7595249304 0.49607935794 +1403715406812143104.0000000000 -1.0085133378 2.3811250245 1.2396474207 0.2492798840 0.3234802351 -0.7631111820 0.500880625419 +1403715406862142976.0000000000 -0.9928785486 2.3851705190 1.2295563891 0.2413356467 0.3138602095 -0.7665923715 0.505554161755 +1403715406912143104.0000000000 -0.9773135251 2.3883649928 1.2198448284 0.2331979812 0.3045184027 -0.7701895287 0.509603114101 +1403715406962142976.0000000000 -0.9618405784 2.3906730049 1.2108253615 0.2250823842 0.2950147888 -0.7733783933 0.513994217319 +1403715407012143104.0000000000 -0.9463219125 2.3923154165 1.2023559817 0.2175953230 0.2854681984 -0.7771514883 0.516909805835 +1403715407062142976.0000000000 -0.9305398356 2.3929280321 1.1944075220 0.2107409192 0.2755154249 -0.7814407267 0.518680929156 +1403715407112143104.0000000000 -0.9150855398 2.3927588108 1.1864099211 0.2036744771 0.2658250947 -0.7859345830 0.519769715909 +1403715407162142976.0000000000 -0.8998023799 2.3920750092 1.1783119987 0.1967276525 0.2569916155 -0.7906320197 0.519763936503 +1403715407212143104.0000000000 -0.8847427589 2.3911004712 1.1703862373 0.1895180876 0.2503653855 -0.7959330885 0.51758147854 +1403715407262142976.0000000000 -0.8692874016 2.3890434187 1.1631482926 0.1831747050 0.2448806915 -0.8010783923 0.514542402252 +1403715407312143104.0000000000 -0.8534088133 2.3860340077 1.1559163161 0.1765868309 0.2416016923 -0.8056182022 0.511297394589 +1403715407362142976.0000000000 -0.8365478393 2.3814234006 1.1500643207 0.1717240217 0.2385273510 -0.8088389203 0.509308515738 +1403715407412143104.0000000000 -0.8186419355 2.3748080440 1.1450461432 0.1680043462 0.2361396177 -0.8105581638 0.508928367954 +1403715407462142976.0000000000 -0.7994624749 2.3662582101 1.1411835370 0.1661907587 0.2336098670 -0.8105006266 0.510779596333 +1403715407512143104.0000000000 -0.7795729841 2.3557440792 1.1379961474 0.1637497159 0.2322772286 -0.8101447184 0.512736633087 +1403715407562142976.0000000000 -0.7584754720 2.3438300643 1.1356086187 0.1635709383 0.2301025063 -0.8094574886 0.514855279514 +1403715407612143104.0000000000 -0.7366839928 2.3306276958 1.1340843510 0.1626712467 0.2292095819 -0.8079071062 0.517964420471 +1403715407662142976.0000000000 -0.7142272660 2.3161673618 1.1335062565 0.1605134502 0.2299617666 -0.8055344356 0.521983995141 +1403715407712143104.0000000000 -0.6909824492 2.3007873584 1.1337042782 0.1572702609 0.2324489760 -0.8017317869 0.527692789928 +1403715407762142976.0000000000 -0.6666819203 2.2848030550 1.1348279959 0.1546384458 0.2350371913 -0.7985686495 0.532102040801 +1403715407812143104.0000000000 -0.6415585724 2.2685890336 1.1362060514 0.1529512686 0.2373387871 -0.7964776831 0.534695717033 +1403715407862142976.0000000000 -0.6155146785 2.2523334604 1.1374478245 0.1521148347 0.2389944266 -0.7946952177 0.536844718835 +1403715407912143104.0000000000 -0.5880858288 2.2361996962 1.1390549811 0.1542449156 0.2386215548 -0.7938254661 0.537688933223 +1403715407962142976.0000000000 -0.5599619700 2.2201038021 1.1418760488 0.1553035966 0.2389282444 -0.7935791305 0.537611616782 +1403715408012143104.0000000000 -0.5308233455 2.2039311703 1.1473008981 0.1588218836 0.2369586167 -0.7931801494 0.538044118857 +1403715408062142976.0000000000 -0.5014536586 2.1880287049 1.1548441390 0.1605376709 0.2364259396 -0.7933452827 0.537525528452 +1403715408112143104.0000000000 -0.4715837403 2.1721598049 1.1659074442 0.1627954845 0.2354709610 -0.7930860545 0.537648181324 +1403715408162142976.0000000000 -0.4414604509 2.1559125190 1.1804478555 0.1651796153 0.2347683492 -0.7927289060 0.537754961445 +1403715408212143104.0000000000 -0.4110669100 2.1393369667 1.1977878112 0.1675997868 0.2339732883 -0.7919767506 0.538460433364 +1403715408262142976.0000000000 -0.3806408945 2.1224350714 1.2155810381 0.1687011233 0.2339344825 -0.7915339016 0.538784438787 +1403715408312143104.0000000000 -0.3501048496 2.1055400269 1.2326685533 0.1704019743 0.2335222160 -0.7914276362 0.53858410535 +1403715408362142976.0000000000 -0.3192449210 2.0883561452 1.2477770775 0.1717680617 0.2331952013 -0.7908410610 0.539153176141 +1403715408412143104.0000000000 -0.2879986915 2.0709969437 1.2603137701 0.1742583945 0.2332101581 -0.7890769123 0.540929441429 +1403715408462142976.0000000000 -0.2567970035 2.0540324797 1.2691729477 0.1767623812 0.2346137046 -0.7863184642 0.543520692325 +1403715408512143104.0000000000 -0.2255866784 2.0374866038 1.2747073893 0.1814456514 0.2366441625 -0.7825739322 0.54649341861 +1403715408562142976.0000000000 -0.1947341740 2.0216174326 1.2763811889 0.1857446969 0.2407451882 -0.7785839817 0.548951405231 +1403715408612143104.0000000000 -0.1640507901 2.0062929124 1.2753004154 0.1918131054 0.2451267607 -0.7735827897 0.551987564391 +1403715408662142976.0000000000 -0.1340263023 1.9916397897 1.2719840877 0.1965326904 0.2521528006 -0.7680629906 0.55486314459 +1403715408712143104.0000000000 -0.1049708063 1.9783331871 1.2683009959 0.2028141240 0.2595073944 -0.7628808012 0.55635890083 +1403715408762142976.0000000000 -0.0769997058 1.9664747200 1.2647013474 0.2101673350 0.2676409715 -0.7581481892 0.556245741406 +1403715408812143104.0000000000 -0.0500440980 1.9556827049 1.2617259023 0.2173937971 0.2770742859 -0.7531808386 0.555597337555 +1403715408862142976.0000000000 -0.0239577494 1.9463472445 1.2593717845 0.2254826943 0.2868899183 -0.7490347993 0.552990595549 +1403715408912143104.0000000000 0.0008748077 1.9382513103 1.2578263019 0.2338488966 0.2974314735 -0.7446243997 0.549894276628 +1403715408962142976.0000000000 0.0247051509 1.9316273974 1.2568228420 0.2417313030 0.3088840821 -0.7399664987 0.54644869999 +1403715409012143104.0000000000 0.0473521824 1.9260319852 1.2567905255 0.2507677505 0.3200376646 -0.7346627441 0.543104116183 +1403715409062142976.0000000000 0.0686369147 1.9216600040 1.2575809061 0.2590929988 0.3318039168 -0.7295125093 0.539062591567 +1403715409112143104.0000000000 0.0885127788 1.9183908244 1.2600715544 0.2690210208 0.3421588206 -0.7246850380 0.534215899675 +1403715409162142976.0000000000 0.1067315320 1.9156255121 1.2630962188 0.2790177623 0.3507853325 -0.7205450959 0.529068524435 +1403715409212143104.0000000000 0.1232636967 1.9132291628 1.2667494125 0.2868950927 0.3591542481 -0.7173015639 0.523619994124 +1403715409262142976.0000000000 0.1382895893 1.9110474668 1.2710677215 0.2925401038 0.3665455568 -0.7154486966 0.517878175825 +1403715409312143104.0000000000 0.1520842033 1.9089848585 1.2767326871 0.2980294303 0.3723000939 -0.7135644648 0.513222031178 +1403715409362142976.0000000000 0.1646129924 1.9067292220 1.2832822037 0.3021227593 0.3772696764 -0.7114857158 0.510075980472 +1403715409412143104.0000000000 0.1756161137 1.9041394931 1.2905551588 0.3046418559 0.3814997883 -0.7093738766 0.508369899165 +1403715409462142976.0000000000 0.1851823529 1.9013747986 1.2985342481 0.3055660373 0.3854828077 -0.7068061591 0.508387111632 +1403715409512143104.0000000000 0.1936027573 1.8985124227 1.3072877913 0.3047291470 0.3891143995 -0.7038867205 0.510170183139 +1403715409562142976.0000000000 0.2006736727 1.8954973395 1.3159924859 0.3007756979 0.3922533296 -0.7029803391 0.511360878161 +1403715409612143104.0000000000 0.2069576729 1.8929866389 1.3251183722 0.2979796575 0.3926633218 -0.7054710842 0.509248651306 +1403715409662142976.0000000000 0.2126145014 1.8911226404 1.3346489850 0.2955473496 0.3924918820 -0.7084060017 0.506717696105 +1403715409712143104.0000000000 0.2176219723 1.8894841811 1.3442605115 0.2927823527 0.3922199229 -0.7124980110 0.50278087715 +1403715409762142976.0000000000 0.2221825243 1.8878792138 1.3541150746 0.2893347568 0.3919870051 -0.7167620926 0.498882440074 +1403715409812143104.0000000000 0.2268216498 1.8862052919 1.3642298356 0.2856621125 0.3917924255 -0.7210268613 0.494991028195 +1403715409862142976.0000000000 0.2316667301 1.8844315010 1.3749921666 0.2819920317 0.3910814945 -0.7248455783 0.492071789918 +1403715409912143104.0000000000 0.2369696182 1.8825517360 1.3856466855 0.2783161676 0.3901900415 -0.7295318466 0.487929428495 +1403715409962142976.0000000000 0.2430024606 1.8801793818 1.3963186049 0.2744888783 0.3897016384 -0.7331329471 0.485082024572 +1403715410012143104.0000000000 0.2500526230 1.8772102515 1.4072446616 0.2718894697 0.3881933639 -0.7363772349 0.482835993292 +1403715410062142976.0000000000 0.2583681939 1.8735165205 1.4185095738 0.2701421250 0.3865025252 -0.7381356684 0.482488098593 +1403715410112143104.0000000000 0.2681548504 1.8687647272 1.4302637096 0.2694150879 0.3841501836 -0.7379509637 0.485048989383 +1403715410162142976.0000000000 0.2789932577 1.8631461229 1.4416215175 0.2693496602 0.3819413385 -0.7359519370 0.489843159555 +1403715410212143104.0000000000 0.2904734989 1.8571594291 1.4508234962 0.2703482089 0.3793615424 -0.7341286749 0.494015945844 +1403715410262142976.0000000000 0.3024472036 1.8510996312 1.4567017874 0.2712612532 0.3770375956 -0.7322198154 0.498110556009 +1403715410312143104.0000000000 0.3149752715 1.8450592266 1.4591599209 0.2717817890 0.3753148230 -0.7305742820 0.501532313307 +1403715410362142976.0000000000 0.3277874629 1.8394953214 1.4586513644 0.2722690828 0.3742166184 -0.7292332657 0.504034039761 +1403715410412143104.0000000000 0.3410026686 1.8340039462 1.4565680908 0.2715578802 0.3741617254 -0.7282328160 0.505901459393 +1403715410462142976.0000000000 0.3539894092 1.8288038652 1.4534691318 0.2698727050 0.3752074508 -0.7273744055 0.507261832004 +1403715410512143104.0000000000 0.3668917180 1.8238851120 1.4501434808 0.2669178740 0.3773645670 -0.7262924807 0.508773097394 +1403715410562142976.0000000000 0.3802281358 1.8194815358 1.4473569864 0.2647798336 0.3792008701 -0.7247845572 0.510671798258 +1403715410612143104.0000000000 0.3941972600 1.8159213830 1.4444127834 0.2636979331 0.3808942215 -0.7241464865 0.5108765587 +1403715410662142976.0000000000 0.4087628765 1.8129765191 1.4417701310 0.2635922470 0.3819270320 -0.7231870644 0.511518659884 +1403715410712143104.0000000000 0.4238131132 1.8107619882 1.4393482083 0.2652909681 0.3818588613 -0.7227260845 0.511342858543 +1403715410762142976.0000000000 0.4393151544 1.8089101185 1.4377227486 0.2686960982 0.3808994778 -0.7205002735 0.513417325885 +1403715410812143104.0000000000 0.4550400192 1.8077021839 1.4368872491 0.2743134055 0.3783604483 -0.7170477549 0.517144122937 +1403715410862142976.0000000000 0.4702235594 1.8071388428 1.4356040490 0.2781559925 0.3773971491 -0.7131800343 0.521128462441 +1403715410912143104.0000000000 0.4846270504 1.8077679373 1.4337934258 0.2827600053 0.3762447926 -0.7110926073 0.522335083347 +1403715410962142976.0000000000 0.4979211664 1.8094172435 1.4308289349 0.2837862584 0.3777119042 -0.7103010416 0.521796423155 +1403715411012143104.0000000000 0.5103510538 1.8124163199 1.4272149669 0.2851969150 0.3794367144 -0.7114846863 0.518150596386 +1403715411062142976.0000000000 0.5217910335 1.8163293706 1.4232359228 0.2861647040 0.3814746167 -0.7127816241 0.5143240568 +1403715411112143104.0000000000 0.5325733954 1.8207879149 1.4192129227 0.2865939438 0.3838776686 -0.7142631108 0.510225494819 +1403715411162142976.0000000000 0.5433079953 1.8255895591 1.4156986961 0.2885387248 0.3849725781 -0.7158310521 0.506090331114 +1403715411212143104.0000000000 0.5536737901 1.8303923436 1.4130723729 0.2917890030 0.3846806369 -0.7172629324 0.502408072281 +1403715411262142976.0000000000 0.5636522992 1.8351748865 1.4108979341 0.2948347278 0.3845318169 -0.7180186943 0.499656801945 +1403715411312143104.0000000000 0.5730153287 1.8396911857 1.4090697965 0.2982124125 0.3836907738 -0.7176202902 0.498870590642 +1403715411362142976.0000000000 0.5817954390 1.8440075112 1.4074446206 0.3019281687 0.3824799529 -0.7160489060 0.499822399223 +1403715411412143104.0000000000 0.5898022661 1.8479658426 1.4057223952 0.3063702192 0.3806304542 -0.7141046370 0.501310595795 +1403715411462142976.0000000000 0.5969898417 1.8515234550 1.4038470386 0.3104871750 0.3788747018 -0.7117083468 0.503510579395 +1403715411512143104.0000000000 0.6027178975 1.8548269590 1.4012888654 0.3118771225 0.3790688170 -0.7098306269 0.505153415784 +1403715411562142976.0000000000 0.6069430029 1.8581565362 1.3979568889 0.3110058371 0.3811668781 -0.7094836879 0.504598926787 +1403715411612143104.0000000000 0.6098651269 1.8613026031 1.3946503606 0.3089429712 0.3838422107 -0.7096093214 0.503660608792 +1403715411662142976.0000000000 0.6117879488 1.8643856705 1.3914059374 0.3065409345 0.3868552704 -0.7101537254 0.502053126199 +1403715411712143104.0000000000 0.6129774648 1.8672795483 1.3885485978 0.3048999954 0.3891795771 -0.7103000280 0.501048021471 +1403715411762142976.0000000000 0.6135868542 1.8700332361 1.3858119590 0.3034449517 0.3913365380 -0.7102615857 0.500305261919 +1403715411812143104.0000000000 0.6135216088 1.8727297855 1.3829614326 0.3027819365 0.3925772611 -0.7096120915 0.500656441631 +1403715411862142976.0000000000 0.6127982714 1.8758128705 1.3795283090 0.3023676115 0.3937071375 -0.7095784937 0.500066874163 +1403715411912143104.0000000000 0.6115027473 1.8790041994 1.3763526997 0.3024717264 0.3941527887 -0.7094093525 0.499892793016 +1403715411962142976.0000000000 0.6095972744 1.8823942057 1.3734970027 0.3034086189 0.3940014736 -0.7095353793 0.499265054249 +1403715412012143104.0000000000 0.6073088199 1.8856997092 1.3705784841 0.3036727713 0.3941358457 -0.7097511095 0.498691433391 +1403715412062142976.0000000000 0.6046000115 1.8889965710 1.3675732937 0.3038725196 0.3940898103 -0.7102589024 0.497882521082 +1403715412112143104.0000000000 0.6013911384 1.8923550799 1.3649368681 0.3040073534 0.3940221617 -0.7105803463 0.497394849787 +1403715412162142976.0000000000 0.5976983525 1.8955989976 1.3621155160 0.3026398421 0.3947703589 -0.7114302070 0.496419731947 +1403715412212143104.0000000000 0.5937722942 1.8990286271 1.3592942791 0.3018765094 0.3952718119 -0.7120416321 0.495608193949 +1403715412262142976.0000000000 0.5895470618 1.9024464303 1.3562297787 0.3009732310 0.3957556233 -0.7123558640 0.495319819821 +1403715412312143104.0000000000 0.5849795262 1.9058551037 1.3530869529 0.3002867207 0.3961017409 -0.7127660899 0.494869474955 +1403715412362142976.0000000000 0.5803041485 1.9091474506 1.3500624270 0.2997072574 0.3962030053 -0.7133771740 0.494258784497 +1403715412412143104.0000000000 0.5754436270 1.9125235978 1.3471927430 0.2993291097 0.3962304043 -0.7139312950 0.493665531338 +1403715412462142976.0000000000 0.5703798507 1.9160200565 1.3444620161 0.2988967445 0.3962379831 -0.7151832039 0.492106880351 +1403715412512143104.0000000000 0.5651857155 1.9195025475 1.3418273908 0.2981737878 0.3965087847 -0.7161758495 0.49088219419 +1403715412562142976.0000000000 0.5601269323 1.9228373894 1.3390790118 0.2975888992 0.3968034025 -0.7170969238 0.489652845152 +1403715412612143104.0000000000 0.5552888997 1.9259584547 1.3365925119 0.2962848574 0.3975068799 -0.7173895819 0.489444329291 +1403715412662142976.0000000000 0.5508612002 1.9289113173 1.3344441562 0.2957638362 0.3978877424 -0.7177128389 0.488975846615 +1403715412712143104.0000000000 0.5464020062 1.9316358144 1.3323347088 0.2942986687 0.3989975128 -0.7184371769 0.48789066521 +1403715412762142976.0000000000 0.5423947332 1.9340286078 1.3308765663 0.2933781159 0.3995489677 -0.7188200027 0.487429694641 +1403715412812143104.0000000000 0.5385619216 1.9364200639 1.3295420457 0.2925182125 0.4000365361 -0.7192747478 0.486875448526 +1403715412862142976.0000000000 0.5351625107 1.9386432657 1.3285760771 0.2919977576 0.4004976380 -0.7196071549 0.486317277233 +1403715412912143104.0000000000 0.5323573316 1.9406089576 1.3279597499 0.2915174204 0.4006636735 -0.7196148971 0.486457207009 +1403715412962142976.0000000000 0.5301462769 1.9423243859 1.3278172035 0.2917112567 0.4001537278 -0.7192977154 0.487229241212 +1403715413012143104.0000000000 0.5283720926 1.9438800365 1.3272051291 0.2921639685 0.3994643555 -0.7181871746 0.489158079209 +1403715413062142976.0000000000 0.5268164848 1.9455574423 1.3240154850 0.2919195685 0.3991577733 -0.7173253191 0.490816079748 +1403715413112143104.0000000000 0.5256603842 1.9473680938 1.3183467607 0.2919806970 0.3988963605 -0.7165672356 0.492097920159 +1403715413162142976.0000000000 0.5249157317 1.9492780884 1.3106204215 0.2924351484 0.3982737663 -0.7158991290 0.493303282156 +1403715413212143104.0000000000 0.5242662174 1.9513056885 1.3001728178 0.2923810607 0.3982189900 -0.7151274147 0.494497454097 +1403715413262142976.0000000000 0.5236180498 1.9536794313 1.2875640631 0.2932957215 0.3974924573 -0.7148289479 0.494971657103 +1403715413312143104.0000000000 0.5229380678 1.9564228005 1.2728812736 0.2956233151 0.3956016373 -0.7152085453 0.494553269956 +1403715413362142976.0000000000 0.5222392452 1.9594329619 1.2571152563 0.2990344018 0.3931718946 -0.7158275015 0.493543590702 +1403715413412143104.0000000000 0.5214231668 1.9621888714 1.2417790820 0.3020550154 0.3908604603 -0.7165594305 0.492476853049 +1403715413462142976.0000000000 0.5203573451 1.9646352150 1.2273892787 0.3044912712 0.3889976103 -0.7172671952 0.491420080613 +1403715413512143104.0000000000 0.5188069052 1.9665284064 1.2141114188 0.3059270323 0.3879964756 -0.7174039316 0.491120132647 +1403715413562142976.0000000000 0.5166493930 1.9677551096 1.2020003500 0.3054709093 0.3881750446 -0.7172511009 0.491486028824 +1403715413612143104.0000000000 0.5138469757 1.9684447045 1.1912935273 0.3043283370 0.3886790616 -0.7166212775 0.492713704846 +1403715413662142976.0000000000 0.5105668705 1.9684626401 1.1819123863 0.3028368965 0.3896057887 -0.7154243870 0.494636321047 +1403715413712143104.0000000000 0.5068645014 1.9682938624 1.1734368315 0.3008119591 0.3909187936 -0.7140069166 0.496879044766 +1403715413762142976.0000000000 0.5028913930 1.9681958908 1.1644660691 0.2985719047 0.3922028428 -0.7135592944 0.497860302932 +1403715413812143104.0000000000 0.4986465741 1.9682967814 1.1540245512 0.2969266788 0.3932082763 -0.7136557853 0.497912862924 +1403715413862142976.0000000000 0.4945103119 1.9685922349 1.1422642390 0.2952808914 0.3941554484 -0.7138164195 0.497912439083 +1403715413912143104.0000000000 0.4904572063 1.9690755556 1.1297759752 0.2946861491 0.3945389617 -0.7132913063 0.498712937095 +1403715413962142976.0000000000 0.4862172150 1.9698391189 1.1169518476 0.2937964666 0.3953350973 -0.7121514497 0.500234054966 +1403715414012143104.0000000000 0.4816715164 1.9711347427 1.1058128472 0.2930746968 0.3956933466 -0.7119052611 0.500724372144 +1403715414062142976.0000000000 0.4768775980 1.9732854358 1.0976007126 0.2929297689 0.3959033085 -0.7123438300 0.500018988318 +1403715414112143104.0000000000 0.4718420377 1.9760094124 1.0922042405 0.2915780395 0.3967031475 -0.7135815352 0.498407716821 +1403715414162142976.0000000000 0.4667447630 1.9793666780 1.0897786403 0.2899221470 0.3977857416 -0.7159855327 0.495051885563 +1403715414212143104.0000000000 0.4618644489 1.9831176544 1.0895448348 0.2872064297 0.3993134268 -0.7194122345 0.490415426777 +1403715414262142976.0000000000 0.4577329017 1.9872479875 1.0920365238 0.2848895095 0.4007610454 -0.7223112205 0.486307569928 +1403715414312143104.0000000000 0.4547168625 1.9912206973 1.0960830101 0.2825222777 0.4021663147 -0.7251849010 0.482234670325 +1403715414362142976.0000000000 0.4530158661 1.9946819071 1.1002761176 0.2798088097 0.4037495940 -0.7269347321 0.479853301038 +1403715414412143104.0000000000 0.4528224828 1.9977631512 1.1042218586 0.2786297388 0.4044900508 -0.7271247623 0.479627821837 +1403715414462142976.0000000000 0.4540385377 2.0005958406 1.1067948901 0.2783062729 0.4046157518 -0.7266101339 0.480488735661 +1403715414512143104.0000000000 0.4566343987 2.0033857863 1.1079384010 0.2784365015 0.4044051455 -0.7254088711 0.482401868387 +1403715414562142976.0000000000 0.4605147716 2.0061880928 1.1072730966 0.2796810135 0.4034112126 -0.7233536102 0.485589825776 +1403715414612143104.0000000000 0.4654727621 2.0092009159 1.1049850222 0.2810276902 0.4023279786 -0.7208982870 0.489347826024 +1403715414662142976.0000000000 0.4713002591 2.0126897160 1.1017079021 0.2834560119 0.4003132106 -0.7197077081 0.491347980136 +1403715414712143104.0000000000 0.4778226687 2.0168425987 1.0975400454 0.2865275150 0.3975529045 -0.7186554913 0.493343649078 +1403715414762142976.0000000000 0.4846578142 2.0215200985 1.0924724664 0.2902182714 0.3943796428 -0.7184593546 0.494018428903 +1403715414812143104.0000000000 0.4914310779 2.0264212360 1.0864482031 0.2938757651 0.3909299704 -0.7195414189 0.493022250371 +1403715414862142976.0000000000 0.4985117387 2.0311758170 1.0796874398 0.2985075580 0.3865880746 -0.7211786336 0.491268029638 +1403715414912143104.0000000000 0.5054069582 2.0355755776 1.0715734541 0.3036304668 0.3817309888 -0.7228651592 0.489444535532 +1403715414962142976.0000000000 0.5118002783 2.0393627583 1.0625976460 0.3075354102 0.3777605928 -0.7245505330 0.487591459311 +1403715415012143104.0000000000 0.5173447284 2.0424472619 1.0532879668 0.3110871797 0.3737588323 -0.7260212357 0.486232729448 +1403715415062142976.0000000000 0.5223178240 2.0446657005 1.0434179602 0.3133619281 0.3706469832 -0.7272331578 0.48534219893 +1403715415112143104.0000000000 0.5267189811 2.0458184271 1.0332878925 0.3143779984 0.3682399100 -0.7282412567 0.485005685365 +1403715415162142976.0000000000 0.5300422295 2.0458656774 1.0231125468 0.3148042214 0.3661539662 -0.7291867471 0.484887887104 +1403715415212143104.0000000000 0.5321707063 2.0447983411 1.0134836070 0.3141966956 0.3647270465 -0.7292321519 0.486287041486 +1403715415262142976.0000000000 0.5333768485 2.0427586481 1.0042834820 0.3127875902 0.3642148340 -0.7293268479 0.487435972231 +1403715415312143104.0000000000 0.5333763291 2.0392948014 0.9954380471 0.3065814297 0.3672060986 -0.7273757181 0.49202852851 +1403715415362142976.0000000000 0.5327483903 2.0350060818 0.9873067336 0.2996426286 0.3705015027 -0.7259836644 0.495873623732 +1403715415412143104.0000000000 0.5316831480 2.0302876634 0.9807543456 0.2926171692 0.3735435336 -0.7237397808 0.501040068802 +1403715415462142976.0000000000 0.5300439912 2.0257452794 0.9749540136 0.2846665301 0.3775014301 -0.7227202819 0.504116088888 +1403715415512143104.0000000000 0.5285682186 2.0214784833 0.9712587319 0.2794841610 0.3796833854 -0.7208476242 0.508043141168 +1403715415562142976.0000000000 0.5274023497 2.0182751631 0.9681011542 0.2764138096 0.3808849741 -0.7202047293 0.509732469395 +1403715415612143104.0000000000 0.5265256981 2.0160780580 0.9641677479 0.2743778309 0.3812588302 -0.7190502537 0.512176964535 +1403715415662142976.0000000000 0.5254865550 2.0148589499 0.9577913822 0.2724128440 0.3812541016 -0.7186800233 0.513746607411 +1403715415712143104.0000000000 0.5245165887 2.0148289702 0.9487288218 0.2713550881 0.3809930379 -0.7191811044 0.513798852016 +1403715415762142976.0000000000 0.5242727909 2.0146151333 0.9453703764 0.2715901522 0.3807285870 -0.7204971350 0.512023838069 +1403715415812143104.0000000000 0.5246510620 2.0150587346 0.9487191653 0.2707007597 0.3813133584 -0.7198641601 0.512949132424 +1403715415862142976.0000000000 0.5252955389 2.0163279523 0.9509710448 0.2712250828 0.3807810469 -0.7186913284 0.514709163777 +1403715415912143104.0000000000 0.5264462951 2.0186095118 0.9510148843 0.2727038113 0.3791030233 -0.7181647913 0.515900049924 +1403715415962142976.0000000000 0.5273645500 2.0215402148 0.9487328066 0.2724802277 0.3795221778 -0.7180104446 0.515924842856 +1403715416012143104.0000000000 0.5272233726 2.0222267477 0.9474736977 0.2705304774 0.3817616860 -0.7188184419 0.514170519814 +1403715416062142976.0000000000 0.5267286198 2.0212520233 0.9483548397 0.2692738791 0.3819410032 -0.7185748524 0.51503672639 +1403715416112143104.0000000000 0.5269698869 2.0211138873 0.9488795886 0.2692745280 0.3812863858 -0.7185835564 0.515509062029 +1403715416162142976.0000000000 0.5272818628 2.0212567508 0.9483904664 0.2697309223 0.3808080050 -0.7186333827 0.515554608395 +1403715416212143104.0000000000 0.5273077693 2.0211815680 0.9482115313 0.2697424837 0.3806398585 -0.7197577915 0.514102141846 +1403715416262142976.0000000000 0.5273668694 2.0217480293 0.9476142200 0.2697842053 0.3807907052 -0.7205643156 0.512837194936 +1403715416312143104.0000000000 0.5273099856 2.0220219192 0.9472206386 0.2699363336 0.3806263596 -0.7208375086 0.512495108657 +1403715416362142976.0000000000 0.5273626687 2.0216077792 0.9470429243 0.2696028408 0.3808568745 -0.7211739108 0.51202591706 +1403715416412143104.0000000000 0.5275022179 2.0211325008 0.9471109196 0.2696372532 0.3807659062 -0.7213979522 0.51175977847 +1403715416462142976.0000000000 0.5275374594 2.0210804288 0.9468618258 0.2694459854 0.3809336884 -0.7217388328 0.511254773273 +1403715416512143104.0000000000 0.5275770624 2.0214474180 0.9465042863 0.2695695698 0.3805866893 -0.7218249848 0.511326422341 +1403715416562142976.0000000000 0.5274688140 2.0214393837 0.9463934198 0.2697013609 0.3805305185 -0.7214512795 0.511825899817 +1403715416612143104.0000000000 0.5274573042 2.0211044519 0.9462235447 0.2695432980 0.3806511240 -0.7217513149 0.511396296176 +1403715416662142976.0000000000 0.5275025711 2.0210106552 0.9460909176 0.2698111899 0.3804066858 -0.7220285551 0.511045439096 +1403715416712143104.0000000000 0.5273614946 2.0211768309 0.9458537990 0.2697685887 0.3804137361 -0.7220598731 0.511018431703 +1403715416762142976.0000000000 0.5271586706 2.0214257873 0.9456811878 0.2698069875 0.3803811413 -0.7221544604 0.510888747325 +1403715416812143104.0000000000 0.5270655692 2.0215036215 0.9455757041 0.2699785692 0.3801735262 -0.7219549726 0.511234466528 +1403715416862142976.0000000000 0.5271435976 2.0214481397 0.9454783133 0.2698758882 0.3802942091 -0.7222236764 0.510819225108 +1403715416912143104.0000000000 0.5271555661 2.0213197982 0.9454149938 0.2697849385 0.3803010413 -0.7225127167 0.510453307528 +1403715416962142976.0000000000 0.5270604563 2.0214778241 0.9453871143 0.2698271877 0.3802714500 -0.7223202277 0.510725368213 +1403715417012143104.0000000000 0.5270185473 2.0217299911 0.9452934415 0.2700842411 0.3800413693 -0.7222548041 0.510853264923 +1403715417062142976.0000000000 0.5270373219 2.0216813812 0.9452118491 0.2699562374 0.3801242302 -0.7222586118 0.5108538902 +1403715417112143104.0000000000 0.5271682508 2.0215084103 0.9451720228 0.2699660895 0.3800864368 -0.7225280482 0.510495671548 +1403715417162142976.0000000000 0.5272086715 2.0214253048 0.9451771189 0.2699822821 0.3800261958 -0.7226082471 0.510418435279 +1403715417212143104.0000000000 0.5271885330 2.0215744685 0.9451798559 0.2700997492 0.3799307614 -0.7225078788 0.51056939501 +1403715417262142976.0000000000 0.5271891524 2.0217650296 0.9451628655 0.2701314232 0.3799292995 -0.7225383284 0.510510632233 +1403715417312143104.0000000000 0.5272027578 2.0218203766 0.9452016001 0.2701862748 0.3798215169 -0.7225169448 0.510592064763 +1403715417362142976.0000000000 0.5272653967 2.0217665499 0.9451859700 0.2701770297 0.3798915423 -0.7226683748 0.510330489782 +1403715417412143104.0000000000 0.5272837587 2.0217508456 0.9451710902 0.2701594561 0.3798261654 -0.7227575959 0.510262099192 +1403715417462142976.0000000000 0.5272102105 2.0219064128 0.9451294787 0.2702562423 0.3797645936 -0.7227364538 0.510286620771 +1403715417512143104.0000000000 0.5270933448 2.0220061532 0.9450763465 0.2703463492 0.3797277474 -0.7226964077 0.510323026792 +1403715417562142976.0000000000 0.5270295697 2.0218879889 0.9450605417 0.2703151867 0.3796735169 -0.7227378147 0.510321243536 +1403715417612143104.0000000000 0.5269915325 2.0217135259 0.9450268009 0.2702935601 0.3796591926 -0.7228483250 0.510186816734 +1403715417662142976.0000000000 0.5269400037 2.0216377121 0.9449850977 0.2702581815 0.3796865625 -0.7228909590 0.510124779799 +1403715417712143104.0000000000 0.5269172696 2.0216197157 0.9450235034 0.2703605118 0.3796028279 -0.7228665374 0.510167478151 +1403715417762142976.0000000000 0.5269290501 2.0215745393 0.9450942475 0.2703804029 0.3795952194 -0.7228192478 0.510229597566 +1403715417812143104.0000000000 0.5270096472 2.0214076633 0.9451792752 0.2703311448 0.3795785990 -0.7229010420 0.510152176171 diff --git a/data/euroc_groundtruth/V1_02_medium.txt b/data/euroc_groundtruth/V1_02_medium.txt new file mode 100755 index 00000000..aa815c09 --- /dev/null +++ b/data/euroc_groundtruth/V1_02_medium.txt @@ -0,0 +1,1672 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403715524912143104.0000000000 0.5493701398 2.0509640750 0.9455930356 0.2656202293 0.4116597639 -0.7031751512 0.515292964635 +1403715524962142976.0000000000 0.5491333966 2.0503565652 0.9453359435 0.2656659227 0.4115273888 -0.7032155778 0.51531997529 +1403715525012143104.0000000000 0.5489640733 2.0499457879 0.9451654031 0.2657705007 0.4114530940 -0.7032184722 0.515321426672 +1403715525062142976.0000000000 0.5487788913 2.0496252245 0.9449970840 0.2658001352 0.4115288947 -0.7032196597 0.515243987942 +1403715525112143104.0000000000 0.5486024796 2.0493540096 0.9449108527 0.2659336063 0.4113830342 -0.7033295670 0.515141569248 +1403715525162142976.0000000000 0.5484760499 2.0491368486 0.9448253278 0.2658876242 0.4114090569 -0.7033250842 0.515150643146 +1403715525212143104.0000000000 0.5484385574 2.0490520775 0.9447950415 0.2659377858 0.4111871746 -0.7034812052 0.515088725857 +1403715525262142976.0000000000 0.5484558007 2.0490109208 0.9448013375 0.2657586109 0.4109784677 -0.7036069355 0.515176028408 +1403715525312143104.0000000000 0.5485237270 2.0490429932 0.9447799416 0.2657458561 0.4110124459 -0.7036837488 0.51505057124 +1403715525362142976.0000000000 0.5486226253 2.0490741364 0.9448130070 0.2657471031 0.4110361881 -0.7037562415 0.514931919596 +1403715525412143104.0000000000 0.5486710351 2.0491532762 0.9448393193 0.2657915784 0.4110925767 -0.7037708387 0.514843992637 +1403715525462142976.0000000000 0.5487357476 2.0492992642 0.9448284950 0.2658490354 0.4112574482 -0.7037765305 0.514674845762 +1403715525512143104.0000000000 0.5487966247 2.0493318730 0.9448296062 0.2657775967 0.4112923625 -0.7037610199 0.514705050001 +1403715525562142976.0000000000 0.5488244767 2.0493206712 0.9448401577 0.2657767769 0.4112312682 -0.7038390413 0.514647600605 +1403715525612143104.0000000000 0.5488198967 2.0492442710 0.9448492958 0.2655669557 0.4112071292 -0.7039371064 0.514641077944 +1403715525662142976.0000000000 0.5487810853 2.0491391023 0.9448933764 0.2653793865 0.4109748282 -0.7040839723 0.514722480335 +1403715525712143104.0000000000 0.5487316211 2.0491806774 0.9449440279 0.2653945771 0.4111415874 -0.7039499269 0.514764814159 +1403715525762142976.0000000000 0.5487214463 2.0492576861 0.9450276754 0.2655249469 0.4111870740 -0.7039160238 0.514707610374 +1403715525812143104.0000000000 0.5487738394 2.0493633243 0.9450779536 0.2655641428 0.4113583724 -0.7038196968 0.514682241736 +1403715525862142976.0000000000 0.5488467381 2.0495252173 0.9451635965 0.2656682543 0.4115403227 -0.7037233696 0.514614769009 +1403715525912143104.0000000000 0.5488505835 2.0495642270 0.9453095493 0.2656633338 0.4114362199 -0.7036743715 0.514767528946 +1403715525962142976.0000000000 0.5488248091 2.0496136763 0.9454040823 0.2656505507 0.4113506291 -0.7036346353 0.514896829347 +1403715526012143104.0000000000 0.5488482442 2.0496963296 0.9454228536 0.2656661919 0.4113474414 -0.7036428510 0.514880078462 +1403715526062142976.0000000000 0.5488689410 2.0497397200 0.9454688727 0.2656891910 0.4112803044 -0.7036102870 0.514966337702 +1403715526112143104.0000000000 0.5488643892 2.0497385706 0.9454662604 0.2657061120 0.4112949590 -0.7036562490 0.514883095484 +1403715526162142976.0000000000 0.5488512919 2.0497563596 0.9454354305 0.2657160954 0.4112774415 -0.7036326877 0.514924133808 +1403715526212143104.0000000000 0.5488248660 2.0497630369 0.9453831708 0.2656881961 0.4112839633 -0.7036537193 0.514904580743 +1403715526262142976.0000000000 0.5488269194 2.0497619200 0.9453534887 0.2657112912 0.4112393578 -0.7036872062 0.514882526524 +1403715526312143104.0000000000 0.5488240058 2.0497301040 0.9453308199 0.2656756919 0.4112195505 -0.7036969588 0.514903387212 +1403715526362142976.0000000000 0.5488345696 2.0497014455 0.9452973208 0.2657277742 0.4112586887 -0.7037101717 0.514827189698 +1403715526412143104.0000000000 0.5488283078 2.0497133907 0.9452810556 0.2658150982 0.4112488682 -0.7036738241 0.514839636522 +1403715526462142976.0000000000 0.5488261959 2.0497059167 0.9452665746 0.2658000936 0.4112332211 -0.7037016232 0.514821885381 +1403715526512143104.0000000000 0.5488029175 2.0496570240 0.9452776596 0.2658237662 0.4112007227 -0.7036966264 0.51484245073 +1403715526562142976.0000000000 0.5488030247 2.0496244113 0.9452984753 0.2658702840 0.4111426391 -0.7037243599 0.514826910328 +1403715526612143104.0000000000 0.5488121997 2.0496170182 0.9453054212 0.2659181180 0.4111215271 -0.7037415966 0.514795502749 +1403715526662142976.0000000000 0.5488183691 2.0495980223 0.9452732493 0.2659274830 0.4111290896 -0.7037504437 0.514772530855 +1403715526712143104.0000000000 0.5488042596 2.0495858912 0.9452565810 0.2659706337 0.4111048092 -0.7037662870 0.514747968612 +1403715526762142976.0000000000 0.5487852087 2.0495617738 0.9452710580 0.2659734831 0.4111105646 -0.7037690547 0.514738115602 +1403715526812143104.0000000000 0.5487783535 2.0495536903 0.9452780391 0.2660086417 0.4110790267 -0.7037887918 0.514718149013 +1403715526862142976.0000000000 0.5487694547 2.0495559992 0.9452931796 0.2660114088 0.4110666413 -0.7038032496 0.514706841395 +1403715526912143104.0000000000 0.5487241155 2.0495867779 0.9456181758 0.2661083313 0.4109558934 -0.7038205532 0.514721515542 +1403715526962142976.0000000000 0.5486979636 2.0495512639 0.9456150251 0.2660204891 0.4110106836 -0.7039126051 0.514597281069 +1403715527012143104.0000000000 0.5486109761 2.0495907556 0.9454099812 0.2660146756 0.4110428694 -0.7038496080 0.51466074375 +1403715527062142976.0000000000 0.5486056474 2.0497446702 0.9454128357 0.2660915143 0.4109944090 -0.7039226792 0.51455977635 +1403715527112143104.0000000000 0.5484781821 2.0496812817 0.9453290283 0.2660125210 0.4110717643 -0.7038980161 0.514572566577 +1403715527162142976.0000000000 0.5485065533 2.0496724305 0.9451883980 0.2661006918 0.4109915349 -0.7038977638 0.514591408946 +1403715527212143104.0000000000 0.5485901196 2.0496591854 0.9451879106 0.2660800008 0.4110014682 -0.7040054698 0.51444681434 +1403715527262142976.0000000000 0.5485327619 2.0496012587 0.9451411568 0.2660474613 0.4110205809 -0.7039819640 0.514480538788 +1403715527312143104.0000000000 0.5485116793 2.0497292677 0.9453118254 0.2663243506 0.4110598804 -0.7038674434 0.514462571215 +1403715527362142976.0000000000 0.5486095809 2.0496636010 0.9454802652 0.2662002934 0.4110439769 -0.7039504438 0.514425918429 +1403715527412143104.0000000000 0.5485941481 2.0495772231 0.9455072021 0.2661548917 0.4111479104 -0.7039975219 0.514301913858 +1403715527462142976.0000000000 0.5487631048 2.0497092586 0.9456547274 0.2662408965 0.4110957274 -0.7040656624 0.514205825463 +1403715527512143104.0000000000 0.5488556604 2.0498124924 0.9457503209 0.2663083236 0.4110774556 -0.7040099338 0.514261815988 +1403715527562142976.0000000000 0.5489060220 2.0498235313 0.9457693254 0.2663200477 0.4110109088 -0.7039709842 0.514362244363 +1403715527612143104.0000000000 0.5490372638 2.0498760092 0.9458543333 0.2662631389 0.4110412077 -0.7040811867 0.514216636222 +1403715527662142976.0000000000 0.5490603372 2.0498360759 0.9459497131 0.2662118638 0.4111428575 -0.7041577323 0.514057080855 +1403715527712143104.0000000000 0.5491577646 2.0497907291 0.9461083083 0.2661831428 0.4111752854 -0.7041653076 0.514035639587 +1403715527762142976.0000000000 0.5492068441 2.0499661072 0.9461077733 0.2663628536 0.4110348624 -0.7041824342 0.514031391548 +1403715527812143104.0000000000 0.5492457272 2.0500404346 0.9461174902 0.2663111573 0.4110840800 -0.7042499949 0.513926250891 +1403715527862142976.0000000000 0.5492194850 2.0499429034 0.9461883069 0.2661198195 0.4111670456 -0.7044459020 0.513690445059 +1403715527912143104.0000000000 0.5491222448 2.0498387727 0.9462853664 0.2661645666 0.4111726160 -0.7044835611 0.513611151959 +1403715527962142976.0000000000 0.5490316168 2.0496809376 0.9463281989 0.2661664490 0.4111914525 -0.7045609914 0.513488870599 +1403715528012143104.0000000000 0.5487628905 2.0495317454 0.9465011435 0.2662408970 0.4111935745 -0.7043715112 0.5137084809 +1403715528062142976.0000000000 0.5484369021 2.0493170029 0.9465994142 0.2660596829 0.4113254571 -0.7043322472 0.513750619517 +1403715528112143104.0000000000 0.5483808629 2.0493351648 0.9466172454 0.2661930271 0.4111886808 -0.7043966037 0.513702799113 +1403715528162142976.0000000000 0.5484098540 2.0495139937 0.9466187239 0.2659872069 0.4113126057 -0.7045002208 0.513568091968 +1403715528212143104.0000000000 0.5484356230 2.0497899666 0.9468505441 0.2659296843 0.4113588990 -0.7046701952 0.513327551615 +1403715528262142976.0000000000 0.5484931285 2.0500579644 0.9470306878 0.2657726096 0.4114553486 -0.7048045907 0.513147059916 +1403715528312143104.0000000000 0.5489454671 2.0500726482 0.9471553573 0.2654702647 0.4117022751 -0.7052192024 0.512535512718 +1403715528362142976.0000000000 0.5493487036 2.0498414835 0.9469395562 0.2651775783 0.4119027465 -0.7058824591 0.511612092615 +1403715528412143104.0000000000 0.5497105161 2.0496189545 0.9470994677 0.2641189230 0.4126599437 -0.7072377538 0.509674136008 +1403715528462142976.0000000000 0.5503024087 2.0497577828 0.9482435730 0.2626557623 0.4131031457 -0.7100766273 0.506111573542 +1403715528512143104.0000000000 0.5514830208 2.0501762576 0.9505834535 0.2614821669 0.4129932783 -0.7130330001 0.502640596475 +1403715528562142976.0000000000 0.5534389094 2.0511540200 0.9550125286 0.2619182867 0.4120083223 -0.7144306966 0.501235207475 +1403715528612143104.0000000000 0.5564416361 2.0521688642 0.9616067009 0.2629919360 0.4104578671 -0.7144178198 0.501962906786 +1403715528662142976.0000000000 0.5604883613 2.0531766066 0.9697234951 0.2645692431 0.4083299436 -0.7141402715 0.503262799574 +1403715528712143104.0000000000 0.5652792042 2.0542541534 0.9794676753 0.2655277377 0.4065979372 -0.7137375069 0.504729540673 +1403715528762142976.0000000000 0.5700731709 2.0554772282 0.9899771553 0.2664712585 0.4050219263 -0.7134217885 0.505944324257 +1403715528812143104.0000000000 0.5750433210 2.0566348325 1.0010641460 0.2663326534 0.4041546459 -0.7130317390 0.507258986295 +1403715528862142976.0000000000 0.5802433833 2.0582029681 1.0129696830 0.2666309337 0.4033529216 -0.7118122376 0.509448431402 +1403715528912143104.0000000000 0.5857467133 2.0602038208 1.0252694159 0.2666411841 0.4025862546 -0.7115061357 0.510476057683 +1403715528962142976.0000000000 0.5913969048 2.0626917850 1.0377778650 0.2659139098 0.4025310347 -0.7112336825 0.511278013972 +1403715529012143104.0000000000 0.5971820175 2.0656334750 1.0501389196 0.2644657793 0.4043967430 -0.7110239130 0.510848432424 +1403715529062142976.0000000000 0.6031496551 2.0698815071 1.0627774882 0.2658535009 0.4059677602 -0.7113100964 0.508478161287 +1403715529112143104.0000000000 0.6095016493 2.0748699252 1.0777072281 0.2692052945 0.4083022640 -0.7101847909 0.506414191586 +1403715529162142976.0000000000 0.6160185946 2.0806631587 1.0949865458 0.2729113738 0.4125091215 -0.7081316626 0.503890022858 +1403715529212143104.0000000000 0.6227176365 2.0867478385 1.1142648543 0.2764365858 0.4181413143 -0.7061467415 0.500097425297 +1403715529262142976.0000000000 0.6297900423 2.0928843480 1.1346700514 0.2796820640 0.4250464252 -0.7040615311 0.495389583994 +1403715529312143104.0000000000 0.6370751383 2.0992844167 1.1547512362 0.2828281125 0.4329520338 -0.7014108845 0.490493186893 +1403715529362142976.0000000000 0.6447388558 2.1057928713 1.1731499246 0.2855583137 0.4416858001 -0.6981718538 0.485722313692 +1403715529412143104.0000000000 0.6532160604 2.1121048778 1.1897386793 0.2892694645 0.4499056187 -0.6937177721 0.482352323401 +1403715529462142976.0000000000 0.6626256163 2.1181696047 1.2044526976 0.2933498018 0.4567118915 -0.6890655356 0.480155005814 +1403715529512143104.0000000000 0.6729971605 2.1239480744 1.2171793094 0.2967811696 0.4624012958 -0.6847720041 0.478741351235 +1403715529562142976.0000000000 0.6839520727 2.1296745689 1.2277533196 0.3000154234 0.4670197350 -0.6813057842 0.477185227481 +1403715529612143104.0000000000 0.6955168026 2.1351685026 1.2364999393 0.3026735033 0.4708344863 -0.6778811579 0.476634842047 +1403715529662142976.0000000000 0.7077756618 2.1406557755 1.2437267672 0.3054973827 0.4736874088 -0.6746636730 0.476571627657 +1403715529712143104.0000000000 0.7207669725 2.1463189401 1.2504905229 0.3069039140 0.4772225559 -0.6710165442 0.477289657431 +1403715529762142976.0000000000 0.7344393164 2.1524193745 1.2576597455 0.3078964899 0.4804745538 -0.6685846861 0.476800243468 +1403715529812143104.0000000000 0.7488114232 2.1588509197 1.2663006735 0.3102728465 0.4819290997 -0.6667378136 0.47637778239 +1403715529862142976.0000000000 0.7634742693 2.1656782990 1.2758121730 0.3117596993 0.4833896048 -0.6653279323 0.475898226922 +1403715529912143104.0000000000 0.7785769217 2.1730447082 1.2868706171 0.3145425403 0.4834052464 -0.6640998863 0.475766433272 +1403715529962142976.0000000000 0.7940483554 2.1805378612 1.2989778466 0.3172514554 0.4829907533 -0.6626088853 0.476467114754 +1403715530012143104.0000000000 0.8098550629 2.1879746072 1.3119000459 0.3186914063 0.4831736957 -0.6599000867 0.479072899402 +1403715530062142976.0000000000 0.8257644848 2.1957224876 1.3259374605 0.3197733667 0.4832866393 -0.6559423400 0.483651387721 +1403715530112143104.0000000000 0.8414851885 2.2041039279 1.3407976076 0.3195714293 0.4838541970 -0.6517092672 0.488911289128 +1403715530162142976.0000000000 0.8567357815 2.2136318546 1.3565313190 0.3175718596 0.4851608770 -0.6496097790 0.491705371636 +1403715530212143104.0000000000 0.8713510640 2.2246186349 1.3744866085 0.3141281439 0.4874525115 -0.6492118649 0.492176302533 +1403715530262142976.0000000000 0.8856459055 2.2370796770 1.3951209052 0.3095744809 0.4901796685 -0.6498517564 0.491508115915 +1403715530312143104.0000000000 0.9001787729 2.2513807423 1.4198912605 0.3061649261 0.4921247573 -0.6505461672 0.490780954887 +1403715530362142976.0000000000 0.9150638154 2.2676338955 1.4484239548 0.3062113963 0.4915613519 -0.6527345977 0.488405121854 +1403715530412143104.0000000000 0.9302360675 2.2858096976 1.4803820388 0.3080329481 0.4902940876 -0.6550106316 0.485477582408 +1403715530462142976.0000000000 0.9457808063 2.3054803695 1.5147048549 0.3112480608 0.4897229520 -0.6564932891 0.481988211792 +1403715530512143104.0000000000 0.9614829154 2.3263055132 1.5493312902 0.3143013023 0.4909041280 -0.6560426715 0.479411974994 +1403715530562142976.0000000000 0.9772263691 2.3481008492 1.5823766667 0.3174415217 0.4927755580 -0.6552810826 0.476455488521 +1403715530612143104.0000000000 0.9929349445 2.3703124237 1.6123714567 0.3201872060 0.4946182155 -0.6539863063 0.474483809216 +1403715530662142976.0000000000 1.0086175016 2.3931122969 1.6389201401 0.3235146978 0.4957962853 -0.6525736168 0.472939698575 +1403715530712143104.0000000000 1.0241175330 2.4163661062 1.6622344500 0.3266540973 0.4973934602 -0.6511006617 0.471131377493 +1403715530762142976.0000000000 1.0396856882 2.4402559002 1.6838295262 0.3301678169 0.5002150049 -0.6490727574 0.468485556974 +1403715530812143104.0000000000 1.0551969059 2.4649606239 1.7049138383 0.3343285097 0.5044893128 -0.6460587801 0.465105400338 +1403715530862142976.0000000000 1.0706543151 2.4899780283 1.7257290303 0.3392491040 0.5091720347 -0.6423489629 0.461564398968 +1403715530912143104.0000000000 1.0862900949 2.5151029779 1.7461750642 0.3434266455 0.5138642029 -0.6388657568 0.458096348907 +1403715530962142976.0000000000 1.1021372645 2.5397489433 1.7661309689 0.3450075223 0.5192456866 -0.6354454522 0.455590609816 +1403715531012143104.0000000000 1.1179620359 2.5643815871 1.7849342903 0.3456606687 0.5245199966 -0.6350809374 0.449521610411 +1403715531062142976.0000000000 1.1338117021 2.5890551733 1.8022321504 0.3436249790 0.5308512656 -0.6363142101 0.441840506979 +1403715531112143104.0000000000 1.1498787107 2.6137876445 1.8179402505 0.3401796167 0.5370610910 -0.6396806645 0.432032244617 +1403715531162142976.0000000000 1.1671918767 2.6382236589 1.8329222635 0.3373611964 0.5421504661 -0.6425702523 0.423513596133 +1403715531212143104.0000000000 1.1864029459 2.6628109838 1.8478018272 0.3395540740 0.5431735053 -0.6471079266 0.413420978342 +1403715531262142976.0000000000 1.2084938995 2.6865759466 1.8641117477 0.3474129452 0.5399865305 -0.6485376956 0.408800256611 +1403715531312143104.0000000000 1.2330349144 2.7088286454 1.8813139371 0.3572549890 0.5350108899 -0.6473585476 0.408728676902 +1403715531362142976.0000000000 1.2593127952 2.7292013353 1.8986361047 0.3663136428 0.5302660992 -0.6445471875 0.411328460342 +1403715531412143104.0000000000 1.2863586925 2.7476801049 1.9152579367 0.3730710012 0.5268124012 -0.6414418276 0.414534804048 +1403715531462142976.0000000000 1.3132799516 2.7640308978 1.9286015412 0.3766798131 0.5252995553 -0.6379189496 0.418607345066 +1403715531512143104.0000000000 1.3402217327 2.7786770569 1.9380697930 0.3795195991 0.5241528673 -0.6351224803 0.42172038201 +1403715531562142976.0000000000 1.3667946604 2.7920095068 1.9443898355 0.3813262128 0.5235466117 -0.6334492724 0.423357159083 +1403715531612143104.0000000000 1.3930053979 2.8043406535 1.9473984304 0.3829151182 0.5229948400 -0.6334240181 0.422642192485 +1403715531662142976.0000000000 1.4189756949 2.8154793876 1.9475294898 0.3837804860 0.5226623395 -0.6343631842 0.420856232012 +1403715531712143104.0000000000 1.4450711955 2.8247289246 1.9461823084 0.3823174650 0.5238359558 -0.6331367310 0.422572037905 +1403715531762142976.0000000000 1.4709717393 2.8322770072 1.9443786473 0.3789272304 0.5260180787 -0.6305438644 0.426771097841 +1403715531812143104.0000000000 1.4969179226 2.8384085816 1.9434066236 0.3770624161 0.5268849924 -0.6263247696 0.433512885805 +1403715531862142976.0000000000 1.5224360304 2.8436778094 1.9432241496 0.3762333272 0.5268417279 -0.6218824332 0.440622873285 +1403715531912143104.0000000000 1.5474164531 2.8485374436 1.9435866667 0.3767486563 0.5256887050 -0.6183108717 0.446546191782 +1403715531962142976.0000000000 1.5711633313 2.8530666871 1.9437631003 0.3765926291 0.5247772105 -0.6151774687 0.45204375135 +1403715532012143104.0000000000 1.5934915638 2.8578482565 1.9435546201 0.3766310979 0.5239249016 -0.6137297328 0.454958820911 +1403715532062142976.0000000000 1.6146607033 2.8627270622 1.9431232917 0.3757900115 0.5238117938 -0.6120665957 0.458014797068 +1403715532112143104.0000000000 1.6343357303 2.8675823305 1.9424077816 0.3743552418 0.5242120876 -0.6107675716 0.460459350664 +1403715532162142976.0000000000 1.6526651425 2.8728220663 1.9418213686 0.3741190055 0.5239964587 -0.6099780177 0.461941012358 +1403715532212143104.0000000000 1.6695382859 2.8784822409 1.9410444632 0.3747011463 0.5235846838 -0.6096694954 0.462343201747 +1403715532262142976.0000000000 1.6848216779 2.8847553511 1.9402209683 0.3765134692 0.5238511126 -0.6086470233 0.461916031764 +1403715532312143104.0000000000 1.6984671053 2.8917684135 1.9390949109 0.3788210152 0.5245904001 -0.6086206621 0.459217203787 +1403715532362142976.0000000000 1.7107403411 2.8991192395 1.9373888869 0.3808435653 0.5254219314 -0.6103303921 0.454298123816 +1403715532412143104.0000000000 1.7218951740 2.9065549201 1.9360016979 0.3841741268 0.5249181775 -0.6122443063 0.449475312462 +1403715532462142976.0000000000 1.7316861275 2.9135408910 1.9341085418 0.3864173988 0.5252352289 -0.6135879740 0.445330603358 +1403715532512143104.0000000000 1.7406440111 2.9199757030 1.9323291800 0.3892316004 0.5247799332 -0.6151540386 0.441237228455 +1403715532562142976.0000000000 1.7486045922 2.9256869231 1.9303458770 0.3938842831 0.5227425041 -0.6173027867 0.436500533163 +1403715532612143104.0000000000 1.7554898072 2.9302474126 1.9285807057 0.3998869314 0.5195140840 -0.6192219433 0.432157082086 +1403715532662142976.0000000000 1.7613986618 2.9332221739 1.9268355858 0.4067706304 0.5154713645 -0.6208089424 0.428279329069 +1403715532712143104.0000000000 1.7658947758 2.9341444493 1.9249141388 0.4132545728 0.5115267038 -0.6216692107 0.425544923507 +1403715532762142976.0000000000 1.7685030363 2.9326566142 1.9220739525 0.4184356263 0.5086083576 -0.6220994857 0.423345479665 +1403715532812143104.0000000000 1.7693706212 2.9283768982 1.9183914048 0.4217575196 0.5061328366 -0.6226967060 0.422136185047 +1403715532862142976.0000000000 1.7687001175 2.9211660779 1.9140519774 0.4231839376 0.5035373493 -0.6239037632 0.422030315245 +1403715532912143104.0000000000 1.7665959403 2.9109989938 1.9083343386 0.4227133752 0.5004408457 -0.6266619098 0.422098582299 +1403715532962142976.0000000000 1.7630053567 2.8977489762 1.9003040822 0.4210390453 0.4957808907 -0.6312302253 0.422464002479 +1403715533012143104.0000000000 1.7580137922 2.8814091503 1.8893055091 0.4182526783 0.4898519082 -0.6368455072 0.423718780785 +1403715533062142976.0000000000 1.7516127380 2.8619207548 1.8752810113 0.4137342031 0.4833571860 -0.6434848245 0.425578571443 +1403715533112143104.0000000000 1.7433975538 2.8393963132 1.8586040046 0.4082510887 0.4757580829 -0.6501798368 0.429245238772 +1403715533162142976.0000000000 1.7337915821 2.8135814336 1.8408436450 0.4020477834 0.4672590144 -0.6551897186 0.436752820255 +1403715533212143104.0000000000 1.7222892143 2.7842503167 1.8249903266 0.3956513147 0.4581024734 -0.6571382351 0.449189827411 +1403715533262142976.0000000000 1.7081793468 2.7522475716 1.8124632530 0.3895012521 0.4487015995 -0.6595247945 0.460415784561 +1403715533312143104.0000000000 1.6906116114 2.7180509780 1.8028951375 0.3819609672 0.4410654377 -0.6620433781 0.470388844145 +1403715533362142976.0000000000 1.6701485106 2.6823582301 1.7971464835 0.3738683116 0.4360140471 -0.6656655204 0.476449001741 +1403715533412143104.0000000000 1.6476046766 2.6449228936 1.7956420789 0.3659493501 0.4322666253 -0.6695495418 0.480551817077 +1403715533462142976.0000000000 1.6221087070 2.6066137268 1.7974118944 0.3586217500 0.4294512653 -0.6748401265 0.481199391964 +1403715533512143104.0000000000 1.5946244942 2.5673537902 1.8037947154 0.3543984246 0.4255245062 -0.6811692925 0.478893564621 +1403715533562142976.0000000000 1.5650118474 2.5269945558 1.8140878249 0.3536602185 0.4199065280 -0.6882213621 0.474293489688 +1403715533612143104.0000000000 1.5330648440 2.4852676793 1.8278072109 0.3535625327 0.4150291855 -0.6945746322 0.469372337136 +1403715533662142976.0000000000 1.4989677175 2.4416729152 1.8450025209 0.3543288638 0.4102317907 -0.7012731361 0.46300855591 +1403715533712143104.0000000000 1.4628769842 2.3949920170 1.8659668527 0.3545914754 0.4064167275 -0.7064731495 0.45824231385 +1403715533762142976.0000000000 1.4252816955 2.3452004790 1.8900901190 0.3550865093 0.4029060098 -0.7104613312 0.454780183214 +1403715533812143104.0000000000 1.3864667177 2.2918595901 1.9153818529 0.3518508370 0.4029709700 -0.7125051557 0.454039413424 +1403715533862142976.0000000000 1.3464812154 2.2352434723 1.9404430799 0.3473322595 0.4044448784 -0.7129172589 0.455558584361 +1403715533912143104.0000000000 1.3056612588 2.1760217272 1.9631649331 0.3403845119 0.4083815050 -0.7120543547 0.458630053859 +1403715533962142976.0000000000 1.2645036499 2.1148015649 1.9836844796 0.3349246098 0.4114960660 -0.7105433686 0.46219542914 +1403715534012143104.0000000000 1.2226114566 2.0521395009 2.0005835111 0.3294696693 0.4151149801 -0.7090086525 0.465226849062 +1403715534062142976.0000000000 1.1800983928 1.9881193681 2.0139033519 0.3247369335 0.4184566405 -0.7072349756 0.468250630912 +1403715534112143104.0000000000 1.1377009765 1.9224759793 2.0239709534 0.3192775759 0.4224594645 -0.7043585021 0.472725005481 +1403715534162142976.0000000000 1.0949834614 1.8563545835 2.0305329917 0.3141122151 0.4268792199 -0.7016855946 0.476177460814 +1403715534212143104.0000000000 1.0522238086 1.7898362803 2.0338594900 0.3082665432 0.4315817004 -0.6989649217 0.479746821207 +1403715534262142976.0000000000 1.0097482625 1.7232359656 2.0343482926 0.3034994186 0.4356537326 -0.6965398717 0.482624217496 +1403715534312143104.0000000000 0.9681701863 1.6568130456 2.0322443242 0.3006075163 0.4385928151 -0.6947768743 0.484310394949 +1403715534362142976.0000000000 0.9270779428 1.5907691093 2.0273772634 0.2980241223 0.4405401545 -0.6935839346 0.485847013522 +1403715534412143104.0000000000 0.8866758903 1.5249819310 2.0193034911 0.2954668891 0.4407058382 -0.6937972578 0.486952817749 +1403715534462142976.0000000000 0.8470335045 1.4593717077 2.0086348311 0.2928591719 0.4394438578 -0.6948534874 0.488161072106 +1403715534512143104.0000000000 0.8080469765 1.3939085639 1.9954934944 0.2894612479 0.4369538956 -0.6964183304 0.490188727132 +1403715534562142976.0000000000 0.7702702334 1.3285784026 1.9816059910 0.2859345408 0.4328646799 -0.6989429930 0.492288837821 +1403715534612143104.0000000000 0.7337747585 1.2635363882 1.9676970520 0.2825412146 0.4271353627 -0.7027874717 0.493776886426 +1403715534662142976.0000000000 0.6977642060 1.1988860122 1.9534024409 0.2773661879 0.4210744240 -0.7071548584 0.495677650817 +1403715534712143104.0000000000 0.6623664634 1.1346564266 1.9388704317 0.2715365541 0.4139371081 -0.7122773931 0.497579024428 +1403715534762142976.0000000000 0.6278080201 1.0708315702 1.9237131739 0.2636122199 0.4063928079 -0.7192257886 0.498064000101 +1403715534812143104.0000000000 0.5939246864 1.0074096868 1.9080198614 0.2537535473 0.3984553416 -0.7268074717 0.498591392886 +1403715534862142976.0000000000 0.5612405468 0.9442389134 1.8921097489 0.2432713385 0.3895607655 -0.7348096162 0.499115511411 +1403715534912143104.0000000000 0.5299843778 0.8813588675 1.8758547719 0.2326153673 0.3801542276 -0.7428697019 0.499517227045 +1403715534962142976.0000000000 0.5005626705 0.8184041920 1.8598941205 0.2220761529 0.3707107408 -0.7498547212 0.500972679979 +1403715535012143104.0000000000 0.4731565970 0.7557347176 1.8441631256 0.2127975085 0.3616200642 -0.7556450385 0.502940081282 +1403715535062142976.0000000000 0.4477220432 0.6934634351 1.8282765366 0.2045229510 0.3535642602 -0.7612460471 0.503653782031 +1403715535112143104.0000000000 0.4242055488 0.6315476111 1.8122728595 0.1963760688 0.3466549889 -0.7671796802 0.502694834349 +1403715535162142976.0000000000 0.4030142195 0.5699007019 1.7964828107 0.1899912976 0.3404955944 -0.7730253293 0.500397739095 +1403715535212143104.0000000000 0.3844868586 0.5083493018 1.7805355613 0.1844517957 0.3354024003 -0.7788007834 0.496942757998 +1403715535262142976.0000000000 0.3688920541 0.4462619047 1.7655179569 0.1801316343 0.3309617075 -0.7835295222 0.494063184614 +1403715535312143104.0000000000 0.3561562158 0.3832603204 1.7514427392 0.1769692409 0.3269508183 -0.7874667594 0.491610773964 +1403715535362142976.0000000000 0.3470819001 0.3189847209 1.7385159849 0.1757986942 0.3224780298 -0.7906720751 0.489837125089 +1403715535412143104.0000000000 0.3409291945 0.2536897914 1.7266899466 0.1808508633 0.3146650760 -0.7940788097 0.487563020769 +1403715535462142976.0000000000 0.3373663623 0.1865203846 1.7157597726 0.1877598295 0.3062797265 -0.7951410900 0.488558719701 +1403715535512143104.0000000000 0.3358203921 0.1174008357 1.7055388814 0.1952672055 0.2989097735 -0.7938889012 0.492203289629 +1403715535562142976.0000000000 0.3352529424 0.0465467205 1.6953937722 0.2004705502 0.2944444827 -0.7905117678 0.498201917071 +1403715535612143104.0000000000 0.3355188630 -0.0259385475 1.6856501227 0.2049891592 0.2917178628 -0.7852400516 0.506239266109 +1403715535662142976.0000000000 0.3364203914 -0.0993302545 1.6751286280 0.2076364687 0.2919627865 -0.7806930252 0.51201877759 +1403715535712143104.0000000000 0.3379891460 -0.1732894100 1.6642166189 0.2091556357 0.2954386818 -0.7762053957 0.516212252 +1403715535762142976.0000000000 0.3395079961 -0.2472888862 1.6530710982 0.2112033601 0.3009517001 -0.7721402423 0.518286273339 +1403715535812143104.0000000000 0.3408306911 -0.3212698091 1.6417194872 0.2116515496 0.3095065270 -0.7666916593 0.521146074359 +1403715535862142976.0000000000 0.3421260194 -0.3948310052 1.6295425078 0.2104234609 0.3208869890 -0.7610808022 0.522981376338 +1403715535912143104.0000000000 0.3440338118 -0.4678072320 1.6169287256 0.2101717064 0.3326154898 -0.7573521460 0.521164577386 +1403715535962142976.0000000000 0.3467773825 -0.5402780653 1.6043504241 0.2105003514 0.3445815958 -0.7539832725 0.518133525952 +1403715536012143104.0000000000 0.3504652067 -0.6121240236 1.5917751616 0.2122396564 0.3544359130 -0.7525507684 0.51283218781 +1403715536062142976.0000000000 0.3553785133 -0.6835265216 1.5800272371 0.2129347459 0.3639265237 -0.7515362050 0.507355508443 +1403715536112143104.0000000000 0.3624334669 -0.7547181289 1.5688894872 0.2144633589 0.3716801652 -0.7509443410 0.501938162662 +1403715536162142976.0000000000 0.3714094730 -0.8259251851 1.5583398521 0.2154096327 0.3790226627 -0.7500836421 0.497307793188 +1403715536212143104.0000000000 0.3826719397 -0.8976203607 1.5483481447 0.2145079125 0.3866954004 -0.7485807682 0.494044386928 +1403715536262142976.0000000000 0.3966313039 -0.9690334529 1.5391270911 0.2132082558 0.3939400071 -0.7466491871 0.491801282869 +1403715536312143104.0000000000 0.4134176592 -1.0399346909 1.5310439300 0.2125129756 0.4002891110 -0.7438729152 0.491182195192 +1403715536362142976.0000000000 0.4330216846 -1.1102465468 1.5242202973 0.2121029179 0.4062089833 -0.7393930308 0.493259120627 +1403715536412143104.0000000000 0.4554720995 -1.1799474033 1.5183172997 0.2101698862 0.4123973393 -0.7334648083 0.497781506727 +1403715536462142976.0000000000 0.4808237747 -1.2484816337 1.5133393180 0.2079654800 0.4179800802 -0.7270159029 0.503478786662 +1403715536512143104.0000000000 0.5091346858 -1.3151373224 1.5091773218 0.2062065331 0.4223104327 -0.7211169625 0.509041344689 +1403715536562142976.0000000000 0.5404329108 -1.3795139888 1.5058910010 0.2054554753 0.4253554543 -0.7155299295 0.5146627101 +1403715536612143104.0000000000 0.5745967809 -1.4411838601 1.5032685145 0.2058983854 0.4270760100 -0.7107089678 0.519715979773 +1403715536662142976.0000000000 0.6115755457 -1.5000790967 1.5013590545 0.2070082538 0.4278710963 -0.7054391155 0.525765691215 +1403715536712143104.0000000000 0.6509904322 -1.5555319587 1.5002992456 0.2102186198 0.4269090677 -0.7003705830 0.532012994475 +1403715536762142976.0000000000 0.6926373354 -1.6070026840 1.5007891334 0.2162579525 0.4246313122 -0.6936816911 0.540117078163 +1403715536812143104.0000000000 0.7355904247 -1.6542304703 1.5017788009 0.2220703875 0.4233942898 -0.6867713717 0.547509909816 +1403715536862142976.0000000000 0.7792462818 -1.6973403561 1.5032043109 0.2259735574 0.4236300744 -0.6792142869 0.555104912506 +1403715536912143104.0000000000 0.8230044303 -1.7361454625 1.5048110408 0.2276489652 0.4245405681 -0.6711391654 0.563483340856 +1403715536962142976.0000000000 0.8662148814 -1.7701434422 1.5067182925 0.2267884039 0.4260636142 -0.6624826567 0.572846878373 +1403715537012143104.0000000000 0.9088292634 -1.7987906286 1.5091961596 0.2258536519 0.4270706291 -0.6541381252 0.581982919732 +1403715537062142976.0000000000 0.9512223450 -1.8212039050 1.5131122108 0.2271285686 0.4259843041 -0.6455903720 0.59174577103 +1403715537112143104.0000000000 0.9929216443 -1.8370620920 1.5184212529 0.2294944840 0.4238305275 -0.6361079309 0.602550135665 +1403715537162142976.0000000000 1.0330283112 -1.8454416675 1.5250928826 0.2332683929 0.4203058667 -0.6264591880 0.613577803566 +1403715537212143104.0000000000 1.0709560679 -1.8458389900 1.5328172554 0.2382165642 0.4157811196 -0.6181510900 0.623111674652 +1403715537262142976.0000000000 1.1061662360 -1.8379673804 1.5417299487 0.2447234247 0.4102746269 -0.6118843676 0.630382976126 +1403715537312143104.0000000000 1.1382034825 -1.8209857575 1.5520471027 0.2571567602 0.4020028962 -0.6119005134 0.630747044239 +1403715537362142976.0000000000 1.1660463493 -1.7956311988 1.5629870306 0.2702405810 0.3941300019 -0.6181764291 0.624090916897 +1403715537412143104.0000000000 1.1892154027 -1.7635787829 1.5731879542 0.2789338108 0.3889565190 -0.6298596795 0.611707070153 +1403715537462142976.0000000000 1.2077205833 -1.7257609785 1.5833131921 0.2859635996 0.3850772581 -0.6454530274 0.594416280464 +1403715537512143104.0000000000 1.2218154890 -1.6837680226 1.5932120287 0.2888333272 0.3834303319 -0.6627388494 0.574746646004 +1403715537562142976.0000000000 1.2320762935 -1.6388198298 1.6028086210 0.2887505478 0.3834404880 -0.6793381448 0.555064138912 +1403715537612143104.0000000000 1.2396067941 -1.5920900885 1.6130895641 0.2880462792 0.3832650757 -0.6935676145 0.53768130609 +1403715537662142976.0000000000 1.2450168024 -1.5448176495 1.6242346904 0.2865232875 0.3827939299 -0.7038337789 0.525348669633 +1403715537712143104.0000000000 1.2494684840 -1.4980938151 1.6373970106 0.2885680242 0.3794126916 -0.7079241608 0.521169729958 +1403715537762142976.0000000000 1.2526514862 -1.4518888194 1.6514153107 0.2912016843 0.3754655483 -0.7074474008 0.523206819744 +1403715537812143104.0000000000 1.2542041302 -1.4059090889 1.6661021741 0.2959907853 0.3702974595 -0.7042080545 0.528545421403 +1403715537862142976.0000000000 1.2532506430 -1.3602962865 1.6801242145 0.2979221634 0.3671591833 -0.7004066448 0.534665363161 +1403715537912143104.0000000000 1.2495379496 -1.3142654225 1.6933764352 0.3000622860 0.3645407401 -0.6984277662 0.5378395009 +1403715537962142976.0000000000 1.2427320010 -1.2678480754 1.7045111068 0.2980805003 0.3653226880 -0.6990236615 0.537636745036 +1403715538012143104.0000000000 1.2332296172 -1.2208414943 1.7148561974 0.2977162469 0.3657382853 -0.7026159643 0.532852089898 +1403715538062142976.0000000000 1.2214821437 -1.1741930324 1.7250413414 0.2963057601 0.3654929660 -0.7063756111 0.528820654291 +1403715538112143104.0000000000 1.2074875062 -1.1279187493 1.7351028404 0.2957022887 0.3637468220 -0.7116353701 0.523281478659 +1403715538162142976.0000000000 1.1913029766 -1.0827163807 1.7439518504 0.2940434021 0.3608962313 -0.7172306280 0.518529279937 +1403715538212143104.0000000000 1.1731817483 -1.0388610579 1.7502808589 0.2907603577 0.3573378547 -0.7225759243 0.515414498798 +1403715538262142976.0000000000 1.1534654934 -0.9962888984 1.7535414720 0.2865280232 0.3529674351 -0.7270261908 0.514537267366 +1403715538312143104.0000000000 1.1325421359 -0.9550020054 1.7544086373 0.2826922837 0.3469465895 -0.7302637770 0.516166594014 +1403715538362142976.0000000000 1.1102607621 -0.9153024181 1.7523243943 0.2782535665 0.3403983169 -0.7323614665 0.519952518013 +1403715538412143104.0000000000 1.0864369904 -0.8770908195 1.7484529808 0.2734969349 0.3328387685 -0.7312336719 0.528880986446 +1403715538462142976.0000000000 1.0606165822 -0.8398928239 1.7434943981 0.2657564059 0.3263815719 -0.7281832256 0.540923092706 +1403715538512143104.0000000000 1.0325132305 -0.8026770581 1.7393803282 0.2581252411 0.3190184265 -0.7248775832 0.553309219886 +1403715538562142976.0000000000 1.0022620914 -0.7651735508 1.7355380199 0.2487929800 0.3120026070 -0.7227492751 0.564260499887 +1403715538612143104.0000000000 0.9695522821 -0.7264082571 1.7318865255 0.2401249584 0.3038084407 -0.7227626853 0.572411160386 +1403715538662142976.0000000000 0.9347136674 -0.6861877174 1.7284218433 0.2311239726 0.2950876266 -0.7253848711 0.577340272877 +1403715538712143104.0000000000 0.8977862750 -0.6446777347 1.7246094920 0.2214297928 0.2855268773 -0.7303530242 0.579678970856 +1403715538762142976.0000000000 0.8588074124 -0.6016222748 1.7196936238 0.2098744853 0.2760466743 -0.7383026791 0.578498131346 +1403715538812143104.0000000000 0.8183128930 -0.5573811068 1.7142551427 0.1971808907 0.2660309301 -0.7483891509 0.574683320935 +1403715538862142976.0000000000 0.7764240077 -0.5122931175 1.7089331394 0.1834881844 0.2550178888 -0.7577260138 0.571969623786 +1403715538912143104.0000000000 0.7334988755 -0.4665044076 1.7025432205 0.1697328142 0.2423967083 -0.7666993961 0.569742611638 +1403715538962142976.0000000000 0.6902538842 -0.4206584299 1.6938849032 0.1560531584 0.2281090221 -0.7743776250 0.569168674141 +1403715539012143104.0000000000 0.6465505642 -0.3746486689 1.6825717991 0.1419812248 0.2125524282 -0.7806049063 0.570367230231 +1403715539062142976.0000000000 0.6027314139 -0.3282205342 1.6681938989 0.1285038733 0.1953937403 -0.7866221333 0.571431238343 +1403715539112143104.0000000000 0.5587440675 -0.2813327624 1.6507559604 0.1146504150 0.1777537758 -0.7920208047 0.572679598404 +1403715539162142976.0000000000 0.5149157320 -0.2342925904 1.6306188778 0.1014489986 0.1591876655 -0.7964450376 0.574493420279 +1403715539212143104.0000000000 0.4713359901 -0.1867137947 1.6075383757 0.0888442805 0.1401523407 -0.8007688147 0.575528731362 +1403715539262142976.0000000000 0.4281586001 -0.1388623486 1.5814118854 0.0754142035 0.1225484262 -0.8054268009 0.574962824426 +1403715539312143104.0000000000 0.3851676418 -0.0903987848 1.5520082999 0.0621064509 0.1057771308 -0.8105140275 0.572731174814 +1403715539362142976.0000000000 0.3426703454 -0.0414405366 1.5202041325 0.0495782656 0.0898447448 -0.8153569169 0.569792080918 +1403715539412143104.0000000000 0.3006366969 0.0069441455 1.4876522689 0.0375512235 0.0753900598 -0.8191892493 0.567305224941 +1403715539462142976.0000000000 0.2597730888 0.0544357159 1.4579027645 0.0272996939 0.0625982155 -0.8205421406 0.567491661215 +1403715539512143104.0000000000 0.2201696668 0.1015114873 1.4316421298 0.0197536642 0.0506812796 -0.8227130488 0.565848424908 +1403715539562142976.0000000000 0.1820877557 0.1478471955 1.4102926008 0.0174130959 0.0379520838 -0.8251426045 0.563379184599 +1403715539612143104.0000000000 0.1450233102 0.1923519416 1.3937708847 0.0172236585 0.0261923918 -0.8262136698 0.562484022977 +1403715539662142976.0000000000 0.1087477348 0.2355681841 1.3823137392 0.0175941332 0.0163851330 -0.8262020532 0.562860676499 +1403715539712143104.0000000000 0.0728184664 0.2774327011 1.3755610713 0.0177236555 0.0083670819 -0.8246308070 0.565331669127 +1403715539762142976.0000000000 0.0368385194 0.3180021116 1.3729125022 0.0164379276 0.0035115542 -0.8234435735 0.567149138048 +1403715539812143104.0000000000 0.0004083798 0.3581006099 1.3740463142 0.0151312969 0.0009872572 -0.8221081869 0.569129333445 +1403715539862142976.0000000000 -0.0362907173 0.3977780091 1.3779204361 0.0134629876 0.0013658514 -0.8226896765 0.568329639064 +1403715539912143104.0000000000 -0.0730637708 0.4367005209 1.3854651377 0.0135303925 0.0027661889 -0.8260942036 0.563362799143 +1403715539962142976.0000000000 -0.1102664004 0.4744169854 1.3978689545 0.0170362977 0.0027150873 -0.8296418826 0.558029335673 +1403715540012143104.0000000000 -0.1483197790 0.5106083488 1.4119692228 0.0192587370 0.0041139454 -0.8347560303 0.550267704306 +1403715540062142976.0000000000 -0.1866440645 0.5445306125 1.4271968484 0.0240738321 0.0034375308 -0.8403062958 0.541566213212 +1403715540112143104.0000000000 -0.2255374095 0.5757890484 1.4427580976 0.0294976331 0.0026914875 -0.8465949746 0.531412828685 +1403715540162142976.0000000000 -0.2649902978 0.6030638954 1.4605657307 0.0361503031 0.0010816031 -0.8502314741 0.525165141837 +1403715540212143104.0000000000 -0.3056477522 0.6264901870 1.4786601922 0.0405223965 0.0002758624 -0.8529187263 0.520468544367 +1403715540262142976.0000000000 -0.3480499189 0.6455159515 1.4976719607 0.0428086388 0.0004300383 -0.8523501474 0.521216329193 +1403715540312143104.0000000000 -0.3920659395 0.6608822481 1.5164022313 0.0412293188 0.0036141385 -0.8512612212 0.523107459895 +1403715540362142976.0000000000 -0.4375649206 0.6727096662 1.5347139631 0.0361905093 0.0092345550 -0.8500147052 0.525433126993 +1403715540412143104.0000000000 -0.4837750854 0.6817067024 1.5519975792 0.0309519130 0.0150271355 -0.8497908139 0.525995947545 +1403715540462142976.0000000000 -0.5303800395 0.6874618642 1.5685348803 0.0251833550 0.0207627985 -0.8496779291 0.526290909675 +1403715540512143104.0000000000 -0.5774575644 0.6909229637 1.5832568790 0.0180123418 0.0268134740 -0.8522794922 0.52208836442 +1403715540562142976.0000000000 -0.6242603319 0.6908764730 1.5971327637 0.0132511814 0.0296451381 -0.8552857158 0.517138198449 +1403715540612143104.0000000000 -0.6706630883 0.6874226056 1.6099901551 0.0087162353 0.0317838744 -0.8583460129 0.512011654857 +1403715540662142976.0000000000 -0.7159117709 0.6800871841 1.6228400415 0.0087758315 0.0301745779 -0.8613573595 0.507026605729 +1403715540712143104.0000000000 -0.7601335250 0.6685391182 1.6356075471 0.0134893737 0.0240808863 -0.8635071682 0.503580696803 +1403715540762142976.0000000000 -0.8038559880 0.6528479255 1.6478446950 0.0181275303 0.0179531378 -0.8648197966 0.501433741276 +1403715540812143104.0000000000 -0.8476253142 0.6323756892 1.6599007099 0.0216131780 0.0125819126 -0.8631697476 0.504294113372 +1403715540862142976.0000000000 -0.8918271688 0.6079604947 1.6711258386 0.0228878095 0.0093227878 -0.8605992387 0.508682793208 +1403715540912143104.0000000000 -0.9364934918 0.5797327144 1.6820651588 0.0242939905 0.0063741493 -0.8575619853 0.513767081122 +1403715540962142976.0000000000 -0.9818960377 0.5480025838 1.6923735177 0.0231352927 0.0058493744 -0.8539940633 0.519735204587 +1403715541012143104.0000000000 -1.0277315251 0.5130041758 1.7020430085 0.0205943050 0.0068281916 -0.8508074499 0.525029459819 +1403715541062142976.0000000000 -1.0737820696 0.4754330203 1.7115114529 0.0184643707 0.0081498849 -0.8482529860 0.529206498497 +1403715541112143104.0000000000 -1.1201699909 0.4357601054 1.7199372194 0.0156778664 0.0102476758 -0.8471585137 0.531010020924 +1403715541162142976.0000000000 -1.1661523139 0.3940236454 1.7282401968 0.0171568242 0.0094239185 -0.8462412914 0.532440146808 +1403715541212143104.0000000000 -1.2118424382 0.3496642469 1.7374124240 0.0243090216 0.0045471528 -0.8436766458 0.536281746975 +1403715541262142976.0000000000 -1.2580902151 0.3029211083 1.7468133050 0.0320356954 -0.0012391198 -0.8396061086 0.54224880003 +1403715541312143104.0000000000 -1.3058660240 0.2546055437 1.7553341654 0.0353600373 -0.0054583603 -0.8350812138 0.54896196621 +1403715541362142976.0000000000 -1.3554645801 0.2052913386 1.7620693673 0.0319953673 -0.0052320262 -0.8316764096 0.554313333821 +1403715541412143104.0000000000 -1.4062553030 0.1553110572 1.7674984427 0.0269410266 -0.0035010132 -0.8296303133 0.557651743623 +1403715541462142976.0000000000 -1.4579906656 0.1053620705 1.7706435460 0.0204236921 -0.0001918806 -0.8316800500 0.55487938364 +1403715541512143104.0000000000 -1.5100166002 0.0546541871 1.7731965536 0.0150307881 0.0024944056 -0.8354272693 0.549389780603 +1403715541562142976.0000000000 -1.5621936912 0.0028628306 1.7751982385 0.0096196604 0.0054546634 -0.8398123101 0.542764214574 +1403715541612143104.0000000000 -1.6139322223 -0.0504125815 1.7775061860 0.0069107581 0.0068171747 -0.8438576328 0.536479322153 +1403715541662142976.0000000000 -1.6655859039 -0.1052086891 1.7797297597 0.0016937868 0.0102776123 -0.8464107069 0.5324287906 +1403715541712143104.0000000000 -1.7165847051 -0.1619968518 1.7821378494 0.0052417419 -0.0152746333 0.8475748255 -0.530430131921 +1403715541762142976.0000000000 -1.7666101238 -0.2217827647 1.7850630064 0.0152507615 -0.0230149066 0.8454169073 -0.533392895719 +1403715541812143104.0000000000 -1.8151139406 -0.2836718908 1.7875439690 0.0264866572 -0.0315540268 0.8423979584 -0.537278773103 +1403715541862142976.0000000000 -1.8611105346 -0.3474275977 1.7910615362 0.0367327949 -0.0398127195 0.8373208783 -0.544021503202 +1403715541912143104.0000000000 -1.9037898136 -0.4122955160 1.7944881758 0.0457312362 -0.0482427621 0.8330625627 -0.549170334767 +1403715541962142976.0000000000 -1.9425400780 -0.4778546023 1.7978333715 0.0522445644 -0.0565768086 0.8295544807 -0.553090348712 +1403715542012143104.0000000000 -1.9771914593 -0.5437031408 1.8007686941 0.0572652138 -0.0657225524 0.8270410058 -0.55534171106 +1403715542062142976.0000000000 -2.0067587479 -0.6096567771 1.8041418439 0.0596792696 -0.0755201793 0.8227332241 -0.560218822724 +1403715542112143104.0000000000 -2.0308740441 -0.6752161073 1.8083327933 0.0570536367 -0.0834837876 0.8176268831 -0.566799452901 +1403715542162142976.0000000000 -2.0498145537 -0.7398207502 1.8129056997 0.0536422977 -0.0923506899 0.8115519927 -0.574436434387 +1403715542212143104.0000000000 -2.0633009097 -0.8033909901 1.8180905199 0.0459627289 -0.0999115545 0.8049658644 -0.583039506416 +1403715542262142976.0000000000 -2.0716694407 -0.8649167921 1.8241082056 0.0361549084 -0.1071843435 0.7985722589 -0.591173989965 +1403715542312143104.0000000000 -2.0753521262 -0.9237145324 1.8310161698 0.0216698683 -0.1120748338 0.7936900681 -0.597516296267 +1403715542362142976.0000000000 -2.0748687789 -0.9795356629 1.8386007812 0.0068962223 -0.1181114112 0.7882628994 -0.60385738222 +1403715542412143104.0000000000 -2.0707100134 -1.0322075275 1.8466961905 0.0126635023 0.1218970544 -0.7833867915 0.609332322075 +1403715542462142976.0000000000 -2.0639725305 -1.0819855155 1.8558342262 0.0334379006 0.1247686658 -0.7771298082 0.615941513452 +1403715542512143104.0000000000 -2.0560793370 -1.1282823280 1.8648657550 0.0516510596 0.1277488517 -0.7718760504 0.620660746095 +1403715542562142976.0000000000 -2.0477273826 -1.1713111844 1.8731446529 0.0653748413 0.1318995768 -0.7683839976 0.622827956982 +1403715542612143104.0000000000 -2.0396966577 -1.2105130357 1.8786018078 0.0749116691 0.1371181166 -0.7692200225 0.619586491822 +1403715542662142976.0000000000 -2.0321828373 -1.2461292147 1.8828103412 0.0814979654 0.1427667848 -0.7717534450 0.614306395043 +1403715542712143104.0000000000 -2.0249920127 -1.2786553442 1.8866772349 0.0882684903 0.1466678758 -0.7733161576 0.610474674469 +1403715542762142976.0000000000 -2.0182078568 -1.3086618803 1.8891587952 0.0916638656 0.1513931707 -0.7750704981 0.606583519919 +1403715542812143104.0000000000 -2.0116193174 -1.3362017715 1.8901777591 0.0934565864 0.1559085651 -0.7777837782 0.601673316777 +1403715542862142976.0000000000 -2.0051810450 -1.3616564587 1.8898901447 0.0958159495 0.1588841137 -0.7809695010 0.596373859838 +1403715542912143104.0000000000 -1.9989116474 -1.3847376166 1.8886743238 0.0991884046 0.1602759243 -0.7834790396 0.592143464833 +1403715542962142976.0000000000 -1.9925827630 -1.4062757143 1.8862676865 0.1042755507 0.1595086608 -0.7854701538 0.588829545927 +1403715543012143104.0000000000 -1.9867060510 -1.4262980698 1.8818859367 0.1099445410 0.1576762968 -0.7865295494 0.586874476516 +1403715543062142976.0000000000 -1.9814846700 -1.4452778968 1.8759144341 0.1145406663 0.1556745208 -0.7864976099 0.58657257777 +1403715543112143104.0000000000 -1.9771636709 -1.4631493376 1.8685721552 0.1182320426 0.1536121954 -0.7866267089 0.586210626242 +1403715543162142976.0000000000 -1.9739836353 -1.4799570910 1.8603323789 0.1196522776 0.1522374737 -0.7858953314 0.587261110783 +1403715543212143104.0000000000 -1.9720589433 -1.4957513602 1.8520611844 0.1212011521 0.1501510320 -0.7846290931 0.589170717739 +1403715543262142976.0000000000 -1.9713948766 -1.5103031837 1.8440363184 0.1232389481 0.1474557205 -0.7829914522 0.591602364668 +1403715543312143104.0000000000 -1.9722265983 -1.5232456460 1.8357720510 0.1249728260 0.1446838828 -0.7823028287 0.5928327344 +1403715543362142976.0000000000 -1.9749468248 -1.5347614942 1.8271085030 0.1239003656 0.1440671754 -0.7820355251 0.593560263015 +1403715543412143104.0000000000 -1.9794107012 -1.5446196880 1.8190664786 0.1227046681 0.1433693707 -0.7812357363 0.595029001278 +1403715543462142976.0000000000 -1.9853114395 -1.5529710537 1.8106603098 0.1187185602 0.1448777491 -0.7807969298 0.596047393868 +1403715543512143104.0000000000 -1.9925220199 -1.5597179805 1.8023000165 0.1143839814 0.1464421137 -0.7802872424 0.597179061449 +1403715543562142976.0000000000 -2.0005855443 -1.5650298058 1.7946706585 0.1114661943 0.1471056079 -0.7781909500 0.600294988305 +1403715543612143104.0000000000 -2.0094126348 -1.5685587973 1.7871515610 0.1091430825 0.1476076491 -0.7749845868 0.604730237082 +1403715543662142976.0000000000 -2.0194193857 -1.5696976113 1.7792780517 0.1052817637 0.1493157219 -0.7704231831 0.610793487427 +1403715543712143104.0000000000 -2.0305812141 -1.5682434770 1.7705673744 0.0995045316 0.1504625447 -0.7666489239 0.616205564964 +1403715543762142976.0000000000 -2.0428411100 -1.5642674034 1.7610350867 0.0900710835 0.1514177533 -0.7630336819 0.621883802749 +1403715543812143104.0000000000 -2.0555958276 -1.5572257706 1.7506351087 0.0783883786 0.1516865675 -0.7603695381 0.626645524083 +1403715543862142976.0000000000 -2.0683017846 -1.5467063800 1.7392058855 0.0660006414 0.1499763726 -0.7594377438 0.629607271493 +1403715543912143104.0000000000 -2.0804999812 -1.5325543052 1.7271920509 0.0531488101 0.1462385768 -0.7597399560 0.631335633285 +1403715543962142976.0000000000 -2.0918717836 -1.5144297129 1.7141535638 0.0397762881 0.1405651571 -0.7622212825 0.630617158103 +1403715544012143104.0000000000 -2.1019195438 -1.4924951116 1.7006521548 0.0257493077 0.1333455749 -0.7654361938 0.629017777217 +1403715544062142976.0000000000 -2.1102097654 -1.4667056285 1.6860041938 0.0120791762 0.1234073989 -0.7693727652 0.626650026386 +1403715544112143104.0000000000 -2.1161398910 -1.4377832697 1.6695663627 0.0043675630 0.1068540103 -0.7754093906 0.622337064456 +1403715544162142976.0000000000 -2.1202897484 -1.4062679019 1.6501294059 0.0024168874 -0.0869839600 0.7819149016 -0.617281974471 +1403715544212143104.0000000000 -2.1231059425 -1.3724155429 1.6275725744 0.0095871928 -0.0650082959 0.7875834719 -0.612694281001 +1403715544262142976.0000000000 -2.1247400075 -1.3368867173 1.6016928152 0.0184058822 -0.0418694913 0.7922692570 -0.608455087532 +1403715544312143104.0000000000 -2.1251799134 -1.2998238359 1.5721244614 0.0273143953 -0.0171429131 0.7963705265 -0.60394869715 +1403715544362142976.0000000000 -2.1246218205 -1.2614283435 1.5392135929 0.0361642610 0.0080955437 0.7996147387 -0.599368733022 +1403715544412143104.0000000000 -2.1229527117 -1.2217743632 1.5034777290 0.0442172338 0.0335473073 0.8016799838 -0.595171082995 +1403715544462142976.0000000000 -2.1207192357 -1.1809176772 1.4658866198 0.0538481568 0.0569795779 0.8018075720 -0.592417353832 +1403715544512143104.0000000000 -2.1177878071 -1.1386798069 1.4279394532 0.0641314306 0.0780955631 0.8013734042 -0.58956671352 +1403715544562142976.0000000000 -2.1141252932 -1.0954973774 1.3921800674 0.0736096675 0.0969393289 0.8002117889 -0.587235452207 +1403715544612143104.0000000000 -2.1096384451 -1.0512755171 1.3598527315 0.0821594098 0.1122897437 0.7985815526 -0.585583767412 +1403715544662142976.0000000000 -2.1040645377 -1.0062524710 1.3323759543 0.0897509506 0.1241404908 0.7972068258 -0.583947927717 +1403715544712143104.0000000000 -2.0979453653 -0.9607129370 1.3119758329 0.0978056333 0.1316182200 0.7934822077 -0.586085905211 +1403715544762142976.0000000000 -2.0908527273 -0.9143620880 1.2983057581 0.1041698051 0.1366349295 0.7892196032 -0.58958626655 +1403715544812143104.0000000000 -2.0826122542 -0.8664261948 1.2915787947 0.1092987921 0.1396479039 0.7857265447 -0.592609512158 +1403715544862142976.0000000000 -2.0731766490 -0.8167746761 1.2920009726 0.1131903124 0.1409910817 0.7831763279 -0.594932187331 +1403715544912143104.0000000000 -2.0624079571 -0.7651235974 1.2982338151 0.1149097135 0.1417851131 0.7828303900 -0.594869162009 +1403715544962142976.0000000000 -2.0505259525 -0.7118207841 1.3074937334 0.1157175440 0.1424528241 0.7846714751 -0.592121034211 +1403715545012143104.0000000000 -2.0378472879 -0.6572951958 1.3176770774 0.1167212281 0.1433274001 0.7878333858 -0.587496355367 +1403715545062142976.0000000000 -2.0246974769 -0.6020009435 1.3284097946 0.1180608443 0.1454094298 0.7900005170 -0.583795270492 +1403715545112143104.0000000000 -2.0112301342 -0.5461274397 1.3383947490 0.1205617078 0.1483501310 0.7919212101 -0.579929228684 +1403715545162142976.0000000000 -1.9974227522 -0.4898296669 1.3463333542 0.1243163141 0.1522008857 0.7933742580 -0.576140287702 +1403715545212143104.0000000000 -1.9832062809 -0.4334435089 1.3517249822 0.1278694218 0.1581189287 0.7938876828 -0.573053367898 +1403715545262142976.0000000000 -1.9688131575 -0.3771690862 1.3537181989 0.1323760783 0.1644077899 0.7946305331 -0.569217856753 +1403715545312143104.0000000000 -1.9541015072 -0.3209163184 1.3529060828 0.1365448866 0.1720385284 0.7946249119 -0.56597657906 +1403715545362142976.0000000000 -1.9387934577 -0.2648801339 1.3500163599 0.1389208904 0.1802933621 0.7937193763 -0.564096482391 +1403715545412143104.0000000000 -1.9227844895 -0.2091939583 1.3467612909 0.1372200833 0.1901384376 0.7917239974 -0.564084333482 +1403715545462142976.0000000000 -1.9063169279 -0.1533732403 1.3443134863 0.1334325463 0.2003970615 0.7897914976 -0.56415083414 +1403715545512143104.0000000000 -1.8899818914 -0.0976320336 1.3429974245 0.1281759659 0.2103941430 0.7876329256 -0.564747377846 +1403715545562142976.0000000000 -1.8749345775 -0.0419136838 1.3436909255 0.1235904329 0.2192588987 0.7856146822 -0.565208378683 +1403715545612143104.0000000000 -1.8612298598 0.0141478105 1.3466169111 0.1190084553 0.2268371318 0.7835869556 -0.566015358634 +1403715545662142976.0000000000 -1.8491698397 0.0711006466 1.3502567460 0.1155386406 0.2320066791 0.7820917539 -0.56670646013 +1403715545712143104.0000000000 -1.8389146993 0.1289269581 1.3537299922 0.1129793687 0.2340318328 0.7814685083 -0.567249269767 +1403715545762142976.0000000000 -1.8307992296 0.1875952476 1.3563316025 0.1119508804 0.2332967764 0.7821245422 -0.566851669228 +1403715545812143104.0000000000 -1.8245873188 0.2472409309 1.3579876871 0.1123700010 0.2294008759 0.7836511265 -0.566250062258 +1403715545862142976.0000000000 -1.8199751877 0.3074827082 1.3597108323 0.1124830533 0.2230987844 0.7850914746 -0.566750272723 +1403715545912143104.0000000000 -1.8167352974 0.3686357347 1.3613343678 0.1134993410 0.2132954291 0.7878671121 -0.566470099031 +1403715545962142976.0000000000 -1.8144842320 0.4305000771 1.3631528261 0.1143030253 0.2005143005 0.7906210351 -0.5671395001 +1403715546012143104.0000000000 -1.8128611272 0.4925409023 1.3650573135 0.1136732889 0.1855701308 0.7941626772 -0.567404399075 +1403715546062142976.0000000000 -1.8114423866 0.5547192558 1.3675376278 0.1108464270 0.1692436596 0.7972537579 -0.568732009672 +1403715546112143104.0000000000 -1.8096158794 0.6168966619 1.3707787352 0.1054601043 0.1518077020 0.8006226044 -0.569943886125 +1403715546162142976.0000000000 -1.8073912560 0.6789100973 1.3749745473 0.0959301880 0.1343540904 0.8035898194 -0.571830201723 +1403715546212143104.0000000000 -1.8051248397 0.7406944307 1.3794880472 0.0857508485 0.1151423019 0.8063927525 -0.573689612019 +1403715546262142976.0000000000 -1.8024374977 0.8026141405 1.3843827494 0.0729612859 0.0960043234 0.8091930698 -0.575035995829 +1403715546312143104.0000000000 -1.7996290067 0.8645364634 1.3900543551 0.0591227284 0.0767271156 0.8115797046 -0.576156086382 +1403715546362142976.0000000000 -1.7963901900 0.9264496495 1.3962775711 0.0452005018 0.0566868878 0.8131840497 -0.577473127218 +1403715546412143104.0000000000 -1.7929756427 0.9883453433 1.4027926439 0.0304269424 0.0368423533 0.8154600519 -0.576837711961 +1403715546462142976.0000000000 -1.7898046153 1.0504860007 1.4103765345 0.0155924632 0.0165803114 0.8165613963 -0.576809721174 +1403715546512143104.0000000000 -1.7867699788 1.1126166874 1.4183607226 0.0009803834 -0.0040406734 0.8177119775 -0.5756125725 +1403715546562142976.0000000000 -1.7839173605 1.1743471115 1.4264575038 0.0138501789 0.0248363518 -0.8176941406 0.574950102642 +1403715546612143104.0000000000 -1.7815719392 1.2359049674 1.4340008332 0.0266164016 0.0472356127 -0.8179879104 0.572674551944 +1403715546662142976.0000000000 -1.7794251023 1.2971031925 1.4409847895 0.0391424924 0.0700705986 -0.8188085022 0.568428195251 +1403715546712143104.0000000000 -1.7773475761 1.3576515698 1.4472858450 0.0512084198 0.0934084296 -0.8201812147 0.562099046438 +1403715546762142976.0000000000 -1.7751994139 1.4175006749 1.4523067930 0.0628002375 0.1168743884 -0.8232457034 0.551962878554 +1403715546812143104.0000000000 -1.7724622730 1.4758832229 1.4572033364 0.0758031294 0.1386236897 -0.8263536530 0.540533993716 +1403715546862142976.0000000000 -1.7690295398 1.5322924496 1.4626835981 0.0897666198 0.1588688553 -0.8275766003 0.530866849014 +1403715546912143104.0000000000 -1.7651146854 1.5861933656 1.4688966632 0.1044804542 0.1778362597 -0.8265143458 0.523767253345 +1403715546962142976.0000000000 -1.7612456091 1.6372281907 1.4745007258 0.1137152432 0.2006816852 -0.8232012313 0.518782649494 +1403715547012143104.0000000000 -1.7565259464 1.6853257696 1.4803147520 0.1213097812 0.2239874220 -0.8180214629 0.515707725383 +1403715547062142976.0000000000 -1.7502982355 1.7311206743 1.4859147800 0.1297897736 0.2461337658 -0.8126982602 0.511951483871 +1403715547112143104.0000000000 -1.7418994595 1.7746840392 1.4917080514 0.1395565897 0.2669794520 -0.8066273546 0.508525556274 +1403715547162142976.0000000000 -1.7314390068 1.8163187501 1.4975219332 0.1493484443 0.2873654359 -0.7997599936 0.505470178173 +1403715547212143104.0000000000 -1.7187736814 1.8559241100 1.5035103007 0.1595143347 0.3072837698 -0.7922828557 0.502413911443 +1403715547262142976.0000000000 -1.7037969608 1.8935267623 1.5094491956 0.1685973024 0.3269776812 -0.7842100705 0.49967500535 +1403715547312143104.0000000000 -1.6863643421 1.9293442396 1.5152218464 0.1769244229 0.3456105690 -0.7765730486 0.496170720057 +1403715547362142976.0000000000 -1.6664555637 1.9637012948 1.5208044211 0.1855991231 0.3624235386 -0.7696600026 0.491757688833 +1403715547412143104.0000000000 -1.6438286160 1.9968077764 1.5258165981 0.1943232427 0.3777748875 -0.7641059493 0.485455157557 +1403715547462142976.0000000000 -1.6183112621 2.0289166568 1.5298937775 0.2023340699 0.3924816945 -0.7596181218 0.477492777732 +1403715547512143104.0000000000 -1.5899314667 2.0599593768 1.5333749335 0.2106945586 0.4066819446 -0.7547859439 0.469591074993 +1403715547562142976.0000000000 -1.5583634136 2.0898370516 1.5360498762 0.2185437776 0.4219604724 -0.7486189857 0.462339259848 +1403715547612143104.0000000000 -1.5231748204 2.1187787064 1.5385230085 0.2270840142 0.4374015116 -0.7412282953 0.455733894249 +1403715547662142976.0000000000 -1.4844487639 2.1467689311 1.5407582572 0.2350631817 0.4531031730 -0.7330969869 0.449457031374 +1403715547712143104.0000000000 -1.4421278692 2.1736110404 1.5429533224 0.2423801694 0.4688561311 -0.7242913687 0.443652786548 +1403715547762142976.0000000000 -1.3959629333 2.1997005948 1.5455224416 0.2502091240 0.4839540643 -0.7150870618 0.43798898614 +1403715547812143104.0000000000 -1.3459545994 2.2249482866 1.5481475763 0.2586411310 0.4979528445 -0.7059247407 0.432224467697 +1403715547862142976.0000000000 -1.2919479749 2.2496346319 1.5507953242 0.2678144390 0.5109939856 -0.6966151984 0.426483104448 +1403715547912143104.0000000000 -1.2339197639 2.2735718530 1.5538503569 0.2778904597 0.5225866490 -0.6856811137 0.423699772383 +1403715547962142976.0000000000 -1.1720865555 2.2969943818 1.5571283990 0.2895405498 0.5315613365 -0.6749165438 0.42201477994 +1403715548012143104.0000000000 -1.1066256032 2.3200047229 1.5609057859 0.3028493592 0.5365426332 -0.6651555527 0.421867703338 +1403715548062142976.0000000000 -1.0381793819 2.3426242168 1.5644706996 0.3142576063 0.5402974469 -0.6546792930 0.425106867781 +1403715548112143104.0000000000 -0.9678111501 2.3648479684 1.5678742211 0.3243674750 0.5425788603 -0.6440960983 0.430736738181 +1403715548162142976.0000000000 -0.8961399863 2.3870570283 1.5704884225 0.3322347381 0.5440371343 -0.6355522082 0.435565225886 +1403715548212143104.0000000000 -0.8234992028 2.4093633969 1.5724657694 0.3376650516 0.5452186682 -0.6281274540 0.440652718587 +1403715548262142976.0000000000 -0.7502102943 2.4320985061 1.5739509000 0.3413599975 0.5458606495 -0.6219123917 0.445796456399 +1403715548312143104.0000000000 -0.6764813275 2.4556501352 1.5740966600 0.3442525518 0.5458622926 -0.6175698312 0.449590971653 +1403715548362142976.0000000000 -0.6027595509 2.4798993006 1.5707571747 0.3451853264 0.5457395902 -0.6158977622 0.451315118989 +1403715548412143104.0000000000 -0.5292708118 2.5047926970 1.5641821232 0.3444677306 0.5459753811 -0.6144407956 0.453558567849 +1403715548462142976.0000000000 -0.4556721059 2.5306847104 1.5548565052 0.3439792704 0.5452393257 -0.6153360326 0.453601042939 +1403715548512143104.0000000000 -0.3822141479 2.5575270514 1.5441082141 0.3439209152 0.5440134409 -0.6166903229 0.453277868266 +1403715548562142976.0000000000 -0.3089326989 2.5854861915 1.5333387679 0.3452373757 0.5412304355 -0.6195703967 0.451678307666 +1403715548612143104.0000000000 -0.2359574819 2.6141733034 1.5223941749 0.3461270152 0.5386258826 -0.6225214243 0.450050357387 +1403715548662142976.0000000000 -0.1632217103 2.6433902058 1.5113474648 0.3465991285 0.5359161372 -0.6252469757 0.449142691613 +1403715548712143104.0000000000 -0.0908737576 2.6733392229 1.5004028360 0.3472602558 0.5330359178 -0.6275942813 0.448785520219 +1403715548762142976.0000000000 -0.0189529235 2.7037125878 1.4897217789 0.3478727266 0.5304098535 -0.6293657351 0.448941783407 +1403715548812143104.0000000000 0.0528996218 2.7341592663 1.4793143486 0.3473891700 0.5283193965 -0.6316056894 0.448635300562 +1403715548862142976.0000000000 0.1247660865 2.7647745537 1.4692776296 0.3469999961 0.5261914313 -0.6328574778 0.449672095123 +1403715548912143104.0000000000 0.1966874939 2.7953173876 1.4595473249 0.3474917587 0.5236382981 -0.6343627195 0.450151475122 +1403715548962142976.0000000000 0.2683848690 2.8260469550 1.4496457996 0.3483151375 0.5228681679 -0.6343076802 0.450487747669 +1403715549012143104.0000000000 0.3395265424 2.8573378739 1.4396771999 0.3500770780 0.5233387355 -0.6331073057 0.450264085702 +1403715549062142976.0000000000 0.4100183586 2.8892442145 1.4299759708 0.3531131957 0.5249555351 -0.6301335940 0.450182641651 +1403715549112143104.0000000000 0.4801898333 2.9216427212 1.4212821575 0.3587985465 0.5259194492 -0.6257007056 0.45074489792 +1403715549162142976.0000000000 0.5497521721 2.9538847640 1.4136707481 0.3648699667 0.5266403764 -0.6194257570 0.453686624222 +1403715549212143104.0000000000 0.6181532673 2.9861829208 1.4068944206 0.3711634007 0.5267510466 -0.6131171216 0.457010350158 +1403715549262142976.0000000000 0.6850701861 3.0185365129 1.4003684412 0.3778959751 0.5261122826 -0.6071351704 0.460203632097 +1403715549312143104.0000000000 0.7497783753 3.0507302207 1.3937251083 0.3829535036 0.5262308448 -0.6017574436 0.462942427508 +1403715549362142976.0000000000 0.8117952251 3.0836914502 1.3877866942 0.3909473221 0.5241307667 -0.5996960143 0.461315316359 +1403715549412143104.0000000000 0.8711209208 3.1166818681 1.3814723851 0.3975635291 0.5226136866 -0.6002668465 0.456615689485 +1403715549462142976.0000000000 0.9277872865 3.1491186003 1.3749970680 0.4033324691 0.5214958778 -0.6027231450 0.449543968141 +1403715549512143104.0000000000 0.9822090718 3.1803091467 1.3682567723 0.4068958192 0.5214252115 -0.6057083722 0.442344785229 +1403715549562142976.0000000000 1.0341138686 3.2102525231 1.3610798588 0.4081080961 0.5227683255 -0.6102840076 0.433260302584 +1403715549612143104.0000000000 1.0841196174 3.2382311194 1.3541661626 0.4089160590 0.5226642065 -0.6158865459 0.42460987564 +1403715549662142976.0000000000 1.1326439198 3.2636892818 1.3471753792 0.4079683495 0.5215739648 -0.6229058961 0.416546119452 +1403715549712143104.0000000000 1.1805280677 3.2860877844 1.3410412103 0.4079112304 0.5170790977 -0.6295693355 0.41216512071 +1403715549762142976.0000000000 1.2277473425 3.3049020246 1.3355755085 0.4075018061 0.5107839800 -0.6357334916 0.410956118658 +1403715549812143104.0000000000 1.2744860444 3.3201105339 1.3311663582 0.4067626165 0.5023868228 -0.6415293575 0.413027526489 +1403715549862142976.0000000000 1.3199455253 3.3317902924 1.3269257040 0.4052870767 0.4927688280 -0.6478654006 0.416163057343 +1403715549912143104.0000000000 1.3642363338 3.3398191633 1.3233072527 0.4037738321 0.4812789386 -0.6565597623 0.417452457624 +1403715549962142976.0000000000 1.4072732519 3.3438304012 1.3210396411 0.4024427363 0.4675316223 -0.6664945843 0.418615569831 +1403715550012143104.0000000000 1.4489186531 3.3431913585 1.3191729007 0.3993342768 0.4531894233 -0.6776449172 0.419462570588 +1403715550062142976.0000000000 1.4884233853 3.3379208888 1.3168110248 0.3926465714 0.4397869596 -0.6893201449 0.421015246727 +1403715550112143104.0000000000 1.5257118247 3.3273745776 1.3147994518 0.3818734670 0.4280702440 -0.6995899755 0.426030970121 +1403715550162142976.0000000000 1.5610563572 3.3115350723 1.3145214534 0.3678745616 0.4182002472 -0.7085683765 0.433252485224 +1403715550212143104.0000000000 1.5942913988 3.2909001626 1.3177021827 0.3538114589 0.4081958276 -0.7165038854 0.441379428718 +1403715550262142976.0000000000 1.6254828184 3.2662013088 1.3242316072 0.3390849923 0.3987543963 -0.7243576073 0.448689598882 +1403715550312143104.0000000000 1.6551875317 3.2375664278 1.3346232592 0.3250637473 0.3889370126 -0.7318867702 0.455415542144 +1403715550362142976.0000000000 1.6833378803 3.2051387355 1.3489132504 0.3120742307 0.3782549980 -0.7380343269 0.463506378965 +1403715550412143104.0000000000 1.7102919281 3.1691491847 1.3659434050 0.2983658667 0.3676099580 -0.7431026065 0.472905111525 +1403715550462142976.0000000000 1.7361284778 3.1302741804 1.3835279789 0.2840332005 0.3566644785 -0.7477093228 0.482748753861 +1403715550512143104.0000000000 1.7608926759 3.0890349539 1.4014374702 0.2704267086 0.3446023703 -0.7523947037 0.491956107298 +1403715550562142976.0000000000 1.7846514797 3.0461290511 1.4180517925 0.2574931716 0.3316407737 -0.7579227664 0.499264202563 +1403715550612143104.0000000000 1.8076686132 3.0022678001 1.4320399091 0.2470261718 0.3167452112 -0.7640137978 0.50490935655 +1403715550662142976.0000000000 1.8297875193 2.9573441879 1.4429238676 0.2385213181 0.3000164875 -0.7703994694 0.509492242882 +1403715550712143104.0000000000 1.8509214538 2.9110349835 1.4507855679 0.2307184698 0.2824438693 -0.7767274292 0.513506522964 +1403715550762142976.0000000000 1.8710398263 2.8636315072 1.4559460164 0.2250587920 0.2633511498 -0.7832541837 0.516243736747 +1403715550812143104.0000000000 1.8895900759 2.8150406659 1.4578309201 0.2203754931 0.2435991176 -0.7897707100 0.518031212996 +1403715550862142976.0000000000 1.9062291008 2.7648878308 1.4564985515 0.2151507540 0.2242489765 -0.7958723049 0.519624695256 +1403715550912143104.0000000000 1.9206924417 2.7130640902 1.4526550745 0.2099979766 0.2046886117 -0.8015669639 0.521050692792 +1403715550962142976.0000000000 1.9325984987 2.6589317318 1.4468587581 0.2033762174 0.1860156113 -0.8062978587 0.52337373797 +1403715551012143104.0000000000 1.9414055712 2.6025676206 1.4406089689 0.1946720845 0.1690268216 -0.8104798428 0.525980168361 +1403715551062142976.0000000000 1.9467265155 2.5433749307 1.4362659309 0.1818903169 0.1549111731 -0.8130892699 0.530852409039 +1403715551112143104.0000000000 1.9482767769 2.4819934366 1.4353598767 0.1688930264 0.1408307635 -0.8151270796 0.535919476877 +1403715551162142976.0000000000 1.9462372461 2.4186481336 1.4379778773 0.1559353620 0.1266707271 -0.8169092591 0.540645865751 +1403715551212143104.0000000000 1.9410969496 2.3534702070 1.4442649640 0.1457362366 0.1104990594 -0.8189363567 0.543961534349 +1403715551262142976.0000000000 1.9328441742 2.2863290918 1.4540891630 0.1368469844 0.0929958199 -0.8199593194 0.547988498803 +1403715551312143104.0000000000 1.9212109711 2.2179940861 1.4655676037 0.1294510412 0.0738749526 -0.8217309987 0.550039166857 +1403715551362142976.0000000000 1.9058413386 2.1486773420 1.4774653565 0.1215240962 0.0549390756 -0.8232856062 0.551737621234 +1403715551412143104.0000000000 1.8867308174 2.0782304511 1.4893410126 0.1133774048 0.0358983860 -0.8240716634 0.553861682711 +1403715551462142976.0000000000 1.8638423127 2.0070023221 1.5008592013 0.1036999171 0.0176137974 -0.8237780490 0.55706894298 +1403715551512143104.0000000000 1.8370475681 1.9351948589 1.5119124442 0.0926558597 0.0004181246 -0.8231628596 0.560194272984 +1403715551562142976.0000000000 1.8058842560 1.8628540454 1.5226763270 0.0788353484 -0.0152088628 -0.8211830027 0.564988632157 +1403715551612143104.0000000000 1.7706266711 1.7906095060 1.5329063271 0.0622777802 -0.0285969224 -0.8190499274 0.569614703649 +1403715551662142976.0000000000 1.7314847323 1.7187107466 1.5435746852 0.0441132009 -0.0408475862 -0.8148113582 0.576600338783 +1403715551712143104.0000000000 1.6893119652 1.6475464406 1.5546355202 0.0262743390 -0.0534702507 -0.8093738733 0.584264088142 +1403715551762142976.0000000000 1.6444437833 1.5781024745 1.5656311001 0.0097360179 -0.0666921272 -0.8043366083 0.590338877859 +1403715551812143104.0000000000 1.5971958340 1.5107294124 1.5768301751 0.0044823324 0.0815638554 0.7977896555 -0.597376691696 +1403715551862142976.0000000000 1.5479589178 1.4456489699 1.5881376560 0.0172332818 0.0972106558 0.7907210817 -0.604163283656 +1403715551912143104.0000000000 1.4969484873 1.3833367833 1.5995213376 0.0290254410 0.1132934545 0.7819591327 -0.612259774757 +1403715551962142976.0000000000 1.4441566876 1.3245659054 1.6101404977 0.0433076338 0.1274403481 0.7746323179 -0.617922469705 +1403715552012143104.0000000000 1.3897316735 1.2697946937 1.6200523306 0.0604735343 0.1394509102 0.7689807803 -0.620938769034 +1403715552062142976.0000000000 1.3344760053 1.2193629411 1.6284775414 0.0799549672 0.1494594725 0.7666311806 -0.619310666975 +1403715552112143104.0000000000 1.2790802533 1.1730505839 1.6366200821 0.0949379957 0.1617858318 0.7643947407 -0.616857197461 +1403715552162142976.0000000000 1.2236494759 1.1307878113 1.6439520583 0.1101216357 0.1738794304 0.7628953807 -0.612886455347 +1403715552212143104.0000000000 1.1689145774 1.0924443341 1.6518042596 0.1249632283 0.1860500079 0.7584874989 -0.611936516386 +1403715552262142976.0000000000 1.1143608002 1.0574298256 1.6597323295 0.1419769038 0.1972971195 0.7523886304 -0.612231781421 +1403715552312143104.0000000000 1.0608455973 1.0261018776 1.6676371410 0.1574071149 0.2097571281 0.7446382967 -0.613790480953 +1403715552362142976.0000000000 1.0086658387 0.9987526958 1.6746181022 0.1726902859 0.2230474123 0.7378729380 -0.613165103658 +1403715552412143104.0000000000 0.9581408967 0.9756175365 1.6809807381 0.1878399628 0.2373626912 0.7320268298 -0.610337465417 +1403715552462142976.0000000000 0.9097651066 0.9566838917 1.6873985885 0.2022166356 0.2527735228 0.7256381137 -0.607176503468 +1403715552512143104.0000000000 0.8635356643 0.9415135795 1.6939827125 0.2153272005 0.2695137037 0.7179925215 -0.604552147661 +1403715552562142976.0000000000 0.8199425336 0.9301526995 1.7004388482 0.2270216331 0.2876168808 0.7094108744 -0.602058069661 +1403715552612143104.0000000000 0.7786692736 0.9228781127 1.7068735851 0.2383954510 0.3064176834 0.6993319837 -0.600175465023 +1403715552662142976.0000000000 0.7400998957 0.9199383749 1.7128120258 0.2480894516 0.3268011828 0.6890140518 -0.597421331464 +1403715552712143104.0000000000 0.7041394367 0.9213077173 1.7177272543 0.2576493533 0.3477696996 0.6791421806 -0.592822861595 +1403715552762142976.0000000000 0.6705201538 0.9268948041 1.7217454602 0.2669176543 0.3694415057 0.6696985323 -0.586320574048 +1403715552812143104.0000000000 0.6391698952 0.9367558180 1.7252616624 0.2766308208 0.3908686841 0.6597475757 -0.579163359692 +1403715552862142976.0000000000 0.6100633389 0.9513081379 1.7274740739 0.2860836388 0.4124811107 0.6501373886 -0.570383082501 +1403715552912143104.0000000000 0.5834492867 0.9702629501 1.7288876853 0.2929068547 0.4350754561 0.6398744807 -0.561672120451 +1403715552962142976.0000000000 0.5592439979 0.9934856308 1.7291970074 0.2974804259 0.4582225882 0.6297030637 -0.552278469097 +1403715553012143104.0000000000 0.5367280934 1.0212520937 1.7287306336 0.3013398596 0.4811663127 0.6182847138 -0.543504628567 +1403715553062142976.0000000000 0.5154732459 1.0535176721 1.7272099020 0.3056968639 0.5028694565 0.6060912092 -0.535093620992 +1403715553112143104.0000000000 0.4954940121 1.0905882445 1.7246486739 0.3122189732 0.5223264998 0.5940591567 -0.526106508971 +1403715553162142976.0000000000 0.4765566960 1.1325282556 1.7214699329 0.3229919452 0.5383581439 0.5817510269 -0.517119381759 +1403715553212143104.0000000000 0.4586051910 1.1791208118 1.7182394279 0.3355545579 0.5521833234 0.5684923703 -0.50922798528 +1403715553262142976.0000000000 0.4416885290 1.2301224175 1.7149074222 0.3467767656 0.5656262774 0.5532491095 -0.503714415093 +1403715553312143104.0000000000 0.4260675001 1.2859366609 1.7111061925 0.3612909110 0.5764445977 0.5379435564 -0.497792359853 +1403715553362142976.0000000000 0.4125287996 1.3467579977 1.7069974378 0.3796616707 0.5842388404 0.5216595526 -0.492334545125 +1403715553412143104.0000000000 0.4019621507 1.4119356213 1.7020030806 0.3993973465 0.5906372151 0.5064294883 -0.484931555062 +1403715553462142976.0000000000 0.3948504093 1.4810540192 1.6963494955 0.4235495267 0.5935552716 0.4920404330 -0.475598728162 +1403715553512143104.0000000000 0.3917769919 1.5529833876 1.6897518172 0.4449469881 0.5972680172 0.4774445316 -0.466197182179 +1403715553562142976.0000000000 0.3932173474 1.6270384309 1.6817306308 0.4645520183 0.6008855077 0.4646913101 -0.45518129926 +1403715553612143104.0000000000 0.3998155114 1.7024546047 1.6725252085 0.4801049950 0.6056669882 0.4542604669 -0.443073494338 +1403715553662142976.0000000000 0.4118206497 1.7784213453 1.6627285166 0.4933042754 0.6096087288 0.4467152696 -0.430666411038 +1403715553712143104.0000000000 0.4294512438 1.8541558272 1.6518108975 0.5001190107 0.6156524314 0.4425729118 -0.418308829225 +1403715553762142976.0000000000 0.4523751185 1.9293066312 1.6393920544 0.5016129967 0.6239185664 0.4444571338 -0.401955072474 +1403715553812143104.0000000000 0.4797469963 2.0035986780 1.6262520980 0.4988900958 0.6335121904 0.4494907443 -0.384355366547 +1403715553862142976.0000000000 0.5108545064 2.0766566617 1.6140806870 0.4951555243 0.6418236066 0.4556421628 -0.367795710026 +1403715553912143104.0000000000 0.5446991506 2.1485505000 1.6030254043 0.4915278179 0.6484049195 0.4619605393 -0.352936148369 +1403715553962142976.0000000000 0.5802117284 2.2189833133 1.5928012230 0.4849871888 0.6555587526 0.4681607401 -0.340375777604 +1403715554012143104.0000000000 0.6162877473 2.2880571265 1.5832682421 0.4753429227 0.6639929960 0.4737855889 -0.329681092609 +1403715554062142976.0000000000 0.6524567565 2.3556952849 1.5734898702 0.4628408675 0.6732074705 0.4794991183 -0.320391367854 +1403715554112143104.0000000000 0.6878002674 2.4226316497 1.5639461359 0.4496177533 0.6821424240 0.4853776152 -0.311342512311 +1403715554162142976.0000000000 0.7215649489 2.4891711712 1.5545762997 0.4371782169 0.6897069678 0.4920415208 -0.301785763586 +1403715554212143104.0000000000 0.7520882532 2.5556470639 1.5464181168 0.4264949480 0.6958318514 0.4968444703 -0.295068917914 +1403715554262142976.0000000000 0.7786605943 2.6225248615 1.5388063466 0.4191529778 0.6991689622 0.5023034430 -0.288383069377 +1403715554312143104.0000000000 0.8010213527 2.6899675408 1.5309604434 0.4152012704 0.7001047916 0.5083660104 -0.281114185326 +1403715554362142976.0000000000 0.8186068198 2.7582222056 1.5212623905 0.4176119337 0.6959140225 0.5170960420 -0.271874289843 +1403715554412143104.0000000000 0.8311650449 2.8263733400 1.5094214690 0.4277161263 0.6847650019 0.5284190202 -0.262543608931 +1403715554462142976.0000000000 0.8389480218 2.8937628144 1.4958304631 0.4505827395 0.6618045133 0.5438326377 -0.251467777886 +1403715554512143104.0000000000 0.8425277278 2.9583455977 1.4791040521 0.4762135211 0.6341112024 0.5597430820 -0.240439904054 +1403715554562142976.0000000000 0.8426564551 3.0180149181 1.4595591314 0.5028481110 0.6042620611 0.5747311991 -0.227365757163 +1403715554612143104.0000000000 0.8394289780 3.0702138603 1.4385611656 0.5280223196 0.5750384509 0.5864851924 -0.215773791528 +1403715554662142976.0000000000 0.8336302382 3.1133971737 1.4154263954 0.5479058623 0.5505659450 0.5954419268 -0.205244289098 +1403715554712143104.0000000000 0.8257871143 3.1455206024 1.3911021913 0.5632268125 0.5313503991 0.6011484373 -0.197643283232 +1403715554762142976.0000000000 0.8163230531 3.1647669005 1.3661996363 0.5757725660 0.5159395376 0.6045002095 -0.192020422297 +1403715554812143104.0000000000 0.8048530335 3.1692082099 1.3427091095 0.5874109827 0.5023792856 0.6055951246 -0.189256270495 +1403715554862142976.0000000000 0.7923230629 3.1557985839 1.3234942857 0.5948283129 0.4950467880 0.6030747617 -0.193413514759 +1403715554912143104.0000000000 0.7790062678 3.1232003457 1.3102850259 0.5985562820 0.4937665519 0.5979925046 -0.200823140893 +1403715554962142976.0000000000 0.7655279369 3.0714052450 1.3052379812 0.6021960390 0.4943342721 0.5895196422 -0.213213858545 +1403715555012143104.0000000000 0.7532906149 3.0009156457 1.3071888690 0.5953726594 0.5081624850 0.5773244129 -0.232376435001 +1403715555062142976.0000000000 0.7431369371 2.9145345366 1.3156966968 0.5784252733 0.5321960524 0.5625764209 -0.256318816536 +1403715555112143104.0000000000 0.7344793478 2.8158750902 1.3299800124 0.5541028430 0.5613434812 0.5456483511 -0.283074923795 +1403715555162142976.0000000000 0.7272308120 2.7095612331 1.3472104025 0.5239044378 0.5924886115 0.5285232533 -0.308455111892 +1403715555212143104.0000000000 0.7210148859 2.5995522128 1.3648960389 0.4920892565 0.6210453265 0.5113978390 -0.332600535729 +1403715555262142976.0000000000 0.7154086566 2.4880781087 1.3802089201 0.4536162703 0.6510560707 0.4918501933 -0.35838758278 +1403715555312143104.0000000000 0.7099018300 2.3788128675 1.3913731471 0.4182933667 0.6755124723 0.4724875645 -0.38140406471 +1403715555362142976.0000000000 0.7040116865 2.2745338641 1.3968377397 0.3971045650 0.6889963335 0.4598520387 -0.39513050936 +1403715555412143104.0000000000 0.6980085327 2.1765108115 1.4000123523 0.3858105108 0.6959286575 0.4510746504 -0.404184627573 +1403715555462142976.0000000000 0.6923189910 2.0866976980 1.4040534624 0.3891352704 0.6943788864 0.4482878762 -0.406755065653 +1403715555512143104.0000000000 0.6873835251 2.0046310523 1.4106304414 0.3968525540 0.6900699996 0.4488150014 -0.406049923636 +1403715555562142976.0000000000 0.6833370127 1.9299816791 1.4201358543 0.4081847430 0.6831999286 0.4528221411 -0.401964154734 +1403715555612143104.0000000000 0.6802779124 1.8615451423 1.4331454756 0.4176289956 0.6768647061 0.4570752316 -0.398148746527 +1403715555662142976.0000000000 0.6787643710 1.7986136819 1.4494062105 0.4248358251 0.6715029736 0.4632009586 -0.392483311871 +1403715555712143104.0000000000 0.6787925808 1.7399445501 1.4683813184 0.4278663350 0.6684178807 0.4693837963 -0.387074654302 +1403715555762142976.0000000000 0.6799140028 1.6846913962 1.4907578192 0.4233711448 0.6693895273 0.4722815681 -0.386813462723 +1403715555812143104.0000000000 0.6818196863 1.6335181443 1.5166487131 0.4156650025 0.6722793871 0.4735833094 -0.388563869354 +1403715555862142976.0000000000 0.6836755092 1.5870521062 1.5459383871 0.4067338807 0.6760285011 0.4730484058 -0.392145663851 +1403715555912143104.0000000000 0.6854146535 1.5460611454 1.5779263700 0.4014078996 0.6776283471 0.4734274330 -0.394408401444 +1403715555962142976.0000000000 0.6872104290 1.5101353265 1.6113952590 0.3956187533 0.6796001811 0.4742188263 -0.395911480881 +1403715556012143104.0000000000 0.6888691913 1.4789716235 1.6440997626 0.3874837515 0.6832032441 0.4731811741 -0.398985270469 +1403715556062142976.0000000000 0.6899657402 1.4527951139 1.6751482302 0.3758426469 0.6889686648 0.4699608561 -0.403981778519 +1403715556112143104.0000000000 0.6906903042 1.4322560636 1.7034991223 0.3688599824 0.6920549093 0.4675766974 -0.40789011754 +1403715556162142976.0000000000 0.6909904578 1.4180005579 1.7295166594 0.3689985031 0.6913600923 0.4653036537 -0.411526229304 +1403715556212143104.0000000000 0.6908613532 1.4101713413 1.7547817621 0.3718555909 0.6890853463 0.4628756419 -0.415488802789 +1403715556262142976.0000000000 0.6907063440 1.4089335027 1.7796638804 0.3774820251 0.6851173853 0.4620376026 -0.417902791138 +1403715556312143104.0000000000 0.6908212855 1.4137229313 1.8039133425 0.3830489742 0.6807647522 0.4630115725 -0.418871244229 +1403715556362142976.0000000000 0.6915690089 1.4241629105 1.8272079503 0.3869013279 0.6770830019 0.4652030158 -0.418870057639 +1403715556412143104.0000000000 0.6928884136 1.4401323735 1.8490704544 0.3909942973 0.6732139090 0.4682809578 -0.417874905699 +1403715556462142976.0000000000 0.6949183162 1.4606391780 1.8674085180 0.3967433597 0.6683768063 0.4745787704 -0.413088540093 +1403715556512143104.0000000000 0.6975708656 1.4854729766 1.8811304102 0.4053744007 0.6619303652 0.4852584879 -0.402546875258 +1403715556562142976.0000000000 0.7003036612 1.5133200836 1.8905831176 0.4137470213 0.6552724187 0.4961685665 -0.391469300618 +1403715556612143104.0000000000 0.7029546520 1.5434218538 1.8968050644 0.4200331572 0.6497713986 0.5053915354 -0.38203229229 +1403715556662142976.0000000000 0.7061243918 1.5750118336 1.8993436193 0.4223120122 0.6468038358 0.5137697519 -0.37328006155 +1403715556712143104.0000000000 0.7090551066 1.6077368597 1.8979842632 0.4217752372 0.6456673780 0.5212807291 -0.365356931969 +1403715556762142976.0000000000 0.7108612606 1.6414638386 1.8934623453 0.4219415753 0.6439264447 0.5282478046 -0.358159598212 +1403715556812143104.0000000000 0.7108534923 1.6761603778 1.8868730611 0.4268236091 0.6390926238 0.5338607862 -0.352668237504 +1403715556862142976.0000000000 0.7093828334 1.7108290887 1.8795452240 0.4311554233 0.6349569063 0.5378193724 -0.34883384408 +1403715556912143104.0000000000 0.7066969663 1.7453299309 1.8720035163 0.4362606495 0.6300955725 0.5418926001 -0.344976267629 +1403715556962142976.0000000000 0.7028564405 1.7790828818 1.8644906956 0.4396286735 0.6269055542 0.5447717091 -0.341964677212 +1403715557012143104.0000000000 0.6976597849 1.8113212127 1.8568085407 0.4365388994 0.6285768144 0.5468096326 -0.33959417441 +1403715557062142976.0000000000 0.6909532938 1.8422730673 1.8489831902 0.4296608817 0.6330320828 0.5483989724 -0.337521074806 +1403715557112143104.0000000000 0.6824656715 1.8721157986 1.8414316638 0.4207386005 0.6389192983 0.5497131010 -0.335524465379 +1403715557162142976.0000000000 0.6718339266 1.9013291503 1.8345658263 0.4107464773 0.6458447162 0.5504249564 -0.333473089316 +1403715557212143104.0000000000 0.6581932154 1.9304615967 1.8281340668 0.4019950399 0.6517706067 0.5510262937 -0.33160984282 +1403715557262142976.0000000000 0.6411642041 1.9599360015 1.8218641955 0.3943572039 0.6570746564 0.5516293097 -0.329302894472 +1403715557312143104.0000000000 0.6201976300 1.9901271203 1.8162643305 0.3902623341 0.6602909767 0.5518952476 -0.327296153958 +1403715557362142976.0000000000 0.5954894810 2.0206763800 1.8106036314 0.3867590306 0.6630832132 0.5520949082 -0.325467843322 +1403715557412143104.0000000000 0.5665026413 2.0522316252 1.8054263706 0.3872238672 0.6637442128 0.5505834352 -0.326127547918 +1403715557462142976.0000000000 0.5335081833 2.0846788404 1.8002794019 0.3916926631 0.6617599723 0.5487632462 -0.327886407607 +1403715557512143104.0000000000 0.4966986894 2.1179231654 1.7952921788 0.4008168034 0.6567755664 0.5461677950 -0.3311985585 +1403715557562142976.0000000000 0.4570601106 2.1515831406 1.7899213611 0.4112949953 0.6508761069 0.5435362198 -0.334312874392 +1403715557612143104.0000000000 0.4149662862 2.1852797325 1.7838702234 0.4212383203 0.6450955697 0.5419958565 -0.335634436527 +1403715557662142976.0000000000 0.3707142880 2.2187176563 1.7776709965 0.4310216473 0.6392343120 0.5402994812 -0.337159167915 +1403715557712143104.0000000000 0.3247739459 2.2515457175 1.7712281116 0.4402283281 0.6340417517 0.5388151546 -0.337443781062 +1403715557762142976.0000000000 0.2778119099 2.2828618434 1.7648943873 0.4452950426 0.6316932625 0.5366848501 -0.338593146306 +1403715557812143104.0000000000 0.2299675829 2.3127661124 1.7601306648 0.4466636219 0.6324297790 0.5336190319 -0.340257126674 +1403715557862142976.0000000000 0.1815340304 2.3416598826 1.7579772076 0.4463267400 0.6347865492 0.5305663621 -0.341083294068 +1403715557912143104.0000000000 0.1323449382 2.3695440760 1.7586885556 0.4455295905 0.6375677251 0.5277413995 -0.341320663237 +1403715557962142976.0000000000 0.0822922445 2.3965906127 1.7628703193 0.4454092711 0.6400348111 0.5246491578 -0.341627403785 +1403715558012143104.0000000000 0.0318899072 2.4227782610 1.7699339233 0.4455021976 0.6421557379 0.5215792942 -0.342226299603 +1403715558062142976.0000000000 -0.0189793457 2.4485756315 1.7796958827 0.4464075276 0.6434436416 0.5197744590 -0.341372393727 +1403715558112143104.0000000000 -0.0705544688 2.4738307539 1.7921240578 0.4456031423 0.6457799893 0.5183652964 -0.340152119556 +1403715558162142976.0000000000 -0.1230695730 2.4985866609 1.8069462048 0.4451122887 0.6474485854 0.5177920577 -0.338491897541 +1403715558212143104.0000000000 -0.1759550119 2.5231441610 1.8217692983 0.4461760897 0.6477755186 0.5193544489 -0.334043007528 +1403715558262142976.0000000000 -0.2297444260 2.5473005092 1.8365619491 0.4483640922 0.6471086748 0.5206566606 -0.330358359306 +1403715558312143104.0000000000 -0.2845027878 2.5712282712 1.8506006681 0.4541288869 0.6435402648 0.5231826196 -0.325427147211 +1403715558362142976.0000000000 -0.3401805411 2.5939562971 1.8644369084 0.4611521681 0.6391269891 0.5234377574 -0.323833728706 +1403715558412143104.0000000000 -0.3967337118 2.6150448390 1.8781615435 0.4685692115 0.6339841039 0.5227312745 -0.324436534199 +1403715558462142976.0000000000 -0.4541790744 2.6336687700 1.8913558214 0.4737120685 0.6306043261 0.5175892281 -0.331717426531 +1403715558512143104.0000000000 -0.5113566508 2.6507025531 1.9025375511 0.4799666184 0.6261719913 0.5108207833 -0.341471536027 +1403715558562142976.0000000000 -0.5671287653 2.6661872662 1.9109755809 0.4851021046 0.6223280019 0.5038970472 -0.351385218796 +1403715558612143104.0000000000 -0.6212436127 2.6807251734 1.9165612783 0.4899435532 0.6186446790 0.4978503654 -0.359693048999 +1403715558662142976.0000000000 -0.6732083595 2.6944528529 1.9180137510 0.4911578952 0.6177797459 0.4937687533 -0.365108923271 +1403715558712143104.0000000000 -0.7228144606 2.7071400004 1.9160307917 0.4921305553 0.6164028699 0.4914931677 -0.369174057249 +1403715558762142976.0000000000 -0.7698479038 2.7182780361 1.9117201959 0.4916080125 0.6146018737 0.4929215140 -0.370964256972 +1403715558812143104.0000000000 -0.8144280290 2.7282193053 1.9071469726 0.4915140951 0.6110580735 0.4964717445 -0.372206571644 +1403715558862142976.0000000000 -0.8564030594 2.7367804429 1.9028438907 0.4909633002 0.6063491964 0.5020800652 -0.373110302776 +1403715558912143104.0000000000 -0.8953840085 2.7441135459 1.8989083601 0.4910679352 0.6000123923 0.5096237235 -0.372989373331 +1403715558962142976.0000000000 -0.9316163305 2.7497230003 1.8958758615 0.4908986641 0.5927980465 0.5168709999 -0.374771059582 +1403715559012143104.0000000000 -0.9646172633 2.7535961065 1.8935696740 0.4908840844 0.5847202706 0.5254438926 -0.375557900362 +1403715559062142976.0000000000 -0.9943851800 2.7548338488 1.8922833788 0.4883018724 0.5775356582 0.5337127962 -0.378370844599 +1403715559112143104.0000000000 -1.0212824893 2.7535615368 1.8923518466 0.4845961679 0.5702617050 0.5408044881 -0.384055526603 +1403715559162142976.0000000000 -1.0452577592 2.7499303885 1.8931228264 0.4801532977 0.5629020442 0.5482263412 -0.389925605851 +1403715559212143104.0000000000 -1.0663492780 2.7442809966 1.8944146964 0.4762416255 0.5543962731 0.5560175606 -0.395832235718 +1403715559262142976.0000000000 -1.0847400000 2.7366367839 1.8956391818 0.4724849951 0.5454652621 0.5640903241 -0.401282548084 +1403715559312143104.0000000000 -1.1001809731 2.7270321584 1.8963583124 0.4686181604 0.5359889119 0.5728187863 -0.406191511634 +1403715559362142976.0000000000 -1.1123938477 2.7156225186 1.8966456138 0.4641146786 0.5268081831 0.5822419297 -0.40995736185 +1403715559412143104.0000000000 -1.1216195323 2.7023223882 1.8963350996 0.4573736914 0.5192984913 0.5923126844 -0.412679133658 +1403715559462142976.0000000000 -1.1283504226 2.6875503810 1.8945541054 0.4494532248 0.5136390276 0.6039961338 -0.411528150329 +1403715559512143104.0000000000 -1.1332497323 2.6704697013 1.8906392061 0.4371366553 0.5128327479 0.6138949695 -0.411153357817 +1403715559562142976.0000000000 -1.1365250141 2.6514591073 1.8838901387 0.4231510599 0.5144327116 0.6210318831 -0.413063634195 +1403715559612143104.0000000000 -1.1387971473 2.6312174971 1.8741643085 0.4104170409 0.5161182888 0.6261698840 -0.416042114293 +1403715559662142976.0000000000 -1.1405639564 2.6103823390 1.8611702548 0.4018932685 0.5155971637 0.6309000794 -0.417859372583 +1403715559712143104.0000000000 -1.1424012632 2.5886315473 1.8453313846 0.3969379743 0.5123579976 0.6363728444 -0.418281161135 +1403715559762142976.0000000000 -1.1443093228 2.5657416406 1.8284193632 0.3944053276 0.5067999836 0.6419294782 -0.41895675099 +1403715559812143104.0000000000 -1.1458145064 2.5415363588 1.8111608227 0.3914410439 0.5009244972 0.6474711659 -0.420273299809 +1403715559862142976.0000000000 -1.1465206943 2.5157362457 1.7940080888 0.3878326260 0.4946077994 0.6532651345 -0.422129888812 +1403715559912143104.0000000000 -1.1468002271 2.4884315137 1.7767742249 0.3854231539 0.4861412340 0.6602876834 -0.423244454377 +1403715559962142976.0000000000 -1.1467041587 2.4591960092 1.7596876328 0.3828679902 0.4768878059 0.6677686207 -0.424352674001 +1403715560012143104.0000000000 -1.1461974234 2.4277200005 1.7429532335 0.3801799691 0.4669782479 0.6756387916 -0.425331318336 +1403715560062142976.0000000000 -1.1452254989 2.3936264324 1.7272463839 0.3756234834 0.4579885744 0.6823595987 -0.428414335115 +1403715560112143104.0000000000 -1.1437233524 2.3570216607 1.7134674000 0.3709697411 0.4488258859 0.6899353194 -0.430030266843 +1403715560162142976.0000000000 -1.1416436952 2.3171022851 1.7031993332 0.3635844105 0.4411313468 0.6957608267 -0.434886632811 +1403715560212143104.0000000000 -1.1388775448 2.2742467120 1.6966277690 0.3527681370 0.4361462025 0.7004119378 -0.441309697342 +1403715560262142976.0000000000 -1.1358843516 2.2289093155 1.6936520965 0.3414957838 0.4313464427 0.7038980059 -0.449275498273 +1403715560312143104.0000000000 -1.1329434289 2.1818419964 1.6934266691 0.3303059575 0.4264317301 0.7083676653 -0.455268277709 +1403715560362142976.0000000000 -1.1303110449 2.1333919592 1.6950647720 0.3200214042 0.4205690023 0.7123965341 -0.461734981786 +1403715560412143104.0000000000 -1.1279366088 2.0841031169 1.6973078235 0.3112973782 0.4133972591 0.7164224369 -0.467905482285 +1403715560462142976.0000000000 -1.1259025745 2.0341548604 1.6989060576 0.3035968855 0.4054627339 0.7218360912 -0.471573493791 +1403715560512143104.0000000000 -1.1244017097 1.9832691736 1.7002697933 0.2964827893 0.3973093514 0.7261735085 -0.476356243178 +1403715560562142976.0000000000 -1.1230212214 1.9318783742 1.7010513232 0.2888902042 0.3893784383 0.7302888379 -0.481253670114 +1403715560612143104.0000000000 -1.1218935741 1.8800595931 1.7017445756 0.2823318895 0.3799361993 0.7354157810 -0.484871960056 +1403715560662142976.0000000000 -1.1210386127 1.8272010772 1.7033800088 0.2755745597 0.3700236184 0.7399584213 -0.489492307016 +1403715560712143104.0000000000 -1.1205196332 1.7732718170 1.7052166870 0.2684597230 0.3598326247 0.7449490818 -0.493457926157 +1403715560762142976.0000000000 -1.1203351426 1.7187292585 1.7071000637 0.2629435686 0.3480361389 0.7499939046 -0.4972330125 +1403715560812143104.0000000000 -1.1201586946 1.6636679606 1.7087149467 0.2573160138 0.3359043004 0.7551308524 -0.500733627535 +1403715560862142976.0000000000 -1.1200738944 1.6080681044 1.7099271220 0.2539056903 0.3216195364 0.7610686442 -0.502859118459 +1403715560912143104.0000000000 -1.1193744006 1.5514267679 1.7112427276 0.2484398288 0.3082564687 0.7671012674 -0.50478831857 +1403715560962142976.0000000000 -1.1182397573 1.4934256353 1.7129908114 0.2424692749 0.2944170623 0.7725097542 -0.507696684913 +1403715561012143104.0000000000 -1.1163428896 1.4343445954 1.7149686292 0.2347048404 0.2810269491 0.7775545153 -0.511220566416 +1403715561062142976.0000000000 -1.1138264741 1.3742973484 1.7172097889 0.2256738244 0.2682779209 0.7823478119 -0.514810822909 +1403715561112143104.0000000000 -1.1105645419 1.3133446902 1.7192035970 0.2148145644 0.2565413210 0.7866515781 -0.518864672423 +1403715561162142976.0000000000 -1.1068133185 1.2513652297 1.7209895017 0.2027912910 0.2459494025 0.7902994714 -0.523269843608 +1403715561212143104.0000000000 -1.1027605774 1.1886459151 1.7227004373 0.1915796781 0.2361496046 0.7936738965 -0.526889302555 +1403715561262142976.0000000000 -1.0985804944 1.1249187598 1.7252745962 0.1775064398 0.2311077308 0.7947917995 -0.53234075181 +1403715561312143104.0000000000 -1.0946797165 1.0609061524 1.7274020744 0.1624791064 0.2284985987 0.7954233891 -0.537299322974 +1403715561362142976.0000000000 -1.0914692833 0.9966290715 1.7292288897 0.1484847293 0.2261655737 0.7960059462 -0.541457248567 +1403715561412143104.0000000000 -1.0891512969 0.9326152937 1.7306649657 0.1365433097 0.2222421624 0.7963753397 -0.545665340748 +1403715561462142976.0000000000 -1.0882784013 0.8691353866 1.7315900294 0.1289880500 0.2153050878 0.7974936332 -0.54864351554 +1403715561512143104.0000000000 -1.0890835950 0.8061580959 1.7327212173 0.1265592232 0.2045722769 0.7986628192 -0.551607331213 +1403715561562142976.0000000000 -1.0908640713 0.7437468064 1.7339723163 0.1250193390 0.1933123493 0.7995208574 -0.554767427866 +1403715561612143104.0000000000 -1.0935428027 0.6818781982 1.7352929139 0.1254839762 0.1807454374 0.8006959639 -0.557199095468 +1403715561662142976.0000000000 -1.0968508495 0.6201739921 1.7363256210 0.1269979994 0.1673205276 0.8019820871 -0.559195923818 +1403715561712143104.0000000000 -1.0995922865 0.5582867703 1.7382395028 0.1257467585 0.1553508121 0.8006668698 -0.564788846858 +1403715561762142976.0000000000 -1.1017351705 0.4972656390 1.7398407923 0.1250226887 0.1421269594 0.7999901143 -0.569372524602 +1403715561812143104.0000000000 -1.1025643273 0.4371304564 1.7424369090 0.1207833391 0.1304606956 0.7982841366 -0.575442290051 +1403715561862142976.0000000000 -1.1022666837 0.3781605839 1.7450974781 0.1165125582 0.1179963641 0.7972438842 -0.580434208973 +1403715561912143104.0000000000 -1.1001423773 0.3204426836 1.7486465953 0.1098059309 0.1058512761 0.7954006785 -0.586579854414 +1403715561962142976.0000000000 -1.0968253109 0.2638308157 1.7528551436 0.1046206655 0.0930916800 0.7921307468 -0.594068460291 +1403715562012143104.0000000000 -1.0919668104 0.2093524245 1.7575907394 0.0985721653 0.0812083978 0.7881914854 -0.602032313715 +1403715562062142976.0000000000 -1.0856562621 0.1573207140 1.7628911759 0.0924037333 0.0710915079 0.7837720435 -0.610007320805 +1403715562112143104.0000000000 -1.0781971094 0.1083169423 1.7683961946 0.0893957614 0.0612834272 0.7791760766 -0.617363248911 +1403715562162142976.0000000000 -1.0692896879 0.0622779716 1.7741196170 0.0874249444 0.0530830499 0.7749842204 -0.623649362262 +1403715562212143104.0000000000 -1.0587191964 0.0196622480 1.7796300477 0.0873082001 0.0453768911 0.7720644948 -0.627881065032 +1403715562262142976.0000000000 -1.0464592717 -0.0189650005 1.7841081379 0.0897747511 0.0378454397 0.7723024541 -0.627739704146 +1403715562312143104.0000000000 -1.0319012165 -0.0534956528 1.7880537380 0.0929062764 0.0315836367 0.7743853591 -0.6250585679 +1403715562362142976.0000000000 -1.0148602810 -0.0844373691 1.7913715722 0.0966975976 0.0263359863 0.7792157945 -0.618691147521 +1403715562412143104.0000000000 -0.9947827018 -0.1123985746 1.7939588887 0.1005285325 0.0217084508 0.7862944574 -0.609232126208 +1403715562462142976.0000000000 -0.9714495054 -0.1378413123 1.7961290744 0.1044545934 0.0166555491 0.7933387347 -0.599521044383 +1403715562512143104.0000000000 -0.9445685149 -0.1613999615 1.7982913585 0.1070219354 0.0107846360 0.7994619705 -0.591008083495 +1403715562562142976.0000000000 -0.9139028861 -0.1841580006 1.8013922840 0.1101916360 0.0021356697 0.8019099781 -0.587191305558 +1403715562612143104.0000000000 -0.8785529192 -0.2063946794 1.8051944434 0.1093789298 -0.0059149660 0.8026888845 -0.586252349763 +1403715562662142976.0000000000 -0.8385133434 -0.2273464258 1.8091929378 0.1000948153 -0.0083697390 0.8057757453 -0.583640663139 +1403715562712143104.0000000000 -0.7944837296 -0.2474383907 1.8136372098 0.0839939755 -0.0051642349 0.8095533272 -0.580983436236 +1403715562762142976.0000000000 -0.7476707106 -0.2670395146 1.8182494472 0.0683083371 -0.0011552235 0.8125440206 -0.578882415607 +1403715562812143104.0000000000 -0.6988944344 -0.2863007294 1.8227240010 0.0539879764 0.0018418253 0.8145771638 -0.577534371506 +1403715562862142976.0000000000 -0.6486246917 -0.3049658977 1.8267723834 0.0398127487 0.0034509744 0.8166710225 -0.575718226991 +1403715562912143104.0000000000 -0.5974581108 -0.3228489549 1.8305316304 0.0264299122 0.0027417538 0.8178338191 -0.574840662195 +1403715562962142976.0000000000 -0.5462278335 -0.3402588717 1.8336559442 0.0151220791 -0.0008397999 0.8183723723 -0.574488709817 +1403715563012143104.0000000000 -0.4950464017 -0.3573648851 1.8363976949 0.0046914006 -0.0062933338 0.8184365508 -0.574543294286 +1403715563062142976.0000000000 -0.4441719755 -0.3742167735 1.8386619988 0.0042752602 0.0142808480 -0.8166871540 0.576888093212 +1403715563112143104.0000000000 -0.3937002728 -0.3907639771 1.8405803230 0.0099002486 0.0264669389 -0.8134669414 0.580924282032 +1403715563162142976.0000000000 -0.3432325450 -0.4068148356 1.8426517940 0.0168304238 0.0395451398 -0.8093213211 0.585791701917 +1403715563212143104.0000000000 -0.2926951732 -0.4220326534 1.8447853380 0.0244150727 0.0548662577 -0.8038504354 0.591792257005 +1403715563262142976.0000000000 -0.2418525001 -0.4360880990 1.8469790159 0.0351972300 0.0707346504 -0.7975977441 0.597992978922 +1403715563312143104.0000000000 -0.1908549921 -0.4477719604 1.8486561733 0.0462104917 0.0887531386 -0.7917298013 0.602620438209 +1403715563362142976.0000000000 -0.1399865070 -0.4566639283 1.8499695499 0.0592054704 0.1078269596 -0.7863621813 0.605394564585 +1403715563412143104.0000000000 -0.0896533232 -0.4628035257 1.8510695306 0.0727947121 0.1277132938 -0.7812929428 0.606606612275 +1403715563462142976.0000000000 -0.0399155098 -0.4671135446 1.8511489682 0.0840134617 0.1491749983 -0.7765698042 0.606323261429 +1403715563512143104.0000000000 0.0094033224 -0.4692749462 1.8490054752 0.0953158436 0.1700250922 -0.7718197022 0.605227812726 +1403715563562142976.0000000000 0.0582383825 -0.4688861549 1.8439794329 0.1061785562 0.1904400942 -0.7659565076 0.60478865162 +1403715563612143104.0000000000 0.1063936938 -0.4659147132 1.8356504206 0.1157101885 0.2104351308 -0.7598170436 0.604157486307 +1403715563662142976.0000000000 0.1540563083 -0.4602868907 1.8245776032 0.1256492635 0.2286166163 -0.7531932460 0.603859784609 +1403715563712143104.0000000000 0.2009923337 -0.4519107228 1.8109555985 0.1344630574 0.2466584430 -0.7457958895 0.604042870891 +1403715563762142976.0000000000 0.2476618776 -0.4406829223 1.7954814050 0.1445271167 0.2630067859 -0.7381066406 0.604266439733 +1403715563812143104.0000000000 0.2942317967 -0.4260015991 1.7777888748 0.1574492185 0.2775039430 -0.7309432536 0.603260528453 +1403715563862142976.0000000000 0.3404403481 -0.4078688080 1.7579252903 0.1762563078 0.2885906496 -0.7248282497 0.600227589645 +1403715563912143104.0000000000 0.3854713822 -0.3866466443 1.7353744907 0.1935937010 0.3006560755 -0.7196630051 0.595157594466 +1403715563962142976.0000000000 0.4290643948 -0.3619704371 1.7107146854 0.2130679655 0.3118004176 -0.7149623695 0.588397273913 +1403715564012143104.0000000000 0.4706432695 -0.3342899271 1.6844322586 0.2332464534 0.3226881914 -0.7119632359 0.578426117818 +1403715564062142976.0000000000 0.5098065430 -0.3041839664 1.6580669156 0.2534862596 0.3340655904 -0.7089445261 0.567047225899 +1403715564112143104.0000000000 0.5457922413 -0.2721991173 1.6317967563 0.2722858008 0.3460759948 -0.7046372467 0.556397518915 +1403715564162142976.0000000000 0.5786275610 -0.2389375956 1.6064455674 0.2902987295 0.3582645549 -0.6987250457 0.546951978598 +1403715564212143104.0000000000 0.6083573953 -0.2049842443 1.5812781161 0.3062364926 0.3719292893 -0.6930961360 0.536195450045 +1403715564262142976.0000000000 0.6347380188 -0.1710048088 1.5578201603 0.3203830059 0.3871199414 -0.6857916191 0.52648146746 +1403715564312143104.0000000000 0.6573641532 -0.1372161223 1.5371433441 0.3314405631 0.4051055159 -0.6762535570 0.518379977134 +1403715564362142976.0000000000 0.6766859470 -0.1034256194 1.5199250005 0.3431926508 0.4234361295 -0.6659120422 0.50939356171 +1403715564412143104.0000000000 0.6923631676 -0.0697024688 1.5052670179 0.3513012080 0.4451552732 -0.6574142607 0.496216418369 +1403715564462142976.0000000000 0.7051346982 -0.0363918745 1.4940966544 0.3572966849 0.4683832084 -0.6488681848 0.481587300211 +1403715564512143104.0000000000 0.7160070178 -0.0036585046 1.4876137271 0.3643649501 0.4901950734 -0.6391353844 0.467389488162 +1403715564562142976.0000000000 0.7249023910 0.0285039437 1.4851137363 0.3703910663 0.5117822545 -0.6278578233 0.454625049534 +1403715564612143104.0000000000 0.7320887570 0.0601270165 1.4864920615 0.3775813510 0.5321006481 -0.6146951736 0.443228008248 +1403715564662142976.0000000000 0.7383866430 0.0910970158 1.4917064014 0.3847052243 0.5511449028 -0.6003783477 0.433344004418 +1403715564712143104.0000000000 0.7440997713 0.1215371218 1.5003871614 0.3913001418 0.5696332193 -0.5845505292 0.425091605735 +1403715564762142976.0000000000 0.7493318360 0.1521030613 1.5127155776 0.3988232540 0.5867861485 -0.5685366855 0.416398925578 +1403715564812143104.0000000000 0.7543294819 0.1826424418 1.5286885873 0.4064083302 0.6028664289 -0.5513074748 0.40919971434 +1403715564862142976.0000000000 0.7593350295 0.2135478753 1.5479291237 0.4145461862 0.6174024932 -0.5348537166 0.401119835925 +1403715564912143104.0000000000 0.7643214753 0.2448183834 1.5708913738 0.4238358624 0.6300213654 -0.5172217650 0.394864390316 +1403715564962142976.0000000000 0.7689037962 0.2767367918 1.5971692710 0.4335312262 0.6413823027 -0.4989863265 0.389476653461 +1403715565012143104.0000000000 0.7723684789 0.3097073882 1.6264834409 0.4428725864 0.6523429757 -0.4817716051 0.382372377128 +1403715565062142976.0000000000 0.7742608603 0.3436546839 1.6585755859 0.4514548248 0.6635317470 -0.4647451105 0.374067031574 +1403715565112143104.0000000000 0.7744831218 0.3786701952 1.6923216629 0.4613268728 0.6737006738 -0.4491373506 0.362740346339 +1403715565162142976.0000000000 0.7730794187 0.4144647078 1.7251512524 0.4716846326 0.6831725768 -0.4347759843 0.348939365929 +1403715565212143104.0000000000 0.7702694344 0.4505028496 1.7551903131 0.4810947885 0.6923672412 -0.4208695717 0.334730057735 +1403715565262142976.0000000000 0.7664671766 0.4866278634 1.7820414644 0.4909254767 0.7001247028 -0.4070972874 0.321075342329 +1403715565312143104.0000000000 0.7622532971 0.5228877601 1.8059245521 0.5022136360 0.7055333357 -0.3932414228 0.308812822735 +1403715565362142976.0000000000 0.7572470407 0.5588360481 1.8268323753 0.5135492706 0.7099563861 -0.3781498410 0.298716879751 +1403715565412143104.0000000000 0.7513054146 0.5941521999 1.8447064361 0.5254382100 0.7133161563 -0.3630085987 0.288651183822 +1403715565462142976.0000000000 0.7437535130 0.6284813924 1.8594266177 0.5372994149 0.7161872946 -0.3484845840 0.277387080517 +1403715565512143104.0000000000 0.7346973587 0.6613145072 1.8711031308 0.5473868500 0.7200657762 -0.3326815619 0.266825584918 +1403715565562142976.0000000000 0.7236580204 0.6924311282 1.8815109096 0.5559185460 0.7250310721 -0.3158897545 0.255926117814 +1403715565612143104.0000000000 0.7104071991 0.7215160800 1.8924425239 0.5637462449 0.7305098400 -0.2986045689 0.24368187538 +1403715565662142976.0000000000 0.6950507463 0.7486533409 1.9046388262 0.5709689592 0.7363558269 -0.2808835600 0.229954276825 +1403715565712143104.0000000000 0.6775803055 0.7735737672 1.9181378242 0.5767969812 0.7431099848 -0.2620107360 0.215506768313 +1403715565762142976.0000000000 0.6579771730 0.7959950970 1.9323779518 0.5810925258 0.7508397100 -0.2419129424 0.200123298622 +1403715565812143104.0000000000 0.6363352312 0.8156078322 1.9471284195 0.5830883641 0.7598297593 -0.2203974319 0.184639292924 +1403715565862142976.0000000000 0.6126031281 0.8325147948 1.9627865449 0.5855174014 0.7682227317 -0.1991462535 0.16536014273 +1403715565912143104.0000000000 0.5875657211 0.8468818111 1.9789493566 0.5882477133 0.7755801701 -0.1748025471 0.147932745313 +1403715565962142976.0000000000 0.5613437609 0.8591432780 1.9950617564 0.5916143628 0.7814907754 -0.1500537694 0.129415918695 +1403715566012143104.0000000000 0.5342697175 0.8694140037 2.0111629696 0.5956487065 0.7857653402 -0.1246103816 0.110669333664 +1403715566062142976.0000000000 0.5066043118 0.8775097610 2.0271560630 0.5981707127 0.7898266414 -0.1000733074 0.0913838511866 +1403715566112143104.0000000000 0.4786864617 0.8833029176 2.0428951031 0.5997563067 0.7932570858 -0.0746724336 0.0738890798675 +1403715566162142976.0000000000 0.4508389314 0.8868796203 2.0584680146 0.6019174644 0.7950025263 -0.0496510692 0.056578446691 +1403715566212143104.0000000000 0.4227749290 0.8882828659 2.0731867171 0.6028954427 0.7964638690 -0.0249439404 0.0392452590449 +1403715566262142976.0000000000 0.3945285615 0.8871191105 2.0881199152 0.6040826597 0.7966350381 -0.0007129628 0.0213599611663 +1403715566312143104.0000000000 0.3663176756 0.8838086336 2.1027478340 0.6045362861 0.7962325297 0.0232124839 0.00328906854818 +1403715566362142976.0000000000 0.3385020223 0.8780520527 2.1164395609 0.6041740295 0.7953423073 0.0471146312 -0.0135855724247 +1403715566412143104.0000000000 0.3110598562 0.8700288674 2.1278713004 0.6031057983 0.7939769560 0.0706834983 -0.0294589966021 +1403715566462142976.0000000000 0.2838635498 0.8602081940 2.1365369052 0.6026902669 0.7911985088 0.0929652368 -0.0461175304583 +1403715566512143104.0000000000 0.2570209708 0.8489508039 2.1423279437 0.6029808626 0.7870677998 0.1145978911 -0.0616902032518 +1403715566562142976.0000000000 0.2304165280 0.8359324461 2.1451515213 0.6025231264 0.7828190355 0.1347109982 -0.0775447396579 +1403715566612143104.0000000000 0.2041122596 0.8206357239 2.1449765613 0.6019933934 0.7779267409 0.1545932057 -0.0923844187525 +1403715566662142976.0000000000 0.1782768592 0.8030209768 2.1418651239 0.6008778099 0.7726489596 0.1750843913 -0.106324497532 +1403715566712143104.0000000000 0.1528518772 0.7830690088 2.1369429146 0.5986020430 0.7671658777 0.1964675063 -0.120551354961 +1403715566762142976.0000000000 0.1280535426 0.7603238918 2.1315962790 0.5954578595 0.7612235458 0.2179924787 -0.135823157075 +1403715566812143104.0000000000 0.1038991474 0.7344293574 2.1263228513 0.5901200844 0.7556741179 0.2397014485 -0.152506160695 +1403715566862142976.0000000000 0.0805541370 0.7060246797 2.1219940732 0.5852472457 0.7484729442 0.2610599682 -0.17065053835 +1403715566912143104.0000000000 0.0580942885 0.6751662764 2.1185399045 0.5803197306 0.7397517500 0.2830930084 -0.189353392581 +1403715566962142976.0000000000 0.0367348731 0.6419241346 2.1152154238 0.5744108783 0.7302133840 0.3057416336 -0.208236908917 +1403715567012143104.0000000000 0.0170280140 0.6062650504 2.1112547634 0.5655156975 0.7213721341 0.3291696236 -0.226851490803 +1403715567062142976.0000000000 -0.0008943716 0.5680615682 2.1072663062 0.5544747353 0.7122032632 0.3525322348 -0.247073477393 +1403715567112143104.0000000000 -0.0173317111 0.5280317745 2.1037504757 0.5417735483 0.7023923304 0.3750665151 -0.269168248106 +1403715567162142976.0000000000 -0.0317824860 0.4865461226 2.1003226678 0.5295842225 0.6904371411 0.3988305275 -0.289432748187 +1403715567212143104.0000000000 -0.0438434158 0.4439241953 2.0969091680 0.5158026028 0.6777538003 0.4228998388 -0.309440119159 +1403715567262142976.0000000000 -0.0539359995 0.4006347809 2.0925856174 0.4995146877 0.6653470077 0.4489568945 -0.325938863812 +1403715567312143104.0000000000 -0.0628018659 0.3571314753 2.0883268426 0.4834661401 0.6508056583 0.4746818774 -0.342621659813 +1403715567362142976.0000000000 -0.0703458285 0.3137065130 2.0828915972 0.4684459938 0.6338678602 0.5015766669 -0.356638099404 +1403715567412143104.0000000000 -0.0762833754 0.2702725004 2.0760514605 0.4531834109 0.6157978911 0.5283669388 -0.369115335962 +1403715567462142976.0000000000 -0.0812081637 0.2270172435 2.0665923730 0.4378538925 0.5967126465 0.5539368309 -0.381276767854 +1403715567512143104.0000000000 -0.0854197174 0.1840837090 2.0536201216 0.4230572654 0.5768659030 0.5784232117 -0.392013862456 +1403715567562142976.0000000000 -0.0890565308 0.1411241399 2.0375564849 0.4089039411 0.5562896624 0.6002247658 -0.403818782357 +1403715567612143104.0000000000 -0.0924748387 0.0981003462 2.0187917380 0.3945310278 0.5358081176 0.6198322711 -0.416008275095 +1403715567662142976.0000000000 -0.0953177268 0.0548197142 1.9977954043 0.3811652051 0.5141392663 0.6374623409 -0.428970471288 +1403715567712143104.0000000000 -0.0978762901 0.0111985963 1.9756931910 0.3676430855 0.4917030220 0.6539677802 -0.442032625772 +1403715567762142976.0000000000 -0.0999885959 -0.0327263168 1.9537809392 0.3547897886 0.4681960361 0.6678837364 -0.456998897554 +1403715567812143104.0000000000 -0.1011586716 -0.0768476327 1.9319000868 0.3411221698 0.4448769644 0.6811271582 -0.470941552862 +1403715567862142976.0000000000 -0.1013644717 -0.1208607748 1.9102578740 0.3274927179 0.4209248764 0.6941275752 -0.483484930005 +1403715567912143104.0000000000 -0.1005876327 -0.1649903925 1.8887978785 0.3130927986 0.3969078434 0.7071295816 -0.494373156797 +1403715567962142976.0000000000 -0.0987501449 -0.2088006740 1.8676723697 0.2992943058 0.3720788213 0.7196493321 -0.504068554999 +1403715568012143104.0000000000 -0.0958964325 -0.2523795627 1.8473125763 0.2868016536 0.3468475588 0.7304144298 -0.513747353475 +1403715568062142976.0000000000 -0.0914527162 -0.2959855433 1.8281007906 0.2733839718 0.3225294800 0.7388694684 -0.524697862824 +1403715568112143104.0000000000 -0.0851197007 -0.3394366963 1.8098626460 0.2598523753 0.2983858367 0.7461059769 -0.535507709357 +1403715568162142976.0000000000 -0.0765652861 -0.3822555239 1.7922262694 0.2453774700 0.2745978835 0.7527196187 -0.545709698688 +1403715568212143104.0000000000 -0.0659231954 -0.4242320446 1.7746044437 0.2311642546 0.2505622759 0.7593962056 -0.554165170515 +1403715568262142976.0000000000 -0.0528014491 -0.4653263782 1.7573395907 0.2136453180 0.2289690701 0.7656694590 -0.561853292684 +1403715568312143104.0000000000 -0.0376528430 -0.5055651532 1.7401071386 0.1965415613 0.2071558192 0.7715964168 -0.568416089528 +1403715568362142976.0000000000 -0.0206294039 -0.5445036525 1.7236344281 0.1796227295 0.1855251773 0.7764260183 -0.574872787516 +1403715568412143104.0000000000 -0.0018545676 -0.5819115860 1.7075270496 0.1628484307 0.1639702679 0.7812394348 -0.579878509102 +1403715568462142976.0000000000 0.0185476396 -0.6177361728 1.6926677524 0.1468217957 0.1415884690 0.7849630649 -0.585003463737 +1403715568512143104.0000000000 0.0406107997 -0.6518577272 1.6788923880 0.1310138496 0.1189985587 0.7887643014 -0.588664243116 +1403715568562142976.0000000000 0.0646161576 -0.6840639607 1.6667517045 0.1141552627 0.0971733300 0.7918559282 -0.592022051087 +1403715568612143104.0000000000 0.0902821665 -0.7144449795 1.6557806613 0.0991298527 0.0740764612 0.7945535129 -0.594449884658 +1403715568662142976.0000000000 0.1176320907 -0.7427034690 1.6460283118 0.0838171552 0.0511601588 0.7968915348 -0.596088252138 +1403715568712143104.0000000000 0.1468489011 -0.7690166406 1.6377844728 0.0669079058 0.0291888016 0.7985158198 -0.597531448107 +1403715568762142976.0000000000 0.1775564961 -0.7934223900 1.6305037997 0.0504749119 0.0069964917 0.7996024499 -0.598363814531 +1403715568812143104.0000000000 0.2095238533 -0.8159762589 1.6240683113 0.0339696324 -0.0148542663 0.8007757626 -0.597815684703 +1403715568862142976.0000000000 0.2425228075 -0.8368152495 1.6183853719 0.0189126129 -0.0367017287 0.8013658617 -0.596747896392 +1403715568912143104.0000000000 0.2764604270 -0.8559341899 1.6129540849 0.0036853200 -0.0574120065 0.8015507897 -0.595152595136 +1403715568962142976.0000000000 0.3113067514 -0.8730295330 1.6071942252 0.0119245096 0.0762470815 -0.8033095082 0.590540449597 +1403715569012143104.0000000000 0.3466640842 -0.8887836130 1.6013123919 0.0254732727 0.0948658527 -0.8042270034 0.586148879926 +1403715569062142976.0000000000 0.3826009832 -0.9032509060 1.5955588029 0.0387170944 0.1130026869 -0.8038802285 0.582673113845 +1403715569112143104.0000000000 0.4191540956 -0.9165596549 1.5893994661 0.0520412613 0.1307241255 -0.8032000899 0.578854494402 +1403715569162142976.0000000000 0.4565999831 -0.9288586979 1.5834034315 0.0664121148 0.1468691247 -0.8018795234 0.57533305241 +1403715569212143104.0000000000 0.4945571253 -0.9403459334 1.5776526173 0.0807589469 0.1613285736 -0.8000731543 0.572131131403 +1403715569262142976.0000000000 0.5327515964 -0.9516088741 1.5730305052 0.0944373487 0.1741049272 -0.7961074123 0.571823442596 +1403715569312143104.0000000000 0.5711149824 -0.9625877861 1.5691112290 0.1067949891 0.1857213430 -0.7893268992 0.575382880551 +1403715569362142976.0000000000 0.6092770879 -0.9729522940 1.5655131561 0.1179543652 0.1964660089 -0.7819448835 0.579698261414 +1403715569412143104.0000000000 0.6473677619 -0.9817814321 1.5624292536 0.1285903350 0.2063061754 -0.7746771767 0.583761560593 +1403715569462142976.0000000000 0.6850644701 -0.9889133554 1.5595406885 0.1377299315 0.2165740475 -0.7681215181 0.586613570682 +1403715569512143104.0000000000 0.7222718461 -0.9941494041 1.5566528584 0.1444751582 0.2284888526 -0.7620575794 0.588377445723 +1403715569562142976.0000000000 0.7588303801 -0.9969354443 1.5540193679 0.1514513841 0.2406657974 -0.7570367416 0.58824979734 +1403715569612143104.0000000000 0.7947706791 -0.9973067910 1.5513717645 0.1576976821 0.2534762661 -0.7523846235 0.587195539802 +1403715569662142976.0000000000 0.8301201660 -0.9948405151 1.5485754916 0.1645288937 0.2667731542 -0.7488448950 0.583946616123 +1403715569712143104.0000000000 0.8649791255 -0.9898018305 1.5459785688 0.1719326547 0.2801896659 -0.7459103713 0.57926732293 +1403715569762142976.0000000000 0.8994249225 -0.9819038083 1.5440477119 0.1817006760 0.2935868847 -0.7425633314 0.573926218544 +1403715569812143104.0000000000 0.9332900089 -0.9712176241 1.5425875792 0.1923420674 0.3077329093 -0.7386166551 0.568111276405 +1403715569862142976.0000000000 0.9666105524 -0.9579289407 1.5416518056 0.2056569647 0.3214243969 -0.7341659025 0.561597718554 +1403715569912143104.0000000000 0.9993104453 -0.9427771544 1.5411539819 0.2177356957 0.3362451343 -0.7263427859 0.558530691904 +1403715569962142976.0000000000 1.0312766712 -0.9253648878 1.5409370142 0.2304264142 0.3506993206 -0.7179175539 0.555435000741 +1403715570012143104.0000000000 1.0623951331 -0.9060814631 1.5408303433 0.2432744661 0.3652644546 -0.7093541978 0.551557825122 +1403715570062142976.0000000000 1.0923306023 -0.8849723614 1.5402178269 0.2557007363 0.3801136786 -0.7002093414 0.547574289908 +1403715570112143104.0000000000 1.1212577577 -0.8618456289 1.5392786037 0.2682145644 0.3952014252 -0.6908514380 0.542771656978 +1403715570162142976.0000000000 1.1490689314 -0.8369392375 1.5381773047 0.2806321281 0.4103564744 -0.6812650781 0.53733701333 +1403715570212143104.0000000000 1.1749032983 -0.8100247642 1.5368935424 0.2932359366 0.4256014532 -0.6712595448 0.531306608387 +1403715570262142976.0000000000 1.1990754464 -0.7811307884 1.5353934753 0.3058487963 0.4411610196 -0.6608719309 0.524482372933 +1403715570312143104.0000000000 1.2216836686 -0.7504262022 1.5335637769 0.3190211404 0.4563651760 -0.6490076563 0.518406597346 +1403715570362142976.0000000000 1.2423217082 -0.7178287014 1.5312840981 0.3324192165 0.4718376890 -0.6363051734 0.511842149552 +1403715570412143104.0000000000 1.2607197319 -0.6833712681 1.5283959743 0.3456120401 0.4873970310 -0.6230176647 0.504822187798 +1403715570462142976.0000000000 1.2770839093 -0.6471774043 1.5255561271 0.3604007675 0.5019301954 -0.6095496796 0.496615096295 +1403715570512143104.0000000000 1.2911390569 -0.6095819898 1.5225549437 0.3742397868 0.5170711723 -0.5950943689 0.488307973313 +1403715570562142976.0000000000 1.3022029217 -0.5706312532 1.5186123313 0.3870679989 0.5326256213 -0.5792980250 0.480522746595 +1403715570612143104.0000000000 1.3099999844 -0.5302408541 1.5138334952 0.3990969654 0.5484174199 -0.5638848594 0.471162191918 +1403715570662142976.0000000000 1.3145051756 -0.4887266120 1.5079099750 0.4097762660 0.5650596369 -0.5506626192 0.457779093425 +1403715570712143104.0000000000 1.3162025973 -0.4463745064 1.5015212766 0.4195839469 0.5817442898 -0.5378415874 0.44300036087 +1403715570762142976.0000000000 1.3152862312 -0.4033835356 1.4949154118 0.4291986795 0.5981722854 -0.5230318251 0.429436980838 +1403715570812143104.0000000000 1.3119029664 -0.3595433298 1.4884239635 0.4392250637 0.6140467190 -0.5071393057 0.41573753122 +1403715570862142976.0000000000 1.3066235599 -0.3152230008 1.4818748718 0.4486074445 0.6292813499 -0.4914120583 0.401585025084 +1403715570912143104.0000000000 1.2994401790 -0.2705169166 1.4755487083 0.4583090305 0.6433485022 -0.4754781096 0.387267484505 +1403715570962142976.0000000000 1.2901144214 -0.2259535219 1.4683978880 0.4647354339 0.6577896382 -0.4609558983 0.372630417718 +1403715571012143104.0000000000 1.2792506437 -0.1811150719 1.4615310673 0.4716921327 0.6700754586 -0.4476057779 0.35798670268 +1403715571062142976.0000000000 1.2676575393 -0.1364374788 1.4548108483 0.4783417582 0.6796496951 -0.4362505838 0.344892566532 +1403715571112143104.0000000000 1.2553017755 -0.0920274341 1.4480530787 0.4852757982 0.6863851469 -0.4273844930 0.332754150956 +1403715571162142976.0000000000 1.2425294387 -0.0481461491 1.4416954980 0.4930742811 0.6900494138 -0.4197228044 0.323330059229 +1403715571212143104.0000000000 1.2297132805 -0.0047463234 1.4361340681 0.5025189191 0.6906125930 -0.4115418825 0.318060153485 +1403715571262142976.0000000000 1.2162310397 0.0375346648 1.4313312203 0.5111566936 0.6897375255 -0.4029319094 0.317217365404 +1403715571312143104.0000000000 1.2013639290 0.0783002847 1.4265528646 0.5180174941 0.6885640145 -0.3952245505 0.318331632736 +1403715571362142976.0000000000 1.1847630243 0.1176043643 1.4220012725 0.5237389728 0.6869562309 -0.3894756388 0.319526762528 +1403715571412143104.0000000000 1.1659437060 0.1554802303 1.4171171256 0.5246975983 0.6881744716 -0.3867936565 0.318589067997 +1403715571462142976.0000000000 1.1452076158 0.1921004436 1.4119065510 0.5209884552 0.6922618487 -0.3867022117 0.315920815827 +1403715571512143104.0000000000 1.1225918853 0.2274031895 1.4067726384 0.5165511292 0.6964304041 -0.3886627428 0.311610165947 +1403715571562142976.0000000000 1.0980698007 0.2619102647 1.4009394317 0.5126384406 0.7001416960 -0.3948153430 0.301867983788 +1403715571612143104.0000000000 1.0723726201 0.2957480182 1.3934179824 0.5089339925 0.7032365264 -0.4036872296 0.288931133423 +1403715571662142976.0000000000 1.0465815659 0.3290932349 1.3839059766 0.5074286998 0.7041765375 -0.4162052632 0.270969920019 +1403715571712143104.0000000000 1.0217758390 0.3612205500 1.3712990648 0.5049343851 0.7049249927 -0.4304376562 0.250689938974 +1403715571762142976.0000000000 0.9987419721 0.3914134487 1.3556030056 0.5009980328 0.7057154225 -0.4453641788 0.229384964309 +1403715571812143104.0000000000 0.9786209609 0.4190566517 1.3376727465 0.4946658071 0.7078096244 -0.4583182832 0.21037021193 +1403715571862142976.0000000000 0.9631453409 0.4441252527 1.3194960934 0.4881971349 0.7095540368 -0.4693165600 0.194778317253 +1403715571912143104.0000000000 0.9532498527 0.4662707736 1.3012019332 0.4807581084 0.7118440326 -0.4786966595 0.181656881723 +1403715571962142976.0000000000 0.9496677841 0.4853145721 1.2827285680 0.4711034506 0.7156655705 -0.4862115142 0.171705251841 +1403715572012143104.0000000000 0.9535389735 0.5014815485 1.2647502403 0.4607758331 0.7207473740 -0.4905441083 0.166058219482 +1403715572062142976.0000000000 0.9655983731 0.5149952879 1.2474234960 0.4496956485 0.7274079611 -0.4911168957 0.165697545613 +1403715572112143104.0000000000 0.9858536581 0.5259041742 1.2304519812 0.4379103148 0.7364369029 -0.4856901010 0.173206148904 +1403715572162142976.0000000000 1.0142556854 0.5357466062 1.2144301625 0.4291504477 0.7456211237 -0.4743048515 0.186852725444 +1403715572212143104.0000000000 1.0501234956 0.5461754523 1.1999274783 0.4259149645 0.7525188178 -0.4592534910 0.203465237337 +1403715572262142976.0000000000 1.0927080473 0.5582432912 1.1865995337 0.4293061438 0.7573555058 -0.4371298431 0.225890179375 +1403715572312143104.0000000000 1.1398829113 0.5727670666 1.1735410243 0.4371712774 0.7599152320 -0.4111847173 0.249674273081 +1403715572362142976.0000000000 1.1898853756 0.5907880495 1.1614090198 0.4493222666 0.7594269381 -0.3863762690 0.268502523544 +1403715572412143104.0000000000 1.2405880765 0.6119369020 1.1493643129 0.4634475867 0.7572499580 -0.3618024771 0.28440781109 +1403715572462142976.0000000000 1.2901343414 0.6361375947 1.1372119544 0.4770907317 0.7549493253 -0.3411357381 0.293363866249 +1403715572512143104.0000000000 1.3376098811 0.6628521314 1.1248513279 0.4895810732 0.7534724715 -0.3249237688 0.294981612836 +1403715572562142976.0000000000 1.3824598476 0.6917398011 1.1123186067 0.5002945067 0.7533795151 -0.3114564644 0.291752606703 +1403715572612143104.0000000000 1.4243259496 0.7224291268 1.0998210134 0.5087323278 0.7548365895 -0.2986649201 0.286727060793 +1403715572662142976.0000000000 1.4628793338 0.7547702221 1.0877632489 0.5166979629 0.7569579029 -0.2853607936 0.280369695099 +1403715572712143104.0000000000 1.4979159609 0.7882291726 1.0754548309 0.5216072706 0.7612428760 -0.2726641749 0.27219365674 +1403715572762142976.0000000000 1.5296012296 0.8230210011 1.0641313442 0.5243583479 0.7668055267 -0.2601356723 0.263414196946 +1403715572812143104.0000000000 1.5575821359 0.8591586445 1.0556133370 0.5272107163 0.7723980605 -0.2502191331 0.250680039548 +1403715572862142976.0000000000 1.5819505419 0.8963127845 1.0503303605 0.5309107070 0.7771753036 -0.2404651286 0.237294944197 +1403715572912143104.0000000000 1.6037538941 0.9348108604 1.0491041330 0.5363004919 0.7804409235 -0.2314256105 0.22301554687 +1403715572962142976.0000000000 1.6233667455 0.9742628983 1.0510348576 0.5422753756 0.7828818761 -0.2208144161 0.210414777518 +1403715573012143104.0000000000 1.6406943310 1.0141179051 1.0558346870 0.5485419159 0.7847157408 -0.2095049828 0.198571485357 +1403715573062142976.0000000000 1.6555718936 1.0541931932 1.0638427592 0.5544496878 0.7865865478 -0.1984160002 0.185737011239 +1403715573112143104.0000000000 1.6684878533 1.0942209762 1.0747922225 0.5597492655 0.7885612289 -0.1869274037 0.172945349012 +1403715573162142976.0000000000 1.6793446197 1.1337307272 1.0880699843 0.5643113910 0.7907431946 -0.1766227475 0.158373795856 +1403715573212143104.0000000000 1.6889920365 1.1721868293 1.1017520040 0.5672981637 0.7935668328 -0.1640583948 0.14666055537 +1403715573262142976.0000000000 1.6972102838 1.2099652062 1.1154060593 0.5698945747 0.7964193885 -0.1528974482 0.132509251287 +1403715573312143104.0000000000 1.7044849623 1.2466437531 1.1282216321 0.5709930611 0.7999465383 -0.1408965880 0.119166318996 +1403715573362142976.0000000000 1.7111863380 1.2825202307 1.1404971308 0.5716116639 0.8033828752 -0.1292011074 0.105561050098 +1403715573412143104.0000000000 1.7175378699 1.3175610614 1.1522554247 0.5718883751 0.8066925455 -0.1174243061 0.0916643652718 +1403715573462142976.0000000000 1.7238959153 1.3523254714 1.1637474616 0.5719088016 0.8097367453 -0.1080722969 0.0746130325981 +1403715573512143104.0000000000 1.7307736221 1.3862805287 1.1749607369 0.5717684764 0.8124000907 -0.0982793410 0.0585497485673 +1403715573562142976.0000000000 1.7383069179 1.4196132564 1.1860459995 0.5713432138 0.8148105585 -0.0881101283 0.0434429628669 +1403715573612143104.0000000000 1.7469874276 1.4524447161 1.1968860939 0.5706366952 0.8171086152 -0.0751156459 0.0326330003885 +1403715573662142976.0000000000 1.7569347495 1.4849410834 1.2071751832 0.5690360649 0.8197352853 -0.0600173684 0.0250984935492 +1403715573712143104.0000000000 1.7679206173 1.5174159805 1.2166939930 0.5659155304 0.8231037333 -0.0424858154 0.020852150035 +1403715573762142976.0000000000 1.7793491844 1.5500435254 1.2259383570 0.5612633541 0.8270916864 -0.0256292016 0.0156822710454 +1403715573812143104.0000000000 1.7912762792 1.5831661130 1.2348657842 0.5563738281 0.8308166526 -0.0070444956 0.0119259524872 +1403715573862142976.0000000000 1.8028333202 1.6168808548 1.2439799676 0.5510338382 0.8343920293 0.0107351807 0.00603377449204 +1403715573912143104.0000000000 1.8136486810 1.6512453471 1.2533630658 0.5458459966 0.8374132115 0.0280604817 -0.00196737731 +1403715573962142976.0000000000 1.8235637744 1.6870273412 1.2632182088 0.5417728791 0.8392325853 0.0449335056 -0.0123205235099 +1403715574012143104.0000000000 1.8325068977 1.7241919600 1.2728872467 0.5370868780 0.8409026555 0.0618616757 -0.0243627274761 +1403715574062142976.0000000000 1.8406664830 1.7630792572 1.2827876318 0.5320273304 0.8421467298 0.0797972170 -0.0369893142441 +1403715574112143104.0000000000 1.8477120738 1.8042642385 1.2934249474 0.5288601193 0.8415622971 0.0975073311 -0.0507168081897 +1403715574162142976.0000000000 1.8538067117 1.8478671535 1.3048640938 0.5279183712 0.8389463511 0.1151621745 -0.0648759343755 +1403715574212143104.0000000000 1.8592845517 1.8936200424 1.3162666061 0.5291469854 0.8342615299 0.1343543980 -0.0772014459617 +1403715574262142976.0000000000 1.8641671497 1.9413178225 1.3279831841 0.5347954858 0.8260899650 0.1543341904 -0.0880347416474 +1403715574312143104.0000000000 1.8685764944 1.9904668292 1.3391112845 0.5416342355 0.8165523477 0.1758335803 -0.094642328778 +1403715574362142976.0000000000 1.8719050950 2.0404537103 1.3496047132 0.5484303437 0.8066158133 0.1970000289 -0.0989245995415 +1403715574412143104.0000000000 1.8739811957 2.0908265595 1.3591110954 0.5541022613 0.7973591475 0.2169557532 -0.100594607319 +1403715574462142976.0000000000 1.8744774596 2.1408929944 1.3673149298 0.5572367040 0.7903445716 0.2338119465 -0.100869656368 +1403715574512143104.0000000000 1.8727941295 2.1901732574 1.3749650351 0.5598518193 0.7842304386 0.2475694726 -0.101281370043 +1403715574562142976.0000000000 1.8684032377 2.2379235214 1.3820065310 0.5599544478 0.7803073803 0.2586525225 -0.103297053419 +1403715574612143104.0000000000 1.8614392052 2.2840734801 1.3878419109 0.5578311225 0.7780116527 0.2694875933 -0.104397050544 +1403715574662142976.0000000000 1.8516361904 2.3285219050 1.3933648813 0.5554788329 0.7760667138 0.2790167657 -0.106364309716 +1403715574712143104.0000000000 1.8383592954 2.3710687488 1.3987430730 0.5527804555 0.7745011687 0.2870914255 -0.110273392258 +1403715574762142976.0000000000 1.8214707863 2.4117706736 1.4039707141 0.5491635177 0.7738994933 0.2931940670 -0.11634536593 +1403715574812143104.0000000000 1.8011582736 2.4511045670 1.4097504225 0.5451357615 0.7744868771 0.2953926531 -0.125460190133 +1403715574862142976.0000000000 1.7773350446 2.4892559541 1.4163715119 0.5408515502 0.7759999915 0.2940681169 -0.137213543396 +1403715574912143104.0000000000 1.7510075608 2.5266968422 1.4236736261 0.5386975892 0.7764566686 0.2917676320 -0.147619775103 +1403715574962142976.0000000000 1.7227642905 2.5636658810 1.4320857193 0.5400743462 0.7747785806 0.2890454556 -0.156494652408 +1403715575012143104.0000000000 1.6932860496 2.6001844283 1.4409565496 0.5416559721 0.7732255643 0.2864356638 -0.163357415069 +1403715575062142976.0000000000 1.6628067903 2.6367135384 1.4505837436 0.5464423326 0.7697285127 0.2844816779 -0.167299040074 +1403715575112143104.0000000000 1.6315651106 2.6725127942 1.4601223833 0.5518808873 0.7659786166 0.2830528640 -0.169071941203 +1403715575162142976.0000000000 1.5996041283 2.7074287531 1.4707978845 0.5615980210 0.7594282291 0.2799688042 -0.171737871204 +1403715575212143104.0000000000 1.5673930027 2.7411281251 1.4819774717 0.5734226203 0.7513618424 0.2767379430 -0.173372406176 +1403715575262142976.0000000000 1.5354032744 2.7725484496 1.4925673044 0.5835144253 0.7446036562 0.2747101253 -0.172077475757 +1403715575312143104.0000000000 1.5039514703 2.8010981513 1.5019102809 0.5886155074 0.7418898290 0.2735762070 -0.168188361661 +1403715575362142976.0000000000 1.4729538836 2.8260653443 1.5096679611 0.5850411974 0.7461347674 0.2717943657 -0.164734723305 +1403715575412143104.0000000000 1.4421079217 2.8478857815 1.5172898107 0.5791394371 0.7521349983 0.2696209924 -0.161848624296 +1403715575462142976.0000000000 1.4113638256 2.8675407137 1.5249688010 0.5739074124 0.7575210631 0.2687742493 -0.156692449791 +1403715575512143104.0000000000 1.3802560866 2.8854031276 1.5334525488 0.5715280364 0.7607666575 0.2685511754 -0.149900175122 +1403715575562142976.0000000000 1.3485477329 2.9017536406 1.5432431788 0.5746606044 0.7595731818 0.2705451045 -0.140068260566 +1403715575612143104.0000000000 1.3157615086 2.9160487668 1.5540633678 0.5812422242 0.7555590951 0.2729304606 -0.129602833088 +1403715575662142976.0000000000 1.2816104749 2.9273256048 1.5650266546 0.5865687599 0.7522515010 0.2749454906 -0.120248685078 +1403715575712143104.0000000000 1.2454747541 2.9355344827 1.5764270286 0.5918434590 0.7488075111 0.2769194723 -0.111014580619 +1403715575762142976.0000000000 1.2069058676 2.9398879767 1.5876906377 0.5943844364 0.7474725859 0.2776914762 -0.104303974907 +1403715575812143104.0000000000 1.1658045440 2.9403027226 1.5985917398 0.5935760210 0.7489703799 0.2768432284 -0.100342933407 +1403715575862142976.0000000000 1.1219973987 2.9367951961 1.6095807612 0.5922448511 0.7509111815 0.2748688576 -0.0991238871544 +1403715575912143104.0000000000 1.0756959481 2.9291742685 1.6204747442 0.5905419393 0.7532465025 0.2712352780 -0.101544809491 +1403715575962142976.0000000000 1.0268980851 2.9178335984 1.6311944365 0.5861456912 0.7579837798 0.2645875906 -0.109028552309 +1403715576012143104.0000000000 0.9760653727 2.9037701012 1.6417730104 0.5818153943 0.7624404106 0.2575289703 -0.1177042765 +1403715576062142976.0000000000 0.9238058780 2.8874346668 1.6520700706 0.5780615278 0.7660379179 0.2517957471 -0.125018719365 +1403715576112143104.0000000000 0.8709213214 2.8688062379 1.6616436073 0.5759571573 0.7681005215 0.2474469880 -0.130632806144 +1403715576162142976.0000000000 0.8172771235 2.8484971977 1.6707253679 0.5744474957 0.7696331271 0.2428514714 -0.136740948793 +1403715576212143104.0000000000 0.7632033553 2.8269788335 1.6792978544 0.5726127109 0.7711261261 0.2392267732 -0.142301552881 +1403715576262142976.0000000000 0.7092938331 2.8044663326 1.6875881871 0.5720649522 0.7714694718 0.2375407849 -0.145433558723 +1403715576312143104.0000000000 0.6552981188 2.7813761636 1.6968619519 0.5745474898 0.7695098606 0.2364584836 -0.147773955835 +1403715576362142976.0000000000 0.6017993121 2.7572613296 1.7066358093 0.5793700554 0.7656851598 0.2363833331 -0.148927817177 +1403715576412143104.0000000000 0.5485936013 2.7314752355 1.7176039782 0.5868509323 0.7596711930 0.2350979731 -0.152429015676 +1403715576462142976.0000000000 0.4959550313 2.7039755962 1.7293130872 0.5942770517 0.7536762498 0.2339493936 -0.155159844992 +1403715576512143104.0000000000 0.4442569194 2.6742696927 1.7412790725 0.6013257563 0.7480448127 0.2328541375 -0.15689245888 +1403715576562142976.0000000000 0.3939929755 2.6420550765 1.7532560973 0.6082686529 0.7429157474 0.2309627438 -0.157294784016 +1403715576612143104.0000000000 0.3452806009 2.6067837184 1.7656311530 0.6155001750 0.7376601790 0.2292091280 -0.156461402689 +1403715576662142976.0000000000 0.2984281237 2.5678652052 1.7770639638 0.6180073511 0.7365480101 0.2277685961 -0.153900648027 +1403715576712143104.0000000000 0.2532872589 2.5256932669 1.7884230712 0.6191906847 0.7369348172 0.2261182411 -0.149668006935 +1403715576762142976.0000000000 0.2096852267 2.4798492887 1.7997567717 0.6171116881 0.7403192175 0.2232167288 -0.145859221823 +1403715576812143104.0000000000 0.1675512868 2.4305890642 1.8106279053 0.6118792227 0.7465175437 0.2202386639 -0.140749084482 +1403715576862142976.0000000000 0.1266861615 2.3780238870 1.8212629311 0.6045756197 0.7541871928 0.2176992789 -0.135266486236 +1403715576912143104.0000000000 0.0865389373 2.3228373402 1.8321144347 0.5971203358 0.7617781691 0.2150972843 -0.12990182423 +1403715576962142976.0000000000 0.0466779077 2.2655584110 1.8432210675 0.5906949779 0.7683967049 0.2119216490 -0.125439873045 +1403715577012143104.0000000000 0.0068724964 2.2066500740 1.8550018424 0.5862858751 0.7735522946 0.2058902269 -0.124478651493 +1403715577062142976.0000000000 -0.0327902974 2.1464242911 1.8669769362 0.5825924228 0.7782396207 0.1975384206 -0.126125865825 +1403715577112143104.0000000000 -0.0720210455 2.0855555199 1.8782513183 0.5790743836 0.7829331311 0.1878408887 -0.128079549325 +1403715577162142976.0000000000 -0.1105154705 2.0243974413 1.8885147524 0.5766116818 0.7868023117 0.1779603782 -0.129580841216 +1403715577212143104.0000000000 -0.1481237521 1.9630811566 1.8961981826 0.5749890093 0.7897904973 0.1689722022 -0.130640746182 +1403715577262142976.0000000000 -0.1846695976 1.9019573307 1.8986402852 0.5748315107 0.7914333789 0.1618486024 -0.130410777758 +1403715577312143104.0000000000 -0.2202210956 1.8411544055 1.8945906798 0.5751539870 0.7924668814 0.1576168754 -0.127871238708 +1403715577362142976.0000000000 -0.2547148340 1.7805319751 1.8845951682 0.5764599145 0.7925927864 0.1558073067 -0.123347983843 +1403715577412143104.0000000000 -0.2880545531 1.7197350875 1.8708561636 0.5776838982 0.7925396212 0.1551248903 -0.118737235194 +1403715577462142976.0000000000 -0.3204440948 1.6582289903 1.8557561534 0.5782963468 0.7927607585 0.1546221270 -0.114872594132 +1403715577512143104.0000000000 -0.3519101513 1.5965099340 1.8404225698 0.5790300160 0.7927206237 0.1541306316 -0.112080336013 +1403715577562142976.0000000000 -0.3826140008 1.5346043661 1.8262853471 0.5792842068 0.7928906596 0.1539314589 -0.109814914989 +1403715577612143104.0000000000 -0.4124973236 1.4723357506 1.8152590165 0.5790108327 0.7933990985 0.1530923421 -0.108752291037 +1403715577662142976.0000000000 -0.4414703248 1.4099878010 1.8081031915 0.5788049154 0.7937409949 0.1523904690 -0.108338579744 +1403715577712143104.0000000000 -0.4695917684 1.3472821016 1.8045927774 0.5772483580 0.7949707629 0.1508831016 -0.109727430481 +1403715577762142976.0000000000 -0.4970711557 1.2846667519 1.8044204849 0.5757776849 0.7960672782 0.1480360474 -0.113323760595 +1403715577812143104.0000000000 -0.5232878350 1.2228300521 1.8049983776 0.5751387374 0.7968577797 0.1432757148 -0.117069130124 +1403715577862142976.0000000000 -0.5479008680 1.1614268694 1.8032492039 0.5738552633 0.7983622697 0.1370358838 -0.12053625873 +1403715577912143104.0000000000 -0.5707098280 1.1009459972 1.7982064736 0.5729512098 0.7999603266 0.1298760824 -0.122158054423 +1403715577962142976.0000000000 -0.5915181797 1.0408946643 1.7889692137 0.5710440457 0.8025194631 0.1212632783 -0.123152046498 +1403715578012143104.0000000000 -0.6101063270 0.9815484420 1.7756607417 0.5679992547 0.8060877553 0.1108813367 -0.123712192831 +1403715578062142976.0000000000 -0.6264736360 0.9231994678 1.7589147925 0.5637108198 0.8105646410 0.0993611895 -0.123864557053 +1403715578112143104.0000000000 -0.6406367280 0.8657072061 1.7390322918 0.5556765487 0.8174240230 0.0850635964 -0.125720819132 +1403715578162142976.0000000000 -0.6519444440 0.8096406092 1.7163739398 0.5448238368 0.8258083143 0.0677970373 -0.128884353849 +1403715578212143104.0000000000 -0.6595243994 0.7567926953 1.6921286181 0.5387453925 0.8312437188 0.0513975093 -0.127065251159 +1403715578262142976.0000000000 -0.6627475081 0.7080102969 1.6673976929 0.5380450180 0.8337123122 0.0384396407 -0.11812592084 +1403715578312143104.0000000000 -0.6614815691 0.6627883917 1.6430727690 0.5394419286 0.8348312882 0.0259028109 -0.106715370187 +1403715578362142976.0000000000 -0.6558388891 0.6197404974 1.6186505360 0.5422040738 0.8350252523 0.0146831816 -0.0923686887333 +1403715578412143104.0000000000 -0.6464869137 0.5790118160 1.5940453790 0.5443716655 0.8353214804 0.0039745769 -0.0766923523726 +1403715578462142976.0000000000 -0.6340744405 0.5405025701 1.5691949125 0.5443640799 0.8367332602 -0.0056758973 -0.0592704307181 +1403715578512143104.0000000000 -0.6191519723 0.5042803033 1.5435735977 0.5406537189 0.8401440795 -0.0139879001 -0.0406917759208 +1403715578562142976.0000000000 -0.6020367757 0.4697136557 1.5168665222 0.5325861341 0.8459143028 -0.0194266064 -0.0200900245021 +1403715578612143104.0000000000 -0.5839228006 0.4370708036 1.4892813160 0.5187152493 0.8545970808 -0.0243356674 -0.00246880292612 +1403715578662142976.0000000000 -0.5653668472 0.4075862515 1.4618950765 0.5037697004 0.8632881202 -0.0279181765 0.0130493659877 +1403715578712143104.0000000000 -0.5469772569 0.3824008364 1.4355562026 0.4893903719 0.8711089210 -0.0324285689 0.0247931358167 +1403715578762142976.0000000000 -0.5288114656 0.3628438856 1.4104383107 0.4781706999 0.8768468781 -0.0366687390 0.0338782762904 +1403715578812143104.0000000000 -0.5111933556 0.3494470099 1.3867890511 0.4707398488 0.8804121820 -0.0418897348 0.0390337620055 +1403715578862142976.0000000000 -0.4939576183 0.3426804515 1.3640811371 0.4676486405 0.8816406099 -0.0457370719 0.0438486514994 +1403715578912143104.0000000000 -0.4771978000 0.3428793828 1.3427083796 0.4698362831 0.8801022042 -0.0470035491 0.0496451769429 +1403715578962142976.0000000000 -0.4608167589 0.3502418496 1.3231887936 0.4779834255 0.8753066765 -0.0440644714 0.05855244939 +1403715579012143104.0000000000 -0.4456118997 0.3640924116 1.3055955119 0.4896570444 0.8683250009 -0.0393582721 0.0685463213261 +1403715579062142976.0000000000 -0.4318529832 0.3833325246 1.2902725780 0.5006900150 0.8612236102 -0.0311455873 0.0814454083666 +1403715579112143104.0000000000 -0.4206195557 0.4072711573 1.2783595720 0.5124809129 0.8529866302 -0.0209120060 0.0966426954679 +1403715579162142976.0000000000 -0.4132203175 0.4351160387 1.2702117239 0.5248257708 0.8438705504 -0.0104652585 0.111044508317 +1403715579212143104.0000000000 -0.4103424293 0.4665138241 1.2649785697 0.5381777348 0.8333278121 0.0016128037 0.126201751801 +1403715579262142976.0000000000 -0.4136885028 0.4999016925 1.2622479272 0.5488741109 0.8250614423 0.0071718502 0.134012653504 +1403715579312143104.0000000000 -0.4231497543 0.5342006693 1.2601293277 0.5562299992 0.8193944728 0.0100394917 0.138203091389 +1403715579362142976.0000000000 -0.4386730406 0.5692656078 1.2575439507 0.5592057014 0.8170112910 0.0108982483 0.140223970893 +1403715579412143104.0000000000 -0.4598514745 0.6046866438 1.2544712019 0.5595984240 0.8169975103 0.0089216116 0.138870719982 +1403715579462142976.0000000000 -0.4869036414 0.6405101337 1.2514735105 0.5590284303 0.8180010674 0.0057019551 0.135384473186 +1403715579512143104.0000000000 -0.5196313024 0.6766131376 1.2478415745 0.5555371833 0.8214831347 0.0000970435 0.128623045735 +1403715579562142976.0000000000 -0.5574831032 0.7132683658 1.2446358125 0.5521585209 0.8253324585 -0.0080412333 0.117824612214 +1403715579612143104.0000000000 -0.5989129253 0.7513702681 1.2420892553 0.5515823272 0.8264825672 -0.0114587413 0.112036599949 +1403715579662142976.0000000000 -0.6437576883 0.7909001034 1.2405572321 0.5539574029 0.8255866882 -0.0137882580 0.10652558382 +1403715579712143104.0000000000 -0.6920580038 0.8314234266 1.2403506308 0.5575565833 0.8238917326 -0.0164110438 0.100318228983 +1403715579762142976.0000000000 -0.7432059812 0.8725291173 1.2418270433 0.5621525694 0.8213612836 -0.0179789939 0.0950099277504 +1403715579812143104.0000000000 -0.7966614545 0.9139395174 1.2450615253 0.5651561994 0.8194537409 -0.0165397877 0.0939173692123 +1403715579862142976.0000000000 -0.8527071184 0.9554079928 1.2514080810 0.5683896838 0.8170592829 -0.0146257924 0.0955687281105 +1403715579912143104.0000000000 -0.9115913881 0.9967324121 1.2601899809 0.5697836817 0.8160134991 -0.0152254150 0.0961078147951 +1403715579962142976.0000000000 -0.9734061231 1.0381534720 1.2708277540 0.5720322033 0.8146143910 -0.0208142186 0.0935378029207 +1403715580012143104.0000000000 -1.0370140381 1.0797548109 1.2807343379 0.5736733580 0.8134262615 -0.0291179311 0.0915900733322 +1403715580062142976.0000000000 -1.1017751213 1.1212420368 1.2883229012 0.5751654974 0.8119607892 -0.0394146676 0.0913827740083 +1403715580112143104.0000000000 -1.1674971126 1.1621361069 1.2925801550 0.5762513375 0.8103973720 -0.0512557915 0.0925383126315 +1403715580162142976.0000000000 -1.2340785791 1.2024291621 1.2930761329 0.5766298542 0.8089063379 -0.0640764902 0.0951984825321 +1403715580212143104.0000000000 -1.3011971463 1.2422640932 1.2904974500 0.5767010405 0.8071901395 -0.0777942987 0.0990355279483 +1403715580262142976.0000000000 -1.3689941129 1.2815674371 1.2858534291 0.5760383928 0.8055558232 -0.0917533808 0.104119656938 +1403715580312143104.0000000000 -1.4374552974 1.3199887824 1.2809100354 0.5758985390 0.8032059162 -0.1074227920 0.107988298914 +1403715580362142976.0000000000 -1.5061000066 1.3576190762 1.2762967891 0.5762810635 0.8000476461 -0.1252424619 0.110173615325 +1403715580412143104.0000000000 -1.5744468824 1.3940124980 1.2720395747 0.5755847512 0.7971429012 -0.1428116205 0.113447037314 +1403715580462142976.0000000000 -1.6424968198 1.4292463580 1.2683930238 0.5750892686 0.7937564996 -0.1609348980 0.115424915437 +1403715580512143104.0000000000 -1.7100795253 1.4629250360 1.2650902960 0.5736105816 0.7909999615 -0.1775481330 0.117331249553 +1403715580562142976.0000000000 -1.7769062251 1.4951617303 1.2621873987 0.5716103778 0.7888701254 -0.1925261099 0.117810009482 +1403715580612143104.0000000000 -1.8426126295 1.5260269139 1.2592884526 0.5686347426 0.7877758553 -0.2067164325 0.115464487326 +1403715580662142976.0000000000 -1.9065921707 1.5552938972 1.2563140686 0.5655191151 0.7868065487 -0.2207597665 0.111304586271 +1403715580712143104.0000000000 -1.9680305981 1.5831660783 1.2533572220 0.5621267727 0.7862184140 -0.2336649721 0.106182756076 +1403715580762142976.0000000000 -2.0261774392 1.6099364954 1.2507135653 0.5587864079 0.7858240053 -0.2448105164 0.101519427098 +1403715580812143104.0000000000 -2.0806474188 1.6353670458 1.2491324513 0.5569267807 0.7844006651 -0.2560072756 0.0949127614168 +1403715580862142976.0000000000 -2.1310287747 1.6592937573 1.2478227089 0.5543221658 0.7834227807 -0.2673302794 0.086661438812 +1403715580912143104.0000000000 -2.1767986400 1.6816736285 1.2475204235 0.5516743743 0.7823167524 -0.2791989734 0.0753910929432 +1403715580962142976.0000000000 -2.2167371128 1.7021496743 1.2475735218 0.5479114122 0.7822466703 -0.2891332446 0.0654614239698 +1403715581012143104.0000000000 -2.2497250762 1.7206124528 1.2474756239 0.5431304326 0.7843623559 -0.2928076722 0.0636293555453 +1403715581062142976.0000000000 -2.2760194015 1.7371853499 1.2475181816 0.5362587662 0.7886269738 -0.2940109107 0.0636523073642 +1403715581112143104.0000000000 -2.2952270364 1.7527040762 1.2479640373 0.5292610785 0.7933994572 -0.2931043871 0.0670061966358 +1403715581162142976.0000000000 -2.3074045206 1.7679543248 1.2494858129 0.5248709028 0.7968010058 -0.2901435164 0.0737253853777 +1403715581212143104.0000000000 -2.3127408336 1.7829084885 1.2515769890 0.5230522172 0.7989811143 -0.2844186717 0.0845669927816 +1403715581262142976.0000000000 -2.3127967866 1.7981777193 1.2549832404 0.5252757756 0.7982832687 -0.2798378689 0.0923035733129 +1403715581312143104.0000000000 -2.3085132797 1.8138096135 1.2589508383 0.5293822392 0.7965861745 -0.2757140301 0.0958471963335 +1403715581362142976.0000000000 -2.3000578548 1.8294168007 1.2630037044 0.5335132592 0.7956430906 -0.2698297254 0.0975068910704 +1403715581412143104.0000000000 -2.2880301745 1.8442519412 1.2665150333 0.5370819704 0.7959025734 -0.2615030797 0.0984793884747 +1403715581462142976.0000000000 -2.2725881815 1.8583247737 1.2691325316 0.5396119011 0.7977483117 -0.2492731163 0.101388070581 +1403715581512143104.0000000000 -2.2538158769 1.8721665640 1.2705338866 0.5426256483 0.7999903143 -0.2321124648 0.108151312996 +1403715581562142976.0000000000 -2.2328911782 1.8863037317 1.2692041743 0.5458093697 0.8024258190 -0.2120163147 0.115126101277 +1403715581612143104.0000000000 -2.2107956525 1.9010629710 1.2646758620 0.5481851793 0.8052069727 -0.1914197891 0.120387726255 +1403715581662142976.0000000000 -2.1882541371 1.9161469794 1.2574730521 0.5505917686 0.8077767299 -0.1707016727 0.123314223967 +1403715581712143104.0000000000 -2.1658515966 1.9314220708 1.2475884300 0.5516919686 0.8109962040 -0.1493556187 0.124956104569 +1403715581762142976.0000000000 -2.1440184125 1.9473388529 1.2368355505 0.5526001697 0.8140954097 -0.1267459475 0.125766374934 +1403715581812143104.0000000000 -2.1233637144 1.9640856812 1.2275273860 0.5537066828 0.8165974639 -0.1036284110 0.125851673894 +1403715581862142976.0000000000 -2.1048766860 1.9817071915 1.2208302245 0.5544487396 0.8189781475 -0.0821424864 0.122939013374 +1403715581912143104.0000000000 -2.0894173954 2.0002612019 1.2179467748 0.5562740263 0.8205368530 -0.0651384675 0.114172941854 +1403715581962142976.0000000000 -2.0768746765 2.0197905865 1.2182988199 0.5585520133 0.8217259922 -0.0526299343 0.100080628095 +1403715582012143104.0000000000 -2.0666879245 2.0404926555 1.2228332821 0.5655132677 0.8191800868 -0.0407828639 0.0864609017219 +1403715582062142976.0000000000 -2.0586628256 2.0615569081 1.2309472539 0.5751892355 0.8143013386 -0.0309023502 0.071524247591 +1403715582112143104.0000000000 -2.0517581311 2.0824187570 1.2397379205 0.5852822940 0.8083317507 -0.0200328566 0.0603581125147 +1403715582162142976.0000000000 -2.0461534486 2.1018690044 1.2481609684 0.5939937415 0.8028221037 -0.0105980602 0.0503565886764 +1403715582212143104.0000000000 -2.0414741429 2.1200057958 1.2546173874 0.6011481258 0.7980586268 -0.0029635942 0.0414074404064 +1403715582262142976.0000000000 -2.0372113030 2.1363176969 1.2565081719 0.6025871530 0.7972353837 0.0039715500 0.0358983694091 +1403715582312143104.0000000000 -2.0336205255 2.1509137087 1.2537254177 0.5985178534 0.8004131777 0.0095270277 0.0320056220181 +1403715582362142976.0000000000 -2.0305201590 2.1642179537 1.2484232680 0.5924896703 0.8049080216 0.0139171516 0.0297553393534 +1403715582412143104.0000000000 -2.0281612637 2.1766307971 1.2423673438 0.5859632700 0.8096361090 0.0174093952 0.0288674602779 +1403715582462142976.0000000000 -2.0268708731 2.1880978169 1.2362815920 0.5779088647 0.8153763334 0.0197093541 0.0281836911895 +1403715582512143104.0000000000 -2.0266041569 2.1992654326 1.2314711433 0.5697033020 0.8210869226 0.0211430284 0.028414532923 +1403715582562142976.0000000000 -2.0277090708 2.2109983681 1.2295356651 0.5634828629 0.8253810520 0.0211003059 0.0280706130578 +1403715582612143104.0000000000 -2.0300507868 2.2236336084 1.2307433765 0.5579439818 0.8291154275 0.0207379332 0.0289146883433 +1403715582662142976.0000000000 -2.0337836340 2.2373794505 1.2352951969 0.5534944005 0.8321027535 0.0192595833 0.029631480971 +1403715582712143104.0000000000 -2.0386917678 2.2525833622 1.2418478851 0.5495365298 0.8347380320 0.0169460105 0.0305753661137 +1403715582762142976.0000000000 -2.0445753377 2.2693422822 1.2478304183 0.5464634904 0.8367455765 0.0141982517 0.0321388180502 +1403715582812143104.0000000000 -2.0513109831 2.2869113199 1.2511654014 0.5421508336 0.8395289187 0.0111123774 0.0337666006588 +1403715582862142976.0000000000 -2.0588799563 2.3059273653 1.2513642120 0.5366064988 0.8430584190 0.0077090302 0.0353063501379 +1403715582912143104.0000000000 -2.0674148078 2.3263651049 1.2481015663 0.5302490448 0.8469869215 0.0049920004 0.0377383783771 +1403715582962142976.0000000000 -2.0768991120 2.3489871153 1.2416370358 0.5239831456 0.8508108577 0.0019053412 0.0394831257678 +1403715583012143104.0000000000 -2.0875165331 2.3740361113 1.2321940390 0.5184981684 0.8540911917 -0.0012049580 0.0410662117442 +1403715583062142976.0000000000 -2.0990219548 2.4023218718 1.2197814138 0.5150768923 0.8560710184 -0.0037842262 0.0427069793661 +1403715583112143104.0000000000 -2.1117523849 2.4341487742 1.2066502572 0.5161055129 0.8554043201 -0.0072108079 0.0432036224841 +1403715583162142976.0000000000 -2.1252966808 2.4702763867 1.1946246431 0.5260953061 0.8492368847 -0.0098755734 0.0438510615554 +1403715583212143104.0000000000 -2.1397374374 2.5091381174 1.1832803604 0.5391848825 0.8409737644 -0.0132992755 0.0431962886781 +1403715583262142976.0000000000 -2.1549633436 2.5495607904 1.1730872975 0.5548791333 0.8307700906 -0.0174733632 0.040309869158 +1403715583312143104.0000000000 -2.1704241712 2.5906449611 1.1627497486 0.5699117193 0.8205909420 -0.0215689853 0.036958312998 +1403715583362142976.0000000000 -2.1860759804 2.6311182498 1.1521660415 0.5852416701 0.8097937090 -0.0255091651 0.0327966311311 +1403715583412143104.0000000000 -2.2017615958 2.6706262983 1.1410620704 0.5991937964 0.7995697218 -0.0291088014 0.0284206272705 +1403715583462142976.0000000000 -2.2173272898 2.7081863935 1.1290023176 0.6113866433 0.7903141161 -0.0315193573 0.0248294266076 +1403715583512143104.0000000000 -2.2325065147 2.7432698270 1.1168632021 0.6227277992 0.7814390205 -0.0322502998 0.0228705823511 +1403715583562142976.0000000000 -2.2468238193 2.7746639053 1.1050568606 0.6346275918 0.7718458593 -0.0328806919 0.020509737076 +1403715583612143104.0000000000 -2.2603594439 2.8017150508 1.0943535164 0.6508327213 0.7582853207 -0.0326485549 0.0188205513762 +1403715583662142976.0000000000 -2.2728226140 2.8232526936 1.0835937603 0.6682297644 0.7430534655 -0.0308870016 0.0196601745504 +1403715583712143104.0000000000 -2.2844323062 2.8383245618 1.0728130321 0.6849735260 0.7277169715 -0.0288057708 0.0202362457378 +1403715583762142976.0000000000 -2.2955040415 2.8455965702 1.0616768898 0.6993460787 0.7139840338 -0.0262306251 0.0213029571351 +1403715583812143104.0000000000 -2.3061224944 2.8438098309 1.0513674461 0.7113124826 0.7021230657 -0.0238146368 0.0221498468373 +1403715583862142976.0000000000 -2.3166397300 2.8314992081 1.0438151869 0.7196170062 0.6936893482 -0.0226540735 0.0208145497675 +1403715583912143104.0000000000 -2.3267913321 2.8075399112 1.0405590964 0.7222046599 0.6910529458 -0.0230798361 0.0182640735966 +1403715583962142976.0000000000 -2.3365058889 2.7715419948 1.0418338413 0.7211832346 0.6921638050 -0.0251108060 0.0131702958266 +1403715584012143104.0000000000 -2.3449925089 2.7237311451 1.0479445704 0.7165519989 0.6969279016 -0.0284413071 0.005985382192 +1403715584062142976.0000000000 -2.3517919190 2.6649334194 1.0586404015 0.7079763078 0.7055007518 -0.0322128611 -0.000753948030746 +1403715584112143104.0000000000 -2.3568914177 2.5962921436 1.0728517170 0.6950930538 0.7179462456 -0.0364863746 -0.00822067226558 +1403715584162142976.0000000000 -2.3595719388 2.5187231891 1.0906396328 0.6788961115 0.7330113454 -0.0400560052 -0.0137823715399 +1403715584212143104.0000000000 -2.3596892041 2.4335662327 1.1122951577 0.6597264338 0.7499669587 -0.0436546944 -0.0201211601796 +1403715584262142976.0000000000 -2.3564396329 2.3426433400 1.1353404692 0.6364263094 0.7696520715 -0.0453701181 -0.023211934803 +1403715584312143104.0000000000 -2.3503930508 2.2485727540 1.1574188056 0.6140646128 0.7875281895 -0.0456306036 -0.0253347587309 +1403715584362142976.0000000000 -2.3418575058 2.1533163509 1.1762958461 0.5947713398 0.8020841765 -0.0462119575 -0.0277935637329 +1403715584412143104.0000000000 -2.3307563859 2.0579705060 1.1900130525 0.5785169320 0.8140023254 -0.0447026236 -0.0268337293795 +1403715584462142976.0000000000 -2.3170744946 1.9628875574 1.1982856941 0.5658102960 0.8230566641 -0.0427868363 -0.0246114466688 +1403715584512143104.0000000000 -2.3009902277 1.8689295397 1.2034194189 0.5572335047 0.8290260846 -0.0410386966 -0.0228560212056 +1403715584562142976.0000000000 -2.2825466212 1.7770052806 1.2075000264 0.5500024808 0.8339640878 -0.0394252283 -0.02113818105 +1403715584612143104.0000000000 -2.2618993282 1.6878819351 1.2117231683 0.5450602887 0.8373712571 -0.0373582798 -0.0179727134396 +1403715584662142976.0000000000 -2.2388350960 1.6012568563 1.2161359281 0.5407537448 0.8404727102 -0.0325225110 -0.0115454434612 +1403715584712143104.0000000000 -2.2135524856 1.5175760355 1.2204447865 0.5363152122 0.8436449879 -0.0250346116 -0.00154784326209 +1403715584762142976.0000000000 -2.1870969476 1.4377968695 1.2256977180 0.5319612392 0.8465267042 -0.0186068862 0.00797263025304 +1403715584812143104.0000000000 -2.1604598230 1.3618219979 1.2322989787 0.5295304021 0.8480271779 -0.0139725884 0.0158816104953 +1403715584862142976.0000000000 -2.1340987928 1.2893267845 1.2397724075 0.5272120379 0.8493714202 -0.0109909766 0.0222453608729 +1403715584912143104.0000000000 -2.1081765226 1.2200096262 1.2472795529 0.5228291596 0.8519217398 -0.0075429906 0.028672677366 +1403715584962142976.0000000000 -2.0827872088 1.1542705098 1.2544031150 0.5168208288 0.8552581370 -0.0022066141 0.0377475942507 +1403715585012143104.0000000000 -2.0590913886 1.0919855475 1.2611150849 0.5082201074 0.8601436682 0.0005035435 0.0431849374356 +1403715585062142976.0000000000 -2.0372291753 1.0338858652 1.2677765079 0.4989985681 0.8654211384 0.0002222902 0.0452397270627 +1403715585112143104.0000000000 -2.0174169576 0.9808617359 1.2747946596 0.4902109257 0.8704373007 -0.0019181179 0.0450385911029 +1403715585162142976.0000000000 -1.9994379361 0.9332191206 1.2822050726 0.4826667055 0.8746219546 -0.0032091313 0.0453760876823 +1403715585212143104.0000000000 -1.9832045623 0.8918182340 1.2905577748 0.4790316642 0.8766962501 -0.0053383389 0.0436331517693 +1403715585262142976.0000000000 -1.9684320250 0.8571240941 1.2997015301 0.4806106015 0.8758126334 -0.0050688347 0.0440452935931 +1403715585312143104.0000000000 -1.9552593422 0.8291572287 1.3102781385 0.4874460868 0.8720794258 -0.0054492320 0.0429429087533 +1403715585362142976.0000000000 -1.9433178294 0.8067720026 1.3211449588 0.4959888445 0.8672007703 -0.0031004268 0.0441392957715 +1403715585412143104.0000000000 -1.9329211790 0.7893001310 1.3321138822 0.5045816252 0.8622072680 -0.0013782000 0.0446554718969 +1403715585462142976.0000000000 -1.9241109076 0.7755905171 1.3426032461 0.5115927436 0.8580600998 0.0004597493 0.0447830157993 +1403715585512143104.0000000000 -1.9170143147 0.7658512405 1.3530735496 0.5196660498 0.8531368401 0.0029906840 0.0457797406126 +1403715585562142976.0000000000 -1.9117481779 0.7590868186 1.3632130672 0.5285251316 0.8476044112 0.0057545924 0.0468490346828 +1403715585612143104.0000000000 -1.9083008143 0.7549581962 1.3719991504 0.5347522178 0.8436379687 0.0079521537 0.0474532044787 +1403715585662142976.0000000000 -1.9065907290 0.7529445447 1.3795889765 0.5395570878 0.8405449390 0.0097323990 0.0476196909817 +1403715585712143104.0000000000 -1.9065745418 0.7526040933 1.3851323437 0.5407147076 0.8397813260 0.0109057039 0.0477073909924 +1403715585762142976.0000000000 -1.9083247987 0.7540146263 1.3877695146 0.5412695754 0.8394581097 0.0112745362 0.0470129090015 +1403715585812143104.0000000000 -1.9118237516 0.7570656869 1.3855801609 0.5414586886 0.8395599356 0.0092133117 0.0433211036188 +1403715585862142976.0000000000 -1.9165615948 0.7613656042 1.3771695852 0.5408117460 0.8402447020 0.0061669063 0.0383857445909 +1403715585912143104.0000000000 -1.9226041799 0.7671333554 1.3643614799 0.5400821751 0.8411090227 -0.0004138379 0.0290978503572 +1403715585962142976.0000000000 -1.9290477246 0.7746551353 1.3498690075 0.5395871879 0.8416794574 -0.0084113643 0.0187244924562 +1403715586012143104.0000000000 -1.9357667436 0.7843704609 1.3357834039 0.5395463369 0.8417327230 -0.0185533502 0.00561664081036 +1403715586062142976.0000000000 -1.9413006985 0.7967381531 1.3244510858 0.5428706931 0.8393165868 -0.0282885061 -0.00623201908175 +1403715586112143104.0000000000 -1.9445362137 0.8116172404 1.3169762916 0.5534662944 0.8320365921 -0.0348338020 -0.0132957352719 +1403715586162142976.0000000000 -1.9451129253 0.8277712245 1.3125355094 0.5648018178 0.8242716875 -0.0368424642 -0.0147554968191 +1403715586212143104.0000000000 -1.9429998564 0.8436660282 1.3104983609 0.5750885925 0.8172756482 -0.0348428385 -0.0109362846264 +1403715586262142976.0000000000 -1.9386402215 0.8585691340 1.3100234538 0.5838691233 0.8113263033 -0.0290273632 -0.00197196791666 +1403715586312143104.0000000000 -1.9327963911 0.8724749889 1.3096146764 0.5901693269 0.8069455847 -0.0213025099 0.00922994747792 +1403715586362142976.0000000000 -1.9263042304 0.8853268929 1.3093646765 0.5964597120 0.8022540531 -0.0126866634 0.0215242859784 +1403715586412143104.0000000000 -1.9202184060 0.8968980615 1.3089838338 0.6024295344 0.7975146250 -0.0054151057 0.0319336121538 +1403715586462142976.0000000000 -1.9151495711 0.9066436486 1.3085516317 0.6079119793 0.7930487801 -0.0000202346 0.038944286698 +1403715586512143104.0000000000 -1.9114344880 0.9142845200 1.3084573228 0.6119862722 0.7896553554 0.0037024813 0.0436292794651 +1403715586562142976.0000000000 -1.9095102621 0.9194638270 1.3089242069 0.6149775327 0.7872296464 0.0050973483 0.0452342263704 +1403715586612143104.0000000000 -1.9092344488 0.9219006609 1.3096867508 0.6166780705 0.7858627599 0.0055592677 0.0457927338392 +1403715586662142976.0000000000 -1.9105617979 0.9214367758 1.3099370672 0.6153930433 0.7868748461 0.0051009839 0.0457532381704 +1403715586712143104.0000000000 -1.9135430533 0.9182583596 1.3103226082 0.6123300545 0.7894313717 0.0026242978 0.0429316531098 +1403715586762142976.0000000000 -1.9180137686 0.9122803702 1.3104980359 0.6061929017 0.7943991264 -0.0015333202 0.0381817072799 +1403715586812143104.0000000000 -1.9236204825 0.9039114072 1.3105627915 0.5972337912 0.8013866173 -0.0066586062 0.0323566262384 +1403715586862142976.0000000000 -1.9296886264 0.8940418995 1.3108171421 0.5870299016 0.8090330892 -0.0114968279 0.0270032990417 +1403715586912143104.0000000000 -1.9358947112 0.8835902272 1.3117178195 0.5776756220 0.8157835178 -0.0152902773 0.0235443272215 +1403715586962142976.0000000000 -1.9419359759 0.8731475839 1.3132085346 0.5706871122 0.8206787798 -0.0177939375 0.0220439584287 +1403715587012143104.0000000000 -1.9478683174 0.8629447265 1.3152443527 0.5667116368 0.8234065422 -0.0198436940 0.0211143264396 +1403715587062142976.0000000000 -1.9535430806 0.8532341689 1.3175074563 0.5646937409 0.8247604766 -0.0216750267 0.020526288269 +1403715587112143104.0000000000 -1.9587821945 0.8445072841 1.3206469292 0.5656863173 0.8240463943 -0.0225629071 0.0209152029663 +1403715587162142976.0000000000 -1.9636077659 0.8363115274 1.3250230666 0.5701622773 0.8209215665 -0.0204656648 0.0241643476172 +1403715587212143104.0000000000 -1.9683396309 0.8286449879 1.3311813191 0.5768242379 0.8162226341 -0.0175074716 0.0273477324872 +1403715587262142976.0000000000 -1.9734309231 0.8208126565 1.3380027964 0.5821516328 0.8124094565 -0.0146610318 0.0295872538451 +1403715587312143104.0000000000 -1.9793450796 0.8126227330 1.3457816264 0.5864222669 0.8093582977 -0.0122876610 0.0299513651085 +1403715587362142976.0000000000 -1.9863375058 0.8034639046 1.3538518260 0.5888976577 0.8077024255 -0.0125574520 0.0256641981329 +1403715587412143104.0000000000 -1.9937754621 0.7934776912 1.3622105670 0.5914096311 0.8060152510 -0.0147351875 0.0188927947571 +1403715587462142976.0000000000 -2.0010328550 0.7825885584 1.3703880844 0.5918746136 0.8057387217 -0.0182892873 0.0116213624068 +1403715587512143104.0000000000 -2.0076560033 0.7707690145 1.3784689760 0.5907225196 0.8065168710 -0.0234700672 0.00515728053336 +1403715587562142976.0000000000 -2.0128859091 0.7581738730 1.3870275058 0.5894020136 0.8072345197 -0.0312442687 -0.0012216134725 +1403715587612143104.0000000000 -2.0162329194 0.7448185578 1.3958144932 0.5871228986 0.8084337145 -0.0410196120 -0.00624681203727 +1403715587662142976.0000000000 -2.0170010446 0.7307123332 1.4044756460 0.5841380518 0.8099579125 -0.0516980007 -0.00884495682139 +1403715587712143104.0000000000 -2.0150407213 0.7158157084 1.4123181453 0.5797731053 0.8123501491 -0.0623432466 -0.00798130855074 +1403715587762142976.0000000000 -2.0096790902 0.7007636953 1.4201457266 0.5763645688 0.8138048398 -0.0742161532 -0.00418679052782 +1403715587812143104.0000000000 -2.0011897043 0.6858949655 1.4279543789 0.5742918513 0.8139656036 -0.0874304086 0.0021884712371 +1403715587862142976.0000000000 -1.9893853678 0.6709456559 1.4357709266 0.5736859850 0.8127484531 -0.1009443915 0.011600532809 +1403715587912143104.0000000000 -1.9741150520 0.6559610924 1.4435805973 0.5737356102 0.8106877928 -0.1138987972 0.0252945895734 +1403715587962142976.0000000000 -1.9557492108 0.6406892004 1.4513917458 0.5758868572 0.8065828660 -0.1265387014 0.0420281448782 +1403715588012143104.0000000000 -1.9349404699 0.6247149167 1.4591250843 0.5788030373 0.8013114320 -0.1389526943 0.0598262626903 +1403715588062142976.0000000000 -1.9124098005 0.6078714051 1.4661722829 0.5823393294 0.7949098023 -0.1514454572 0.0778690255628 +1403715588112143104.0000000000 -1.8885643896 0.5896090248 1.4710845882 0.5851754275 0.7883597419 -0.1640370352 0.0956581805359 +1403715588162142976.0000000000 -1.8640804217 0.5696514841 1.4718073955 0.5878744038 0.7811820354 -0.1772328347 0.112901882797 +1403715588212143104.0000000000 -1.8393180549 0.5484491427 1.4672513573 0.5900060903 0.7738033333 -0.1909129571 0.129125742984 +1403715588262142976.0000000000 -1.8149629647 0.5255889506 1.4567900218 0.5908829146 0.7667962657 -0.2059199810 0.143100766785 +1403715588312143104.0000000000 -1.7912003876 0.5008852941 1.4411217881 0.5901784446 0.7604955120 -0.2218817063 0.155256201955 +1403715588362142976.0000000000 -1.7680284278 0.4739132114 1.4223212872 0.5886371351 0.7545105766 -0.2374636436 0.166826649389 +1403715588412143104.0000000000 -1.7455759692 0.4441614757 1.4028514854 0.5860970838 0.7489824876 -0.2520951303 0.17878335209 +1403715588462142976.0000000000 -1.7239212722 0.4119168644 1.3835590253 0.5831557864 0.7436791368 -0.2658047212 0.190311640381 +1403715588512143104.0000000000 -1.7031918437 0.3771047474 1.3645015939 0.5785926194 0.7394368318 -0.2799301671 0.200256969916 +1403715588562142976.0000000000 -1.6831470989 0.3398798834 1.3461420921 0.5743872345 0.7346306113 -0.2937130210 0.210071014414 +1403715588612143104.0000000000 -1.6639058390 0.3004207035 1.3277848986 0.5679939389 0.7313440737 -0.3077806159 0.21860883722 +1403715588662142976.0000000000 -1.6457658737 0.2587636541 1.3092183886 0.5596534503 0.7294773517 -0.3222156096 0.225450460032 +1403715588712143104.0000000000 -1.6282102929 0.2151951805 1.2904051521 0.5492270603 0.7289444359 -0.3358382568 0.232813897474 +1403715588762142976.0000000000 -1.6113481141 0.1701777077 1.2713808954 0.5376314162 0.7289264750 -0.3495809794 0.239607581826 +1403715588812143104.0000000000 -1.5946874004 0.1237932322 1.2518137684 0.5233062015 0.7304231662 -0.3627710180 0.247042114375 +1403715588862142976.0000000000 -1.5779091079 0.0768816118 1.2315301940 0.5068230804 0.7328786588 -0.3760813775 0.254129955481 +1403715588912143104.0000000000 -1.5607337575 0.0300546262 1.2107650761 0.4888114098 0.7360061334 -0.3892048499 0.260533993926 +1403715588962142976.0000000000 -1.5426225778 -0.0158937919 1.1901084642 0.4713247167 0.7382523646 -0.4024211126 0.266258719298 +1403715589012143104.0000000000 -1.5230287769 -0.0601954772 1.1701988807 0.4546620626 0.7396164993 -0.4151572692 0.271835032006 +1403715589062142976.0000000000 -1.5014706873 -0.1021567460 1.1524154872 0.4410913547 0.7386604401 -0.4282805466 0.276396354084 +1403715589112143104.0000000000 -1.4770939396 -0.1414010123 1.1382183201 0.4308746473 0.7359069961 -0.4394992374 0.282184960039 +1403715589162142976.0000000000 -1.4495694015 -0.1774647640 1.1271546797 0.4224416125 0.7324918293 -0.4502633971 0.286812965822 +1403715589212143104.0000000000 -1.4184995387 -0.2102154718 1.1206280624 0.4163012719 0.7282690257 -0.4594112697 0.291991031528 +1403715589262142976.0000000000 -1.3843275860 -0.2400482971 1.1171315831 0.4101887381 0.7239052065 -0.4682988436 0.297325821791 +1403715589312143104.0000000000 -1.3467898185 -0.2668662949 1.1169499486 0.4033207139 0.7201665122 -0.4778211426 0.300631921303 +1403715589362142976.0000000000 -1.3057508812 -0.2909892671 1.1197376401 0.3945992065 0.7172540276 -0.4875293312 0.303567582904 +1403715589412143104.0000000000 -1.2610887342 -0.3121435041 1.1253877376 0.3875283670 0.7132638398 -0.4978261767 0.305361355628 +1403715589462142976.0000000000 -1.2125182262 -0.3305082449 1.1317897016 0.3805772294 0.7089653146 -0.5082206617 0.306986830842 +1403715589512143104.0000000000 -1.1597718756 -0.3462673949 1.1382132660 0.3732540437 0.7053451712 -0.5171885239 0.309330953934 +1403715589562142976.0000000000 -1.1027369056 -0.3594319561 1.1452609033 0.3667611954 0.7025523784 -0.5238861338 0.312169344948 +1403715589612143104.0000000000 -1.0411231300 -0.3696139368 1.1549940307 0.3612457785 0.7002938372 -0.5295469536 0.314117896806 +1403715589662142976.0000000000 -0.9737816460 -0.3765315295 1.1689524568 0.3593497343 0.6971260382 -0.5336401796 0.316403561915 +1403715589712143104.0000000000 -0.9007869557 -0.3801769538 1.1871214097 0.3604772660 0.6935841333 -0.5346978946 0.321084649596 +1403715589762142976.0000000000 -0.8215629498 -0.3803755056 1.2107142110 0.3678071899 0.6875293479 -0.5321030141 0.329981286199 +1403715589812143104.0000000000 -0.7372887976 -0.3777031790 1.2395187736 0.3809574326 0.6788516393 -0.5254612496 0.34339825491 +1403715589862142976.0000000000 -0.6497741471 -0.3723845159 1.2717990744 0.3971065752 0.6686952939 -0.5177568817 0.356483917353 +1403715589912143104.0000000000 -0.5612859648 -0.3649942437 1.3039673391 0.4111572348 0.6596083679 -0.5122628837 0.365312561 +1403715589962142976.0000000000 -0.4727973128 -0.3560048304 1.3349895502 0.4231054883 0.6519579735 -0.5074802765 0.372016552868 +1403715590012143104.0000000000 -0.3851338032 -0.3459741100 1.3640714610 0.4323284791 0.6463508795 -0.5039861955 0.375926244669 +1403715590062142976.0000000000 -0.2984174474 -0.3350212291 1.3913901737 0.4378897172 0.6434207049 -0.5006483954 0.378963819047 +1403715590112143104.0000000000 -0.2131583469 -0.3235476520 1.4170583741 0.4400711144 0.6428019472 -0.4979800396 0.380997311212 +1403715590162142976.0000000000 -0.1295268341 -0.3114400552 1.4414977785 0.4398649874 0.6440323802 -0.4959978186 0.381742387097 +1403715590212143104.0000000000 -0.0477781022 -0.2985261606 1.4641999963 0.4373615387 0.6478899064 -0.4946709537 0.379808110979 +1403715590262142976.0000000000 0.0324578409 -0.2846673332 1.4863683789 0.4351752695 0.6527632387 -0.4910657757 0.378651611599 +1403715590312143104.0000000000 0.1110712294 -0.2693531694 1.5082728029 0.4329481473 0.6590957679 -0.4851336924 0.377880895233 +1403715590362142976.0000000000 0.1882695632 -0.2525899573 1.5295247888 0.4305827292 0.6667900164 -0.4762006691 0.378447499728 +1403715590412143104.0000000000 0.2643231608 -0.2330576289 1.5505253669 0.4288288117 0.6754861512 -0.4656071094 0.37819879627 +1403715590462142976.0000000000 0.3391823824 -0.2105987708 1.5711937824 0.4295477558 0.6840112312 -0.4529403216 0.377441950607 +1403715590512143104.0000000000 0.4123888109 -0.1851039356 1.5911112783 0.4305763008 0.6932205156 -0.4400542205 0.374702080352 +1403715590562142976.0000000000 0.4840201421 -0.1564178011 1.6108732695 0.4321583918 0.7029524537 -0.4253763245 0.371687980273 +1403715590612143104.0000000000 0.5538601987 -0.1244212819 1.6300217533 0.4337769346 0.7132374132 -0.4119758919 0.365247625455 +1403715590662142976.0000000000 0.6213182408 -0.0887884332 1.6490548291 0.4379724332 0.7223448479 -0.4020359439 0.353221132216 +1403715590712143104.0000000000 0.6868353543 -0.0494881602 1.6680512769 0.4444817576 0.7304654112 -0.3946287774 0.336339676977 +1403715590762142976.0000000000 0.7511550973 -0.0070020417 1.6873929641 0.4536907804 0.7366404967 -0.3864651401 0.319640657572 +1403715590812143104.0000000000 0.8146366951 0.0381262473 1.7074837293 0.4652043769 0.7412168728 -0.3764732253 0.304056484612 +1403715590862142976.0000000000 0.8772808530 0.0851321083 1.7276788321 0.4770874520 0.7451999286 -0.3640673299 0.290722563243 +1403715590912143104.0000000000 0.9387531788 0.1334424143 1.7473693334 0.4889292154 0.7491227557 -0.3496286430 0.278429759986 +1403715590962142976.0000000000 0.9990626515 0.1829378314 1.7665193341 0.4976732949 0.7549389154 -0.3336843349 0.266539472189 +1403715591012143104.0000000000 1.0579039311 0.2331537501 1.7847559763 0.5038741460 0.7619200274 -0.3172983366 0.254775356914 +1403715591062142976.0000000000 1.1151284771 0.2841851590 1.8022442352 0.5086644131 0.7697715501 -0.3002175305 0.242036587634 +1403715591112143104.0000000000 1.1713133233 0.3360802888 1.8190637645 0.5128214860 0.7775931472 -0.2819197729 0.22996578578 +1403715591162142976.0000000000 1.2266937077 0.3885865360 1.8349464306 0.5155167314 0.7860390408 -0.2608413534 0.219879317707 +1403715591212143104.0000000000 1.2804606080 0.4418125308 1.8502798026 0.5174201261 0.7943432891 -0.2390057519 0.210169938037 +1403715591262142976.0000000000 1.3326434984 0.4961529463 1.8646551165 0.5191081924 0.8020202606 -0.2153701838 0.2022519966 +1403715591312143104.0000000000 1.3830823260 0.5519968770 1.8783665487 0.5209894513 0.8087813913 -0.1914808178 0.194364989558 +1403715591362142976.0000000000 1.4311751308 0.6097295325 1.8924835884 0.5238373014 0.8141899222 -0.1696284220 0.184161479852 +1403715591412143104.0000000000 1.4769439797 0.6694087827 1.9062393614 0.5264708282 0.8190078429 -0.1476658238 0.1739236177 +1403715591462142976.0000000000 1.5199474880 0.7306730653 1.9194783091 0.5297562490 0.8226937584 -0.1270421818 0.162461012729 +1403715591512143104.0000000000 1.5600725881 0.7933583895 1.9314352718 0.5313633851 0.8268206279 -0.1080152139 0.149510253591 +1403715591562142976.0000000000 1.5973939564 0.8575690958 1.9408717209 0.5333803636 0.8301321890 -0.0897092283 0.135418576434 +1403715591612143104.0000000000 1.6320669923 0.9231859068 1.9470587724 0.5350069828 0.8331272274 -0.0732730748 0.119572605139 +1403715591662142976.0000000000 1.6645430969 0.9905600147 1.9505227793 0.5379413960 0.8345560409 -0.0569546561 0.104362043537 +1403715591712143104.0000000000 1.6953588142 1.0592721242 1.9508195173 0.5417152032 0.8344664516 -0.0388093325 0.0932963856433 +1403715591762142976.0000000000 1.7242215624 1.1292216864 1.9480432300 0.5451775021 0.8339183970 -0.0213945012 0.0830895520714 +1403715591812143104.0000000000 1.7508394726 1.1998053169 1.9419832927 0.5476313026 0.8334900979 -0.0041571923 0.0733275590943 +1403715591862142976.0000000000 1.7748301316 1.2710453642 1.9323123952 0.5494795012 0.8329922866 0.0120112476 0.0636542075541 +1403715591912143104.0000000000 1.7960486762 1.3426276714 1.9192572279 0.5509937619 0.8321950238 0.0289862571 0.0549282587495 +1403715591962142976.0000000000 1.8146833159 1.4148258502 1.9029220125 0.5525595739 0.8307350444 0.0474196520 0.0480476830272 +1403715592012143104.0000000000 1.8305963108 1.4872837739 1.8832650177 0.5532496832 0.8291501715 0.0673348143 0.0434833764106 +1403715592062142976.0000000000 1.8429165415 1.5598182442 1.8609860871 0.5539308568 0.8271641279 0.0868264916 0.0376997585472 +1403715592112143104.0000000000 1.8512657666 1.6322218491 1.8375704771 0.5552632912 0.8242408034 0.1064289920 0.0313471709401 +1403715592162142976.0000000000 1.8546634385 1.7046966964 1.8159038395 0.5590344862 0.8192816621 0.1254509836 0.0228046504467 +1403715592212143104.0000000000 1.8527084505 1.7767953421 1.7979627766 0.5653048102 0.8120465729 0.1443801324 0.01285349349 +1403715592262142976.0000000000 1.8456403947 1.8475438321 1.7832428625 0.5698414317 0.8053690360 0.1632627498 0.00259481373472 +1403715592312143104.0000000000 1.8334400299 1.9161624184 1.7721270771 0.5736376819 0.7985270459 0.1823035177 -0.00773267932705 +1403715592362142976.0000000000 1.8159193976 1.9825269040 1.7639396194 0.5753321799 0.7925906041 0.2011763641 -0.0179189182943 +1403715592412143104.0000000000 1.7930065582 2.0463605505 1.7588126119 0.5759148905 0.7867089575 0.2205574857 -0.0276667766233 +1403715592462142976.0000000000 1.7651261480 2.1071279129 1.7558827435 0.5749479956 0.7815289295 0.2392716681 -0.0373684840435 +1403715592512143104.0000000000 1.7324169192 2.1647656420 1.7542001643 0.5749477290 0.7749756601 0.2581943257 -0.0467282071905 +1403715592562142976.0000000000 1.6955307318 2.2190122169 1.7526856109 0.5752006071 0.7676960340 0.2768375072 -0.0561075355449 +1403715592612143104.0000000000 1.6540805780 2.2698938604 1.7509213154 0.5751901507 0.7601786267 0.2949523757 -0.0654816164298 +1403715592662142976.0000000000 1.6079444482 2.3172551061 1.7486599659 0.5747812158 0.7520369367 0.3139953316 -0.0739860228496 +1403715592712143104.0000000000 1.5570944090 2.3600443279 1.7468477136 0.5736498621 0.7438876694 0.3324795391 -0.0837515792086 +1403715592762142976.0000000000 1.5013323213 2.3980155522 1.7456361625 0.5704505791 0.7371561889 0.3491576755 -0.0963109941574 +1403715592812143104.0000000000 1.4408965175 2.4310015675 1.7454134501 0.5648309889 0.7327164969 0.3619157159 -0.114496741332 +1403715592862142976.0000000000 1.3763099909 2.4591766056 1.7460071530 0.5554537282 0.7316629224 0.3701166085 -0.138398771332 +1403715592912143104.0000000000 1.3085742729 2.4834498913 1.7470735434 0.5446671517 0.7309316394 0.3769861935 -0.164189044204 +1403715592962142976.0000000000 1.2385361436 2.5046302780 1.7482202347 0.5331796483 0.7297895308 0.3834046041 -0.190072651433 +1403715593012143104.0000000000 1.1667979679 2.5237883431 1.7492488295 0.5227727400 0.7266302701 0.3902520597 -0.215454038785 +1403715593062142976.0000000000 1.0943181985 2.5413532919 1.7499455472 0.5131026882 0.7216563286 0.3983464844 -0.239286132448 +1403715593112143104.0000000000 1.0218087981 2.5580704905 1.7500703024 0.5047620869 0.7143797684 0.4092546207 -0.259590904443 +1403715593162142976.0000000000 0.9495726840 2.5743176117 1.7494313010 0.4976428240 0.7053807639 0.4223125478 -0.27648093886 +1403715593212143104.0000000000 0.8778257349 2.5903373732 1.7482444919 0.4923753132 0.6946809355 0.4360141261 -0.291335941103 +1403715593262142976.0000000000 0.8066367005 2.6061431721 1.7467326319 0.4869987649 0.6839358626 0.4505762828 -0.30338911022 +1403715593312143104.0000000000 0.7359505598 2.6217568359 1.7442977153 0.4825099394 0.6725395655 0.4666918732 -0.311566023031 +1403715593362142976.0000000000 0.6659025393 2.6374168868 1.7417356800 0.4810907666 0.6589219271 0.4845602112 -0.31555501887 +1403715593412143104.0000000000 0.5960720537 2.6519648250 1.7390857704 0.4791645549 0.6452624047 0.5027733147 -0.318208661861 +1403715593462142976.0000000000 0.5264549635 2.6650620296 1.7365970762 0.4775095613 0.6307760251 0.5205871349 -0.321084506199 +1403715593512143104.0000000000 0.4568883096 2.6760058672 1.7334129544 0.4745894617 0.6170428971 0.5374135809 -0.324360215145 +1403715593562142976.0000000000 0.3870827855 2.6840162138 1.7315559424 0.4708604108 0.6038772711 0.5510137098 -0.331672438697 +1403715593612143104.0000000000 0.3174698155 2.6891278406 1.7303713819 0.4687442424 0.5888057976 0.5636564728 -0.340408502401 +1403715593662142976.0000000000 0.2485343053 2.6911638843 1.7299504352 0.4656056382 0.5746562731 0.5730843170 -0.352924812304 +1403715593712143104.0000000000 0.1803235187 2.6903310914 1.7299635011 0.4642507100 0.5589842167 0.5814000800 -0.366035340841 +1403715593762142976.0000000000 0.1135786657 2.6862422826 1.7299786390 0.4606801922 0.5444253496 0.5898307784 -0.378780216174 +1403715593812143104.0000000000 0.0488221189 2.6792652154 1.7299856765 0.4558780627 0.5297324967 0.5991532225 -0.390607334654 +1403715593862142976.0000000000 -0.0135136084 2.6695137158 1.7292664766 0.4502611475 0.5147434922 0.6107970252 -0.399037630142 +1403715593912143104.0000000000 -0.0729026872 2.6562009274 1.7280662158 0.4410879142 0.5011336811 0.6223867337 -0.40858443351 +1403715593962142976.0000000000 -0.1294348978 2.6400504532 1.7259372255 0.4300809376 0.4880308948 0.6354522776 -0.416000763987 +1403715594012143104.0000000000 -0.1835136985 2.6212790665 1.7238479645 0.4183342147 0.4749367296 0.6490360004 -0.422118298499 +1403715594062142976.0000000000 -0.2354065561 2.5996670079 1.7220221945 0.4043400307 0.4634807315 0.6616673436 -0.428825229582 +1403715594112143104.0000000000 -0.2851187490 2.5755990907 1.7202658531 0.3900906483 0.4525965678 0.6736483305 -0.434952364845 +1403715594162142976.0000000000 -0.3330875734 2.5490791432 1.7188885304 0.3766963581 0.4413140356 0.6843733884 -0.441559555469 +1403715594212143104.0000000000 -0.3795797681 2.5204232057 1.7177465059 0.3645251519 0.4293777014 0.6942284850 -0.448110492911 +1403715594262142976.0000000000 -0.4244805493 2.4898384116 1.7172198606 0.3531184223 0.4174558262 0.7032323646 -0.454425191146 +1403715594312143104.0000000000 -0.4678209223 2.4573245411 1.7168978858 0.3430941272 0.4041966004 0.7121492367 -0.460168439594 +1403715594362142976.0000000000 -0.5097784220 2.4228146100 1.7167802001 0.3347983310 0.3896245803 0.7201525483 -0.466350802763 +1403715594412143104.0000000000 -0.5501609553 2.3861736682 1.7164252713 0.3270636498 0.3738984543 0.7286204149 -0.471531129242 +1403715594462142976.0000000000 -0.5885974350 2.3474731148 1.7160283967 0.3193795287 0.3571127022 0.7373344066 -0.476240703186 +1403715594512143104.0000000000 -0.6250528020 2.3066483281 1.7159751211 0.3130128931 0.3383765274 0.7461899082 -0.480338292553 +1403715594562142976.0000000000 -0.6594215877 2.2635828041 1.7159110515 0.3055622738 0.3194394974 0.7549839406 -0.484344251365 +1403715594612143104.0000000000 -0.6912804189 2.2184649754 1.7154038688 0.2966149726 0.3008043413 0.7636702660 -0.488204906838 +1403715594662142976.0000000000 -0.7205129193 2.1707019296 1.7147984657 0.2858190721 0.2832110102 0.7732047452 -0.49015650947 +1403715594712143104.0000000000 -0.7468348388 2.1202122660 1.7138055667 0.2707479222 0.2681945782 0.7838564161 -0.490241113845 +1403715594762142976.0000000000 -0.7703216343 2.0668681107 1.7125913243 0.2500836661 0.2570128825 0.7942485938 -0.490481099937 +1403715594812143104.0000000000 -0.7922799751 2.0105161219 1.7116868386 0.2289236358 0.2462223042 0.8030712653 -0.491980780891 +1403715594862142976.0000000000 -0.8132153723 1.9515375220 1.7108039572 0.2079303026 0.2351050668 0.8103872185 -0.494735437194 +1403715594912143104.0000000000 -0.8336683119 1.8901818978 1.7097532184 0.1887314828 0.2223643130 0.8174992050 -0.496618152653 +1403715594962142976.0000000000 -0.8540861638 1.8262980769 1.7082473680 0.1712809637 0.2086803064 0.8236515574 -0.498711813778 +1403715595012143104.0000000000 -0.8744959181 1.7602269849 1.7065263413 0.1563700586 0.1931876047 0.8288857249 -0.501174030873 +1403715595062142976.0000000000 -0.8952518401 1.6914771565 1.7043219709 0.1427709654 0.1769750310 0.8337032960 -0.503224705278 +1403715595112143104.0000000000 -0.9163310890 1.6197167139 1.7026249617 0.1283258625 0.1614031331 0.8368606009 -0.507095490268 +1403715595162142976.0000000000 -0.9374847163 1.5453173524 1.7018486876 0.1120965447 0.1473623361 0.8377958300 -0.513631048346 +1403715595212143104.0000000000 -0.9592713366 1.4689266774 1.7009790583 0.0980077694 0.1312880632 0.8384736934 -0.519730494753 +1403715595262142976.0000000000 -0.9814255028 1.3907001865 1.6998219497 0.0839446219 0.1147689529 0.8385658150 -0.525917067474 +1403715595312143104.0000000000 -1.0041190109 1.3107136734 1.6979414178 0.0705494096 0.0975722819 0.8374966306 -0.533012030187 +1403715595362142976.0000000000 -1.0270915243 1.2295110561 1.6950119676 0.0582082405 0.0791528509 0.8356397497 -0.540419129606 +1403715595412143104.0000000000 -1.0500852874 1.1478200830 1.6912968616 0.0441233519 0.0619183258 0.8339744552 -0.546539896877 +1403715595462142976.0000000000 -1.0734405120 1.0652030049 1.6878681411 0.0310363562 0.0436333278 0.8306049116 -0.554281839928 +1403715595512143104.0000000000 -1.0973595380 0.9825712764 1.6841364986 0.0203151174 0.0230352657 0.8270169401 -0.561337379291 +1403715595562142976.0000000000 -1.1216395376 0.9001737369 1.6804912682 0.0116319646 0.0012098462 0.8230281861 -0.567880126952 +1403715595612143104.0000000000 -1.1462431608 0.8182798903 1.6764389821 0.0084406193 -0.0245502692 0.8169081768 -0.576183192084 +1403715595662142976.0000000000 -1.1697893057 0.7369715620 1.6725692920 0.0066033589 -0.0514924802 0.8086722947 -0.585964196778 +1403715595712143104.0000000000 -1.1920610332 0.6572368877 1.6687188699 0.0073543987 -0.0798473355 0.7984649903 -0.596677446429 +1403715595762142976.0000000000 -1.2116757330 0.5798218211 1.6654005857 0.0068564477 -0.1069670371 0.7868747595 -0.607732799033 +1403715595812143104.0000000000 -1.2284360697 0.5057380991 1.6624836546 0.0074205368 -0.1337765009 0.7745336607 -0.618179902534 +1403715595862142976.0000000000 -1.2414064293 0.4359317582 1.6612215458 0.0034652154 -0.1554312134 0.7618674551 -0.628798148108 +1403715595912143104.0000000000 -1.2504716034 0.3713029112 1.6617340967 0.0000716803 -0.1751695504 0.7476756482 -0.640544103549 +1403715595962142976.0000000000 -1.2550463276 0.3134537861 1.6643499505 0.0078804065 0.1899326582 -0.7325159023 0.653669593507 +1403715596012143104.0000000000 -1.2552814016 0.2635292206 1.6695521543 0.0203223671 0.1995372996 -0.7172737308 0.667300728774 +1403715596062142976.0000000000 -1.2519024077 0.2227068345 1.6778426166 0.0371766603 0.2048484235 -0.7024893555 0.68056133056 +1403715596112143104.0000000000 -1.2465586858 0.1921176997 1.6880818448 0.0548152905 0.2069960593 -0.6910438671 0.690366778677 +1403715596162142976.0000000000 -1.2400901761 0.1719440073 1.6996412489 0.0660902377 0.2103057777 -0.6854606329 0.693936078583 +1403715596212143104.0000000000 -1.2329496581 0.1625706582 1.7125052447 0.0738924399 0.2143322513 -0.6876454248 0.689742968914 +1403715596262142976.0000000000 -1.2254965062 0.1634947021 1.7262599510 0.0767138169 0.2198939747 -0.6987849021 0.676358847661 +1403715596312143104.0000000000 -1.2177288657 0.1735485087 1.7396204823 0.0781719834 0.2263637571 -0.7179259488 0.653629040476 +1403715596362142976.0000000000 -1.2083788189 0.1910027354 1.7535678039 0.0792447869 0.2332064131 -0.7385915948 0.627548793898 +1403715596412143104.0000000000 -1.1972431962 0.2141131174 1.7682654569 0.0836697606 0.2383439140 -0.7588465287 0.600286178143 +1403715596462142976.0000000000 -1.1837568281 0.2407753541 1.7837382710 0.0893931238 0.2434266305 -0.7762300885 0.574647017491 +1403715596512143104.0000000000 -1.1677277544 0.2692106073 1.7995555772 0.0950988203 0.2487031141 -0.7910335195 0.550789384755 +1403715596562142976.0000000000 -1.1487968181 0.2980265225 1.8158929651 0.1014768474 0.2544978227 -0.8023093098 0.530314132531 +1403715596612143104.0000000000 -1.1270543090 0.3259775595 1.8320499139 0.1073765943 0.2610497756 -0.8116899286 0.511353831976 +1403715596662142976.0000000000 -1.1022370088 0.3518339797 1.8479499369 0.1131170812 0.2683663761 -0.8190224672 0.494354338848 +1403715596712143104.0000000000 -1.0739893746 0.3747928768 1.8639835479 0.1187434607 0.2764086950 -0.8234826308 0.481014116949 +1403715596762142976.0000000000 -1.0421467078 0.3944699388 1.8798145907 0.1238215359 0.2854722265 -0.8259611180 0.47006602387 +1403715596812143104.0000000000 -1.0065278723 0.4107680246 1.8951837142 0.1299673001 0.2938141531 -0.8284165860 0.458811185921 +1403715596862142976.0000000000 -0.9670024088 0.4227884295 1.9100826717 0.1358504638 0.3008232038 -0.8310755286 0.447619835678 +1403715596912143104.0000000000 -0.9233319187 0.4297955769 1.9241854281 0.1403005691 0.3077536309 -0.8331351521 0.437594871153 +1403715596962142976.0000000000 -0.8754436744 0.4316405809 1.9372634285 0.1430722882 0.3142167164 -0.8349542716 0.428543509838 +1403715597012143104.0000000000 -0.8230633579 0.4279152966 1.9498431578 0.1453558324 0.3200384727 -0.8352405947 0.422871383389 +1403715597062142976.0000000000 -0.7658559999 0.4181288221 1.9623194262 0.1476666394 0.3242725980 -0.8345335980 0.420232696914 +1403715597112143104.0000000000 -0.7036280656 0.4022981965 1.9752975196 0.1519581023 0.3263563913 -0.8317830268 0.422536669875 +1403715597162142976.0000000000 -0.6361279848 0.3807765774 1.9888336818 0.1590969293 0.3265784330 -0.8265763132 0.429891024081 +1403715597212143104.0000000000 -0.5639906471 0.3541523962 2.0027513878 0.1701334702 0.3247891954 -0.8193112868 0.440789741439 +1403715597262142976.0000000000 -0.4884080762 0.3233325575 2.0167881532 0.1821642932 0.3230170924 -0.8104862352 0.453418339784 +1403715597312143104.0000000000 -0.4101816024 0.2890758297 2.0308319378 0.1962729581 0.3209306388 -0.8005353237 0.466501496863 +1403715597362142976.0000000000 -0.3306968048 0.2522913874 2.0438243346 0.2094220631 0.3205032265 -0.7907059473 0.477707218109 +1403715597412143104.0000000000 -0.2504100306 0.2133010922 2.0570622332 0.2239687136 0.3201950927 -0.7800503189 0.48870708813 +1403715597462142976.0000000000 -0.1701754768 0.1719656799 2.0699532955 0.2359150038 0.3230065470 -0.7667506934 0.502099846435 +1403715597512143104.0000000000 -0.0910715097 0.1299584347 2.0815788438 0.2463732649 0.3283180902 -0.7542494050 0.512460028735 +1403715597562142976.0000000000 -0.0135698888 0.0878694263 2.0921142335 0.2552199788 0.3361822319 -0.7432008895 0.519130722649 +1403715597612143104.0000000000 0.0619600661 0.0462981407 2.1008534488 0.2629531605 0.3457899273 -0.7341753177 0.521796478012 +1403715597662142976.0000000000 0.1355091543 0.0049758187 2.1083158396 0.2700262857 0.3565021306 -0.7263894726 0.521871986287 +1403715597712143104.0000000000 0.2072141841 -0.0363306389 2.1147003037 0.2749828166 0.3685384126 -0.7209940467 0.518393165104 +1403715597762142976.0000000000 0.2774805650 -0.0778343265 2.1208313681 0.2796364012 0.3794787956 -0.7160908535 0.514794343783 +1403715597812143104.0000000000 0.3463967615 -0.1194452097 2.1261757863 0.2845856499 0.3881643041 -0.7125533398 0.510497031166 +1403715597862142976.0000000000 0.4138882131 -0.1613638893 2.1312435738 0.2886248455 0.3956642924 -0.7079248758 0.508908475616 +1403715597912143104.0000000000 0.4802112090 -0.2034023748 2.1371198667 0.2933175260 0.4007774322 -0.7021501419 0.510222948314 +1403715597962142976.0000000000 0.5451167785 -0.2455000752 2.1433490961 0.2984390351 0.4037204736 -0.6957660387 0.513666760534 +1403715598012143104.0000000000 0.6079221420 -0.2871836484 2.1488067830 0.3021843061 0.4060342637 -0.6910049735 0.51607455706 +1403715598062142976.0000000000 0.6683955365 -0.3282468954 2.1538499035 0.3038071400 0.4085042570 -0.6870816010 0.518405601095 +1403715598112143104.0000000000 0.7267244422 -0.3685961992 2.1572220595 0.3028970197 0.4116008666 -0.6834850992 0.521235303094 +1403715598162142976.0000000000 0.7836499814 -0.4079790725 2.1590527541 0.3033291826 0.4130141849 -0.6795116812 0.525047202834 +1403715598212143104.0000000000 0.8387543879 -0.4463004974 2.1587780838 0.3061854900 0.4118770472 -0.6752111337 0.529809087012 +1403715598262142976.0000000000 0.8916688862 -0.4832322772 2.1557689895 0.3102966658 0.4090101205 -0.6699717146 0.536250503234 +1403715598312143104.0000000000 0.9422117977 -0.5188139592 2.1495413042 0.3146272809 0.4052637923 -0.6644467471 0.543398061246 +1403715598362142976.0000000000 0.9897425537 -0.5525248424 2.1413250895 0.3205191135 0.4000095940 -0.6583742695 0.551183403126 +1403715598412143104.0000000000 1.0336653884 -0.5841124633 2.1334261944 0.3287777615 0.3923626293 -0.6505658641 0.560999828017 +1403715598462142976.0000000000 1.0724644948 -0.6131851030 2.1256654902 0.3363084557 0.3850816234 -0.6438904608 0.569222136345 +1403715598512143104.0000000000 1.1050992490 -0.6394385441 2.1181566438 0.3436075602 0.3778974738 -0.6385273957 0.575682298506 +1403715598562142976.0000000000 1.1310845748 -0.6629836133 2.1104735419 0.3482171925 0.3727128907 -0.6355265067 0.579599816388 +1403715598612143104.0000000000 1.1503409017 -0.6839065212 2.1021968826 0.3493423274 0.3703329779 -0.6346289307 0.581428881356 +1403715598662142976.0000000000 1.1630776898 -0.7021024556 2.0924610026 0.3449229989 0.3723496626 -0.6389483278 0.578038829205 +1403715598712143104.0000000000 1.1698913909 -0.7175066589 2.0817342334 0.3372318013 0.3768786366 -0.6461152678 0.571639979495 +1403715598762142976.0000000000 1.1713958352 -0.7303777771 2.0695525856 0.3280229710 0.3830967713 -0.6554855588 0.562117849279 +1403715598812143104.0000000000 1.1682290229 -0.7408162916 2.0562814103 0.3184097518 0.3896410012 -0.6652637645 0.551560734479 +1403715598862142976.0000000000 1.1614822757 -0.7494425771 2.0423264983 0.3101583721 0.3951966880 -0.6731629684 0.542653646462 +1403715598912143104.0000000000 1.1521653351 -0.7566261476 2.0273581326 0.3022951750 0.4004137832 -0.6794587979 0.535371059527 +1403715598962142976.0000000000 1.1412844699 -0.7627589562 2.0118105534 0.2965498194 0.4040204760 -0.6838504087 0.530258689878 +1403715599012143104.0000000000 1.1289210419 -0.7678165650 1.9952477179 0.2919255747 0.4071440249 -0.6867910595 0.526622485684 +1403715599062142976.0000000000 1.1158995764 -0.7718689500 1.9786474049 0.2898792876 0.4084292407 -0.6882602890 0.524836477968 +1403715599112143104.0000000000 1.1020969206 -0.7749698350 1.9613649551 0.2881856334 0.4095165760 -0.6881386218 0.525081376408 +1403715599162142976.0000000000 1.0875736978 -0.7769659985 1.9432165659 0.2884687153 0.4092314915 -0.6888381617 0.524230267731 +1403715599212143104.0000000000 1.0720062018 -0.7777793830 1.9239775523 0.2892441027 0.4088770889 -0.6921922618 0.519641460986 +1403715599262142976.0000000000 1.0555560484 -0.7775648581 1.9036334393 0.2903463865 0.4081852526 -0.6961533069 0.514251250599 +1403715599312143104.0000000000 1.0384958500 -0.7766739380 1.8825068985 0.2928255133 0.4065079018 -0.7004187803 0.508348381344 +1403715599362142976.0000000000 1.0207688361 -0.7756056815 1.8607157334 0.2966719671 0.4036428048 -0.7045201043 0.50270234999 +1403715599412143104.0000000000 1.0024265400 -0.7749357381 1.8386029974 0.3024042720 0.3994304515 -0.7078204513 0.497993151892 +1403715599462142976.0000000000 0.9835819203 -0.7750150281 1.8159491239 0.3088689723 0.3948541266 -0.7104943055 0.493850198471 +1403715599512143104.0000000000 0.9639373378 -0.7764155827 1.7933945571 0.3145771170 0.3905555864 -0.7119415673 0.491575809157 +1403715599562142976.0000000000 0.9430730830 -0.7794402021 1.7708241132 0.3189216807 0.3874907457 -0.7132046117 0.489365983122 +1403715599612143104.0000000000 0.9210049101 -0.7845417781 1.7493813355 0.3239861876 0.3837487759 -0.7126012267 0.489866633773 +1403715599662142976.0000000000 0.8972372328 -0.7917172111 1.7285255779 0.3291464539 0.3798051660 -0.7118795945 0.490548764847 +1403715599712143104.0000000000 0.8715396545 -0.8010670297 1.7076706355 0.3306068986 0.3785630587 -0.7090880134 0.494553615343 +1403715599762142976.0000000000 0.8438860223 -0.8119360767 1.6870932337 0.3305653015 0.3780699843 -0.7056627121 0.499829776221 +1403715599812143104.0000000000 0.8137915272 -0.8241651836 1.6661266943 0.3276520489 0.3795621559 -0.7022572738 0.505382455255 +1403715599862142976.0000000000 0.7811864171 -0.8375088826 1.6444221148 0.3207226866 0.3840075840 -0.6988213839 0.511198402971 +1403715599912143104.0000000000 0.7462602378 -0.8512862959 1.6221673599 0.3115770756 0.3901479170 -0.6980171728 0.513299479187 +1403715599962142976.0000000000 0.7095672945 -0.8652227343 1.5997186450 0.3019008926 0.3965790328 -0.6989885555 0.512831279363 +1403715600012143104.0000000000 0.6719072338 -0.8789895880 1.5774724711 0.2931938728 0.4021461345 -0.7000854271 0.512051007408 +1403715600062142976.0000000000 0.6337021364 -0.8923067876 1.5551776575 0.2841858102 0.4094267216 -0.6991685645 0.512612429851 +1403715600112143104.0000000000 0.5953717644 -0.9047140623 1.5329821156 0.2747046501 0.4193410650 -0.6953607144 0.514940679466 +1403715600162142976.0000000000 0.5572112552 -0.9154547613 1.5105866614 0.2651529139 0.4318124449 -0.6890211005 0.518152359541 +1403715600212143104.0000000000 0.5200980791 -0.9237273622 1.4881073655 0.2569354082 0.4457205872 -0.6811286834 0.520942483258 +1403715600262142976.0000000000 0.4845424321 -0.9289468158 1.4659503216 0.2524280931 0.4594749950 -0.6728731036 0.521923915117 +1403715600312143104.0000000000 0.4506389134 -0.9304135063 1.4442287928 0.2520208493 0.4727759190 -0.6648497504 0.520522075775 +1403715600362142976.0000000000 0.4181884615 -0.9278021074 1.4226129088 0.2538810686 0.4867255257 -0.6558529427 0.518169454071 +1403715600412143104.0000000000 0.3876728289 -0.9206842153 1.4014992460 0.2608800034 0.4989903435 -0.6493050482 0.511227166124 +1403715600462142976.0000000000 0.3586726886 -0.9094245762 1.3803622655 0.2689238136 0.5117482801 -0.6439261848 0.501151423089 +1403715600512143104.0000000000 0.3315711619 -0.8938632843 1.3599879976 0.2810028314 0.5227549177 -0.6425427958 0.484668402556 +1403715600562142976.0000000000 0.3064310917 -0.8751748758 1.3408343106 0.2952822100 0.5323841652 -0.6415207904 0.466718965223 +1403715600612143104.0000000000 0.2835491383 -0.8545983295 1.3224235571 0.3084754829 0.5429758672 -0.6384983505 0.449822120907 +1403715600662142976.0000000000 0.2633505521 -0.8327828067 1.3059708083 0.3208144139 0.5539219510 -0.6330238305 0.435349760536 +1403715600712143104.0000000000 0.2455641150 -0.8098516341 1.2926625144 0.3326542792 0.5652683491 -0.6244627144 0.424098034035 +1403715600762142976.0000000000 0.2302112071 -0.7862448012 1.2825835835 0.3441297072 0.5769460522 -0.6131518512 0.415635423019 +1403715600812143104.0000000000 0.2172108528 -0.7621277213 1.2755506119 0.3546814645 0.5884676610 -0.6018047335 0.407109240111 +1403715600862142976.0000000000 0.2066585374 -0.7374836018 1.2719143684 0.3642847632 0.6000550743 -0.5879336442 0.40195092868 +1403715600912143104.0000000000 0.1982316387 -0.7118713417 1.2718228209 0.3735517186 0.6105085428 -0.5757584838 0.3952728185 +1403715600962142976.0000000000 0.1923071701 -0.6856724900 1.2751743490 0.3816896432 0.6199428341 -0.5634690134 0.390495287636 +1403715601012143104.0000000000 0.1882329928 -0.6589527645 1.2813438983 0.3890936314 0.6277896035 -0.5524171555 0.386421591043 +1403715601062142976.0000000000 0.1866329435 -0.6314277391 1.2906277829 0.3966321368 0.6334508081 -0.5422039301 0.383976457455 +1403715601112143104.0000000000 0.1865749037 -0.6035083574 1.3025945150 0.4014619170 0.6386230424 -0.5340053999 0.381873240543 +1403715601162142976.0000000000 0.1876829682 -0.5751157263 1.3173388792 0.4045304369 0.6429248097 -0.5269243211 0.38125263867 +1403715601212143104.0000000000 0.1901840445 -0.5459256691 1.3354267475 0.4067361510 0.6460475933 -0.5207695544 0.382082820664 +1403715601262142976.0000000000 0.1936412559 -0.5157467288 1.3558617245 0.4072240727 0.6490020310 -0.5155586690 0.383619834337 +1403715601312143104.0000000000 0.1974994734 -0.4841704221 1.3775053733 0.4071035802 0.6518104584 -0.5104477615 0.385814572138 +1403715601362142976.0000000000 0.2017636128 -0.4509477183 1.3992753469 0.4071785432 0.6544523351 -0.5059514143 0.38718334339 +1403715601412143104.0000000000 0.2063333504 -0.4158612014 1.4206042232 0.4087016533 0.6554849215 -0.5037569472 0.386692919968 +1403715601462142976.0000000000 0.2110288314 -0.3792222303 1.4407980669 0.4106114631 0.6555813144 -0.5029994860 0.385490445518 +1403715601512143104.0000000000 0.2160062594 -0.3409847981 1.4599389743 0.4122489383 0.6553364222 -0.5033496426 0.383697959228 +1403715601562142976.0000000000 0.2215818011 -0.3013404491 1.4783964632 0.4146985326 0.6541707333 -0.5037215677 0.382557657119 +1403715601612143104.0000000000 0.2274066802 -0.2603282580 1.4961379860 0.4165657793 0.6530729087 -0.5048870681 0.380864511211 +1403715601662142976.0000000000 0.2335833951 -0.2181029933 1.5131641695 0.4180796440 0.6519824313 -0.5065841741 0.378814987997 +1403715601712143104.0000000000 0.2398822862 -0.1749021725 1.5303160709 0.4211990398 0.6497921977 -0.5072472029 0.378235037837 +1403715601762142976.0000000000 0.2465102672 -0.1309355265 1.5475820201 0.4252230218 0.6471308565 -0.5062412490 0.379640400993 +1403715601812143104.0000000000 0.2532072846 -0.0861475944 1.5640253988 0.4273602626 0.6454917575 -0.5057170777 0.380728031804 +1403715601862142976.0000000000 0.2597969025 -0.0407869768 1.5803329970 0.4300142058 0.6422223083 -0.5057863432 0.383168976567 +1403715601912143104.0000000000 0.2663446201 0.0048194793 1.5962428445 0.4322959591 0.6374489795 -0.5066565002 0.387399268401 +1403715601962142976.0000000000 0.2727269885 0.0505643973 1.6125233248 0.4362055829 0.6298947370 -0.5073845441 0.394358002619 +1403715602012143104.0000000000 0.2784556550 0.0964446282 1.6288060333 0.4424314515 0.6194496455 -0.5068189825 0.404562809025 +1403715602062142976.0000000000 0.2826511916 0.1423672317 1.6439259709 0.4474666031 0.6088286777 -0.5073885553 0.41431646627 +1403715602112143104.0000000000 0.2848402770 0.1880200202 1.6577721007 0.4512211757 0.5980393701 -0.5094570605 0.423322413674 +1403715602162142976.0000000000 0.2841858818 0.2332160928 1.6698420301 0.4521825888 0.5884252787 -0.5145718427 0.429537444782 +1403715602212143104.0000000000 0.2800514608 0.2779010035 1.6804680860 0.4499425556 0.5802412606 -0.5226776473 0.433220328714 +1403715602262142976.0000000000 0.2725447464 0.3218423983 1.6900185252 0.4469992992 0.5719605396 -0.5321752568 0.435708920893 +1403715602312143104.0000000000 0.2620748361 0.3647369170 1.6977808568 0.4397622286 0.5662952940 -0.5419842344 0.438374168884 +1403715602362142976.0000000000 0.2486409277 0.4070764113 1.7039495095 0.4280149341 0.5635146659 -0.5542575479 0.438238528757 +1403715602412143104.0000000000 0.2334439684 0.4488422450 1.7094190219 0.4148837313 0.5610371084 -0.5666666094 0.438175542826 +1403715602462142976.0000000000 0.2163891718 0.4900555563 1.7151231151 0.4024078255 0.5577052707 -0.5797625583 0.436930370854 +1403715602512143104.0000000000 0.1983923052 0.5307561175 1.7215472615 0.3905456821 0.5538819407 -0.5909383330 0.437585137512 +1403715602562142976.0000000000 0.1798043707 0.5710452443 1.7276118920 0.3797342844 0.5491459716 -0.6012762792 0.438984522638 +1403715602612143104.0000000000 0.1611620576 0.6107664506 1.7318767636 0.3696001309 0.5434841292 -0.6091887318 0.443745235013 +1403715602662142976.0000000000 0.1425118351 0.6498197847 1.7339372667 0.3592764104 0.5372978653 -0.6148271224 0.451906045949 +1403715602712143104.0000000000 0.1239973286 0.6890674379 1.7332843618 0.3505529866 0.5295487016 -0.6214432244 0.458801803709 +1403715602762142976.0000000000 0.1053359254 0.7285072129 1.7283766303 0.3406230491 0.5224489752 -0.6288152689 0.464342938279 +1403715602812143104.0000000000 0.0871241788 0.7686804344 1.7191839944 0.3311426843 0.5151054333 -0.6365657049 0.468823014095 +1403715602862142976.0000000000 0.0696102315 0.8095751925 1.7076133150 0.3243004917 0.5060116012 -0.6447246946 0.472346820326 +1403715602912143104.0000000000 0.0522880799 0.8509334440 1.6926888667 0.3167267613 0.4977176744 -0.6525967384 0.47547741506 +1403715602962142976.0000000000 0.0354263818 0.8925690184 1.6744382853 0.3083356172 0.4901433989 -0.6605210933 0.477912629052 +1403715603012143104.0000000000 0.0198166952 0.9347304145 1.6539895581 0.3015091742 0.4814874112 -0.6672599190 0.481691074491 +1403715603062142976.0000000000 0.0050034765 0.9773769082 1.6319327865 0.2955614423 0.4720952100 -0.6730637877 0.486574438536 +1403715603112143104.0000000000 -0.0090811536 1.0203700442 1.6096268758 0.2903146995 0.4617345247 -0.6788037578 0.491674752589 +1403715603162142976.0000000000 -0.0228456254 1.0636130000 1.5867023937 0.2826429108 0.4529143927 -0.6852816398 0.495348980042 +1403715603212143104.0000000000 -0.0359870727 1.1073483378 1.5642925071 0.2760627332 0.4439265949 -0.6919744580 0.497885423703 +1403715603262142976.0000000000 -0.0486244784 1.1516173885 1.5415020093 0.2679103595 0.4364068634 -0.6997495244 0.498120158163 +1403715603312143104.0000000000 -0.0600886407 1.1962858076 1.5192346012 0.2601099667 0.4301338428 -0.7061709126 0.498648498162 +1403715603362142976.0000000000 -0.0703435311 1.2414653706 1.4975023827 0.2539673241 0.4242905387 -0.7123319322 0.498057582462 +1403715603412143104.0000000000 -0.0789475490 1.2870930054 1.4775157506 0.2510723983 0.4176932253 -0.7171887464 0.498131832291 +1403715603462142976.0000000000 -0.0857882941 1.3330203622 1.4591560584 0.2511990310 0.4105733006 -0.7209402810 0.49857168283 +1403715603512143104.0000000000 -0.0911052053 1.3789501001 1.4421478754 0.2532213365 0.4031897284 -0.7247516755 0.498048196993 +1403715603562142976.0000000000 -0.0956838512 1.4246169447 1.4262945201 0.2562610946 0.3960552084 -0.7285930164 0.496611256191 +1403715603612143104.0000000000 -0.0992218097 1.4694046013 1.4114276138 0.2595885894 0.3894770469 -0.7321768261 0.494811569683 +1403715603662142976.0000000000 -0.1021043137 1.5132774263 1.3973017920 0.2652363036 0.3814017447 -0.7366959251 0.491387348492 +1403715603712143104.0000000000 -0.1043246438 1.5551141520 1.3838103790 0.2701987850 0.3744459252 -0.7390226523 0.490538872062 +1403715603762142976.0000000000 -0.1063558079 1.5950038979 1.3720024641 0.2760179482 0.3675293061 -0.7407834079 0.489873702066 +1403715603812143104.0000000000 -0.1088196642 1.6325740691 1.3628314775 0.2811980036 0.3618964817 -0.7419040841 0.48942512122 +1403715603862142976.0000000000 -0.1123322201 1.6675483268 1.3564801088 0.2847181169 0.3580883547 -0.7449361672 0.485570212114 +1403715603912143104.0000000000 -0.1171090099 1.7000420063 1.3519446687 0.2840606721 0.3581843109 -0.7511403086 0.476237095171 +1403715603962142976.0000000000 -0.1221513968 1.7289744596 1.3499067807 0.2819247859 0.3594261318 -0.7568301538 0.467481966698 +1403715604012143104.0000000000 -0.1269538436 1.7540105375 1.3486936166 0.2770340679 0.3632786719 -0.7611421279 0.460373101878 +1403715604062142976.0000000000 -0.1312749382 1.7748742134 1.3479271118 0.2688241510 0.3695645519 -0.7610851116 0.460331479246 +1403715604112143104.0000000000 -0.1346307783 1.7922846553 1.3471972887 0.2603993218 0.3759582451 -0.7584227386 0.464373277391 +1403715604162142976.0000000000 -0.1366724973 1.8069632249 1.3457402914 0.2538832258 0.3807675957 -0.7547212268 0.470058736267 +1403715604212143104.0000000000 -0.1372055789 1.8193443508 1.3440573751 0.2493255085 0.3840548726 -0.7502221535 0.476975225726 +1403715604262142976.0000000000 -0.1361506729 1.8301071279 1.3420582452 0.2469856179 0.3857375175 -0.7462214056 0.483071719309 +1403715604312143104.0000000000 -0.1338478907 1.8396778140 1.3392959929 0.2454946509 0.3868757934 -0.7434224647 0.487219186648 +1403715604362142976.0000000000 -0.1303525434 1.8483043081 1.3352658674 0.2441231783 0.3877100876 -0.7421561909 0.489171698043 +1403715604412143104.0000000000 -0.1255365896 1.8561423221 1.3308608871 0.2430172912 0.3882735912 -0.7422772279 0.489091741427 +1403715604462142976.0000000000 -0.1189885670 1.8631139461 1.3264322609 0.2420464011 0.3887650800 -0.7419130439 0.489734915628 +1403715604512143104.0000000000 -0.1109665134 1.8694403171 1.3223719552 0.2436313473 0.3875850589 -0.7401874238 0.492487732143 +1403715604562142976.0000000000 -0.1017088247 1.8749201432 1.3181846737 0.2457196784 0.3861409307 -0.7368884625 0.497506196041 +1403715604612143104.0000000000 -0.0913716390 1.8797789026 1.3139779728 0.2485226130 0.3842678162 -0.7333871380 0.502710714157 +1403715604662142976.0000000000 -0.0804399692 1.8842178337 1.3096416663 0.2494477420 0.3834658231 -0.7299800962 0.50779803633 +1403715604712143104.0000000000 -0.0689698980 1.8887574608 1.3049031417 0.2501007051 0.3826946838 -0.7280124910 0.510873985647 +1403715604762142976.0000000000 -0.0573874258 1.8934613307 1.2999903487 0.2495439693 0.3830875592 -0.7263751284 0.513177261977 +1403715604812143104.0000000000 -0.0453889869 1.8986460280 1.2952234372 0.2495574781 0.3829447225 -0.7264366854 0.513190166205 +1403715604862142976.0000000000 -0.0329812655 1.9040646461 1.2907445972 0.2498119068 0.3828142632 -0.7265085594 0.513061949722 +1403715604912143104.0000000000 -0.0203749253 1.9095196539 1.2869045529 0.2489935295 0.3836287839 -0.7260900269 0.513443717733 +1403715604962142976.0000000000 -0.0078851862 1.9152451905 1.2830112369 0.2475299440 0.3848901887 -0.7269682755 0.511962494586 +1403715605012143104.0000000000 0.0047814601 1.9212546790 1.2795006983 0.2467867127 0.3858415232 -0.7282829783 0.509731832289 +1403715605062142976.0000000000 0.0182875410 1.9270713869 1.2770602741 0.2467865873 0.3861985561 -0.7286098783 0.508993812242 +1403715605112143104.0000000000 0.0327455255 1.9327767792 1.2757868648 0.2474150236 0.3862207855 -0.7281627517 0.509311611867 +1403715605162142976.0000000000 0.0476062925 1.9385462909 1.2754325122 0.2482535762 0.3866374180 -0.7266567788 0.510736326065 +1403715605212143104.0000000000 0.0630918573 1.9442792279 1.2753661345 0.2496631245 0.3866449703 -0.7254992726 0.51168818301 +1403715605262142976.0000000000 0.0791474052 1.9500835469 1.2761698710 0.2521062922 0.3860180524 -0.7249242620 0.511778560457 +1403715605312143104.0000000000 0.0956397483 1.9560022927 1.2778934271 0.2556396781 0.3847870015 -0.7245450775 0.511489735055 +1403715605362142976.0000000000 0.1122093542 1.9619114549 1.2794732039 0.2603093459 0.3827020164 -0.7246637053 0.510529847615 +1403715605412143104.0000000000 0.1286294390 1.9675324879 1.2795368153 0.2643931421 0.3811949130 -0.7244351958 0.509882684353 +1403715605462142976.0000000000 0.1447334335 1.9724888675 1.2767598615 0.2666009366 0.3809009639 -0.7251054269 0.507996571069 +1403715605512143104.0000000000 0.1605929549 1.9770482437 1.2717339424 0.2689502762 0.3804065643 -0.7262721830 0.505455548001 +1403715605562142976.0000000000 0.1760071238 1.9812352293 1.2639821443 0.2700990872 0.3806181227 -0.7280686350 0.502088030593 +1403715605612143104.0000000000 0.1910700114 1.9848307544 1.2540438130 0.2715423156 0.3805424560 -0.7292605381 0.499631141576 +1403715605662142976.0000000000 0.2058298350 1.9874628094 1.2428486594 0.2714604193 0.3814945873 -0.7288184251 0.499594659506 +1403715605712143104.0000000000 0.2201844422 1.9889381219 1.2310686715 0.2688166364 0.3840144062 -0.7270226287 0.501705739679 +1403715605762142976.0000000000 0.2346387206 1.9893534708 1.2204644358 0.2659031541 0.3863988534 -0.7241577851 0.505556071097 +1403715605812143104.0000000000 0.2489198156 1.9893562619 1.2104361475 0.2632947849 0.3885832166 -0.7225100388 0.507600417519 +1403715605862142976.0000000000 0.2632860443 1.9891240118 1.2014048522 0.2618611058 0.3899629849 -0.7210924349 0.5092968997 +1403715605912143104.0000000000 0.2779486171 1.9888266667 1.1935950602 0.2610952184 0.3911266315 -0.7197466346 0.51069954677 +1403715605962142976.0000000000 0.2927172757 1.9886102037 1.1857861335 0.2607911917 0.3918575889 -0.7179925209 0.512759518954 +1403715606012143104.0000000000 0.3074396501 1.9886585378 1.1766839425 0.2606919264 0.3924559791 -0.7169965984 0.513744977468 +1403715606062142976.0000000000 0.3221370666 1.9888122798 1.1654976090 0.2608700132 0.3930783415 -0.7160632786 0.514479965338 +1403715606112143104.0000000000 0.3369311291 1.9892778424 1.1531048964 0.2609402639 0.3941658441 -0.7149697662 0.515132700817 +1403715606162142976.0000000000 0.3518323591 1.9904462174 1.1393452233 0.2619048518 0.3945619929 -0.7147427084 0.514654780555 +1403715606212143104.0000000000 0.3669516782 1.9921010981 1.1248348465 0.2625313661 0.3948702645 -0.7149801092 0.513768624434 +1403715606262142976.0000000000 0.3820740171 1.9946730256 1.1119247832 0.2661166246 0.3933206165 -0.7158059521 0.511959640652 +1403715606312143104.0000000000 0.3972271920 1.9975565450 1.1007967939 0.2694759234 0.3923402468 -0.7166005351 0.509838729926 +1403715606362142976.0000000000 0.4123507156 2.0002233634 1.0923378946 0.2721676046 0.3915857046 -0.7173543112 0.50792541098 +1403715606412143104.0000000000 0.4273251064 2.0024849932 1.0864211378 0.2746830083 0.3908621203 -0.7181556785 0.50599255852 +1403715606462142976.0000000000 0.4420237129 2.0040988210 1.0831708256 0.2765638480 0.3904480887 -0.7176934130 0.505943566896 +1403715606512143104.0000000000 0.4565538571 2.0055308945 1.0820592148 0.2789997137 0.3898574530 -0.7169280375 0.506146732821 +1403715606562142976.0000000000 0.4705272905 2.0068402455 1.0814077394 0.2817883368 0.3893333839 -0.7169606552 0.504957689547 +1403715606612143104.0000000000 0.4837031210 2.0078504223 1.0803090927 0.2850484951 0.3886435007 -0.7166471048 0.504103671876 +1403715606662142976.0000000000 0.4960175858 2.0085184446 1.0784248528 0.2882314338 0.3880104287 -0.7164438044 0.503069401712 +1403715606712143104.0000000000 0.5077338644 2.0087868933 1.0757712802 0.2925505462 0.3864348056 -0.7166314348 0.501519397042 +1403715606762142976.0000000000 0.5186120474 2.0082750188 1.0717511388 0.2964931214 0.3849725949 -0.7167351530 0.500178618714 +1403715606812143104.0000000000 0.5284303602 2.0065289387 1.0666819441 0.3002711838 0.3835888264 -0.7155135482 0.500736648126 +1403715606862142976.0000000000 0.5370228483 2.0035625332 1.0605209565 0.3010857419 0.3839898682 -0.7122986882 0.504509401304 +1403715606912143104.0000000000 0.5444484441 1.9997994923 1.0539290244 0.3003454862 0.3852523292 -0.7084100524 0.509439328572 +1403715606962142976.0000000000 0.5503361668 1.9956488252 1.0468105755 0.2970125826 0.3883422791 -0.7039980919 0.515131523613 +1403715607012143104.0000000000 0.5544954375 1.9917651305 1.0387880173 0.2920432428 0.3924436748 -0.7024165001 0.517020083527 +1403715607062142976.0000000000 0.5574570863 1.9881823795 1.0303966992 0.2861102802 0.3969322940 -0.7014934404 0.518162729888 +1403715607112143104.0000000000 0.5596456392 1.9853905723 1.0221107697 0.2820130919 0.4004752394 -0.7014736744 0.517709264743 +1403715607162142976.0000000000 0.5613958304 1.9834605151 1.0143849676 0.2792719569 0.4030118277 -0.7015186419 0.517165578785 +1403715607212143104.0000000000 0.5630697526 1.9822941532 1.0068538126 0.2769366166 0.4051934300 -0.7021122638 0.515909646876 +1403715607262142976.0000000000 0.5643627142 1.9819443106 1.0003151365 0.2755929101 0.4061751387 -0.7026480109 0.515127243964 +1403715607312143104.0000000000 0.5651728299 1.9825121670 0.9942440118 0.2749381154 0.4068485354 -0.7030772187 0.514359530378 +1403715607362142976.0000000000 0.5658120319 1.9837337829 0.9891732707 0.2755438965 0.4064175266 -0.7028351995 0.514706749007 +1403715607412143104.0000000000 0.5659929809 1.9853350919 0.9849551165 0.2758300666 0.4060883934 -0.7024408472 0.515351188301 +1403715607462142976.0000000000 0.5657956109 1.9874878026 0.9813250041 0.2752269082 0.4061365907 -0.7018979756 0.516374331766 +1403715607512143104.0000000000 0.5654009548 1.9906606271 0.9779804633 0.2742414869 0.4063018912 -0.7026100769 0.515799825541 +1403715607562142976.0000000000 0.5646257113 1.9945466551 0.9752704036 0.2732734489 0.4064432759 -0.7028551179 0.515868363897 +1403715607612143104.0000000000 0.5639915368 1.9991765093 0.9733432427 0.2727897736 0.4059345360 -0.7035635088 0.515559192525 +1403715607662142976.0000000000 0.5632195131 2.0047194674 0.9717526629 0.2715384785 0.4058872194 -0.7043091917 0.515238762481 +1403715607712143104.0000000000 0.5626248993 2.0109467851 0.9706031932 0.2709425736 0.4055063090 -0.7041033643 0.516132935965 +1403715607762142976.0000000000 0.5618233403 2.0179463337 0.9681125656 0.2704800548 0.4051643993 -0.7047980364 0.515695721751 +1403715607812143104.0000000000 0.5608568178 2.0256102488 0.9635343519 0.2708814701 0.4039882855 -0.7059618460 0.51481507973 +1403715607862142976.0000000000 0.5598867042 2.0339958115 0.9565432984 0.2727739377 0.4018563377 -0.7079360089 0.512769412079 +1403715607912143104.0000000000 0.5590622838 2.0422467871 0.9472073460 0.2694384524 0.4071204150 -0.7058459697 0.513261488009 +1403715607962142976.0000000000 0.5596338691 2.0439254024 0.9477060443 0.2688357922 0.4085136820 -0.7019484097 0.517795634019 +1403715608012143104.0000000000 0.5590484855 2.0429628807 0.9494267197 0.2670351993 0.4108184428 -0.7032913543 0.515074441522 +1403715608062142976.0000000000 0.5587629369 2.0421894562 0.9482984544 0.2672347460 0.4109289345 -0.7028198412 0.515526208915 +1403715608112143104.0000000000 0.5589711701 2.0413735694 0.9463637460 0.2670653865 0.4111020540 -0.7045260009 0.513141593097 +1403715608162142976.0000000000 0.5597089873 2.0418331409 0.9466529061 0.2667656099 0.4109531860 -0.7054506425 0.512145466953 +1403715608212143104.0000000000 0.5589873920 2.0422244569 0.9467963936 0.2668508699 0.4111661053 -0.7042440546 0.513588705708 +1403715608262142976.0000000000 0.5583777028 2.0419208637 0.9464710038 0.2682674026 0.4100606914 -0.7037324006 0.514435164413 +1403715608312143104.0000000000 0.5590750807 2.0421390938 0.9463176611 0.2673374667 0.4106820725 -0.7045864964 0.513253137589 +1403715608362142976.0000000000 0.5592549281 2.0418605204 0.9462958898 0.2676208936 0.4104798820 -0.7049851501 0.512719476748 +1403715608412143104.0000000000 0.5590228165 2.0415835522 0.9463971774 0.2674963781 0.4105464777 -0.7044559700 0.513457947289 diff --git a/data/euroc_groundtruth/V1_03_difficult.txt b/data/euroc_groundtruth/V1_03_difficult.txt new file mode 100755 index 00000000..34cd1154 --- /dev/null +++ b/data/euroc_groundtruth/V1_03_difficult.txt @@ -0,0 +1,2095 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1403715888384058112.0000000000 0.9080302787 2.0913569065 0.9301217440 0.3470018900 0.5477973657 -0.6209279080 0.440404663327 +1403715888434057984.0000000000 0.9082768931 2.0908487500 0.9298010705 0.3469776734 0.5477940397 -0.6209674630 0.440372108768 +1403715888484058112.0000000000 0.9084458504 2.0904659551 0.9295440871 0.3469659421 0.5478223888 -0.6209793275 0.440329354224 +1403715888534057984.0000000000 0.9085648834 2.0902215552 0.9293704457 0.3470085602 0.5478222586 -0.6209905191 0.440280146339 +1403715888584058112.0000000000 0.9086428495 2.0900649758 0.9292402184 0.3469500113 0.5478489412 -0.6210240493 0.440245792112 +1403715888634057984.0000000000 0.9086788275 2.0899940660 0.9291810783 0.3469458419 0.5478257090 -0.6210598133 0.440227536298 +1403715888684058112.0000000000 0.9086778239 2.0899783264 0.9291674663 0.3469134261 0.5478480225 -0.6210671578 0.440214952595 +1403715888734057984.0000000000 0.9086430992 2.0899988765 0.9291711056 0.3469313334 0.5478433892 -0.6210905336 0.440173624684 +1403715888784058112.0000000000 0.9085780048 2.0900376953 0.9291776708 0.3469018898 0.5478820151 -0.6210927534 0.440145621328 +1403715888834057984.0000000000 0.9085268865 2.0900926152 0.9291975119 0.3468845792 0.5478879687 -0.6211204233 0.440112806254 +1403715888884058112.0000000000 0.9085014326 2.0901411911 0.9291929812 0.3468663041 0.5479041852 -0.6211372301 0.440083301487 +1403715888934057984.0000000000 0.9084830189 2.0901784731 0.9292156044 0.3468657774 0.5479071089 -0.6211552739 0.440054608173 +1403715888984058112.0000000000 0.9084416752 2.0901902621 0.9292354240 0.3468533268 0.5479078718 -0.6211793745 0.440029451779 +1403715889034057984.0000000000 0.9084135359 2.0902050476 0.9292465834 0.3468231604 0.5479328765 -0.6211754918 0.440027574788 +1403715889084058112.0000000000 0.9084129812 2.0902437604 0.9292576563 0.3467947446 0.5479431151 -0.6211934071 0.44001193031 +1403715889134057984.0000000000 0.9084189684 2.0902615521 0.9292627463 0.3467623155 0.5479566277 -0.6212144755 0.439990915961 +1403715889184058112.0000000000 0.9084179120 2.0902798477 0.9292838453 0.3467734600 0.5479471530 -0.6212137467 0.439994961133 +1403715889234057984.0000000000 0.9084272970 2.0902796382 0.9292686118 0.3467246014 0.5479660217 -0.6212329005 0.439982923735 +1403715889284058112.0000000000 0.9084126360 2.0902873498 0.9292506407 0.3467004284 0.5479761318 -0.6212465636 0.439970088884 +1403715889334057984.0000000000 0.9083940374 2.0902986636 0.9292176270 0.3466993852 0.5480038929 -0.6212344166 0.439953485461 +1403715889384058112.0000000000 0.9083699500 2.0902892640 0.9292208258 0.3466823743 0.5480221941 -0.6212338236 0.439944931256 +1403715889434057984.0000000000 0.9083681957 2.0902539110 0.9292301297 0.3466589454 0.5480062291 -0.6212474893 0.43996398205 +1403715889484058112.0000000000 0.9083763756 2.0902451084 0.9292244666 0.3466613595 0.5479910598 -0.6212578298 0.439966372756 +1403715889534057984.0000000000 0.9083955869 2.0902757143 0.9292294379 0.3466726015 0.5479783981 -0.6212637594 0.439964912048 +1403715889584058112.0000000000 0.9083956680 2.0903121671 0.9292273365 0.3466571080 0.5479960521 -0.6212598091 0.439960709688 +1403715889634057984.0000000000 0.9084120504 2.0903374000 0.9292402831 0.3466685944 0.5480029991 -0.6212471687 0.439960855163 +1403715889684058112.0000000000 0.9084281375 2.0903407436 0.9292574707 0.3466502498 0.5479963964 -0.6212601465 0.439965207933 +1403715889734057984.0000000000 0.9083594465 2.0904471481 0.9292774502 0.3467754528 0.5480761031 -0.6212085397 0.439840108179 +1403715889784058112.0000000000 0.9082989093 2.0904168633 0.9292679480 0.3466873493 0.5480390664 -0.6213025408 0.439822937408 +1403715889834057984.0000000000 0.9082771658 2.0903808756 0.9293224840 0.3467336097 0.5479040283 -0.6212371829 0.440046977464 +1403715889884058112.0000000000 0.9082678075 2.0903636617 0.9293252771 0.3467811935 0.5478319110 -0.6212624967 0.440063530972 +1403715889934057984.0000000000 0.9083292973 2.0903213918 0.9293291141 0.3466860019 0.5476284580 -0.6213810527 0.440224346699 +1403715889984058112.0000000000 0.9083398576 2.0902702735 0.9293350593 0.3465740978 0.5476023666 -0.6214494681 0.440248340637 +1403715890034057984.0000000000 0.9083593596 2.0902520282 0.9293703648 0.3466231499 0.5475735153 -0.6215507200 0.440102646827 +1403715890084058112.0000000000 0.9083582794 2.0901820451 0.9293660618 0.3466305782 0.5476421390 -0.6214989351 0.440084541449 +1403715890134057984.0000000000 0.9083645147 2.0901224339 0.9293883854 0.3466708676 0.5475345340 -0.6216395339 0.439988106183 +1403715890184058112.0000000000 0.9083475777 2.0900749611 0.9294002145 0.3467105793 0.5476744329 -0.6215012760 0.439978014991 +1403715890234057984.0000000000 0.9083526610 2.0900477047 0.9293814480 0.3466719844 0.5476571935 -0.6214873146 0.440049601107 +1403715890284058112.0000000000 0.9083610857 2.0900757981 0.9293607969 0.3465799106 0.5477060553 -0.6216414136 0.439843603317 +1403715890334057984.0000000000 0.9083498348 2.0901235399 0.9293455502 0.3465488135 0.5478950023 -0.6215164522 0.439809374561 +1403715890384058112.0000000000 0.9083812896 2.0901576958 0.9293560273 0.3466695750 0.5478320224 -0.6215730589 0.439712648754 +1403715890434057984.0000000000 0.9084198409 2.0901995411 0.9292838525 0.3465330823 0.5480304361 -0.6215657604 0.439583290772 +1403715890484058112.0000000000 0.9084151660 2.0902734540 0.9292821109 0.3465990589 0.5481142257 -0.6214735372 0.43955719822 +1403715890534057984.0000000000 0.9084289274 2.0903358353 0.9292758274 0.3465110227 0.5480232196 -0.6215670306 0.439607880132 +1403715890584058112.0000000000 0.9084540429 2.0903822396 0.9292848382 0.3462889287 0.5480878426 -0.6216358142 0.439605060424 +1403715890634057984.0000000000 0.9084492405 2.0904005308 0.9292578381 0.3461453677 0.5482198369 -0.6215192386 0.439718354174 +1403715890684058112.0000000000 0.9084246487 2.0904927923 0.9292554171 0.3462684790 0.5480886109 -0.6215133319 0.439793353046 +1403715890734057984.0000000000 0.9083966904 2.0905919419 0.9292560156 0.3461511125 0.5483135239 -0.6213835680 0.439788754082 +1403715890784058112.0000000000 0.9084006619 2.0906935271 0.9292885164 0.3461800530 0.5483591247 -0.6213637663 0.43973709316 +1403715890834057984.0000000000 0.9084217461 2.0906836998 0.9293678865 0.3462488654 0.5482991528 -0.6212598248 0.439904526437 +1403715890884058112.0000000000 0.9084527177 2.0906308249 0.9293985113 0.3462614733 0.5482364059 -0.6212592685 0.439973586205 +1403715890934057984.0000000000 0.9084913506 2.0905631426 0.9293833653 0.3462656890 0.5481795067 -0.6213569636 0.439903199522 +1403715890984058112.0000000000 0.9084454739 2.0904929094 0.9293760381 0.3462608651 0.5482013181 -0.6212989483 0.439961754001 +1403715891034057984.0000000000 0.9084201750 2.0904111995 0.9293663564 0.3462797177 0.5481540709 -0.6213147275 0.439983501004 +1403715891084058112.0000000000 0.9084082104 2.0903417346 0.9293188360 0.3462625511 0.5481435211 -0.6213017587 0.440028465688 +1403715891134057984.0000000000 0.9083953462 2.0903248551 0.9292844303 0.3463370063 0.5481769355 -0.6213120945 0.439913635503 +1403715891184058112.0000000000 0.9083900031 2.0903248643 0.9292765451 0.3462914757 0.5481340262 -0.6212955850 0.440026248341 +1403715891234057984.0000000000 0.9084161259 2.0903420591 0.9292525434 0.3463159597 0.5481450436 -0.6213118523 0.43997028239 +1403715891284058112.0000000000 0.9084444677 2.0903453368 0.9292073619 0.3462974051 0.5481671272 -0.6213508076 0.439902354797 +1403715891334057984.0000000000 0.9083868607 2.0903312127 0.9291765401 0.3463277017 0.5481216335 -0.6213475948 0.439939728078 +1403715891384058112.0000000000 0.9083496314 2.0903567788 0.9291677111 0.3463188764 0.5481109736 -0.6213871031 0.439904153817 +1403715891434057984.0000000000 0.9083374548 2.0903801998 0.9291499630 0.3462763336 0.5481181553 -0.6213715958 0.439950597857 +1403715891484058112.0000000000 0.9083121604 2.0903990639 0.9291054848 0.3462572616 0.5481763492 -0.6213663667 0.439900485586 +1403715891534057984.0000000000 0.9082830921 2.0904379556 0.9291328856 0.3462890533 0.5481791993 -0.6213457242 0.439901066242 +1403715891584058112.0000000000 0.9082760905 2.0904549003 0.9292108297 0.3463895704 0.5480704860 -0.6213584558 0.439939401801 +1403715891634057984.0000000000 0.9082991422 2.0904643102 0.9292501690 0.3463517847 0.5480674371 -0.6213898803 0.439928564936 +1403715891684058112.0000000000 0.9083043108 2.0904897693 0.9292921179 0.3463785238 0.5480986322 -0.6213645898 0.439904369342 +1403715891734057984.0000000000 0.9083162130 2.0905061043 0.9293395507 0.3463985820 0.5480922389 -0.6213987525 0.439848281159 +1403715891784058112.0000000000 0.9083645191 2.0904978008 0.9293884537 0.3464620167 0.5479929020 -0.6214091283 0.439907428367 +1403715891834057984.0000000000 0.9083397915 2.0905179075 0.9295847475 0.3467854544 0.5477747888 -0.6212534643 0.440144024696 +1403715891884058112.0000000000 0.9083261133 2.0904648723 0.9295229803 0.3466276190 0.5479070494 -0.6212975239 0.44004152727 +1403715891934057984.0000000000 0.9084138956 2.0905486842 0.9293884212 0.3465772798 0.5479454559 -0.6214570616 0.439808011633 +1403715891984058112.0000000000 0.9084037671 2.0905330971 0.9293685871 0.3464210351 0.5479676815 -0.6214261969 0.439947006256 +1403715892034057984.0000000000 0.9083427488 2.0906219179 0.9294112936 0.3465850884 0.5479454533 -0.6214073013 0.439872166148 +1403715892084058112.0000000000 0.9083403264 2.0906877556 0.9293631307 0.3464709540 0.5479815703 -0.6214218147 0.439896584279 +1403715892134057984.0000000000 0.9082927684 2.0907287686 0.9293749674 0.3465014643 0.5479317466 -0.6215139734 0.439804407871 +1403715892184058112.0000000000 0.9080546004 2.0908258380 0.9297590810 0.3470821495 0.5475410267 -0.6213897326 0.440008642776 +1403715892234057984.0000000000 0.9079516170 2.0907454343 0.9299156920 0.3465591802 0.5478414264 -0.6213878043 0.440049659557 +1403715892284058112.0000000000 0.9081241397 2.0906565183 0.9298480849 0.3466034824 0.5476488886 -0.6216200274 0.439926428294 +1403715892334057984.0000000000 0.9081912143 2.0905067821 0.9297409405 0.3467656738 0.5476417651 -0.6215242939 0.439942742496 +1403715892384058112.0000000000 0.9083121348 2.0904555729 0.9298314899 0.3467165670 0.5476586259 -0.6216812025 0.439738711207 +1403715892434057984.0000000000 0.9083121265 2.0903011417 0.9298891861 0.3466750404 0.5476909941 -0.6215445660 0.439924247859 +1403715892484058112.0000000000 0.9084163761 2.0902366391 0.9298584288 0.3465984344 0.5477220203 -0.6216249657 0.439832372352 +1403715892534057984.0000000000 0.9083633750 2.0902306060 0.9301209556 0.3466596128 0.5476948872 -0.6215496181 0.439924420346 +1403715892584058112.0000000000 0.9082539388 2.0902864164 0.9304066773 0.3468775174 0.5475402223 -0.6215162625 0.439992304847 +1403715892634057984.0000000000 0.9081814437 2.0904211966 0.9303100765 0.3469274413 0.5475285230 -0.6215303184 0.439947645059 +1403715892684058112.0000000000 0.9081549394 2.0904847067 0.9303230929 0.3470036616 0.5474561039 -0.6216135195 0.439860097674 +1403715892734057984.0000000000 0.9082221759 2.0905521898 0.9306371712 0.3471388883 0.5474140490 -0.6215105443 0.4399512411 +1403715892784058112.0000000000 0.9084418898 2.0906235508 0.9307141032 0.3474058763 0.5472857295 -0.6214336223 0.440008795983 +1403715892834057984.0000000000 0.9087761149 2.0907221945 0.9305137728 0.3476079456 0.5471619199 -0.6213937759 0.440059456042 +1403715892884058112.0000000000 0.9090316080 2.0907853155 0.9306419994 0.3475329952 0.5471531161 -0.6215991446 0.43983950282 +1403715892934057984.0000000000 0.9089788964 2.0907483788 0.9308118686 0.3476135626 0.5470514291 -0.6216903908 0.439773354126 +1403715892984058112.0000000000 0.9087766252 2.0906691536 0.9310771633 0.3477262682 0.5470033712 -0.6213754695 0.4401889142 +1403715893034057984.0000000000 0.9086367800 2.0905954965 0.9313632205 0.3479897673 0.5468563227 -0.6214658735 0.440035739805 +1403715893084058112.0000000000 0.9084166774 2.0903981620 0.9318647108 0.3484289094 0.5465151863 -0.6215541045 0.439987433184 +1403715893134057984.0000000000 0.9082848912 2.0903825326 0.9322114962 0.3486875625 0.5462305388 -0.6215722548 0.440110343286 +1403715893184058112.0000000000 0.9080742191 2.0903422734 0.9322257435 0.3493856868 0.5458203359 -0.6212280703 0.440551344892 +1403715893234057984.0000000000 0.9078059825 2.0902236683 0.9321619156 0.3497679959 0.5455585230 -0.6210433859 0.440832575855 +1403715893284058112.0000000000 0.9077738662 2.0902508173 0.9322918540 0.3500749601 0.5454996832 -0.6209682061 0.440767631488 +1403715893334057984.0000000000 0.9076033780 2.0903059185 0.9324534633 0.3507969122 0.5449860246 -0.6206855448 0.441226941541 +1403715893384058112.0000000000 0.9074065015 2.0904118595 0.9325677879 0.3510665442 0.5448198385 -0.6205308729 0.441435228437 +1403715893434057984.0000000000 0.9073682453 2.0905580263 0.9336357726 0.3521719894 0.5441750331 -0.6201221239 0.441924172912 +1403715893484058112.0000000000 0.9071529488 2.0910095944 0.9369885813 0.3570121702 0.5418830793 -0.6174297265 0.444618456033 +1403715893534057984.0000000000 0.9070420524 2.0922856531 0.9415959665 0.3642218583 0.5382294982 -0.6137640235 0.44826908059 +1403715893584058112.0000000000 0.9074599602 2.0940546773 0.9471786137 0.3706043844 0.5345865730 -0.6106094170 0.451692070024 +1403715893634057984.0000000000 0.9073202222 2.0967926211 0.9535188349 0.3769081957 0.5306159480 -0.6085305997 0.453957527619 +1403715893684058112.0000000000 0.9062582353 2.1000662087 0.9595423836 0.3803633619 0.5288933618 -0.6077483891 0.454133703131 +1403715893734057984.0000000000 0.9046692845 2.1033181376 0.9663484683 0.3824553687 0.5276874265 -0.6082188031 0.453148715556 +1403715893784058112.0000000000 0.9021175377 2.1067930963 0.9736088221 0.3820666397 0.5279376076 -0.6087637152 0.452452985828 +1403715893834057984.0000000000 0.8988790204 2.1107922270 0.9806446072 0.3784291217 0.5306582620 -0.6097738341 0.450964610534 +1403715893884058112.0000000000 0.8948999103 2.1151410054 0.9880006383 0.3748375241 0.5329242517 -0.6128535727 0.447100738989 +1403715893934057984.0000000000 0.8906275008 2.1199294465 0.9965879007 0.3727350808 0.5341438518 -0.6148470890 0.444659377785 +1403715893984058112.0000000000 0.8858677256 2.1251728621 1.0051518638 0.3691439682 0.5363270949 -0.6176439568 0.441137076956 +1403715894034057984.0000000000 0.8810409516 2.1306964530 1.0139516747 0.3649525735 0.5387287215 -0.6212858295 0.436560307095 +1403715894084058112.0000000000 0.8768677462 2.1364871418 1.0221995058 0.3597890187 0.5420132725 -0.6246706520 0.431925978653 +1403715894134057984.0000000000 0.8733507292 2.1422839402 1.0302571483 0.3558063185 0.5443494586 -0.6247831388 0.432124472907 +1403715894184058112.0000000000 0.8713106466 2.1482073780 1.0402632001 0.3531910595 0.5456654303 -0.6211579237 0.437799209141 +1403715894234057984.0000000000 0.8703953330 2.1546915011 1.0529123539 0.3521659850 0.5458369922 -0.6168423001 0.444462229785 +1403715894284058112.0000000000 0.8700714783 2.1621621690 1.0675858551 0.3503495739 0.5466899415 -0.6117673156 0.451803093672 +1403715894334057984.0000000000 0.8701314696 2.1710425675 1.0839238124 0.3479055242 0.5479490134 -0.6081564983 0.457011267421 +1403715894384058112.0000000000 0.8705699202 2.1815897938 1.1016952379 0.3461700368 0.5484165450 -0.6055623000 0.461193993516 +1403715894434057984.0000000000 0.8709045807 2.1940703109 1.1187520059 0.3446357899 0.5486051989 -0.6049579192 0.462908656244 +1403715894484058112.0000000000 0.8710908490 2.2086257642 1.1338504615 0.3432523791 0.5488856372 -0.6068939943 0.461066200491 +1403715894534057984.0000000000 0.8713998893 2.2250311006 1.1464517413 0.3423542691 0.5490124718 -0.6101389825 0.457284684011 +1403715894584058112.0000000000 0.8719954183 2.2428170258 1.1569574393 0.3411248803 0.5491511303 -0.6126509557 0.454670934493 +1403715894634057984.0000000000 0.8733018541 2.2621747994 1.1661087874 0.3409911572 0.5488590972 -0.6149922416 0.451954936776 +1403715894684058112.0000000000 0.8749634598 2.2830307114 1.1749445876 0.3419375957 0.5480021934 -0.6181935938 0.447893912962 +1403715894734057984.0000000000 0.8777270470 2.3049179958 1.1850230261 0.3444188152 0.5462351213 -0.6197371609 0.446014263674 +1403715894784058112.0000000000 0.8812452804 2.3278334682 1.1963201526 0.3481986032 0.5436029134 -0.6208390388 0.44476116414 +1403715894834057984.0000000000 0.8855545280 2.3513270379 1.2085681653 0.3521342408 0.5409048000 -0.6209253248 0.444831670122 +1403715894884058112.0000000000 0.8907073123 2.3754986294 1.2215235895 0.3557470703 0.5386486731 -0.6202070308 0.445695936575 +1403715894934057984.0000000000 0.8961841981 2.4000824712 1.2349349610 0.3581197171 0.5369861960 -0.6190895417 0.447352470575 +1403715894984058112.0000000000 0.9017841383 2.4250829719 1.2490108307 0.3603738007 0.5355132604 -0.6185219931 0.448092418792 +1403715895034057984.0000000000 0.9073488870 2.4504054754 1.2634184299 0.3618780740 0.5344869302 -0.6183140921 0.448392310875 +1403715895084058112.0000000000 0.9128505192 2.4758779739 1.2777104445 0.3617140819 0.5343104612 -0.6180085091 0.449155581953 +1403715895134057984.0000000000 0.9182631699 2.5018961812 1.2922492529 0.3628443012 0.5333939599 -0.6187970112 0.448246757439 +1403715895184058112.0000000000 0.9235668900 2.5279573467 1.3064038641 0.3634228435 0.5328135045 -0.6194242851 0.447601565343 +1403715895234057984.0000000000 0.9284604692 2.5541676864 1.3202252941 0.3643009860 0.5320604817 -0.6205240845 0.446258104689 +1403715895284058112.0000000000 0.9332620482 2.5801314888 1.3337170008 0.3645613930 0.5317246905 -0.6205511447 0.44640802082 +1403715895334057984.0000000000 0.9381679466 2.6061516122 1.3467687350 0.3646845876 0.5315437131 -0.6209193266 0.446010787448 +1403715895384058112.0000000000 0.9430340501 2.6324109000 1.3595248580 0.3648436295 0.5313064563 -0.6208824739 0.44621466709 +1403715895434057984.0000000000 0.9473722603 2.6588737755 1.3716397909 0.3646805639 0.5311432701 -0.6209242898 0.446483974256 +1403715895484058112.0000000000 0.9515630205 2.6853854081 1.3839487973 0.3644791093 0.5311371384 -0.6215299578 0.44581255112 +1403715895534057984.0000000000 0.9554390798 2.7117251524 1.3962461019 0.3643863371 0.5310265576 -0.6218024933 0.445640047385 +1403715895584058112.0000000000 0.9592289659 2.7380130029 1.4084468674 0.3642295312 0.5307306193 -0.6229094110 0.444573642927 +1403715895634057984.0000000000 0.9634735685 2.7641897451 1.4206833166 0.3640546857 0.5307589783 -0.6223228736 0.445503460972 +1403715895684058112.0000000000 0.9678311376 2.7903178532 1.4326945471 0.3637040381 0.5307254778 -0.6227244081 0.445268628435 +1403715895734057984.0000000000 0.9720288293 2.8164277150 1.4445269148 0.3637507829 0.5304957894 -0.6232902292 0.444712126683 +1403715895784058112.0000000000 0.9760430570 2.8425314015 1.4558350980 0.3635604203 0.5303568346 -0.6236524798 0.444525627183 +1403715895834057984.0000000000 0.9801254593 2.8683253896 1.4670027290 0.3636158344 0.5301817835 -0.6237797070 0.444510605679 +1403715895884058112.0000000000 0.9841579199 2.8938792359 1.4779900764 0.3632119979 0.5304154044 -0.6238379352 0.444480341494 +1403715895934057984.0000000000 0.9882644178 2.9194605969 1.4893599843 0.3639405306 0.5299111002 -0.6239482882 0.44433101371 +1403715895984058112.0000000000 0.9919595730 2.9449987638 1.5003807377 0.3648504406 0.5290885961 -0.6250188500 0.44305851822 +1403715896034057984.0000000000 0.9956105832 2.9703840833 1.5114485587 0.3656350240 0.5285765831 -0.6258259187 0.44188204819 +1403715896084058112.0000000000 0.9996547078 2.9956149307 1.5224314108 0.3675928139 0.5274541815 -0.6271791163 0.43967484078 +1403715896134057984.0000000000 1.0038706954 3.0204644147 1.5330110819 0.3698416668 0.5259966907 -0.6291984772 0.436639323896 +1403715896184058112.0000000000 1.0081163202 3.0448639788 1.5433909182 0.3735784794 0.5234043093 -0.6309311154 0.434065635976 +1403715896234057984.0000000000 1.0123223488 3.0685081289 1.5534918924 0.3787443565 0.5194881992 -0.6338262527 0.430056978583 +1403715896284058112.0000000000 1.0164370573 3.0908614468 1.5641959075 0.3858029192 0.5143340526 -0.6361538069 0.426526580387 +1403715896334057984.0000000000 1.0202760416 3.1114779087 1.5754956001 0.3933427261 0.5086874542 -0.6390614112 0.422041569677 +1403715896384058112.0000000000 1.0233691251 3.1298121609 1.5866425043 0.3996764102 0.5039771616 -0.6418660457 0.417461096586 +1403715896434057984.0000000000 1.0259400841 3.1452246056 1.5974417631 0.4045425668 0.5002602577 -0.6434334019 0.414823388298 +1403715896484058112.0000000000 1.0277666978 3.1579109000 1.6080285601 0.4094649369 0.4965042508 -0.6452812384 0.411623757475 +1403715896534057984.0000000000 1.0286998180 3.1671610753 1.6185804241 0.4134483209 0.4936257663 -0.6456978720 0.410448957699 +1403715896584058112.0000000000 1.0287412154 3.1728597887 1.6294967654 0.4178853998 0.4902707725 -0.6460396498 0.409437581663 +1403715896634057984.0000000000 1.0276413320 3.1747294500 1.6404547853 0.4212046136 0.4877848404 -0.6456035368 0.409693417478 +1403715896684058112.0000000000 1.0252016272 3.1727889382 1.6513359748 0.4235982412 0.4859765327 -0.6451985956 0.41001233137 +1403715896734057984.0000000000 1.0211627680 3.1673713888 1.6620525225 0.4257801747 0.4846696042 -0.6454322092 0.408930166235 +1403715896784058112.0000000000 1.0156878262 3.1580766076 1.6720192634 0.4260566754 0.4848637672 -0.6469451820 0.406010798085 +1403715896834057984.0000000000 1.0090010746 3.1449001462 1.6820461360 0.4264453068 0.4851340439 -0.6492318422 0.401605994493 +1403715896884058112.0000000000 1.0012377918 3.1275393324 1.6923140213 0.4272031690 0.4846097233 -0.6517367055 0.397353916966 +1403715896934057984.0000000000 0.9924803058 3.1062714124 1.7026727212 0.4291827543 0.4833361890 -0.6547633872 0.39175655527 +1403715896984058112.0000000000 0.9828292130 3.0804504691 1.7133773690 0.4323321267 0.4809448528 -0.6582720113 0.385303698355 +1403715897034057984.0000000000 0.9721853631 3.0496807509 1.7242981432 0.4356142504 0.4782583739 -0.6618000546 0.378853322987 +1403715897084058112.0000000000 0.9610646691 3.0133314319 1.7349815307 0.4381029967 0.4762426753 -0.6643108608 0.374098594883 +1403715897134057984.0000000000 0.9494286086 2.9710827128 1.7456665255 0.4388248263 0.4753109875 -0.6652976712 0.372681158189 +1403715897184058112.0000000000 0.9373226931 2.9228653750 1.7561996870 0.4380529599 0.4756318687 -0.6651969885 0.373358937633 +1403715897234057984.0000000000 0.9244194923 2.8690142876 1.7658686767 0.4333798669 0.4794061092 -0.6637868277 0.376482032625 +1403715897284058112.0000000000 0.9112064055 2.8096147376 1.7749317817 0.4252045435 0.4859723156 -0.6601226062 0.383757930692 +1403715897334057984.0000000000 0.8977329667 2.7457527326 1.7834641210 0.4141399018 0.4948973529 -0.6552067205 0.392770805009 +1403715897384058112.0000000000 0.8841271447 2.6782214373 1.7921296618 0.4014623364 0.5048237917 -0.6491439691 0.403228271755 +1403715897434057984.0000000000 0.8706229471 2.6086658578 1.8014076848 0.3912117637 0.5123272855 -0.6451686821 0.410160310314 +1403715897484058112.0000000000 0.8576824856 2.5374934620 1.8109785635 0.3840595405 0.5173931611 -0.6413581405 0.416488081244 +1403715897534057984.0000000000 0.8451739206 2.4653922715 1.8204801518 0.3788199332 0.5212170568 -0.6388028211 0.420427394056 +1403715897584058112.0000000000 0.8335525447 2.3928566310 1.8298828198 0.3773418483 0.5218362080 -0.6386926990 0.421155241757 +1403715897634057984.0000000000 0.8226157144 2.3200084524 1.8393875498 0.3793131285 0.5199473081 -0.6401795437 0.419459770728 +1403715897684058112.0000000000 0.8119057354 2.2464270103 1.8479584401 0.3815400217 0.5180503011 -0.6414386855 0.417860634718 +1403715897734057984.0000000000 0.8013873685 2.1723149562 1.8569507508 0.3866719993 0.5137576392 -0.6443686512 0.413916530881 +1403715897784058112.0000000000 0.7913604251 2.0967100370 1.8656756184 0.3905860433 0.5106012152 -0.6458112237 0.411894167434 +1403715897834057984.0000000000 0.7815120060 2.0195077874 1.8737384293 0.3938027968 0.5078860907 -0.6463409487 0.411356845267 +1403715897884058112.0000000000 0.7718290539 1.9404907711 1.8817822898 0.3969389992 0.5053349120 -0.6455162294 0.412777004185 +1403715897934057984.0000000000 0.7619478207 1.8595339427 1.8890414887 0.3961248533 0.5059912999 -0.6428554489 0.416887007279 +1403715897984058112.0000000000 0.7523847928 1.7770183712 1.8963487065 0.3960008852 0.5061571800 -0.6406174420 0.420235054546 +1403715898034057984.0000000000 0.7424376694 1.6928750239 1.9035831812 0.3952486700 0.5066698268 -0.6363401214 0.426773271523 +1403715898084058112.0000000000 0.7318606465 1.6076073770 1.9109901545 0.3954590237 0.5056928701 -0.6316761813 0.434594159682 +1403715898134057984.0000000000 0.7206964144 1.5213894930 1.9181102392 0.3944628382 0.5044099836 -0.6274342338 0.443052953976 +1403715898184058112.0000000000 0.7085961465 1.4345900667 1.9252649276 0.3936366403 0.5013489776 -0.6251019037 0.450496401916 +1403715898234057984.0000000000 0.6952016281 1.3474799996 1.9319208800 0.3902605262 0.4988603523 -0.6241318475 0.45748716648 +1403715898284058112.0000000000 0.6803039105 1.2603623179 1.9372982778 0.3850657378 0.4964016241 -0.6255739000 0.462565779937 +1403715898334057984.0000000000 0.6632547472 1.1735584896 1.9416192951 0.3788611579 0.4934589689 -0.6287970155 0.466451264702 +1403715898384058112.0000000000 0.6445502136 1.0872333133 1.9447223033 0.3716062559 0.4904019578 -0.6337480715 0.468804961783 +1403715898434057984.0000000000 0.6247025326 1.0016609404 1.9464606896 0.3628913438 0.4876507937 -0.6404991804 0.469326513028 +1403715898484058112.0000000000 0.6041210554 0.9168487885 1.9476234742 0.3545358542 0.4836074950 -0.6481857028 0.469343598637 +1403715898534057984.0000000000 0.5830754377 0.8326707331 1.9477906027 0.3453195361 0.4798949314 -0.6561166452 0.46900556577 +1403715898584058112.0000000000 0.5620787315 0.7490449930 1.9477113254 0.3369344280 0.4750838480 -0.6630564528 0.470241075358 +1403715898634057984.0000000000 0.5413577541 0.6662013763 1.9456825883 0.3286846741 0.4694945080 -0.6702745985 0.47145864561 +1403715898684058112.0000000000 0.5208232752 0.5839125877 1.9421124548 0.3230798885 0.4614645303 -0.6749322235 0.476588256889 +1403715898734057984.0000000000 0.5003146992 0.5025940339 1.9356191966 0.3180492873 0.4533050092 -0.6795328764 0.481242443454 +1403715898784058112.0000000000 0.4792826156 0.4223587903 1.9254591480 0.3116898934 0.4470684339 -0.6844286065 0.484289901216 +1403715898834057984.0000000000 0.4583596086 0.3430378625 1.9122586886 0.3062263214 0.4413577029 -0.6889752443 0.486561333157 +1403715898884058112.0000000000 0.4377847505 0.2646476976 1.8963405012 0.3010791595 0.4367575483 -0.6926995042 0.488632357358 +1403715898934057984.0000000000 0.4175933815 0.1874850765 1.8773558820 0.2972022648 0.4324696243 -0.6966951423 0.489138749933 +1403715898984058112.0000000000 0.3980485190 0.1112738372 1.8555912628 0.2927424721 0.4298456578 -0.6993280304 0.490382362553 +1403715899034057984.0000000000 0.3794535368 0.0360249423 1.8314687921 0.2909963688 0.4264096923 -0.7012145854 0.491725525997 +1403715899084058112.0000000000 0.3610692162 -0.0383446681 1.8044537320 0.2877898391 0.4249619348 -0.7038339840 0.491123289454 +1403715899134057984.0000000000 0.3434711766 -0.1115622828 1.7764885723 0.2844478951 0.4242872454 -0.7074999650 0.488378467792 +1403715899184058112.0000000000 0.3269184704 -0.1841634870 1.7493819947 0.2795724006 0.4253651558 -0.7108112459 0.48543911027 +1403715899234057984.0000000000 0.3114820949 -0.2562308416 1.7237926514 0.2723371628 0.4287562523 -0.7131928313 0.483069903069 +1403715899284058112.0000000000 0.2976558267 -0.3273545475 1.7011581753 0.2661961393 0.4321174675 -0.7150411274 0.480760122913 +1403715899334057984.0000000000 0.2852517453 -0.3971164679 1.6808958217 0.2598553047 0.4359620181 -0.7179911895 0.476341254909 +1403715899384058112.0000000000 0.2755008722 -0.4661032591 1.6642744380 0.2536912442 0.4402870180 -0.7194764794 0.473436046401 +1403715899434057984.0000000000 0.2691545300 -0.5344232773 1.6516092596 0.2484786687 0.4444069721 -0.7192429504 0.472705376113 +1403715899484058112.0000000000 0.2666101885 -0.6016265283 1.6433188247 0.2475303969 0.4456976819 -0.7189050661 0.47250162429 +1403715899534057984.0000000000 0.2671477943 -0.6679447911 1.6370468142 0.2482100520 0.4465211916 -0.7185325643 0.471933840274 +1403715899584058112.0000000000 0.2708030453 -0.7335988866 1.6312102350 0.2496584134 0.4466933811 -0.7180861963 0.471686245973 +1403715899634057984.0000000000 0.2774124675 -0.7984269400 1.6253562994 0.2516473597 0.4465613591 -0.7186484898 0.46989457007 +1403715899684058112.0000000000 0.2867099452 -0.8625928837 1.6194182385 0.2526094961 0.4471100252 -0.7176030833 0.470453911316 +1403715899734057984.0000000000 0.2990845514 -0.9259342740 1.6131416363 0.2524280363 0.4488574928 -0.7157943079 0.47164133233 +1403715899784058112.0000000000 0.3146732403 -0.9884445869 1.6073097730 0.2520461696 0.4507063455 -0.7124380980 0.475151002372 +1403715899834057984.0000000000 0.3330171447 -1.0499935915 1.6018878738 0.2515995680 0.4524922536 -0.7076414075 0.48082435066 +1403715899884058112.0000000000 0.3537553820 -1.1101008782 1.5970043051 0.2503187250 0.4549660389 -0.7018748685 0.487563440347 +1403715899934057984.0000000000 0.3764888428 -1.1681158993 1.5924277492 0.2480786058 0.4579568491 -0.6965914538 0.493449973331 +1403715899984058112.0000000000 0.4012843845 -1.2238428276 1.5877427764 0.2443888659 0.4615163500 -0.6916776392 0.498857479024 +1403715900034057984.0000000000 0.4285433811 -1.2767747154 1.5832584585 0.2423208125 0.4636623339 -0.6878470702 0.503154322207 +1403715900084058112.0000000000 0.4577736316 -1.3264313073 1.5787765773 0.2406447072 0.4658781847 -0.6851005712 0.505652894063 +1403715900134057984.0000000000 0.4891517237 -1.3731284941 1.5744939392 0.2389673618 0.4671492034 -0.6831847735 0.507862960818 +1403715900184058112.0000000000 0.5225537754 -1.4163808543 1.5703679829 0.2369662236 0.4689003894 -0.6811140326 0.509963830392 +1403715900234057984.0000000000 0.5582691669 -1.4560088078 1.5666422937 0.2363669112 0.4699447185 -0.6795561224 0.511357136704 +1403715900284058112.0000000000 0.5962227709 -1.4923100632 1.5630671516 0.2349216247 0.4710008342 -0.6783639680 0.512632784146 +1403715900334057984.0000000000 0.6362711179 -1.5246721168 1.5599158389 0.2344516935 0.4715671333 -0.6784458039 0.512218833444 +1403715900384058112.0000000000 0.6786158380 -1.5534138666 1.5570484905 0.2333677416 0.4722749508 -0.6780237174 0.512620431399 +1403715900434057984.0000000000 0.7232129964 -1.5780910085 1.5545586231 0.2350476745 0.4712165760 -0.6794969648 0.510873177978 +1403715900484058112.0000000000 0.7700361091 -1.5983918516 1.5534187488 0.2433038126 0.4656686978 -0.6839168013 0.506175589649 +1403715900534057984.0000000000 0.8191706043 -1.6157970318 1.5538363866 0.2541026038 0.4583967838 -0.6863429976 0.504219738751 +1403715900584058112.0000000000 0.8696053140 -1.6308587569 1.5547799244 0.2639511269 0.4516634434 -0.6868993181 0.504479200114 +1403715900634057984.0000000000 0.9209909548 -1.6440131130 1.5565302604 0.2757190545 0.4433548928 -0.6873284314 0.504970364878 +1403715900684058112.0000000000 0.9729598618 -1.6556414730 1.5586813383 0.2886815590 0.4340155556 -0.6874003194 0.50574129338 +1403715900734057984.0000000000 1.0242509428 -1.6662841758 1.5608884158 0.3003615257 0.4254643263 -0.6851510005 0.509245684752 +1403715900784058112.0000000000 1.0741310698 -1.6761513685 1.5627463478 0.3084124288 0.4192439424 -0.6806946969 0.515529843984 +1403715900834057984.0000000000 1.1222114069 -1.6850880326 1.5646751488 0.3126294674 0.4153670210 -0.6745815836 0.524092302071 +1403715900884058112.0000000000 1.1680304612 -1.6927587340 1.5668197154 0.3152495548 0.4128110130 -0.6694208502 0.53111252207 +1403715900934057984.0000000000 1.2108358347 -1.6989239995 1.5688653245 0.3155827424 0.4113863701 -0.6653286839 0.537128038392 +1403715900984058112.0000000000 1.2506070396 -1.7030015122 1.5717873924 0.3168190094 0.4097084211 -0.6610346957 0.542952904077 +1403715901034057984.0000000000 1.2871895266 -1.7049391281 1.5761817223 0.3201159216 0.4067667618 -0.6569415881 0.548173647696 +1403715901084058112.0000000000 1.3199489540 -1.7046573992 1.5811600358 0.3215423010 0.4048142294 -0.6527980528 0.553706321644 +1403715901134057984.0000000000 1.3489528472 -1.7017465737 1.5870168319 0.3248899859 0.4018362629 -0.6496149535 0.557650900675 +1403715901184058112.0000000000 1.3737349131 -1.6963944857 1.5936848613 0.3269757707 0.3990734590 -0.6464453616 0.562081501353 +1403715901234057984.0000000000 1.3941562904 -1.6881403253 1.6011268282 0.3297263110 0.3963709442 -0.6445950559 0.564506730071 +1403715901284058112.0000000000 1.4097418305 -1.6772593098 1.6088127276 0.3313540447 0.3941352343 -0.6442177301 0.565548786943 +1403715901334057984.0000000000 1.4205245652 -1.6635953839 1.6167986478 0.3319629058 0.3928331691 -0.6462477438 0.563778843228 +1403715901384058112.0000000000 1.4266271710 -1.6474242399 1.6244829022 0.3310369422 0.3930130689 -0.6504737282 0.559320301352 +1403715901434057984.0000000000 1.4281626149 -1.6289770249 1.6314994399 0.3290174550 0.3944450783 -0.6573149465 0.551450501552 +1403715901484058112.0000000000 1.4253414902 -1.6089808680 1.6382080010 0.3244057390 0.3973461238 -0.6641740382 0.543828853025 +1403715901534057984.0000000000 1.4192777728 -1.5876339973 1.6454192968 0.3203078374 0.3999525815 -0.6696506581 0.537595403623 +1403715901584058112.0000000000 1.4105135580 -1.5654357249 1.6535548988 0.3165856567 0.4018865509 -0.6725968424 0.5346720581 +1403715901634057984.0000000000 1.3993760563 -1.5422698741 1.6623320131 0.3132172713 0.4036127065 -0.6733673123 0.534385803338 +1403715901684058112.0000000000 1.3858235942 -1.5177330746 1.6713059555 0.3125234259 0.4038659853 -0.6747122778 0.532902163984 +1403715901734057984.0000000000 1.3697298616 -1.4919962811 1.6788025684 0.3095012704 0.4057444890 -0.6770806270 0.530228439218 +1403715901784058112.0000000000 1.3516714479 -1.4651315953 1.6861059219 0.3067155118 0.4075551575 -0.6801836586 0.52647372112 +1403715901834057984.0000000000 1.3320739054 -1.4374604994 1.6929846719 0.3035788150 0.4099962741 -0.6832798598 0.522371124254 +1403715901884058112.0000000000 1.3109722478 -1.4091455484 1.6996945381 0.3003002678 0.4126187535 -0.6852659558 0.519592227882 +1403715901934057984.0000000000 1.2887998097 -1.3799512598 1.7058289307 0.2994715219 0.4135285884 -0.6871134162 0.516900442444 +1403715901984058112.0000000000 1.2654630735 -1.3500897220 1.7116359349 0.2986761288 0.4144649352 -0.6884205386 0.514867506929 +1403715902034057984.0000000000 1.2410268518 -1.3197014300 1.7177454422 0.2993896207 0.4143469894 -0.6881786537 0.514871409243 +1403715902084058112.0000000000 1.2155207294 -1.2888081024 1.7233222536 0.2997529929 0.4141639480 -0.6869013280 0.516510341616 +1403715902134057984.0000000000 1.1890650321 -1.2573502796 1.7277477032 0.2977982784 0.4159909281 -0.6853510005 0.518229427172 +1403715902184058112.0000000000 1.1618630994 -1.2250288618 1.7317970513 0.2958034078 0.4181775255 -0.6835414294 0.519999053286 +1403715902234057984.0000000000 1.1339890593 -1.1921042747 1.7348400383 0.2913249863 0.4215622920 -0.6827507059 0.520832468179 +1403715902284058112.0000000000 1.1057310184 -1.1577322515 1.7375334656 0.2879060088 0.4245523057 -0.6833532880 0.519512996601 +1403715902334057984.0000000000 1.0768782349 -1.1223807132 1.7400354615 0.2830168402 0.4283481694 -0.6841727689 0.518002834258 +1403715902384058112.0000000000 1.0476940291 -1.0857124178 1.7428720485 0.2799267083 0.4310044551 -0.6854967214 0.515723222811 +1403715902434057984.0000000000 1.0187928166 -1.0476681674 1.7464707848 0.2780281475 0.4327461122 -0.6865389010 0.513902217381 +1403715902484058112.0000000000 0.9901636116 -1.0079024959 1.7502705435 0.2793377089 0.4324418399 -0.6897264691 0.50915802785 +1403715902534057984.0000000000 0.9619833078 -0.9670621028 1.7544777882 0.2820305577 0.4308633965 -0.6940129364 0.503151609568 +1403715902584058112.0000000000 0.9342744914 -0.9253910135 1.7585640125 0.2843625370 0.4305633368 -0.6976583790 0.497017048822 +1403715902634057984.0000000000 0.9069529476 -0.8832688457 1.7629007199 0.2872579346 0.4312933185 -0.6999385424 0.491482440548 +1403715902684058112.0000000000 0.8802929951 -0.8409574538 1.7668109817 0.2903637854 0.4333448712 -0.7016653137 0.485352328024 +1403715902734057984.0000000000 0.8536067961 -0.7985463184 1.7682423106 0.2923721872 0.4382089968 -0.7026760078 0.478265415163 +1403715902784058112.0000000000 0.8280830629 -0.7569493088 1.7669457548 0.2942616520 0.4445996832 -0.7022694013 0.471761475644 +1403715902834057984.0000000000 0.8038168715 -0.7159656715 1.7627961078 0.2973208434 0.4512752665 -0.7012078798 0.465035976255 +1403715902884058112.0000000000 0.7811250432 -0.6756090569 1.7553127981 0.2992194191 0.4597054702 -0.6991004763 0.458690684376 +1403715902934057984.0000000000 0.7600527038 -0.6361614134 1.7459013786 0.3019582055 0.4678818687 -0.6956901738 0.453787374452 +1403715902984058112.0000000000 0.7406726667 -0.5976953807 1.7359355364 0.3032285717 0.4778394682 -0.6897506483 0.451625861788 +1403715903034057984.0000000000 0.7232487356 -0.5597181212 1.7270170920 0.3080150702 0.4863708431 -0.6831679659 0.449279033438 +1403715903084058112.0000000000 0.7073705369 -0.5225463749 1.7178553812 0.3109090809 0.4965115741 -0.6753648506 0.447988971669 +1403715903134057984.0000000000 0.6934551564 -0.4856151771 1.7091043136 0.3141672246 0.5064114346 -0.6671193595 0.446987890346 +1403715903184058112.0000000000 0.6815669036 -0.4490447824 1.7010643990 0.3162651104 0.5158516095 -0.6590322055 0.446710251756 +1403715903234057984.0000000000 0.6716263591 -0.4122484750 1.6936778396 0.3197835889 0.5225986740 -0.6541525712 0.443523951778 +1403715903284058112.0000000000 0.6635036730 -0.3752725159 1.6864674721 0.3222322293 0.5286544791 -0.6520191379 0.437677822016 +1403715903334057984.0000000000 0.6578374700 -0.3383578162 1.6798190211 0.3244758388 0.5335189005 -0.6508649075 0.431796115127 +1403715903384058112.0000000000 0.6542948390 -0.3012167202 1.6740961935 0.3266583033 0.5386657020 -0.6503224544 0.424516571744 +1403715903434057984.0000000000 0.6535073701 -0.2639984703 1.6711731562 0.3299317600 0.5436864221 -0.6489378766 0.417647866639 +1403715903484058112.0000000000 0.6558233808 -0.2267897693 1.6715437915 0.3332587515 0.5494556851 -0.6460212808 0.411938781173 +1403715903534057984.0000000000 0.6612379976 -0.1897209076 1.6755998456 0.3379639274 0.5553672442 -0.6420534674 0.406343392745 +1403715903584058112.0000000000 0.6697962117 -0.1530818684 1.6834065573 0.3433427342 0.5619210784 -0.6360035464 0.402318229161 +1403715903634057984.0000000000 0.6814065751 -0.1166046226 1.6948083813 0.3488543158 0.5692051567 -0.6297113431 0.397202442523 +1403715903684058112.0000000000 0.6959100495 -0.0804879003 1.7099821597 0.3558612576 0.5763194084 -0.6215214302 0.393611250699 +1403715903734057984.0000000000 0.7130197733 -0.0447348372 1.7285397475 0.3635985708 0.5834648490 -0.6117267057 0.391350593208 +1403715903784058112.0000000000 0.7330671719 -0.0086862132 1.7508742324 0.3761078527 0.5878157554 -0.6027535615 0.386915578618 +1403715903834057984.0000000000 0.7554942221 0.0269797507 1.7764756489 0.3879251849 0.5934570957 -0.5925305332 0.382400697818 +1403715903884058112.0000000000 0.7798414736 0.0621910979 1.8051831181 0.4015786618 0.5986542404 -0.5812165148 0.377538132817 +1403715903934057984.0000000000 0.8055377073 0.0966749406 1.8345559988 0.4136897880 0.6057359417 -0.5682001968 0.372952094257 +1403715903984058112.0000000000 0.8324063493 0.1305143595 1.8636866042 0.4251712193 0.6138034506 -0.5537222571 0.368600624381 +1403715904034057984.0000000000 0.8593452594 0.1638841636 1.8931148239 0.4375361026 0.6212736911 -0.5401851887 0.361636725929 +1403715904084058112.0000000000 0.8861963854 0.1962026925 1.9217742824 0.4484243081 0.6297631363 -0.5267262844 0.353374381304 +1403715904134057984.0000000000 0.9132949993 0.2273334481 1.9499952417 0.4586087065 0.6385480431 -0.5129385892 0.344715033949 +1403715904184058112.0000000000 0.9397865801 0.2566026487 1.9765745299 0.4657830581 0.6494498454 -0.4975555866 0.337193533875 +1403715904234057984.0000000000 0.9657673160 0.2845069161 2.0027581331 0.4722905886 0.6603983829 -0.4821586499 0.329148313137 +1403715904284058112.0000000000 0.9918551121 0.3110452043 2.0278436824 0.4771052990 0.6721355234 -0.4641365817 0.324317137088 +1403715904334057984.0000000000 1.0182369519 0.3369974261 2.0520621681 0.4831406328 0.6821372040 -0.4457537516 0.320261700324 +1403715904384058112.0000000000 1.0442467084 0.3625973267 2.0740946975 0.4887377535 0.6915910369 -0.4273852460 0.316510817321 +1403715904434057984.0000000000 1.0698212155 0.3881165300 2.0938067859 0.4957072574 0.6988042925 -0.4117206821 0.310536560875 +1403715904484058112.0000000000 1.0948194655 0.4132085102 2.1104145933 0.5010953882 0.7059847031 -0.3963650574 0.305587552511 +1403715904534057984.0000000000 1.1191798231 0.4379557584 2.1235294645 0.5051278328 0.7133284031 -0.3798009714 0.302918609518 +1403715904584058112.0000000000 1.1424833272 0.4626738167 2.1335546293 0.5096619022 0.7198117078 -0.3632433411 0.300283409252 +1403715904634057984.0000000000 1.1641079580 0.4877054716 2.1407012760 0.5143963744 0.7257967736 -0.3469493239 0.297054843443 +1403715904684058112.0000000000 1.1834588056 0.5130042464 2.1451885183 0.5206544142 0.7307318506 -0.3314830329 0.29166580602 +1403715904734057984.0000000000 1.2000640375 0.5387153010 2.1470997231 0.5281711801 0.7352524873 -0.3188532045 0.280662819986 +1403715904784058112.0000000000 1.2141625831 0.5646148154 2.1465477981 0.5359661601 0.7398464643 -0.3081395835 0.26536292435 +1403715904834057984.0000000000 1.2264152602 0.5902943087 2.1430388067 0.5427795743 0.7452294257 -0.2965412039 0.249172131683 +1403715904884058112.0000000000 1.2368097688 0.6153144837 2.1366404772 0.5506709036 0.7497356233 -0.2830798016 0.233503483968 +1403715904934057984.0000000000 1.2454543687 0.6397029574 2.1268738955 0.5588432410 0.7536059280 -0.2679115729 0.21907926953 +1403715904984058112.0000000000 1.2525351721 0.6630197040 2.1144258769 0.5668471826 0.7572909626 -0.2517163832 0.204532471374 +1403715905034057984.0000000000 1.2583367263 0.6850081681 2.0993494379 0.5752573268 0.7600103711 -0.2334077637 0.192312401255 +1403715905084058112.0000000000 1.2628118906 0.7056638145 2.0813176651 0.5834211726 0.7620660481 -0.2147484749 0.180992171719 +1403715905134057984.0000000000 1.2659582296 0.7243234649 2.0604200944 0.5921956806 0.7627082556 -0.1965410157 0.170152936729 +1403715905184058112.0000000000 1.2682911936 0.7412177063 2.0371513250 0.5994269578 0.7633502582 -0.1776392034 0.162566967818 +1403715905234057984.0000000000 1.2691096951 0.7557326485 2.0134769373 0.6045297685 0.7647612984 -0.1602542456 0.154927377316 +1403715905284058112.0000000000 1.2678062981 0.7670769395 1.9885006516 0.6032794564 0.7703835690 -0.1437749397 0.147958848523 +1403715905334057984.0000000000 1.2642682189 0.7755749264 1.9636618652 0.5997197139 0.7772928451 -0.1293804607 0.139329803487 +1403715905384058112.0000000000 1.2587004117 0.7817363306 1.9394029098 0.5953194430 0.7842707604 -0.1151948565 0.131317478863 +1403715905434057984.0000000000 1.2507607380 0.7860528803 1.9166735311 0.5922618661 0.7898513457 -0.1017236691 0.122527665784 +1403715905484058112.0000000000 1.2404524219 0.7889904650 1.8943650335 0.5881125159 0.7959339624 -0.0892335742 0.112472953997 +1403715905534057984.0000000000 1.2282871962 0.7907105766 1.8724497181 0.5845400689 0.8011138490 -0.0762137933 0.10354210063 +1403715905584058112.0000000000 1.2137818528 0.7918867589 1.8515419629 0.5818232214 0.8056257351 -0.0654290406 0.0903767374067 +1403715905634057984.0000000000 1.1972714202 0.7925856400 1.8318497114 0.5800530175 0.8092877823 -0.0569713087 0.0731167038007 +1403715905684058112.0000000000 1.1794509620 0.7927633956 1.8130654641 0.5789422604 0.8120946379 -0.0488803728 0.054211321227 +1403715905734057984.0000000000 1.1609272668 0.7922310046 1.7943484152 0.5769770811 0.8150324627 -0.0389520751 0.0360869566435 +1403715905784058112.0000000000 1.1420031414 0.7912038523 1.7759228786 0.5761638674 0.8166816606 -0.0266568861 0.0188593114896 +1403715905834057984.0000000000 1.1230041333 0.7896130641 1.7571823290 0.5734287065 0.8191631807 -0.0121879856 0.00162941025348 +1403715905884058112.0000000000 1.1045818350 0.7874993082 1.7379872139 0.5679316585 0.8229437684 0.0049631297 -0.0138763366736 +1403715905934057984.0000000000 1.0868028673 0.7856501239 1.7186667347 0.5605155835 0.8273083488 0.0232202765 -0.0290516004711 +1403715905984058112.0000000000 1.0698641670 0.7845075043 1.6992775226 0.5526842628 0.8311772675 0.0443388503 -0.0414550593834 +1403715906034057984.0000000000 1.0533053775 0.7845841241 1.6804532784 0.5459077586 0.8334917204 0.0665936007 -0.053306317433 +1403715906084058112.0000000000 1.0372320907 0.7864170363 1.6626729017 0.5422462008 0.8329343598 0.0897199631 -0.064340797289 +1403715906134057984.0000000000 1.0214907102 0.7901862886 1.6462911748 0.5426239777 0.8288798377 0.1150243463 -0.0727106135701 +1403715906184058112.0000000000 1.0055504403 0.7956770167 1.6308935854 0.5464791524 0.8216499016 0.1407549338 -0.0802497596017 +1403715906234057984.0000000000 0.9889099259 0.8019408086 1.6158850256 0.5503116970 0.8134094922 0.1667964063 -0.0877553018588 +1403715906284058112.0000000000 0.9708609167 0.8085515534 1.6012353971 0.5512836571 0.8064143433 0.1900274181 -0.0983453951274 +1403715906334057984.0000000000 0.9515354299 0.8151494871 1.5866751798 0.5505609848 0.7996949427 0.2135397403 -0.108495990778 +1403715906384058112.0000000000 0.9306996479 0.8215078718 1.5725229703 0.5488722526 0.7930055499 0.2358925700 -0.119315311512 +1403715906434057984.0000000000 0.9083023151 0.8275231501 1.5588061913 0.5471446039 0.7858408116 0.2564550971 -0.131597053501 +1403715906484058112.0000000000 0.8842679457 0.8331837015 1.5462447264 0.5467490154 0.7772651731 0.2751527367 -0.14565485347 +1403715906534057984.0000000000 0.8586401776 0.8382169279 1.5347625473 0.5460711334 0.7683093012 0.2939740370 -0.158386869939 +1403715906584058112.0000000000 0.8312092995 0.8420966175 1.5259556704 0.5433270125 0.7604116482 0.3102807367 -0.174056735583 +1403715906634057984.0000000000 0.8024576322 0.8446892091 1.5206357850 0.5392691482 0.7529955635 0.3243967325 -0.192232221851 +1403715906684058112.0000000000 0.7727519564 0.8461108823 1.5189724548 0.5346375684 0.7454134237 0.3372111733 -0.211684016418 +1403715906734057984.0000000000 0.7427442497 0.8463371540 1.5201067809 0.5286086088 0.7379497862 0.3511144538 -0.229612046843 +1403715906784058112.0000000000 0.7126572949 0.8460005557 1.5232972058 0.5211803707 0.7306010990 0.3657262925 -0.246652253707 +1403715906834057984.0000000000 0.6828469205 0.8452217987 1.5272343560 0.5142875506 0.7218405704 0.3806337756 -0.263765871938 +1403715906884058112.0000000000 0.6541634637 0.8439235588 1.5295615203 0.5077652366 0.7120628444 0.3961369802 -0.279672063322 +1403715906934057984.0000000000 0.6264097932 0.8424217123 1.5297788771 0.5023768932 0.7005778352 0.4125010003 -0.294365552989 +1403715906984058112.0000000000 0.5995970104 0.8405935347 1.5272426936 0.4968965306 0.6885638345 0.4283788715 -0.308974474989 +1403715907034057984.0000000000 0.5740945777 0.8387422550 1.5210421549 0.4914405449 0.6757346721 0.4462969526 -0.320449487114 +1403715907084058112.0000000000 0.5497566250 0.8369636723 1.5120520902 0.4857741362 0.6620789874 0.4665341432 -0.328665173615 +1403715907134057984.0000000000 0.5259647911 0.8346778382 1.5032516355 0.4801989788 0.6472030086 0.4872262880 -0.336374420387 +1403715907184058112.0000000000 0.5028567204 0.8311012661 1.4969248622 0.4741977178 0.6312423223 0.5075618340 -0.345037156995 +1403715907234057984.0000000000 0.4805464401 0.8258821128 1.4942868241 0.4654174621 0.6159118594 0.5269780574 -0.355433952291 +1403715907284058112.0000000000 0.4593175841 0.8192263598 1.4958772129 0.4553443889 0.6005192907 0.5450733856 -0.367332374509 +1403715907334057984.0000000000 0.4390731922 0.8112404941 1.5010456529 0.4455124445 0.5845569532 0.5626417399 -0.37847866895 +1403715907384058112.0000000000 0.4200143972 0.8016913745 1.5093689813 0.4362898890 0.5672513401 0.5792747545 -0.390279142086 +1403715907434057984.0000000000 0.4018611288 0.7908704705 1.5199547677 0.4283123125 0.5495334001 0.5958665474 -0.399380348583 +1403715907484058112.0000000000 0.3846362351 0.7784530070 1.5322605099 0.4196144601 0.5325935629 0.6110410651 -0.408529825695 +1403715907534057984.0000000000 0.3684082574 0.7646749272 1.5450723004 0.4109873635 0.5163158756 0.6253077655 -0.416530313433 +1403715907584058112.0000000000 0.3533655814 0.7492486994 1.5581505485 0.4015371918 0.5013095204 0.6380008969 -0.424748753845 +1403715907634057984.0000000000 0.3393779019 0.7321831940 1.5713773680 0.3914732274 0.4873901035 0.6486826116 -0.434062747273 +1403715907684058112.0000000000 0.3265262605 0.7137122656 1.5850165704 0.3822223800 0.4736092195 0.6574743387 -0.444215998594 +1403715907734057984.0000000000 0.3150558061 0.6936145187 1.5985580782 0.3722768483 0.4605476241 0.6643557869 -0.456001340509 +1403715907784058112.0000000000 0.3049751611 0.6722843851 1.6113104912 0.3626695672 0.4472745813 0.6709585803 -0.46715181418 +1403715907834057984.0000000000 0.2965739972 0.6500606012 1.6233837011 0.3534527661 0.4335388877 0.6771474196 -0.478107254835 +1403715907884058112.0000000000 0.2901043689 0.6269602420 1.6347589200 0.3423109198 0.4208921425 0.6833047749 -0.4886385404 +1403715907934057984.0000000000 0.2856395533 0.6035786546 1.6459268814 0.3293025801 0.4092288801 0.6884982327 -0.500061714206 +1403715907984058112.0000000000 0.2826580638 0.5802098388 1.6564750409 0.3162961539 0.3963598598 0.6947197928 -0.510117647206 +1403715908034057984.0000000000 0.2815516911 0.5571023494 1.6661886240 0.3026153667 0.3828694517 0.7012327024 -0.519718789203 +1403715908084058112.0000000000 0.2823635627 0.5347303437 1.6753143776 0.2896207243 0.3678074691 0.7084383934 -0.528159582466 +1403715908134057984.0000000000 0.2844407163 0.5127410943 1.6841629170 0.2764834262 0.3518196118 0.7147831261 -0.537461587815 +1403715908184058112.0000000000 0.2883929361 0.4918785322 1.6915599301 0.2629903120 0.3349418839 0.7229856712 -0.544005284397 +1403715908234057984.0000000000 0.2945885221 0.4726137097 1.6978520268 0.2488079391 0.3173983715 0.7306221237 -0.550948450958 +1403715908284058112.0000000000 0.3023625933 0.4546203292 1.7032554423 0.2344816576 0.2992799258 0.7386434050 -0.556646924488 +1403715908334057984.0000000000 0.3113847392 0.4382852934 1.7084683092 0.2197733903 0.2811361993 0.7463107065 -0.561856230476 +1403715908384058112.0000000000 0.3212053195 0.4233940824 1.7136223720 0.2048017156 0.2626243807 0.7540145436 -0.566168490794 +1403715908434057984.0000000000 0.3317995099 0.4096649038 1.7187528864 0.1899820586 0.2434242893 0.7606113551 -0.571070748047 +1403715908484058112.0000000000 0.3434442972 0.3975108286 1.7236734927 0.1748234187 0.2238455823 0.7669835920 -0.575383434922 +1403715908534057984.0000000000 0.3560066242 0.3869080038 1.7287320233 0.1607784251 0.2025648432 0.7728041124 -0.579561546515 +1403715908584058112.0000000000 0.3698679786 0.3778932483 1.7336862002 0.1455279364 0.1816074125 0.7781122680 -0.583422373508 +1403715908634057984.0000000000 0.3842305659 0.3704521078 1.7381847819 0.1331056999 0.1584358325 0.7826238758 -0.587095246727 +1403715908684058112.0000000000 0.3994394697 0.3642927342 1.7424348302 0.1196450222 0.1359977929 0.7857238096 -0.591462394366 +1403715908734057984.0000000000 0.4154126794 0.3596044986 1.7462977101 0.1063447006 0.1140673166 0.7876710141 -0.596031732003 +1403715908784058112.0000000000 0.4320125037 0.3565352978 1.7496684176 0.0911324805 0.0940411259 0.7889975899 -0.600278219406 +1403715908834057984.0000000000 0.4490882465 0.3552731764 1.7523643131 0.0763748947 0.0744715834 0.7901554469 -0.603552175407 +1403715908884058112.0000000000 0.4668750088 0.3562859134 1.7539169507 0.0613719447 0.0555260374 0.7924905750 -0.604242527528 +1403715908934057984.0000000000 0.4852638801 0.3596709781 1.7545206161 0.0464286170 0.0367392915 0.7963068437 -0.601988387429 +1403715908984058112.0000000000 0.5039860146 0.3646608714 1.7544390526 0.0340957282 0.0162680963 0.8000263245 -0.598774340204 +1403715909034057984.0000000000 0.5228364937 0.3711651669 1.7537883122 0.0231055676 -0.0042539561 0.8029292600 -0.595611148414 +1403715909084058112.0000000000 0.5420712563 0.3788019432 1.7525382055 0.0122260477 -0.0239947497 0.8055805251 -0.591873967385 +1403715909134057984.0000000000 0.5616925896 0.3870973305 1.7508897757 0.0026756653 -0.0440732151 0.8066806274 -0.589335861763 +1403715909184058112.0000000000 0.5822872102 0.3965325116 1.7487305773 0.0093251554 0.0614332103 -0.8079941327 0.58590484184 +1403715909234057984.0000000000 0.6034569716 0.4065682263 1.7461447805 0.0197752156 0.0788899277 -0.8078611902 0.583734201131 +1403715909284058112.0000000000 0.6256122537 0.4171830561 1.7433180845 0.0327425707 0.0941032366 -0.8075517138 0.581319821102 +1403715909334057984.0000000000 0.6481807966 0.4278736937 1.7400453900 0.0430298766 0.1101687427 -0.8058382530 0.580203402164 +1403715909384058112.0000000000 0.6712736773 0.4391588184 1.7358905058 0.0525114003 0.1261502730 -0.8041003591 0.578576938626 +1403715909434057984.0000000000 0.6950643891 0.4509557828 1.7309823472 0.0618492291 0.1418638802 -0.8018072221 0.577195366332 +1403715909484058112.0000000000 0.7196799330 0.4632709998 1.7249653605 0.0687657455 0.1592970272 -0.7977978313 0.577420427185 +1403715909534057984.0000000000 0.7455642853 0.4763662906 1.7175189717 0.0755144706 0.1774629419 -0.7938092591 0.57677667186 +1403715909584058112.0000000000 0.7728795150 0.4903882063 1.7091831014 0.0829430848 0.1962323184 -0.7899736524 0.574939084131 +1403715909634057984.0000000000 0.8018152283 0.5057556986 1.7009426922 0.0932073387 0.2142455266 -0.7850810205 0.573636677277 +1403715909684058112.0000000000 0.8325154629 0.5226535228 1.6928001602 0.1069920602 0.2310192348 -0.7794609353 0.57238401664 +1403715909734057984.0000000000 0.8644315394 0.5411474723 1.6836195222 0.1210676717 0.2487163094 -0.7744385163 0.568970825963 +1403715909784058112.0000000000 0.8978442467 0.5610873684 1.6745751200 0.1377792241 0.2658559964 -0.7684699027 0.56550109038 +1403715909834057984.0000000000 0.9325944352 0.5825522212 1.6649938112 0.1547430047 0.2847218666 -0.7611024182 0.561881811505 +1403715909884058112.0000000000 0.9685176338 0.6057281546 1.6557532215 0.1759862434 0.3020827325 -0.7522639736 0.558456604274 +1403715909934057984.0000000000 1.0047129935 0.6304811033 1.6467329712 0.1990882988 0.3190537395 -0.7415576336 0.555572530566 +1403715909984058112.0000000000 1.0404564479 0.6568929816 1.6373048784 0.2218596346 0.3372854302 -0.7294867386 0.552146664709 +1403715910034057984.0000000000 1.0751933729 0.6847825399 1.6270867527 0.2434458402 0.3570092015 -0.7166213497 0.547478213387 +1403715910084058112.0000000000 1.1084038092 0.7141077705 1.6159630541 0.2631675042 0.3782984119 -0.7034247966 0.541134670636 +1403715910134057984.0000000000 1.1396180156 0.7448347999 1.6034554616 0.2805920295 0.4004025226 -0.6911560940 0.532211599432 +1403715910184058112.0000000000 1.1690756441 0.7764966911 1.5904905954 0.2971311346 0.4220487219 -0.6791821373 0.521823331727 +1403715910234057984.0000000000 1.1965718388 0.8086069247 1.5766999784 0.3099898423 0.4438251365 -0.6672889767 0.511518296285 +1403715910284058112.0000000000 1.2229232976 0.8412121715 1.5635924248 0.3243610187 0.4629468089 -0.6547460055 0.50177470034 +1403715910334057984.0000000000 1.2478131913 0.8741081117 1.5514237591 0.3376453735 0.4802180092 -0.6420906250 0.493057699121 +1403715910384058112.0000000000 1.2709486520 0.9074454462 1.5398841412 0.3505496775 0.4956334623 -0.6286490104 0.486068736287 +1403715910434057984.0000000000 1.2923493716 0.9413548998 1.5284206630 0.3639717781 0.5088869697 -0.6143375697 0.480778480554 +1403715910484058112.0000000000 1.3119517593 0.9755939310 1.5171029515 0.3766158520 0.5211289023 -0.5998829214 0.476157167098 +1403715910534057984.0000000000 1.3287748363 1.0105307499 1.5063607779 0.3887573254 0.5327410052 -0.5857396032 0.471130428473 +1403715910584058112.0000000000 1.3430783250 1.0458750857 1.4959752137 0.3997299695 0.5439896855 -0.5726980682 0.465089342115 +1403715910634057984.0000000000 1.3549093366 1.0819318706 1.4859978863 0.4096235304 0.5551563967 -0.5612425889 0.457183436903 +1403715910684058112.0000000000 1.3637077284 1.1185140112 1.4772685332 0.4185313333 0.5662134441 -0.5503020064 0.448777852159 +1403715910734057984.0000000000 1.3706127595 1.1556195487 1.4690695833 0.4273850144 0.5768066504 -0.5405298091 0.438706807511 +1403715910784058112.0000000000 1.3752954318 1.1927645751 1.4619707451 0.4355721417 0.5870718576 -0.5296499616 0.430226058653 +1403715910834057984.0000000000 1.3777510698 1.2301628139 1.4555880548 0.4442873279 0.5965365284 -0.5186711250 0.421584160753 +1403715910884058112.0000000000 1.3772146445 1.2675443429 1.4496630796 0.4524666071 0.6060291817 -0.5078648084 0.412402639183 +1403715910934057984.0000000000 1.3736817780 1.3049166127 1.4433948378 0.4605519168 0.6154634958 -0.4970249220 0.402570297239 +1403715910984058112.0000000000 1.3676326963 1.3422674895 1.4375351170 0.4679717189 0.6249849831 -0.4869771970 0.391470881312 +1403715911034057984.0000000000 1.3590427120 1.3791693312 1.4322695015 0.4766698250 0.6331109120 -0.4757831703 0.381558417296 +1403715911084058112.0000000000 1.3482795002 1.4157467832 1.4275064397 0.4867201144 0.6399643251 -0.4633875547 0.372587126663 +1403715911134057984.0000000000 1.3350456023 1.4513717131 1.4232223042 0.4970624078 0.6459727132 -0.4505415989 0.364225869839 +1403715911184058112.0000000000 1.3192704344 1.4860527143 1.4186756253 0.5067201933 0.6524860455 -0.4374655957 0.355134423333 +1403715911234057984.0000000000 1.3009464006 1.5196168979 1.4143408381 0.5154803051 0.6595386306 -0.4240973204 0.345586910359 +1403715911284058112.0000000000 1.2797513435 1.5517111992 1.4097326831 0.5221316828 0.6680493732 -0.4108812474 0.335059907001 +1403715911334057984.0000000000 1.2561761706 1.5823809064 1.4053100960 0.5282292023 0.6765552060 -0.3985853506 0.323073801771 +1403715911384058112.0000000000 1.2300372867 1.6113366794 1.4008119605 0.5335581961 0.6850881253 -0.3866492552 0.310599847826 +1403715911434057984.0000000000 1.2021029200 1.6387214528 1.3957751773 0.5378379034 0.6937779879 -0.3748564260 0.298136131753 +1403715911484058112.0000000000 1.1722938520 1.6641056013 1.3902828406 0.5406238870 0.7028229023 -0.3644830987 0.284460632826 +1403715911534057984.0000000000 1.1408180951 1.6876207351 1.3841711414 0.5422840420 0.7118175133 -0.3546545355 0.271042443271 +1403715911584058112.0000000000 1.1081170811 1.7093271255 1.3776612655 0.5413700001 0.7222365508 -0.3444756009 0.258126806149 +1403715911634057984.0000000000 1.0745891230 1.7294474003 1.3711499043 0.5405157119 0.7320703052 -0.3327877651 0.247321929454 +1403715911684058112.0000000000 1.0406341924 1.7483659793 1.3651183446 0.5388855615 0.7418829167 -0.3201110957 0.238203643723 +1403715911734057984.0000000000 1.0067466837 1.7663437776 1.3611429582 0.5382934382 0.7504697881 -0.3053636354 0.231923094391 +1403715911784058112.0000000000 0.9727809107 1.7839363534 1.3602610640 0.5383383919 0.7579696116 -0.2908679815 0.225985975174 +1403715911834057984.0000000000 0.9380060956 1.8012241672 1.3631386970 0.5398073397 0.7640352237 -0.2776276958 0.218588827401 +1403715911884058112.0000000000 0.9023291462 1.8180509462 1.3696359764 0.5422912652 0.7688168864 -0.2645325820 0.211809565181 +1403715911934057984.0000000000 0.8661400147 1.8348429985 1.3791368460 0.5446560548 0.7730529650 -0.2528810123 0.204426243287 +1403715911984058112.0000000000 0.8296369353 1.8517603495 1.3922354156 0.5478905534 0.7761698646 -0.2424331333 0.196475084133 +1403715912034057984.0000000000 0.7926476862 1.8684808015 1.4082117672 0.5502852796 0.7792731245 -0.2332739375 0.188421810039 +1403715912084058112.0000000000 0.7550624534 1.8847886665 1.4256653956 0.5529405108 0.7817426205 -0.2254818843 0.179703051061 +1403715912134057984.0000000000 0.7172625627 1.9011818587 1.4437179462 0.5561897614 0.7833235533 -0.2188644592 0.170749842202 +1403715912184058112.0000000000 0.6791806821 1.9171927347 1.4611238834 0.5584140199 0.7854242500 -0.2115097946 0.162929851999 +1403715912234057984.0000000000 0.6409241960 1.9328495504 1.4782493538 0.5612476212 0.7869002229 -0.2047184884 0.154529891519 +1403715912284058112.0000000000 0.6027328691 1.9479384040 1.4947147187 0.5638879028 0.7883255632 -0.1971729362 0.147295868129 +1403715912334057984.0000000000 0.5644540467 1.9625680140 1.5105499780 0.5663095841 0.7897555466 -0.1894253042 0.140348443936 +1403715912384058112.0000000000 0.5264012152 1.9768045748 1.5257546238 0.5679432428 0.7916349105 -0.1812801667 0.133761513913 +1403715912434057984.0000000000 0.4883048814 1.9901665708 1.5404212855 0.5689132437 0.7939745250 -0.1728941213 0.126687795716 +1403715912484058112.0000000000 0.4501966708 2.0030875528 1.5546720552 0.5703737668 0.7959900083 -0.1636641215 0.119531284905 +1403715912534057984.0000000000 0.4124110579 2.0154484478 1.5686784763 0.5717674093 0.7979853164 -0.1542314391 0.111866561464 +1403715912584058112.0000000000 0.3745875296 2.0274453524 1.5822308479 0.5726728291 0.8004085692 -0.1440389589 0.103173307442 +1403715912634057984.0000000000 0.3367656346 2.0388135491 1.5954915973 0.5739418967 0.8025614079 -0.1327704062 0.0941164444975 +1403715912684058112.0000000000 0.2992081793 2.0495592354 1.6083709850 0.5753251761 0.8045655844 -0.1199302042 0.0853926710347 +1403715912734057984.0000000000 0.2615878563 2.0600199252 1.6216664933 0.5773283830 0.8061096143 -0.1062729646 0.0747347633042 +1403715912784058112.0000000000 0.2241489597 2.0697499990 1.6349116068 0.5791112147 0.8076574831 -0.0912370634 0.0632090913028 +1403715912834057984.0000000000 0.1869681159 2.0785016170 1.6472486894 0.5802520195 0.8093901100 -0.0742762478 0.0517521274953 +1403715912884058112.0000000000 0.1499532625 2.0868626523 1.6571560412 0.5817968980 0.8104499661 -0.0563008842 0.0389028574348 +1403715912934057984.0000000000 0.1133089914 2.0944937116 1.6637023656 0.5822056962 0.8117696801 -0.0372340013 0.0260795501671 +1403715912984058112.0000000000 0.0771026517 2.1014487964 1.6668926051 0.5828690828 0.8122530956 -0.0183834279 0.0130610341238 +1403715913034057984.0000000000 0.0414573651 2.1077190998 1.6665308626 0.5833164567 0.8122438875 -0.0004784452 -0.00124484281677 +1403715913084058112.0000000000 0.0064639862 2.1137070636 1.6627993936 0.5834556990 0.8118242275 0.0181721053 -0.0138074432957 +1403715913134057984.0000000000 -0.0283020842 2.1190250999 1.6567652648 0.5834441339 0.8108911687 0.0370541818 -0.0259892834918 +1403715913184058112.0000000000 -0.0626401502 2.1234675054 1.6495372860 0.5843986301 0.8086523747 0.0552793479 -0.0387784940339 +1403715913234057984.0000000000 -0.0961421482 2.1273845414 1.6424111958 0.5871484372 0.8046192151 0.0726414825 -0.0506739222176 +1403715913284058112.0000000000 -0.1287045197 2.1306867217 1.6351004978 0.5901278025 0.7998970393 0.0913433966 -0.0597518796499 +1403715913334057984.0000000000 -0.1603465783 2.1336397153 1.6280730103 0.5936056963 0.7945326651 0.1097100727 -0.0656796868123 +1403715913384058112.0000000000 -0.1913644021 2.1358415903 1.6210841711 0.5961766679 0.7897605921 0.1270487093 -0.0686309929017 +1403715913434057984.0000000000 -0.2221611259 2.1365434111 1.6148808931 0.5994874135 0.7845275380 0.1416403895 -0.0711996010837 +1403715913484058112.0000000000 -0.2528841866 2.1354988816 1.6094174900 0.6035604380 0.7790523977 0.1533862183 -0.0725591296503 +1403715913534057984.0000000000 -0.2836420377 2.1323565099 1.6040020904 0.6075537050 0.7738491633 0.1641735671 -0.07129521704 +1403715913584058112.0000000000 -0.3143034453 2.1262445957 1.5979830462 0.6118375600 0.7683750256 0.1762335384 -0.0647793188513 +1403715913634057984.0000000000 -0.3459271404 2.1171388981 1.5919819699 0.6157819523 0.7635125918 0.1853168146 -0.0593193697546 +1403715913684058112.0000000000 -0.3793277323 2.1047503949 1.5868928292 0.6189891120 0.7595555155 0.1922546584 -0.0544614034404 +1403715913734057984.0000000000 -0.4145173325 2.0878425319 1.5821870510 0.6188711374 0.7588498835 0.1958552600 -0.0527833937422 +1403715913784058112.0000000000 -0.4520930317 2.0672042528 1.5776312186 0.6164340677 0.7606499443 0.1962592527 -0.0538795698376 +1403715913834057984.0000000000 -0.4922257998 2.0429697550 1.5738995217 0.6108722077 0.7652434894 0.1953250541 -0.0555488169775 +1403715913884058112.0000000000 -0.5345291499 2.0154365612 1.5711180580 0.6046595652 0.7705459662 0.1931346514 -0.0578336463838 +1403715913934057984.0000000000 -0.5787061822 1.9848140146 1.5696677321 0.5990614420 0.7754410882 0.1901355573 -0.0605390566259 +1403715913984058112.0000000000 -0.6247828696 1.9519212429 1.5692440155 0.5952683432 0.7789103979 0.1872050962 -0.0625175471767 +1403715914034057984.0000000000 -0.6723965959 1.9167847438 1.5693667315 0.5921280680 0.7818458846 0.1848696930 -0.0626463113072 +1403715914084058112.0000000000 -0.7215042317 1.8799199820 1.5703721291 0.5909478016 0.7831809358 0.1837239314 -0.0604469568388 +1403715914134057984.0000000000 -0.7723573561 1.8413480663 1.5715716695 0.5897919487 0.7846203709 0.1819808426 -0.0583035490755 +1403715914184058112.0000000000 -0.8254322233 1.8011811587 1.5735755053 0.5890662894 0.7862046455 0.1771623511 -0.0591325923977 +1403715914234057984.0000000000 -0.8800799152 1.7591053778 1.5757422839 0.5833569294 0.7920839472 0.1682409593 -0.0631877601555 +1403715914284058112.0000000000 -0.9358054426 1.7162301116 1.5782849726 0.5766650420 0.7987809436 0.1581982818 -0.066179582846 +1403715914334057984.0000000000 -0.9923573231 1.6731345580 1.5808442231 0.5682722425 0.8066254469 0.1479826425 -0.0672546236324 +1403715914384058112.0000000000 -1.0495177221 1.6304389411 1.5836818652 0.5590971392 0.8148133891 0.1380931031 -0.0664817633072 +1403715914434057984.0000000000 -1.1069496161 1.5887427202 1.5867946934 0.5506392773 0.8223244146 0.1283835477 -0.0640047504953 +1403715914484058112.0000000000 -1.1645822203 1.5483967146 1.5902581695 0.5442384670 0.8282476828 0.1196772412 -0.0590561167182 +1403715914534057984.0000000000 -1.2228926283 1.5098717698 1.5943101690 0.5382777514 0.8336629259 0.1108191535 -0.0546104703426 +1403715914584058112.0000000000 -1.2814980836 1.4736357299 1.5992077680 0.5342692429 0.8377657947 0.1007243452 -0.0505910625336 +1403715914634057984.0000000000 -1.3407012686 1.4398582834 1.6040536675 0.5292527463 0.8424663151 0.0882607698 -0.0484981955457 +1403715914684058112.0000000000 -1.4003376001 1.4089630356 1.6090214861 0.5236166658 0.8474023206 0.0729592605 -0.0491104934774 +1403715914734057984.0000000000 -1.4596124519 1.3814224502 1.6137685375 0.5183101573 0.8518363055 0.0563201396 -0.0505720410861 +1403715914784058112.0000000000 -1.5184921305 1.3575069156 1.6185144540 0.5115213550 0.8566131588 0.0361639249 -0.0570260474546 +1403715914834057984.0000000000 -1.5758437646 1.3376554872 1.6229250254 0.5050601090 0.8605815453 0.0182449812 -0.0630936669719 +1403715914884058112.0000000000 -1.6309169058 1.3219334608 1.6273607223 0.4994454044 0.8635892103 0.0017353032 -0.0690286363141 +1403715914934057984.0000000000 -1.6827496792 1.3106334368 1.6312617692 0.4955891335 0.8654836662 -0.0107413499 -0.0722084316682 +1403715914984058112.0000000000 -1.7310038701 1.3043974647 1.6350064948 0.4937510822 0.8662123817 -0.0203844261 -0.0739625164029 +1403715915034057984.0000000000 -1.7753472473 1.3034261011 1.6390093625 0.4925221365 0.8664999110 -0.0288374534 -0.0759490003018 +1403715915084058112.0000000000 -1.8152309514 1.3075360286 1.6429655231 0.4921643232 0.8663140373 -0.0352482702 -0.0776648389739 +1403715915134057984.0000000000 -1.8504445059 1.3168599331 1.6468411380 0.4927099471 0.8658956779 -0.0388280165 -0.07716196011 +1403715915184058112.0000000000 -1.8810260167 1.3314625464 1.6511843347 0.4956206038 0.8641399776 -0.0412444060 -0.0769494324953 +1403715915234057984.0000000000 -1.9063886698 1.3516160427 1.6558055667 0.5041472711 0.8598918326 -0.0382938247 -0.0703928135785 +1403715915284058112.0000000000 -1.9274134991 1.3755146536 1.6605110300 0.5148798238 0.8544679617 -0.0321497973 -0.0612344678568 +1403715915334057984.0000000000 -1.9449802591 1.4026846069 1.6644612073 0.5256402288 0.8490242209 -0.0220352205 -0.0487305993528 +1403715915384058112.0000000000 -1.9598564768 1.4323471037 1.6665360904 0.5356492261 0.8435367165 -0.0122920356 -0.0370758729992 +1403715915434057984.0000000000 -1.9730826876 1.4638328937 1.6645618449 0.5424419063 0.8396772530 -0.0025734239 -0.0263109591454 +1403715915484058112.0000000000 -1.9855474407 1.4969895266 1.6593183991 0.5484065467 0.8359754759 0.0043688092 -0.0193952736828 +1403715915534057984.0000000000 -1.9972921522 1.5313892642 1.6504768579 0.5529834840 0.8330078645 0.0091385875 -0.0149549433901 +1403715915584058112.0000000000 -2.0084950537 1.5667400353 1.6383004392 0.5569177996 0.8303759414 0.0140221030 -0.0110336376618 +1403715915634057984.0000000000 -2.0192344598 1.6026682581 1.6231355998 0.5598651044 0.8283223714 0.0201355840 -0.0052604288659 +1403715915684058112.0000000000 -2.0302061790 1.6394829015 1.6069872681 0.5619620790 0.8267771402 0.0252477304 -0.000856962584522 +1403715915734057984.0000000000 -2.0417377650 1.6762631193 1.5902959760 0.5606547939 0.8275740391 0.0280602385 -0.000186665462225 +1403715915784058112.0000000000 -2.0539708683 1.7137211809 1.5738567245 0.5574925788 0.8296857312 0.0286134037 -0.00221025013485 +1403715915834057984.0000000000 -2.0665962615 1.7519976107 1.5575030457 0.5530352893 0.8326534640 0.0285745222 -0.00486563736728 +1403715915884058112.0000000000 -2.0796027435 1.7911791069 1.5413161978 0.5482224863 0.8358020176 0.0288459102 -0.00741662275962 +1403715915934057984.0000000000 -2.0927029940 1.8316211578 1.5256894320 0.5444680119 0.8382263309 0.0289069752 -0.00977696122667 +1403715915984058112.0000000000 -2.1059334989 1.8738883799 1.5109384735 0.5447284214 0.8380155798 0.0292596726 -0.0120294013078 +1403715916034057984.0000000000 -2.1191899843 1.9178961342 1.4965153655 0.5474185622 0.8362322532 0.0293783186 -0.0136180334489 +1403715916084058112.0000000000 -2.1322490499 1.9628879494 1.4822908693 0.5512574007 0.8337378399 0.0283621870 -0.0138592516429 +1403715916134057984.0000000000 -2.1448099593 2.0089512868 1.4675693072 0.5532226479 0.8325324182 0.0263822906 -0.0117664464046 +1403715916184058112.0000000000 -2.1568238406 2.0562811000 1.4532514801 0.5574470526 0.8298873325 0.0216280910 -0.00848672613215 +1403715916234057984.0000000000 -2.1683835122 2.1039807766 1.4388175877 0.5606468700 0.8279115139 0.0147878129 -0.00435119029801 +1403715916284058112.0000000000 -2.1792740698 2.1522418433 1.4244061069 0.5630499362 0.8263979489 0.0061752277 0.00175099530517 +1403715916334057984.0000000000 -2.1897231029 2.2010573103 1.4107932126 0.5653023074 0.8248219898 -0.0037666492 0.00937009851559 +1403715916384058112.0000000000 -2.1998439706 2.2500016746 1.3973642813 0.5671603547 0.8233005618 -0.0154907746 0.016289656155 +1403715916434057984.0000000000 -2.2095342281 2.2992223182 1.3840921009 0.5686071205 0.8217926683 -0.0287521152 0.0227171470665 +1403715916484058112.0000000000 -2.2188370348 2.3484740096 1.3705659459 0.5681467848 0.8212597859 -0.0435206095 0.0291127384639 +1403715916534057984.0000000000 -2.2274360356 2.3977771082 1.3574590471 0.5663867222 0.8212394714 -0.0589335148 0.0360368213045 +1403715916584058112.0000000000 -2.2351182592 2.4466222669 1.3446045589 0.5650651429 0.8205195714 -0.0737036826 0.0449086236277 +1403715916634057984.0000000000 -2.2422959622 2.4952540036 1.3320078442 0.5636319460 0.8194204151 -0.0906897344 0.0514255267664 +1403715916684058112.0000000000 -2.2484632794 2.5439042703 1.3196713703 0.5621451879 0.8180321171 -0.1076428385 0.0568265998353 +1403715916734057984.0000000000 -2.2538154017 2.5923721753 1.3081896355 0.5612544424 0.8161436581 -0.1235657893 0.0602866147523 +1403715916784058112.0000000000 -2.2578412449 2.6407430201 1.2973024069 0.5604657194 0.8140845556 -0.1387295527 0.0624389697555 +1403715916834057984.0000000000 -2.2601734318 2.6886938507 1.2867167308 0.5593604914 0.8122807337 -0.1521355939 0.0645802706034 +1403715916884058112.0000000000 -2.2610076193 2.7361988858 1.2777313268 0.5599524260 0.8091938417 -0.1665208132 0.0626851337321 +1403715916934057984.0000000000 -2.2588876787 2.7833636976 1.2699252875 0.5618934909 0.8053785406 -0.1778600328 0.0633002366763 +1403715916984058112.0000000000 -2.2540554970 2.8297474905 1.2626051253 0.5635604571 0.8019232842 -0.1877773474 0.0637049861826 +1403715917034057984.0000000000 -2.2461192420 2.8750396276 1.2563689946 0.5659993294 0.7982294623 -0.1957503417 0.0644692825796 +1403715917084058112.0000000000 -2.2341992836 2.9197259951 1.2512837758 0.5709150648 0.7933309371 -0.1990994504 0.0710029711526 +1403715917134057984.0000000000 -2.2181294770 2.9632972439 1.2479002051 0.5802868994 0.7852516844 -0.1995349905 0.0826601110873 +1403715917184058112.0000000000 -2.1985609389 3.0047075870 1.2445815961 0.5884440503 0.7778644407 -0.1953014576 0.102556580684 +1403715917234057984.0000000000 -2.1775587274 3.0437517956 1.2416472551 0.5949076472 0.7709392130 -0.1908276221 0.123783843316 +1403715917284058112.0000000000 -2.1568612338 3.0791021974 1.2379366491 0.5972864025 0.7662628117 -0.1899921302 0.141397479649 +1403715917334057984.0000000000 -2.1369413038 3.1115027400 1.2347223423 0.5996512186 0.7613583271 -0.1912018301 0.155543479238 +1403715917384058112.0000000000 -2.1186976064 3.1410707912 1.2316115306 0.6000536562 0.7584063816 -0.1937116303 0.16501870868 +1403715917434057984.0000000000 -2.1023357179 3.1678277918 1.2290741361 0.5987740850 0.7572693953 -0.1970032372 0.170887046479 +1403715917484058112.0000000000 -2.0883462748 3.1918755855 1.2269017206 0.5947473912 0.7589727677 -0.2040472899 0.169117066034 +1403715917534057984.0000000000 -2.0758140424 3.2134831988 1.2238402337 0.5876861682 0.7632958649 -0.2103557798 0.166597828119 +1403715917584058112.0000000000 -2.0648223993 3.2327518592 1.2199643070 0.5823423075 0.7665850187 -0.2183008897 0.159904870158 +1403715917634057984.0000000000 -2.0538087520 3.2505826807 1.2145203429 0.5789583198 0.7685699284 -0.2243561712 0.154181184155 +1403715917684058112.0000000000 -2.0421149677 3.2674114983 1.2078334020 0.5799920642 0.7673775358 -0.2291753945 0.149062274264 +1403715917734057984.0000000000 -2.0299837982 3.2826965301 1.2003470392 0.5848246684 0.7635919611 -0.2316677661 0.145730814558 +1403715917784058112.0000000000 -2.0174570724 3.2956153991 1.1916886922 0.5904152267 0.7593265378 -0.2317638052 0.145322426749 +1403715917834057984.0000000000 -2.0045242579 3.3054531277 1.1834413464 0.5962206832 0.7550521814 -0.2301014050 0.146527962094 +1403715917884058112.0000000000 -1.9916814119 3.3123253695 1.1761691091 0.6013155923 0.7514540305 -0.2276622211 0.148007809133 +1403715917934057984.0000000000 -1.9792105372 3.3152207858 1.1699810235 0.6044931586 0.7493742959 -0.2241351606 0.150962298279 +1403715917984058112.0000000000 -1.9669584821 3.3145611881 1.1647532216 0.6063877053 0.7484253739 -0.2196971023 0.154552883956 +1403715918034057984.0000000000 -1.9552529261 3.3100183330 1.1603768137 0.6063007851 0.7485985648 -0.2151792939 0.160304142519 +1403715918084058112.0000000000 -1.9439916097 3.3020030434 1.1560476362 0.6033825956 0.7501811715 -0.2120188063 0.167945464523 +1403715918134057984.0000000000 -1.9336851396 3.2907748632 1.1514014425 0.5983018185 0.7527006738 -0.2107271968 0.176268766752 +1403715918184058112.0000000000 -1.9245427404 3.2769420526 1.1472677786 0.5950213701 0.7530961555 -0.2113980818 0.184679724533 +1403715918234057984.0000000000 -1.9170371613 3.2610921896 1.1439657996 0.5941803381 0.7512989192 -0.2163935754 0.188874245013 +1403715918284058112.0000000000 -1.9112495693 3.2430336276 1.1406800332 0.5936555846 0.7489381284 -0.2245922296 0.190323559064 +1403715918334057984.0000000000 -1.9071908523 3.2226998334 1.1348958967 0.5907685936 0.7482091057 -0.2367927655 0.187362721079 +1403715918384058112.0000000000 -1.9044389504 3.2001898224 1.1256538318 0.5851508997 0.7492485648 -0.2509871329 0.18229227041 +1403715918434057984.0000000000 -1.9023168713 3.1759264330 1.1125482816 0.5785278901 0.7505564681 -0.2656797051 0.177157452147 +1403715918484058112.0000000000 -1.9000802435 3.1498060027 1.0959442677 0.5709697310 0.7522590076 -0.2794673710 0.173199135034 +1403715918534057984.0000000000 -1.8972638071 3.1217039281 1.0769464389 0.5648377503 0.7526817070 -0.2914201934 0.171763892427 +1403715918584058112.0000000000 -1.8936984090 3.0918708783 1.0549541674 0.5597622374 0.7522854109 -0.3022989906 0.171313217352 +1403715918634057984.0000000000 -1.8884746131 3.0607201325 1.0314797710 0.5554288118 0.7519826298 -0.3094536369 0.173952309912 +1403715918684058112.0000000000 -1.8816718746 3.0277615657 1.0088621821 0.5507383345 0.7524579601 -0.3135201879 0.179441904062 +1403715918734057984.0000000000 -1.8736308334 2.9931894517 0.9887841225 0.5448794100 0.7545785345 -0.3145894732 0.186416542265 +1403715918784058112.0000000000 -1.8640180607 2.9576240906 0.9724846087 0.5390430420 0.7570634540 -0.3127192217 0.196199423853 +1403715918834057984.0000000000 -1.8539287385 2.9213581511 0.9592044475 0.5304799607 0.7619354405 -0.3103182202 0.204323268296 +1403715918884058112.0000000000 -1.8433482366 2.8851072954 0.9490371799 0.5204504967 0.7681354768 -0.3078563236 0.210531835427 +1403715918934057984.0000000000 -1.8325240069 2.8496608486 0.9430433042 0.5104665325 0.7743796194 -0.3068003249 0.213620422259 +1403715918984058112.0000000000 -1.8211828182 2.8159495127 0.9408181904 0.5013991576 0.7801733141 -0.3067760877 0.21404886511 +1403715919034057984.0000000000 -1.8088890557 2.7846172533 0.9421041432 0.4928479169 0.7855173865 -0.3071046676 0.213892705527 +1403715919084058112.0000000000 -1.7954314050 2.7558639462 0.9467781118 0.4853632495 0.7903636343 -0.3053872991 0.215607140586 +1403715919134057984.0000000000 -1.7805271104 2.7300544577 0.9534806706 0.4813018142 0.7932507426 -0.3008423354 0.220444351958 +1403715919184058112.0000000000 -1.7644230047 2.7074802166 0.9606947868 0.4790658360 0.7950903143 -0.2936706421 0.228221101039 +1403715919234057984.0000000000 -1.7475244229 2.6886818108 0.9684282599 0.4790907838 0.7954061619 -0.2851197649 0.237713647535 +1403715919284058112.0000000000 -1.7304942507 2.6740886012 0.9767114508 0.4823249202 0.7937197061 -0.2760401276 0.247332867552 +1403715919334057984.0000000000 -1.7142794373 2.6632947046 0.9844090459 0.4858167281 0.7917782136 -0.2669454662 0.256533594616 +1403715919384058112.0000000000 -1.7000896848 2.6559269344 0.9904012519 0.4914891040 0.7885939401 -0.2641994024 0.258373245465 +1403715919434057984.0000000000 -1.6880007890 2.6514964532 0.9933905678 0.4977289704 0.7852343902 -0.2669493980 0.253792914346 +1403715919484058112.0000000000 -1.6773864978 2.6495287978 0.9929231928 0.5042372409 0.7815960943 -0.2707057083 0.248134579966 +1403715919534057984.0000000000 -1.6677961741 2.6495904132 0.9889060688 0.5098666697 0.7782457186 -0.2745362139 0.242898019545 +1403715919584058112.0000000000 -1.6589515660 2.6511767708 0.9813379271 0.5146719372 0.7752278945 -0.2777851022 0.238683777484 +1403715919634057984.0000000000 -1.6508407873 2.6540517754 0.9701060822 0.5179461174 0.7730654031 -0.2805081450 0.235407906823 +1403715919684058112.0000000000 -1.6433451624 2.6582007634 0.9555802334 0.5195018264 0.7719068966 -0.2818207413 0.234210728001 +1403715919734057984.0000000000 -1.6364550394 2.6635493367 0.9379653112 0.5197404070 0.7715430116 -0.2818477429 0.23484705747 +1403715919784058112.0000000000 -1.6298373561 2.6699768968 0.9179694686 0.5193973518 0.7714370392 -0.2800544497 0.238077278982 +1403715919834057984.0000000000 -1.6243600152 2.6776106554 0.8969669840 0.5192044088 0.7714354941 -0.2789599600 0.239781986468 +1403715919884058112.0000000000 -1.6201338671 2.6861948301 0.8753656348 0.5184428799 0.7718592218 -0.2776862656 0.241538112581 +1403715919934057984.0000000000 -1.6177213431 2.6962946704 0.8538886965 0.5164262808 0.7733992611 -0.2779065315 0.240677043474 +1403715919984058112.0000000000 -1.6166445877 2.7080900708 0.8339999444 0.5126808430 0.7762734470 -0.2797197727 0.237307263939 +1403715920034057984.0000000000 -1.6162443064 2.7219362950 0.8176358421 0.5095703680 0.7787054267 -0.2808263345 0.234717848362 +1403715920084058112.0000000000 -1.6166224405 2.7375816079 0.8049662266 0.5071406810 0.7807674475 -0.2822232770 0.23143151159 +1403715920134057984.0000000000 -1.6176153299 2.7549820695 0.7959549277 0.5050153779 0.7826056572 -0.2838729596 0.227824485567 +1403715920184058112.0000000000 -1.6190646493 2.7739078032 0.7904746875 0.5040688842 0.7835916345 -0.2851620394 0.224902915945 +1403715920234057984.0000000000 -1.6203435019 2.7952902865 0.7887016280 0.5047165217 0.7837670533 -0.2869938085 0.220465400195 +1403715920284058112.0000000000 -1.6212436525 2.8193237769 0.7918420099 0.5091336975 0.7818924507 -0.2874348678 0.216352190525 +1403715920334057984.0000000000 -1.6218059000 2.8449793809 0.7983554133 0.5149035063 0.7794826970 -0.2869919881 0.211935610603 +1403715920384058112.0000000000 -1.6222218389 2.8717006127 0.8071467378 0.5198662473 0.7774881866 -0.2858551727 0.208657674022 +1403715920434057984.0000000000 -1.6222908252 2.8992755644 0.8176051657 0.5266930887 0.7740045435 -0.2853593790 0.205137470218 +1403715920484058112.0000000000 -1.6219795870 2.9271216354 0.8284970396 0.5329315402 0.7707667773 -0.2842280975 0.20277311711 +1403715920534057984.0000000000 -1.6212330748 2.9551003792 0.8394992102 0.5398382342 0.7669337411 -0.2830132628 0.200725710405 +1403715920584058112.0000000000 -1.6200923334 2.9826292325 0.8502545258 0.5464555901 0.7629597857 -0.2819423834 0.199467154819 +1403715920634057984.0000000000 -1.6188487004 3.0091964534 0.8603838409 0.5526260712 0.7592198014 -0.2809568535 0.198123610616 +1403715920684058112.0000000000 -1.6176082817 3.0346362571 0.8711824848 0.5584485585 0.7558071959 -0.2795061533 0.196893373086 +1403715920734057984.0000000000 -1.6165925245 3.0585837562 0.8841279984 0.5641475311 0.7527465560 -0.2763246229 0.19686261295 +1403715920784058112.0000000000 -1.6164654046 3.0806783145 0.9003364626 0.5689873191 0.7509137539 -0.2729986384 0.194560295084 +1403715920834057984.0000000000 -1.6169191792 3.1010845324 0.9182823302 0.5715926289 0.7510984977 -0.2680011478 0.193153560915 +1403715920884058112.0000000000 -1.6185884755 3.1195096141 0.9389847160 0.5724862096 0.7529797315 -0.2635127804 0.189320042006 +1403715920934057984.0000000000 -1.6212897475 3.1356726442 0.9624377093 0.5719174538 0.7563727091 -0.2598666571 0.182428264091 +1403715920984058112.0000000000 -1.6246556333 3.1493756398 0.9877841990 0.5681215440 0.7623633153 -0.2565119950 0.173901360185 +1403715921034057984.0000000000 -1.6280745621 3.1611580147 1.0156521203 0.5642260992 0.7684466050 -0.2525635285 0.165379527651 +1403715921084058112.0000000000 -1.6309715304 3.1714033635 1.0445246963 0.5601655520 0.7746512263 -0.2469949949 0.158503956905 +1403715921134057984.0000000000 -1.6327704275 3.1807024840 1.0737442685 0.5569429489 0.7799320712 -0.2409042094 0.153250376142 +1403715921184058112.0000000000 -1.6332799697 3.1893047790 1.1035612676 0.5559915940 0.7831218525 -0.2347191917 0.150001375518 +1403715921234057984.0000000000 -1.6327569606 3.1974951815 1.1327450836 0.5546088572 0.7862057596 -0.2291111857 0.147640047911 +1403715921284058112.0000000000 -1.6309376894 3.2052224077 1.1612612515 0.5536324954 0.7885852103 -0.2231091149 0.147806457772 +1403715921334057984.0000000000 -1.6283780259 3.2123951399 1.1891897163 0.5512210755 0.7916691492 -0.2174360995 0.148784497419 +1403715921384058112.0000000000 -1.6251735847 3.2194285818 1.2168717815 0.5486910478 0.7945688295 -0.2120165359 0.150490856168 +1403715921434057984.0000000000 -1.6215074004 3.2266437625 1.2445665926 0.5461950572 0.7971131606 -0.2071653300 0.152853180488 +1403715921484058112.0000000000 -1.6175605781 3.2346192195 1.2726838352 0.5441948169 0.7990127587 -0.2044512160 0.153721543792 +1403715921534057984.0000000000 -1.6135704906 3.2433503639 1.3018916675 0.5437637137 0.7997058490 -0.2022253237 0.154584919033 +1403715921584058112.0000000000 -1.6096025550 3.2527399943 1.3329308795 0.5430884453 0.8003862162 -0.2010438866 0.154978066706 +1403715921634057984.0000000000 -1.6056338255 3.2631266453 1.3680994537 0.5436926105 0.7999959162 -0.2000522320 0.156153718639 +1403715921684058112.0000000000 -1.6019160868 3.2745976894 1.4056414938 0.5430557681 0.8003702995 -0.2009618077 0.155280933122 +1403715921734057984.0000000000 -1.5982602545 3.2867130391 1.4443305058 0.5431876825 0.8001185614 -0.2021461911 0.154577963128 +1403715921784058112.0000000000 -1.5947371270 3.2997592076 1.4838729223 0.5453011065 0.7985280264 -0.2055036390 0.150890518679 +1403715921834057984.0000000000 -1.5912152810 3.3129669471 1.5224292139 0.5463334365 0.7976018529 -0.2080183530 0.148591471047 +1403715921884058112.0000000000 -1.5876017464 3.3263934729 1.5587623107 0.5475295854 0.7965178494 -0.2107638224 0.146113927759 +1403715921934057984.0000000000 -1.5832818384 3.3403792339 1.5919658742 0.5492007079 0.7949840405 -0.2126813661 0.145415247849 +1403715921984058112.0000000000 -1.5785274194 3.3546170305 1.6222641516 0.5498807855 0.7941372290 -0.2143819295 0.144974382641 +1403715922034057984.0000000000 -1.5732864143 3.3686945357 1.6515733219 0.5501454211 0.7935332189 -0.2149192478 0.146474445038 +1403715922084058112.0000000000 -1.5675464411 3.3828337527 1.6810368609 0.5514988931 0.7922371319 -0.2147220955 0.148673197156 +1403715922134057984.0000000000 -1.5615462428 3.3970170195 1.7127100381 0.5545604552 0.7897040045 -0.2157055676 0.149336515446 +1403715922184058112.0000000000 -1.5551631990 3.4109261750 1.7470038539 0.5580652252 0.7869319673 -0.2159663206 0.150531829123 +1403715922234057984.0000000000 -1.5486131119 3.4244356641 1.7840473965 0.5621096650 0.7837300372 -0.2164256963 0.151525150307 +1403715922284058112.0000000000 -1.5420893496 3.4375297283 1.8239298395 0.5654269802 0.7811623167 -0.2161092611 0.152887384655 +1403715922334057984.0000000000 -1.5356855844 3.4496408582 1.8660488260 0.5678990616 0.7792219111 -0.2151324837 0.154989946662 +1403715922384058112.0000000000 -1.5296132871 3.4603478429 1.9083385847 0.5685580283 0.7787124086 -0.2130001139 0.158049690652 +1403715922434057984.0000000000 -1.5239259993 3.4697893608 1.9501255403 0.5676854200 0.7793678471 -0.2103869705 0.161419780381 +1403715922484058112.0000000000 -1.5190244948 3.4782148074 1.9917334801 0.5679263647 0.7793253868 -0.2095295714 0.161891767788 +1403715922534057984.0000000000 -1.5148009828 3.4857478779 2.0328145527 0.5680695784 0.7793540370 -0.2099364751 0.160719991079 +1403715922584058112.0000000000 -1.5112028265 3.4926039249 2.0733415023 0.5698142306 0.7781928371 -0.2112571174 0.158423739347 +1403715922634057984.0000000000 -1.5081665671 3.4981979868 2.1125451216 0.5717964760 0.7769304497 -0.2121186683 0.156312305542 +1403715922684058112.0000000000 -1.5051147949 3.5023262730 2.1483745374 0.5728866743 0.7761892882 -0.2125998829 0.15534586273 +1403715922734057984.0000000000 -1.5022970169 3.5050732677 2.1802932495 0.5724695343 0.7765712435 -0.2120641209 0.155706597985 +1403715922784058112.0000000000 -1.4997187085 3.5067356225 2.2082229965 0.5715762169 0.7773590229 -0.2101999621 0.157573962956 +1403715922834057984.0000000000 -1.4976190167 3.5072395774 2.2320946595 0.5698168874 0.7787093314 -0.2081315078 0.160005522949 +1403715922884058112.0000000000 -1.4960797161 3.5069776812 2.2518831628 0.5683869230 0.7798346334 -0.2061189139 0.162201244333 +1403715922934057984.0000000000 -1.4951066463 3.5061530079 2.2681772825 0.5667774388 0.7810259689 -0.2047040799 0.163884137329 +1403715922984058112.0000000000 -1.4946826934 3.5050777021 2.2827500659 0.5661310785 0.7815012064 -0.2034565801 0.165399172566 +1403715923034057984.0000000000 -1.4950730421 3.5034191462 2.2964057872 0.5654297163 0.7820410025 -0.2023138266 0.166643997349 +1403715923084058112.0000000000 -1.4964666556 3.5009163921 2.3094807621 0.5641399603 0.7829022920 -0.2018434222 0.167539067784 +1403715923134057984.0000000000 -1.4990714631 3.4976977080 2.3234508308 0.5623035087 0.7842993787 -0.2015654072 0.167513090104 +1403715923184058112.0000000000 -1.5026779196 3.4936609014 2.3394236227 0.5591033220 0.7866552490 -0.2016085022 0.167125720336 +1403715923234057984.0000000000 -1.5072707778 3.4894579847 2.3582865395 0.5554410171 0.7892472761 -0.2018666223 0.166804917732 +1403715923284058112.0000000000 -1.5129619746 3.4855161305 2.3809097088 0.5521479279 0.7917327626 -0.2034284030 0.164038968394 +1403715923334057984.0000000000 -1.5198704431 3.4816320567 2.4064445717 0.5505243935 0.7930122110 -0.2059353047 0.160141111816 +1403715923384058112.0000000000 -1.5275243092 3.4779697650 2.4321752297 0.5500159471 0.7935429314 -0.2100934910 0.153729629628 +1403715923434057984.0000000000 -1.5349732870 3.4749380540 2.4565532484 0.5506229492 0.7932026766 -0.2141853496 0.147541579729 +1403715923484058112.0000000000 -1.5422690404 3.4719755422 2.4781987788 0.5515380141 0.7925698960 -0.2185335475 0.141003076414 +1403715923534057984.0000000000 -1.5485941698 3.4691421252 2.4967989683 0.5531844679 0.7913101273 -0.2229054223 0.134641745412 +1403715923584058112.0000000000 -1.5539510767 3.4661053123 2.5114678124 0.5553390745 0.7896622936 -0.2267536263 0.128898282771 +1403715923634057984.0000000000 -1.5582675311 3.4625865104 2.5208278269 0.5573381524 0.7881084280 -0.2298552951 0.124200776329 +1403715923684058112.0000000000 -1.5614077336 3.4584970132 2.5239946745 0.5595039755 0.7864374187 -0.2321550403 0.120729139743 +1403715923734057984.0000000000 -1.5633299033 3.4536311999 2.5206984335 0.5616235795 0.7849043761 -0.2335314642 0.118182615102 +1403715923784058112.0000000000 -1.5641095464 3.4478540338 2.5112862327 0.5645854948 0.7827436724 -0.2345058975 0.116458346134 +1403715923834057984.0000000000 -1.5630967904 3.4412459186 2.4973473363 0.5676321830 0.7806640320 -0.2334918648 0.117638951985 +1403715923884058112.0000000000 -1.5607384675 3.4335791423 2.4806609518 0.5727630819 0.7771148972 -0.2316208125 0.119944519331 +1403715923934057984.0000000000 -1.5568375448 3.4249468233 2.4612564777 0.5782974833 0.7731512277 -0.2298741163 0.122340061525 +1403715923984058112.0000000000 -1.5515418187 3.4146939319 2.4388626156 0.5825507839 0.7702476691 -0.2267838639 0.126183166082 +1403715924034057984.0000000000 -1.5453424776 3.4026269550 2.4129547826 0.5853145661 0.7683754329 -0.2239054626 0.129893790182 +1403715924084058112.0000000000 -1.5381733922 3.3887009977 2.3838895234 0.5868854374 0.7672581089 -0.2204961096 0.135136757798 +1403715924134057984.0000000000 -1.5309170319 3.3723858586 2.3531797052 0.5870955666 0.7672830022 -0.2170044755 0.139659041611 +1403715924184058112.0000000000 -1.5234056247 3.3541360514 2.3222642099 0.5863101838 0.7679487744 -0.2147038941 0.142819067979 +1403715924234057984.0000000000 -1.5157361779 3.3339002132 2.2909226890 0.5835637620 0.7700584543 -0.2123613213 0.146171070871 +1403715924284058112.0000000000 -1.5083198687 3.3119885757 2.2602855660 0.5814605295 0.7716629293 -0.2117577383 0.146964745572 +1403715924334057984.0000000000 -1.5009669905 3.2883602738 2.2297693753 0.5779175993 0.7742731537 -0.2104736902 0.149040791682 +1403715924384058112.0000000000 -1.4940442747 3.2633951347 2.1998081371 0.5738090508 0.7772491566 -0.2099331764 0.150183165671 +1403715924434057984.0000000000 -1.4875194501 3.2376976723 2.1702782252 0.5695450887 0.7802576816 -0.2112561730 0.148953588909 +1403715924484058112.0000000000 -1.4810520599 3.2112839358 2.1406077554 0.5636862865 0.7844362170 -0.2119863096 0.148254498948 +1403715924534057984.0000000000 -1.4744088324 3.1846670527 2.1114762931 0.5578827050 0.7883574436 -0.2136505226 0.147013205948 +1403715924584058112.0000000000 -1.4673923617 3.1579675866 2.0829815170 0.5541428960 0.7907407397 -0.2150733139 0.146281246605 +1403715924634057984.0000000000 -1.4599976168 3.1314299362 2.0550931596 0.5520459267 0.7916993771 -0.2194445486 0.142483266143 +1403715924684058112.0000000000 -1.4515058658 3.1051162987 2.0275558178 0.5509776524 0.7911788519 -0.2260180007 0.139195956419 +1403715924734057984.0000000000 -1.4413741767 3.0788981355 2.0002260432 0.5514762500 0.7887700952 -0.2337457681 0.138125299578 +1403715924784058112.0000000000 -1.4293852720 3.0530676607 1.9730450072 0.5517180471 0.7859908353 -0.2419694213 0.138839484385 +1403715924834057984.0000000000 -1.4153970131 3.0268868208 1.9462520683 0.5527622906 0.7818779296 -0.2509094381 0.14200425068 +1403715924884058112.0000000000 -1.3995710537 3.0001381978 1.9195294525 0.5525096369 0.7779265105 -0.2606698727 0.147019259942 +1403715924934057984.0000000000 -1.3820551415 2.9723455424 1.8932862941 0.5538742987 0.7720321990 -0.2711659379 0.153813455388 +1403715924984058112.0000000000 -1.3626798150 2.9435176003 1.8673341560 0.5551074935 0.7657092330 -0.2800934348 0.1645986302 +1403715925034057984.0000000000 -1.3417420032 2.9135234532 1.8429052620 0.5576633097 0.7575887264 -0.2893208143 0.17710003111 +1403715925084058112.0000000000 -1.3198067619 2.8824301909 1.8211885741 0.5604056078 0.7488705644 -0.2970290701 0.192125386237 +1403715925134057984.0000000000 -1.2982284688 2.8491461957 1.8026197777 0.5617933351 0.7406421402 -0.3050661562 0.206814189922 +1403715925184058112.0000000000 -1.2770622459 2.8138592577 1.7873144505 0.5611890321 0.7334022344 -0.3142473837 0.220083199475 +1403715925234057984.0000000000 -1.2566647261 2.7770008923 1.7758960287 0.5593273334 0.7269130217 -0.3258485566 0.229288270945 +1403715925284058112.0000000000 -1.2373501382 2.7380268224 1.7678948490 0.5552330139 0.7216488301 -0.3384484965 0.237469748582 +1403715925334057984.0000000000 -1.2192104031 2.6971894374 1.7627559644 0.5500092814 0.7170367274 -0.3531108386 0.242200036316 +1403715925384058112.0000000000 -1.2014464851 2.6547422589 1.7597497114 0.5432042871 0.7129465194 -0.3685757542 0.246552786291 +1403715925434057984.0000000000 -1.1844018324 2.6106022805 1.7576958330 0.5359507039 0.7090522454 -0.3843157682 0.249605982681 +1403715925484058112.0000000000 -1.1676489206 2.5648269640 1.7554546724 0.5271644563 0.7059842302 -0.3997707802 0.252719658857 +1403715925534057984.0000000000 -1.1507025183 2.5175479563 1.7532959199 0.5192743335 0.7017486064 -0.4146389471 0.256861058953 +1403715925584058112.0000000000 -1.1331821271 2.4686759191 1.7510574197 0.5117565793 0.6970030355 -0.4279728148 0.262928206558 +1403715925634057984.0000000000 -1.1149016939 2.4183241582 1.7490617964 0.5054867956 0.6909463822 -0.4407566278 0.269832895441 +1403715925684058112.0000000000 -1.0955586116 2.3665308476 1.7473754825 0.5002174088 0.6837876399 -0.4525783945 0.278190230413 +1403715925734057984.0000000000 -1.0752178038 2.3135630583 1.7458735182 0.4953945660 0.6759138784 -0.4640274161 0.287059593201 +1403715925784058112.0000000000 -1.0544237873 2.2593285024 1.7438255367 0.4897838406 0.6682465616 -0.4756288937 0.295525765053 +1403715925834057984.0000000000 -1.0328122311 2.2038498165 1.7420185360 0.4851947135 0.6593956877 -0.4868176089 0.304617847041 +1403715925884058112.0000000000 -1.0107591918 2.1470125583 1.7397426648 0.4803062426 0.6503441182 -0.4973275058 0.314680462115 +1403715925934057984.0000000000 -0.9885282148 2.0887276957 1.7369337973 0.4742942847 0.6416697251 -0.5069859706 0.32599098296 +1403715925984058112.0000000000 -0.9658010129 2.0292338271 1.7342612583 0.4684994144 0.6322354523 -0.5165039219 0.33765415764 +1403715926034057984.0000000000 -0.9429069671 1.9687338522 1.7311923913 0.4641795894 0.6212194131 -0.5264889859 0.348472520084 +1403715926084058112.0000000000 -0.9199078227 1.9071867248 1.7264897328 0.4618971844 0.6077149141 -0.5370375995 0.359060149547 +1403715926134057984.0000000000 -0.8973347400 1.8445017684 1.7190003522 0.4595712652 0.5934059214 -0.5472750726 0.370342624419 +1403715926184058112.0000000000 -0.8758646243 1.7805873348 1.7080528947 0.4564646114 0.5787092307 -0.5579155105 0.381400010501 +1403715926234057984.0000000000 -0.8562401681 1.7152503523 1.6932180403 0.4521753371 0.5644678292 -0.5685425860 0.392011303683 +1403715926284058112.0000000000 -0.8384439531 1.6482777425 1.6750890919 0.4469570800 0.5502798745 -0.5790351395 0.402665786366 +1403715926334057984.0000000000 -0.8221376346 1.5797875502 1.6541802688 0.4402258742 0.5367388393 -0.5883768459 0.414638740636 +1403715926384058112.0000000000 -0.8079760433 1.5100440346 1.6316338939 0.4323444744 0.5236890214 -0.5972686868 0.42672963346 +1403715926434057984.0000000000 -0.7961494047 1.4392455812 1.6085172143 0.4239471275 0.5108206701 -0.6036789855 0.441477925358 +1403715926484058112.0000000000 -0.7872215397 1.3677921310 1.5852180372 0.4155550484 0.4979865530 -0.6092291398 0.456249109535 +1403715926534057984.0000000000 -0.7814124388 1.2956763839 1.5612904199 0.4056586805 0.4860161958 -0.6162721811 0.46844198284 +1403715926584058112.0000000000 -0.7790694582 1.2235646607 1.5365135677 0.3937313562 0.4760444722 -0.6244681876 0.477908738416 +1403715926634057984.0000000000 -0.7800482991 1.1517559140 1.5111492530 0.3802200050 0.4672187715 -0.6349114033 0.483763245003 +1403715926684058112.0000000000 -0.7837533532 1.0804911382 1.4859335511 0.3669121379 0.4583580627 -0.6464805896 0.487181913385 +1403715926734057984.0000000000 -0.7893381631 1.0093774700 1.4610465872 0.3520934869 0.4507481911 -0.6574822165 0.490482802577 +1403715926784058112.0000000000 -0.7972061713 0.9388578865 1.4369400727 0.3366270546 0.4441093345 -0.6671873144 0.494277465335 +1403715926834057984.0000000000 -0.8069266715 0.8693525050 1.4151924903 0.3199389139 0.4391041055 -0.6759411928 0.49792587781 +1403715926884058112.0000000000 -0.8180793643 0.8013703700 1.3970379596 0.3057711213 0.4331785387 -0.6844974483 0.500323513619 +1403715926934057984.0000000000 -0.8300118597 0.7348442103 1.3828987000 0.2933948347 0.4267125459 -0.6917561354 0.503298443539 +1403715926984058112.0000000000 -0.8419383783 0.6698072168 1.3723863370 0.2825818756 0.4199023524 -0.6990294549 0.505160686527 +1403715927034057984.0000000000 -0.8534573339 0.6061940274 1.3650359694 0.2743425319 0.4120413522 -0.7041869703 0.508997848864 +1403715927084058112.0000000000 -0.8644061788 0.5437567935 1.3593326071 0.2679222758 0.4030609452 -0.7072298598 0.5153498365 +1403715927134057984.0000000000 -0.8754483184 0.4827003628 1.3534646566 0.2611138838 0.3944825473 -0.7096594006 0.522098261525 +1403715927184058112.0000000000 -0.8868896700 0.4227175073 1.3469550926 0.2501589841 0.3886910540 -0.7086904237 0.533008096196 +1403715927234057984.0000000000 -0.8983584387 0.3650225337 1.3403205926 0.2390538026 0.3829088002 -0.7076142039 0.543614080649 +1403715927284058112.0000000000 -0.9095451349 0.3100886300 1.3336733788 0.2271386524 0.3779457152 -0.7061278794 0.554029319522 +1403715927334057984.0000000000 -0.9201346077 0.2584379976 1.3277657871 0.2167070640 0.3723359593 -0.7043037044 0.56423423666 +1403715927384058112.0000000000 -0.9301460474 0.2106603936 1.3235948150 0.2102169881 0.3642331949 -0.7015937478 0.575247086613 +1403715927434057984.0000000000 -0.9400370734 0.1671256097 1.3198541912 0.2046108777 0.3551361435 -0.6997602133 0.585105419715 +1403715927484058112.0000000000 -0.9496214516 0.1282953006 1.3175673376 0.2056675791 0.3414265053 -0.6990853956 0.593639956531 +1403715927534057984.0000000000 -0.9595939526 0.0940792962 1.3154635942 0.2092682678 0.3254631843 -0.7005845432 0.599551336932 +1403715927584058112.0000000000 -0.9710285905 0.0643752447 1.3136991120 0.2117001584 0.3091586620 -0.7022626052 0.605335607686 +1403715927634057984.0000000000 -0.9846466427 0.0391824096 1.3115968134 0.2139301453 0.2917511427 -0.7047071105 0.610330281151 +1403715927684058112.0000000000 -1.0007653204 0.0178704350 1.3089271535 0.2116502800 0.2754287576 -0.7083832731 0.614439823541 +1403715927734057984.0000000000 -1.0194593513 0.0001714639 1.3050564781 0.2047370995 0.2608021891 -0.7130188247 0.617793730849 +1403715927784058112.0000000000 -1.0407605760 -0.0140363205 1.2999066104 0.1925571104 0.2476500221 -0.7183599475 0.620926897113 +1403715927834057984.0000000000 -1.0646341770 -0.0246016802 1.2943463956 0.1774298829 0.2351477044 -0.7239193902 0.623830834717 +1403715927884058112.0000000000 -1.0907891037 -0.0311262901 1.2888635462 0.1615032375 0.2220004431 -0.7301580614 0.625700977271 +1403715927934057984.0000000000 -1.1192044073 -0.0331266452 1.2823389062 0.1429110889 0.2094860980 -0.7365238369 0.627076257828 +1403715927984058112.0000000000 -1.1488638501 -0.0311969032 1.2751047492 0.1248767903 0.1956735598 -0.7436819791 0.626940794007 +1403715928034057984.0000000000 -1.1794538639 -0.0253930891 1.2660531096 0.1078593063 0.1797609418 -0.7507331803 0.626459947543 +1403715928084058112.0000000000 -1.2104644840 -0.0156528472 1.2542227115 0.0940563915 0.1611486724 -0.7584358730 0.624467394801 +1403715928134057984.0000000000 -1.2417177950 -0.0025719433 1.2390244755 0.0817989165 0.1401696391 -0.7670001392 0.620783533882 +1403715928184058112.0000000000 -1.2731244925 0.0133269990 1.2205065413 0.0687075872 0.1188420780 -0.7749856031 0.616889895314 +1403715928234057984.0000000000 -1.3042502440 0.0315380837 1.1998613566 0.0575631010 0.0955785656 -0.7797637140 0.61605176526 +1403715928284058112.0000000000 -1.3354532311 0.0518297006 1.1766477544 0.0454008684 0.0728773483 -0.7814659133 0.618011876603 +1403715928334057984.0000000000 -1.3667979761 0.0741569269 1.1521207645 0.0333820798 0.0501001075 -0.7800046099 0.622871113869 +1403715928384058112.0000000000 -1.3984386839 0.0996550884 1.1267318634 0.0203622711 0.0291299693 -0.7775059667 0.627870444064 +1403715928434057984.0000000000 -1.4300783155 0.1285945760 1.1007222601 0.0094309590 0.0082487435 -0.7755732237 0.63113325841 +1403715928484058112.0000000000 -1.4617026519 0.1612801391 1.0735098657 0.0003495941 0.0119465870 0.7762315388 -0.630334637278 +1403715928534057984.0000000000 -1.4935191402 0.1976483206 1.0451297841 0.0100894321 0.0299491026 0.7801162037 -0.624835949166 +1403715928584058112.0000000000 -1.5250576314 0.2372515564 1.0170351071 0.0174637800 0.0464297994 0.7848178620 -0.617737981326 +1403715928634057984.0000000000 -1.5565970905 0.2796903694 0.9914528971 0.0250378477 0.0591856051 0.7881796733 -0.612080854895 +1403715928684058112.0000000000 -1.5881211008 0.3246291509 0.9687078920 0.0330007582 0.0677847405 0.7927098281 -0.604919256823 +1403715928734057984.0000000000 -1.6195152483 0.3717120770 0.9487305428 0.0397183990 0.0733906829 0.8005527025 -0.593423648851 +1403715928784058112.0000000000 -1.6505589329 0.4202063503 0.9326794149 0.0442724863 0.0771666824 0.8113365885 -0.577770014954 +1403715928834057984.0000000000 -1.6811168030 0.4690589865 0.9230531754 0.0460682221 0.0776352438 0.8227798839 -0.561145035192 +1403715928884058112.0000000000 -1.7110104420 0.5166675499 0.9202304304 0.0448359495 0.0755762624 0.8340944101 -0.54457734189 +1403715928934057984.0000000000 -1.7403355776 0.5622762645 0.9248911094 0.0416387761 0.0703092799 0.8435019475 -0.530874073649 +1403715928984058112.0000000000 -1.7693222813 0.6045719694 0.9366145014 0.0362032011 0.0628036335 0.8527059611 -0.517337004062 +1403715929034057984.0000000000 -1.7986913758 0.6418917305 0.9556638952 0.0304105114 0.0543753231 0.8602334686 -0.506079938898 +1403715929084058112.0000000000 -1.8287347935 0.6741296695 0.9803942998 0.0239751521 0.0463547340 0.8663799866 -0.496650933347 +1403715929134057984.0000000000 -1.8594951412 0.7011597675 1.0072920811 0.0199635315 0.0371702967 0.8716052931 -0.488389229583 +1403715929184058112.0000000000 -1.8903544501 0.7229715509 1.0342926245 0.0164216085 0.0279236386 0.8760513483 -0.481128502984 +1403715929234057984.0000000000 -1.9215045484 0.7387117603 1.0603182341 0.0157374024 0.0171942849 0.8788411573 -0.47654476277 +1403715929284058112.0000000000 -1.9529860763 0.7480033798 1.0844596552 0.0202902484 0.0037151134 0.8785879481 -0.477134908894 +1403715929334057984.0000000000 -1.9841176776 0.7509083408 1.1067903887 0.0298695848 -0.0125995074 0.8733261085 -0.486056137197 +1403715929384058112.0000000000 -2.0139320087 0.7485278759 1.1273220019 0.0437536128 -0.0311911117 0.8650543003 -0.49879233499 +1403715929434057984.0000000000 -2.0411358140 0.7418454725 1.1461044663 0.0596436591 -0.0496835596 0.8542622333 -0.514013827271 +1403715929484058112.0000000000 -2.0641032810 0.7318553871 1.1640068350 0.0755981312 -0.0666075123 0.8424326427 -0.529297274147 +1403715929534057984.0000000000 -2.0817684849 0.7193173688 1.1815324747 0.0923504826 -0.0825261036 0.8310386605 -0.542250472954 +1403715929584058112.0000000000 -2.0926116419 0.7052216547 1.1996534012 0.1066754749 -0.0947207936 0.8200724539 -0.554192642252 +1403715929634057984.0000000000 -2.0958000195 0.6911487507 1.2175322479 0.1182264026 -0.1029971616 0.8126982940 -0.561191220008 +1403715929684058112.0000000000 -2.0899336326 0.6779955651 1.2359168890 0.1177656118 -0.1002614806 0.8108679503 -0.564421884223 +1403715929734057984.0000000000 -2.0752378804 0.6652566266 1.2542695013 0.1066791417 -0.0885512641 0.8140790017 -0.563962421926 +1403715929784058112.0000000000 -2.0529618411 0.6518595991 1.2727329517 0.0899421792 -0.0727642410 0.8172293274 -0.564581257232 +1403715929834057984.0000000000 -2.0252496464 0.6379680096 1.2892331212 0.0731753203 -0.0574331706 0.8178803110 -0.567819161651 +1403715929884058112.0000000000 -1.9931602385 0.6238638910 1.3037882342 0.0527681602 -0.0399122083 0.8161735177 -0.574006381375 +1403715929934057984.0000000000 -1.9585168272 0.6099102138 1.3153594388 0.0317851779 -0.0218301021 0.8140250120 -0.579548469953 +1403715929984058112.0000000000 -1.9226685445 0.5958217320 1.3236416048 0.0134321776 -0.0058642864 0.8105354982 -0.585506099805 +1403715930034057984.0000000000 -1.8865659416 0.5818883649 1.3287390474 0.0020584091 -0.0077471847 -0.8075332059 0.589767636855 +1403715930084058112.0000000000 -1.8512120215 0.5692242387 1.3322042068 0.0178117545 -0.0215209520 -0.8046234685 0.593127864758 +1403715930134057984.0000000000 -1.8178092895 0.5578524724 1.3347026641 0.0302325072 -0.0327030136 -0.8017828741 0.595953631782 +1403715930184058112.0000000000 -1.7868787819 0.5477187365 1.3371349913 0.0417973731 -0.0433282993 -0.7992272698 0.598006195013 +1403715930234057984.0000000000 -1.7592712754 0.5390560309 1.3394960611 0.0509357940 -0.0521243991 -0.7977817806 0.598525540408 +1403715930284058112.0000000000 -1.7356718504 0.5321966295 1.3417125628 0.0571949824 -0.0590748452 -0.7964625351 0.599071220152 +1403715930334057984.0000000000 -1.7167481977 0.5271149094 1.3429478532 0.0576447313 -0.0616709624 -0.7972015430 0.597782131927 +1403715930384058112.0000000000 -1.7025102739 0.5234812775 1.3432580671 0.0544567836 -0.0612108512 -0.8007755634 0.593334802119 +1403715930434057984.0000000000 -1.6923695881 0.5209819250 1.3415061325 0.0477080682 -0.0579729516 -0.8063566563 0.58664471353 +1403715930484058112.0000000000 -1.6854796116 0.5198014705 1.3368974752 0.0404107640 -0.0547059722 -0.8127773777 0.578590667945 +1403715930534057984.0000000000 -1.6813921051 0.5188987629 1.3293778301 0.0342844852 -0.0518455868 -0.8182954457 0.571427311866 +1403715930584058112.0000000000 -1.6798789367 0.5177256879 1.3192545153 0.0291549287 -0.0495966893 -0.8246494534 0.562710793837 +1403715930634057984.0000000000 -1.6809472674 0.5157462225 1.3089188216 0.0251107327 -0.0482055943 -0.8301575018 0.554873133239 +1403715930684058112.0000000000 -1.6844873839 0.5123710343 1.3011288942 0.0237713670 -0.0486272783 -0.8347688430 0.547933653482 +1403715930734057984.0000000000 -1.6907897422 0.5064824417 1.2972433056 0.0233447710 -0.0497129803 -0.8372456201 0.544061956783 +1403715930784058112.0000000000 -1.6997791461 0.4983264118 1.2970365801 0.0224659082 -0.0506198556 -0.8391654650 0.541049198873 +1403715930834057984.0000000000 -1.7116293142 0.4875473557 1.3003575433 0.0172684646 -0.0479837585 -0.8410171969 0.538599511235 +1403715930884058112.0000000000 -1.7258617625 0.4746736076 1.3074090522 0.0078885978 -0.0421779014 -0.8430240200 0.536161632674 +1403715930934057984.0000000000 -1.7417552673 0.4596575750 1.3180295447 0.0020850706 0.0358950311 0.8439367275 -0.535236395546 +1403715930984058112.0000000000 -1.7582219713 0.4424317857 1.3298797776 0.0100772533 0.0305428317 0.8457506318 -0.532608161086 +1403715931034057984.0000000000 -1.7748089446 0.4230120754 1.3407574145 0.0157668204 0.0271388639 0.8490388426 -0.52739732 +1403715931084058112.0000000000 -1.7911770836 0.4005344439 1.3495144625 0.0194847990 0.0252842730 0.8526441536 -0.521516054838 +1403715931134057984.0000000000 -1.8069836791 0.3750761368 1.3557679760 0.0212559967 0.0245731195 0.8561955673 -0.515629222393 +1403715931184058112.0000000000 -1.8222297135 0.3462126058 1.3618110780 0.0223219227 0.0238482423 0.8585612330 -0.511669426837 +1403715931234057984.0000000000 -1.8370286630 0.3130830287 1.3702520559 0.0229056260 0.0239675982 0.8593640069 -0.510288536214 +1403715931284058112.0000000000 -1.8513346123 0.2759286096 1.3818844973 0.0230555152 0.0243658979 0.8596280295 -0.509818003909 +1403715931334057984.0000000000 -1.8649338838 0.2349137042 1.3974809805 0.0209165932 0.0261682851 0.8583245124 -0.512012449393 +1403715931384058112.0000000000 -1.8783035072 0.1896742880 1.4170487052 0.0192748114 0.0274196660 0.8565434305 -0.514985431982 +1403715931434057984.0000000000 -1.8915800038 0.1405612444 1.4391797471 0.0189979303 0.0270211996 0.8542270477 -0.518849770593 +1403715931484058112.0000000000 -1.9046415270 0.0886159751 1.4605452350 0.0176091635 0.0271699392 0.8524272852 -0.521842347048 +1403715931534057984.0000000000 -1.9176386367 0.0339214206 1.4795859276 0.0174944510 0.0261251325 0.8506049300 -0.524864434588 +1403715931584058112.0000000000 -1.9301500060 -0.0235216038 1.4954651339 0.0183954170 0.0239248382 0.8484047046 -0.52848715027 +1403715931634057984.0000000000 -1.9419057244 -0.0829715245 1.5074575998 0.0192771388 0.0213931038 0.8469416703 -0.530905390906 +1403715931684058112.0000000000 -1.9529957945 -0.1440795209 1.5159849080 0.0210384779 0.0177827186 0.8448773101 -0.534250398514 +1403715931734057984.0000000000 -1.9633094700 -0.2068868832 1.5211021255 0.0225559086 0.0144077489 0.8434482285 -0.536543319335 +1403715931784058112.0000000000 -1.9729141919 -0.2710746501 1.5234913982 0.0231983830 0.0114010042 0.8419058878 -0.539004942694 +1403715931834057984.0000000000 -1.9816296696 -0.3367979827 1.5258568224 0.0216223128 0.0099552437 0.8393696540 -0.543039549829 +1403715931884058112.0000000000 -1.9895295939 -0.4044503935 1.5292242224 0.0206955085 0.0080969587 0.8344889516 -0.550576356903 +1403715931934057984.0000000000 -1.9966218411 -0.4731131871 1.5330249740 0.0196164048 0.0066243239 0.8292719518 -0.558461587762 +1403715931984058112.0000000000 -2.0030319017 -0.5423238484 1.5373517642 0.0189570088 0.0050597456 0.8232336341 -0.567363564646 +1403715932034057984.0000000000 -2.0084664569 -0.6115819586 1.5423962267 0.0163575455 0.0049053596 0.8169882950 -0.57640133065 +1403715932084058112.0000000000 -2.0132383334 -0.6803792308 1.5486118514 0.0154399689 0.0038151571 0.8089776078 -0.587624269396 +1403715932134057984.0000000000 -2.0172138696 -0.7478321499 1.5564310548 0.0153976529 0.0024975661 0.7990110330 -0.601114002176 +1403715932184058112.0000000000 -2.0203225999 -0.8130705040 1.5654867792 0.0162075286 0.0013476336 0.7883287578 -0.615039242255 +1403715932234057984.0000000000 -2.0223819512 -0.8753604461 1.5762440650 0.0179900554 -0.0004463451 0.7756642180 -0.630889197599 +1403715932284058112.0000000000 -2.0233220825 -0.9340223741 1.5883957054 0.0177890999 -0.0005560515 0.7626001442 -0.646625284694 +1403715932334057984.0000000000 -2.0232680304 -0.9878735957 1.6010029986 0.0174271956 -0.0003794084 0.7503729261 -0.660784852071 +1403715932384058112.0000000000 -2.0222862788 -1.0357946178 1.6136617578 0.0174748176 -0.0004611787 0.7394116842 -0.673026581457 +1403715932434057984.0000000000 -2.0205104338 -1.0768010172 1.6260403237 0.0171725029 -0.0000203973 0.7307205343 -0.682460698851 +1403715932484058112.0000000000 -2.0177821122 -1.1101418424 1.6384790389 0.0156632965 0.0006014148 0.7232987772 -0.690357283089 +1403715932534057984.0000000000 -2.0145622918 -1.1354729683 1.6517459906 0.0144884268 0.0012760729 0.7155370727 -0.69842333491 +1403715932584058112.0000000000 -2.0109127753 -1.1520928498 1.6659862689 0.0135070061 0.0020145475 0.7069022803 -0.707179375091 +1403715932634057984.0000000000 -2.0066714654 -1.1592871125 1.6809100799 0.0111773719 0.0032891874 0.6986586050 -0.715360329642 +1403715932684058112.0000000000 -2.0021542634 -1.1566642288 1.6963869991 0.0100140088 0.0042456562 0.6918041299 -0.722003282463 +1403715932734057984.0000000000 -1.9972339398 -1.1433206980 1.7120032722 0.0097447552 0.0046040664 0.6854815385 -0.728010235296 +1403715932784058112.0000000000 -1.9921210326 -1.1194523970 1.7272975999 0.0104488229 0.0049578938 0.6822037152 -0.731070675321 +1403715932834057984.0000000000 -1.9869371014 -1.0844746090 1.7422748743 0.0116532202 0.0054205726 0.6841248765 -0.729251652884 +1403715932884058112.0000000000 -1.9816404662 -1.0390470211 1.7557254438 0.0144923421 0.0057268689 0.6942069023 -0.719606803618 +1403715932934057984.0000000000 -1.9759293624 -0.9833169352 1.7681769946 0.0163016100 0.0070517356 0.7114631454 -0.702498913364 +1403715932984058112.0000000000 -1.9697088363 -0.9187530008 1.7800279061 0.0177688043 0.0088579470 0.7329299226 -0.680014363746 +1403715933034057984.0000000000 -1.9627402170 -0.8471464080 1.7921023804 0.0191202108 0.0104236362 0.7536539545 -0.656910558733 +1403715933084058112.0000000000 -1.9553115184 -0.7706991270 1.8047032447 0.0205977058 0.0118316296 0.7726633097 -0.634371466065 +1403715933134057984.0000000000 -1.9474616969 -0.6908755626 1.8174692322 0.0216519581 0.0133290105 0.7906175140 -0.611782213486 +1403715933184058112.0000000000 -1.9391395182 -0.6089749905 1.8298119531 0.0221479905 0.0147228111 0.8084766283 -0.587927076186 +1403715933234057984.0000000000 -1.9303473234 -0.5267137407 1.8423985631 0.0227238947 0.0156851790 0.8240827194 -0.565796139366 +1403715933284058112.0000000000 -1.9210959093 -0.4454409995 1.8548287896 0.0224949514 0.0169467135 0.8391983118 -0.543095737062 +1403715933334057984.0000000000 -1.9112560031 -0.3665548261 1.8677006102 0.0201652874 0.0196930879 0.8532928251 -0.52066966321 +1403715933384058112.0000000000 -1.9010294336 -0.2912601155 1.8806287452 0.0154155572 0.0242176385 0.8668457361 -0.497749270533 +1403715933434057984.0000000000 -1.8911626118 -0.2210517633 1.8934221340 0.0097851902 0.0298773603 0.8798005053 -0.474302292129 +1403715933484058112.0000000000 -1.8817740233 -0.1573799798 1.9064533407 0.0038910362 0.0357960425 0.8917184796 -0.451155911264 +1403715933534057984.0000000000 -1.8731459745 -0.1025473074 1.9204044866 0.0005755306 -0.0409859619 -0.9018175608 0.430168463107 +1403715933584058112.0000000000 -1.8659918854 -0.0575821245 1.9354502285 0.0026039370 -0.0439333812 -0.9101117424 0.412019045493 +1403715933634057984.0000000000 -1.8605121643 -0.0233814937 1.9516766131 0.0034573444 -0.0464830666 -0.9169904514 0.396176580884 +1403715933684058112.0000000000 -1.8571761988 -0.0013563597 1.9692813540 0.0006104819 -0.0457308714 -0.9217397280 0.385102828506 +1403715933734057984.0000000000 -1.8556266536 0.0077838201 1.9886188188 0.0038970314 0.0433472744 0.9251553983 -0.377085289967 +1403715933784058112.0000000000 -1.8555441766 0.0024986864 2.0105283681 0.0080709995 0.0414930112 0.9265792350 -0.37371661754 +1403715933834057984.0000000000 -1.8568150425 -0.0169895983 2.0349803468 0.0125437206 0.0394366250 0.9258979064 -0.375500299116 +1403715933884058112.0000000000 -1.8590240029 -0.0511619502 2.0620069828 0.0168634174 0.0375364259 0.9215170799 -0.386151412467 +1403715933934057984.0000000000 -1.8616883694 -0.0989306469 2.0928737811 0.0195448177 0.0380719315 0.9122821129 -0.407320358605 +1403715933984058112.0000000000 -1.8647579596 -0.1591256685 2.1280601882 0.0234725946 0.0370550479 0.8969847425 -0.43987990686 +1403715934034057984.0000000000 -1.8678260966 -0.2278668040 2.1656204031 0.0257651882 0.0379295308 0.8777765808 -0.476870821106 +1403715934084058112.0000000000 -1.8710658665 -0.3018682085 2.2041420657 0.0295537682 0.0368375034 0.8553669214 -0.51586529533 +1403715934134057984.0000000000 -1.8740816815 -0.3776886603 2.2410783816 0.0312084443 0.0375556659 0.8305353092 -0.554821327274 +1403715934184058112.0000000000 -1.8768265300 -0.4537235406 2.2738561069 0.0336369724 0.0375708600 0.8034444459 -0.593240260712 +1403715934234057984.0000000000 -1.8789904759 -0.5275296010 2.2993432462 0.0356589710 0.0377431336 0.7798021927 -0.623868923709 +1403715934284058112.0000000000 -1.8805434221 -0.5978261751 2.3190550289 0.0384152427 0.0365408781 0.7583719356 -0.649662251181 +1403715934334057984.0000000000 -1.8814753402 -0.6632580558 2.3345105616 0.0389599854 0.0366439303 0.7402818416 -0.670165753299 +1403715934384058112.0000000000 -1.8819772850 -0.7225466133 2.3469338578 0.0390182298 0.0364765123 0.7232960850 -0.688469182494 +1403715934434057984.0000000000 -1.8817947957 -0.7745768610 2.3561470139 0.0399779990 0.0354735250 0.7076921215 -0.70449645118 +1403715934484058112.0000000000 -1.8807060830 -0.8179702074 2.3627914000 0.0398213824 0.0349858978 0.6933126538 -0.718684776844 +1403715934534057984.0000000000 -1.8787808396 -0.8520818156 2.3676438582 0.0389858496 0.0342122550 0.6806127126 -0.730805008567 +1403715934584058112.0000000000 -1.8761806219 -0.8754712548 2.3708427757 0.0378738428 0.0333880009 0.6686545756 -0.741857042764 +1403715934634057984.0000000000 -1.8728287855 -0.8865485945 2.3733490230 0.0362088352 0.0326632775 0.6589528601 -0.750601864277 +1403715934684058112.0000000000 -1.8684437481 -0.8841965264 2.3764028194 0.0334879872 0.0320220697 0.6521721762 -0.756653549744 +1403715934734057984.0000000000 -1.8631310738 -0.8682370229 2.3804145964 0.0293459170 0.0320952503 0.6480115187 -0.760387916572 +1403715934784058112.0000000000 -1.8572160769 -0.8375805448 2.3861366081 0.0243045223 0.0326199188 0.6463977259 -0.761915488099 +1403715934834057984.0000000000 -1.8510266156 -0.7924150843 2.3917791283 0.0204411355 0.0326924835 0.6534410668 -0.755994797408 +1403715934884058112.0000000000 -1.8450664925 -0.7341853760 2.3968920608 0.0195536699 0.0318765395 0.6712281463 -0.740306906476 +1403715934934057984.0000000000 -1.8389910623 -0.6637074066 2.4033357163 0.0184605945 0.0315721399 0.6948573212 -0.718217035166 +1403715934984058112.0000000000 -1.8330494224 -0.5832439081 2.4097046092 0.0161754560 0.0324772857 0.7197452273 -0.693289541501 +1403715935034057984.0000000000 -1.8275519434 -0.4960914443 2.4144383417 0.0149081818 0.0332604927 0.7447103437 -0.666391768926 +1403715935084058112.0000000000 -1.8224219337 -0.4037164991 2.4161662837 0.0137743612 0.0343281296 0.7693857241 -0.63771267358 +1403715935134057984.0000000000 -1.8178521289 -0.3080484861 2.4155115462 0.0144254839 0.0348232050 0.7912772357 -0.610294671457 +1403715935184058112.0000000000 -1.8132351426 -0.2102948810 2.4126340662 0.0142713522 0.0358490903 0.8112480296 -0.583427635387 +1403715935234057984.0000000000 -1.8090984972 -0.1122591675 2.4067112802 0.0151265353 0.0362240419 0.8276914747 -0.559808743561 +1403715935284058112.0000000000 -1.8055457005 -0.0159569055 2.3973935741 0.0156970579 0.0365550243 0.8415793840 -0.538666383733 +1403715935334057984.0000000000 -1.8024268210 0.0777987659 2.3850395426 0.0171155832 0.0359471485 0.8534803630 -0.519601895001 +1403715935384058112.0000000000 -1.7995601664 0.1680320316 2.3706010358 0.0182020853 0.0354112928 0.8630371917 -0.503568793888 +1403715935434057984.0000000000 -1.7967991490 0.2537850284 2.3539473982 0.0196253401 0.0344522650 0.8714021217 -0.488964446293 +1403715935484058112.0000000000 -1.7941845562 0.3341054057 2.3348289449 0.0204321024 0.0340529355 0.8780954661 -0.476834645527 +1403715935534057984.0000000000 -1.7917825780 0.4077353237 2.3134672750 0.0216481798 0.0331516561 0.8834671776 -0.466816955661 +1403715935584058112.0000000000 -1.7895520657 0.4744438530 2.2908168096 0.0229085523 0.0321220872 0.8875350654 -0.459047794263 +1403715935634057984.0000000000 -1.7871468017 0.5336217219 2.2680014291 0.0229679036 0.0321091316 0.8916764984 -0.450948446446 +1403715935684058112.0000000000 -1.7848502912 0.5847687009 2.2456824691 0.0231481543 0.0319972293 0.8957583973 -0.442783506749 +1403715935734057984.0000000000 -1.7825488583 0.6270703113 2.2240028980 0.0239359711 0.0314108176 0.8999825049 -0.434133528736 +1403715935784058112.0000000000 -1.7800363750 0.6598678732 2.2032914124 0.0238590677 0.0317874154 0.9039475618 -0.425792332688 +1403715935834057984.0000000000 -1.7774875070 0.6824963164 2.1843103689 0.0250270507 0.0312507722 0.9072554959 -0.418669919047 +1403715935884058112.0000000000 -1.7748337749 0.6946192810 2.1674902978 0.0259404360 0.0311422540 0.9096614549 -0.413368227146 +1403715935934057984.0000000000 -1.7723351903 0.6955686870 2.1530246358 0.0269724216 0.0315613577 0.9098339636 -0.412890454922 +1403715935984058112.0000000000 -1.7699258966 0.6847673884 2.1415425176 0.0281581034 0.0317561221 0.9060393803 -0.421059747763 +1403715936034057984.0000000000 -1.7674844537 0.6630413166 2.1335131154 0.0296770885 0.0321553263 0.8972690105 -0.439310400695 +1403715936084058112.0000000000 -1.7651622014 0.6325915096 2.1281111497 0.0315296020 0.0328590071 0.8842913431 -0.464709576392 +1403715936134057984.0000000000 -1.7627494454 0.5953476532 2.1245684138 0.0348555097 0.0319628587 0.8682030401 -0.493950352034 +1403715936184058112.0000000000 -1.7598907472 0.5534271371 2.1220355032 0.0375630206 0.0320481665 0.8507826059 -0.523192977723 +1403715936234057984.0000000000 -1.7565154696 0.5086748824 2.1201043479 0.0406363528 0.0319512291 0.8322018392 -0.552057881573 +1403715936284058112.0000000000 -1.7521066164 0.4624375950 2.1187509249 0.0428165874 0.0322836359 0.8127327397 -0.58016377038 +1403715936334057984.0000000000 -1.7468539939 0.4170257303 2.1162011798 0.0435766290 0.0341100960 0.7959744707 -0.602795338971 +1403715936384058112.0000000000 -1.7406795305 0.3737683302 2.1128104465 0.0416995575 0.0375533725 0.7812100281 -0.621740929301 +1403715936434057984.0000000000 -1.7337944498 0.3339606824 2.1074663489 0.0414380220 0.0398368972 0.7704162278 -0.634944680961 +1403715936484058112.0000000000 -1.7261762939 0.2987343167 2.1009872141 0.0407398925 0.0420754983 0.7629639297 -0.643782537549 +1403715936534057984.0000000000 -1.7180554588 0.2680898992 2.0942939568 0.0387290369 0.0450591269 0.7564507194 -0.651346333299 +1403715936584058112.0000000000 -1.7098596991 0.2426978209 2.0873635849 0.0359647153 0.0484153081 0.7511010857 -0.65742654059 +1403715936634057984.0000000000 -1.7015490028 0.2227494449 2.0809697137 0.0324936857 0.0517634147 0.7464848257 -0.662589702822 +1403715936684058112.0000000000 -1.6931443473 0.2088388174 2.0750124661 0.0289918112 0.0551928876 0.7430053747 -0.666375444582 +1403715936734057984.0000000000 -1.6850295913 0.2013269755 2.0682248964 0.0289599884 0.0562604832 0.7437752528 -0.665428020492 +1403715936784058112.0000000000 -1.6771195492 0.2002137016 2.0601806837 0.0298637214 0.0562888522 0.7490422668 -0.659450836556 +1403715936834057984.0000000000 -1.6695960586 0.2042981491 2.0518698671 0.0330384027 0.0549126807 0.7563345372 -0.651038500665 +1403715936884058112.0000000000 -1.6621971510 0.2127138467 2.0438808092 0.0355935875 0.0539082741 0.7627672382 -0.643438524482 +1403715936934057984.0000000000 -1.6546835963 0.2252674312 2.0358517762 0.0365150320 0.0537724835 0.7690031042 -0.635931913189 +1403715936984058112.0000000000 -1.6470650762 0.2413916274 2.0280388214 0.0359164289 0.0527751137 0.7740752581 -0.62986688461 +1403715937034057984.0000000000 -1.6392690674 0.2607427018 2.0201515853 0.0344308323 0.0501487176 0.7792245522 -0.623785797473 +1403715937084058112.0000000000 -1.6312543933 0.2829750430 2.0116355469 0.0317565510 0.0462993328 0.7854526373 -0.61637005758 +1403715937134057984.0000000000 -1.6231757566 0.3077214956 2.0025081616 0.0270506904 0.0415954844 0.7930299826 -0.607158564557 +1403715937184058112.0000000000 -1.6147421391 0.3341123244 1.9938452683 0.0217288457 0.0350670936 0.7986673611 -0.600357062529 +1403715937234057984.0000000000 -1.6061306945 0.3616680037 1.9846015276 0.0166881171 0.0269916396 0.8034685910 -0.594500783396 +1403715937284058112.0000000000 -1.5972328555 0.3902299180 1.9731987850 0.0092902758 0.0182359777 0.8074239070 -0.589616633292 +1403715937334057984.0000000000 -1.5884043545 0.4194344606 1.9594206127 0.0035854160 0.0069627061 0.8096583883 -0.586849179814 +1403715937384058112.0000000000 -1.5795461055 0.4490873813 1.9432284329 0.0033230518 0.0043148601 -0.8105513489 0.585642254406 +1403715937434057984.0000000000 -1.5707349455 0.4792209741 1.9243171029 0.0107429080 0.0155743779 -0.8111992391 0.584463705658 +1403715937484058112.0000000000 -1.5621727459 0.5095649818 1.9018658989 0.0171472970 0.0263266755 -0.8136571336 0.580495430902 +1403715937534057984.0000000000 -1.5538074833 0.5403957698 1.8754560054 0.0245181547 0.0348237713 -0.8196496548 0.571279798715 +1403715937584058112.0000000000 -1.5457624912 0.5705925423 1.8463159459 0.0291533312 0.0443602594 -0.8276283007 0.558760813295 +1403715937634057984.0000000000 -1.5374617486 0.5989411810 1.8173244928 0.0339694932 0.0542507834 -0.8351171876 0.546335253272 +1403715937684058112.0000000000 -1.5292806489 0.6253167803 1.7887152865 0.0392659004 0.0636184757 -0.8412075133 0.535519185625 +1403715937734057984.0000000000 -1.5208300567 0.6490730854 1.7604053783 0.0436716243 0.0729458865 -0.8455844725 0.527028070209 +1403715937784058112.0000000000 -1.5118623592 0.6698871380 1.7331966169 0.0494210427 0.0814385538 -0.8484619951 0.520612682735 +1403715937834057984.0000000000 -1.5025550547 0.6873420953 1.7061922122 0.0538606049 0.0910852697 -0.8504187050 0.51535476619 +1403715937884058112.0000000000 -1.4923280167 0.7010166451 1.6806784367 0.0600287467 0.0992313230 -0.8515294350 0.511319191412 +1403715937934057984.0000000000 -1.4814648324 0.7112390916 1.6554218268 0.0646084793 0.1089963932 -0.8519585629 0.508047377525 +1403715937984058112.0000000000 -1.4694641438 0.7177278147 1.6305099948 0.0691101374 0.1195140970 -0.8521793316 0.50470838744 +1403715938034057984.0000000000 -1.4562688943 0.7201102314 1.6066938545 0.0752645892 0.1293967860 -0.8519701259 0.501735605679 +1403715938084058112.0000000000 -1.4417842773 0.7180573465 1.5841939690 0.0809545429 0.1397893760 -0.8519333322 0.498111322741 +1403715938134057984.0000000000 -1.4257515456 0.7112822656 1.5645967634 0.0864414397 0.1509969637 -0.8512114351 0.495143299603 +1403715938184058112.0000000000 -1.4078843230 0.6998462944 1.5485666798 0.0924161598 0.1625759148 -0.8505256363 0.491563289253 +1403715938234057984.0000000000 -1.3878346558 0.6830255944 1.5376273972 0.0988135575 0.1740159711 -0.8474033744 0.49179451375 +1403715938284058112.0000000000 -1.3658181963 0.6610180454 1.5311721597 0.1035940031 0.1877539489 -0.8408118000 0.497043513407 +1403715938334057984.0000000000 -1.3418697704 0.6347088918 1.5294096675 0.1078637508 0.2021790798 -0.8305375294 0.507638102557 +1403715938384058112.0000000000 -1.3155686231 0.6052064400 1.5314851097 0.1119113671 0.2169891642 -0.8197162872 0.518128127983 +1403715938434057984.0000000000 -1.2871621506 0.5742878483 1.5359277679 0.1199439548 0.2284625440 -0.8100532298 0.526528326408 +1403715938484058112.0000000000 -1.2570455001 0.5424440045 1.5419582030 0.1294068763 0.2392300888 -0.7998467829 0.535040137613 +1403715938534057984.0000000000 -1.2252568437 0.5100846570 1.5474368018 0.1398741439 0.2482187531 -0.7918950931 0.540115576525 +1403715938584058112.0000000000 -1.1926267873 0.4776993588 1.5515852161 0.1495085968 0.2559898336 -0.7854089512 0.543368350116 +1403715938634057984.0000000000 -1.1595464932 0.4452273843 1.5545427197 0.1569281454 0.2624907960 -0.7811664151 0.544289602241 +1403715938684058112.0000000000 -1.1257495621 0.4124783579 1.5568870583 0.1629606723 0.2680631100 -0.7795080478 0.542174503044 +1403715938734057984.0000000000 -1.0917095630 0.3795856533 1.5577029953 0.1658734117 0.2733102338 -0.7815114850 0.53574931286 +1403715938784058112.0000000000 -1.0573446195 0.3464949512 1.5579088810 0.1660827846 0.2789033031 -0.7856380368 0.526689976432 +1403715938834057984.0000000000 -1.0215806952 0.3124501124 1.5575289768 0.1654574360 0.2837435954 -0.7914895805 0.515419880179 +1403715938884058112.0000000000 -0.9845061604 0.2772431441 1.5565379890 0.1645611911 0.2878718015 -0.7973699716 0.504232653266 +1403715938934057984.0000000000 -0.9458108471 0.2405503075 1.5552230746 0.1632877463 0.2917091530 -0.8023967371 0.494370668936 +1403715938984058112.0000000000 -0.9049491423 0.2017870659 1.5532222275 0.1626960454 0.2946363301 -0.8070088561 0.485238226077 +1403715939034057984.0000000000 -0.8619523555 0.1605388726 1.5506180347 0.1622676856 0.2971610467 -0.8107036174 0.477623445087 +1403715939084058112.0000000000 -0.8164038611 0.1163655875 1.5476340540 0.1611986416 0.2998629811 -0.8130368978 0.47230095626 +1403715939134057984.0000000000 -0.7675085201 0.0688396037 1.5457492437 0.1622367891 0.3012548812 -0.8120956184 0.47267898982 +1403715939184058112.0000000000 -0.7151361300 0.0175350178 1.5457045081 0.1663129731 0.3005312976 -0.8059159850 0.482203649248 +1403715939234057984.0000000000 -0.6596408216 -0.0369390490 1.5474308767 0.1728754056 0.2979712501 -0.7951576394 0.499050655513 +1403715939284058112.0000000000 -0.6021762125 -0.0931381061 1.5496447757 0.1800829438 0.2948427557 -0.7828193746 0.517524598034 +1403715939334057984.0000000000 -0.5437947877 -0.1499297473 1.5518058778 0.1874645338 0.2907411746 -0.7700056655 0.536113694194 +1403715939384058112.0000000000 -0.4849798929 -0.2065801935 1.5535345625 0.1952653090 0.2857012817 -0.7565733785 0.554835975496 +1403715939434057984.0000000000 -0.4271001502 -0.2619114537 1.5543024910 0.2014650184 0.2809833225 -0.7441316654 0.571601507507 +1403715939484058112.0000000000 -0.3707301633 -0.3149866691 1.5544595143 0.2070580109 0.2765620547 -0.7326007497 0.586461040136 +1403715939534057984.0000000000 -0.3164435069 -0.3653769831 1.5544709369 0.2108919414 0.2726517916 -0.7216008597 0.600398025374 +1403715939584058112.0000000000 -0.2649036953 -0.4120656797 1.5549315192 0.2146738467 0.2681346858 -0.7115468927 0.612959990015 +1403715939634057984.0000000000 -0.2167810891 -0.4543938505 1.5579675776 0.2194593285 0.2624298130 -0.6980702183 0.629020004964 +1403715939684058112.0000000000 -0.1731626957 -0.4911813973 1.5633536008 0.2245828923 0.2560536020 -0.6844309735 0.644634252835 +1403715939734057984.0000000000 -0.1350522620 -0.5213384205 1.5702917127 0.2284768715 0.2502230634 -0.6723830867 0.658094007285 +1403715939784058112.0000000000 -0.1027502863 -0.5444795960 1.5791162383 0.2317385238 0.2448395463 -0.6631427917 0.668275759626 +1403715939834057984.0000000000 -0.0767867597 -0.5601716389 1.5902551299 0.2331674098 0.2407005344 -0.6557745694 0.676502716769 +1403715939884058112.0000000000 -0.0579407402 -0.5670401857 1.6038280887 0.2338598087 0.2376131441 -0.6506243586 0.682303105338 +1403715939934057984.0000000000 -0.0463002830 -0.5647022454 1.6195649149 0.2327338167 0.2362836698 -0.6497334254 0.683996691464 +1403715939984058112.0000000000 -0.0416958703 -0.5536204938 1.6377326014 0.2300544321 0.2368725989 -0.6535065469 0.681098761751 +1403715940034057984.0000000000 -0.0436815853 -0.5342408637 1.6563057659 0.2229924367 0.2413732216 -0.6665311026 0.669140964481 +1403715940084058112.0000000000 -0.0516557223 -0.5071188454 1.6756475981 0.2149303019 0.2475580648 -0.6845072792 0.651129598889 +1403715940134057984.0000000000 -0.0644923466 -0.4736620778 1.6962029821 0.2057238199 0.2544099616 -0.7041410790 0.630189354218 +1403715940184058112.0000000000 -0.0810003228 -0.4350572774 1.7177327444 0.1972878511 0.2608471645 -0.7226739087 0.60891598952 +1403715940234057984.0000000000 -0.0998576775 -0.3925638638 1.7391833777 0.1887078199 0.2669599667 -0.7402056764 0.587551947979 +1403715940284058112.0000000000 -0.1199008206 -0.3474017678 1.7603929875 0.1813150838 0.2724635749 -0.7569078498 0.565666816822 +1403715940334057984.0000000000 -0.1401595528 -0.3008509097 1.7813711665 0.1742199306 0.2777922209 -0.7730103768 0.543078129847 +1403715940384058112.0000000000 -0.1596762356 -0.2543761895 1.8022751592 0.1677061921 0.2822536373 -0.7875631736 0.521489947192 +1403715940434057984.0000000000 -0.1780588187 -0.2087414542 1.8221293241 0.1604985218 0.2867334248 -0.8019115820 0.498960902538 +1403715940484058112.0000000000 -0.1940809722 -0.1651970268 1.8414526576 0.1538865245 0.2905467831 -0.8151400228 0.476915346351 +1403715940534057984.0000000000 -0.2068639831 -0.1246706602 1.8602914674 0.1485967547 0.2929250250 -0.8283528072 0.45381225306 +1403715940584058112.0000000000 -0.2154999584 -0.0884669763 1.8787980335 0.1437700552 0.2943080449 -0.8416411580 0.429363607054 +1403715940634057984.0000000000 -0.2194408072 -0.0578000805 1.8968310173 0.1388453488 0.2952481695 -0.8541175882 0.405010657948 +1403715940684058112.0000000000 -0.2174612673 -0.0340548082 1.9150156563 0.1357466566 0.2944077955 -0.8655533372 0.381725445447 +1403715940734057984.0000000000 -0.2093969502 -0.0193017677 1.9338289921 0.1310125466 0.2957464484 -0.8734352954 0.363978757256 +1403715940784058112.0000000000 -0.1946265914 -0.0144412268 1.9534777533 0.1251036756 0.2988436068 -0.8780378041 0.352265785378 +1403715940834057984.0000000000 -0.1717425878 -0.0206809726 1.9744760409 0.1207478295 0.3015036940 -0.8796291128 0.347517061499 +1403715940884058112.0000000000 -0.1399374102 -0.0386325628 1.9975620808 0.1184055798 0.3032330111 -0.8774280817 0.352349004532 +1403715940934057984.0000000000 -0.0984966783 -0.0682462354 2.0231563379 0.1203782891 0.3024990807 -0.8711623880 0.367531587035 +1403715940984058112.0000000000 -0.0485738602 -0.1083177258 2.0520854226 0.1270417777 0.2986613544 -0.8594297807 0.395021814845 +1403715941034057984.0000000000 0.0077705655 -0.1560188852 2.0826344358 0.1362798085 0.2934370191 -0.8435544895 0.428647119333 +1403715941084058112.0000000000 0.0690525639 -0.2094710361 2.1147627809 0.1474327996 0.2865717707 -0.8229029692 0.467943258368 +1403715941134057984.0000000000 0.1331328195 -0.2656834924 2.1483433902 0.1614836452 0.2765247012 -0.7989039928 0.509126243861 +1403715941184058112.0000000000 0.1981007110 -0.3225185245 2.1820722177 0.1743288933 0.2666486448 -0.7723216464 0.54957002439 +1403715941234057984.0000000000 0.2622383276 -0.3777759300 2.2138422490 0.1859506499 0.2567991874 -0.7486874879 0.582188610897 +1403715941284058112.0000000000 0.3243400657 -0.4298611542 2.2442182483 0.1979210343 0.2467635385 -0.7282579921 0.60792706565 +1403715941334057984.0000000000 0.3831789443 -0.4779767821 2.2724346867 0.2072836403 0.2387847824 -0.7117408473 0.627248185662 +1403715941384058112.0000000000 0.4383559107 -0.5214797496 2.2986055304 0.2152483562 0.2315980780 -0.6976290044 0.642918538929 +1403715941434057984.0000000000 0.4894861979 -0.5600550928 2.3212079849 0.2228753294 0.2250354339 -0.6854112495 0.655665356751 +1403715941484058112.0000000000 0.5361474084 -0.5940229369 2.3376695620 0.2288156271 0.2203725231 -0.6777371643 0.663137765445 +1403715941534057984.0000000000 0.5777677396 -0.6232703844 2.3482131049 0.2338058519 0.2164369606 -0.6711343571 0.669379220192 +1403715941584058112.0000000000 0.6139559465 -0.6472591598 2.3533744179 0.2384763110 0.2129686922 -0.6652689724 0.674678130363 +1403715941634057984.0000000000 0.6440377290 -0.6655972449 2.3544206628 0.2444755876 0.2083462581 -0.6578096313 0.681256201945 +1403715941684058112.0000000000 0.6668788511 -0.6772550956 2.3527025992 0.2512814594 0.2030565906 -0.6496539657 0.688168129178 +1403715941734057984.0000000000 0.6816925929 -0.6816684887 2.3492640975 0.2584643417 0.1976289480 -0.6407006984 0.695443454255 +1403715941784058112.0000000000 0.6879628354 -0.6787433829 2.3442976323 0.2645261529 0.1928670631 -0.6312999069 0.70305663921 +1403715941834057984.0000000000 0.6851945646 -0.6681978537 2.3380223939 0.2684879637 0.1895498787 -0.6237700686 0.709151576405 +1403715941884058112.0000000000 0.6724744948 -0.6489676201 2.3301134539 0.2707213967 0.1881303601 -0.6196603105 0.71227662643 +1403715941934057984.0000000000 0.6498891429 -0.6212266193 2.3198475314 0.2668254145 0.1907460981 -0.6212495828 0.711666410708 +1403715941984058112.0000000000 0.6176609396 -0.5847023998 2.3068969814 0.2602831164 0.1966785505 -0.6315848458 0.703328393864 +1403715942034057984.0000000000 0.5767580619 -0.5402857433 2.2906579667 0.2495812354 0.2063108446 -0.6490513730 0.688387505344 +1403715942084058112.0000000000 0.5283113329 -0.4889066763 2.2720941194 0.2380278622 0.2169267700 -0.6704983556 0.668369260545 +1403715942134057984.0000000000 0.4740327049 -0.4316543540 2.2505017308 0.2264374598 0.2277562265 -0.6939281047 0.644450900826 +1403715942184058112.0000000000 0.4156116186 -0.3703593514 2.2248425542 0.2149597637 0.2380779633 -0.7168184187 0.619098165123 +1403715942234057984.0000000000 0.3541568974 -0.3060323507 2.1942222417 0.2044804825 0.2472751290 -0.7383961706 0.593138970348 +1403715942284058112.0000000000 0.2905512087 -0.2398940489 2.1567195467 0.1932548766 0.2562740108 -0.7611225889 0.563620961997 +1403715942334057984.0000000000 0.2264795481 -0.1733078223 2.1145737224 0.1832335924 0.2635553416 -0.7803458116 0.536679091095 +1403715942384058112.0000000000 0.1634251112 -0.1076111877 2.0684339951 0.1752311215 0.2691392402 -0.7964949266 0.512302601372 +1403715942434057984.0000000000 0.1019797751 -0.0441788866 2.0193575547 0.1696506800 0.2727361619 -0.8087300761 0.492736538928 +1403715942484058112.0000000000 0.0429648499 0.0165291074 1.9680427971 0.1657515439 0.2752954055 -0.8203670877 0.473008146747 +1403715942534057984.0000000000 -0.0132232272 0.0732120313 1.9160605574 0.1616140393 0.2779293412 -0.8297471647 0.456240973893 +1403715942584058112.0000000000 -0.0661399024 0.1253423747 1.8641290414 0.1561107817 0.2819064279 -0.8382634345 0.439855208072 +1403715942634057984.0000000000 -0.1149636369 0.1718483518 1.8125556906 0.1496829203 0.2868881470 -0.8451807317 0.425393635588 +1403715942684058112.0000000000 -0.1590476073 0.2122547511 1.7620309827 0.1439486552 0.2915527434 -0.8505207637 0.413388694691 +1403715942734057984.0000000000 -0.1970238043 0.2454407337 1.7125721650 0.1399706096 0.2953784126 -0.8536068951 0.405604598694 +1403715942784058112.0000000000 -0.2285891269 0.2708607732 1.6646479192 0.1371853093 0.2984865234 -0.8550169931 0.401287836628 +1403715942834057984.0000000000 -0.2535966921 0.2887206581 1.6180379095 0.1358517537 0.3007814715 -0.8551239357 0.399797276163 +1403715942884058112.0000000000 -0.2718380615 0.2985969188 1.5726097729 0.1352679689 0.3030135997 -0.8539102095 0.400902343529 +1403715942934057984.0000000000 -0.2831473723 0.3009063610 1.5278270900 0.1357397426 0.3045192257 -0.8525208703 0.402555498319 +1403715942984058112.0000000000 -0.2872477795 0.2957508971 1.4852141375 0.1360878536 0.3063617579 -0.8497949107 0.406781488154 +1403715943034057984.0000000000 -0.2849421949 0.2833488825 1.4468830712 0.1355034313 0.3093643854 -0.8460560184 0.412458132254 +1403715943084058112.0000000000 -0.2755922324 0.2631457509 1.4133384372 0.1329915547 0.3140665034 -0.8411412173 0.419710531762 +1403715943134057984.0000000000 -0.2583805244 0.2362184860 1.3847858137 0.1337578933 0.3160146642 -0.8352374143 0.429676645634 +1403715943184058112.0000000000 -0.2338512358 0.2030191484 1.3616403385 0.1386295517 0.3154128861 -0.8266523320 0.444907271953 +1403715943234057984.0000000000 -0.2028487178 0.1651846964 1.3441209582 0.1492549859 0.3101562180 -0.8150660785 0.466040081197 +1403715943284058112.0000000000 -0.1664470683 0.1235808319 1.3317410572 0.1623392675 0.3038418320 -0.7995277982 0.492017685954 +1403715943334057984.0000000000 -0.1268970065 0.0806019321 1.3231067395 0.1771199769 0.2972048678 -0.7814389729 0.519279223524 +1403715943384058112.0000000000 -0.0857820625 0.0373320412 1.3175532261 0.1910667626 0.2920904599 -0.7615233087 0.546130850419 +1403715943434057984.0000000000 -0.0448988912 -0.0042902175 1.3137684280 0.2051227884 0.2869367416 -0.7411505876 0.571216031383 +1403715943484058112.0000000000 -0.0056212512 -0.0431140449 1.3092751010 0.2167966000 0.2838862350 -0.7242844868 0.589762513174 +1403715943534057984.0000000000 0.0309172167 -0.0791104381 1.3035752033 0.2249865372 0.2815467747 -0.7121013360 0.602514862091 +1403715943584058112.0000000000 0.0639224633 -0.1117429846 1.2973625187 0.2303747207 0.2795868561 -0.7025025437 0.612575590491 +1403715943634057984.0000000000 0.0932536412 -0.1403567000 1.2910334027 0.2357563640 0.2766570943 -0.6945834536 0.620833000949 +1403715943684058112.0000000000 0.1181522588 -0.1644170769 1.2854512484 0.2400981411 0.2727453781 -0.6878385470 0.628363728002 +1403715943734057984.0000000000 0.1385091321 -0.1839659761 1.2813002275 0.2454604473 0.2672725860 -0.6818022164 0.635185226044 +1403715943784058112.0000000000 0.1536724336 -0.1987093261 1.2790166784 0.2492568213 0.2615610279 -0.6744734255 0.643849721627 +1403715943834057984.0000000000 0.1625002001 -0.2075367285 1.2786178364 0.2514030031 0.2561146815 -0.6681189181 0.651781337002 +1403715943884058112.0000000000 0.1642659121 -0.2093512733 1.2815724120 0.2533294778 0.2511988886 -0.6634177044 0.65772353121 +1403715943934057984.0000000000 0.1587643573 -0.2041264517 1.2893298460 0.2529338261 0.2477607666 -0.6597170493 0.662881963136 +1403715943984058112.0000000000 0.1455487665 -0.1909560292 1.3006206905 0.2520481307 0.2461651675 -0.6621992250 0.66133700674 +1403715944034057984.0000000000 0.1249386403 -0.1700153564 1.3136924604 0.2497582480 0.2481088357 -0.6742759939 0.649164622611 +1403715944084058112.0000000000 0.0977320339 -0.1417497924 1.3275501555 0.2448940292 0.2545947382 -0.6947805143 0.626489002881 +1403715944134057984.0000000000 0.0657135508 -0.1085757739 1.3429356640 0.2387888017 0.2637964822 -0.7163250658 0.600224728081 +1403715944184058112.0000000000 0.0298516166 -0.0717502154 1.3587966607 0.2332699041 0.2743636026 -0.7374831295 0.571339127852 +1403715944234057984.0000000000 -0.0085501095 -0.0332821653 1.3736587570 0.2267844422 0.2868737884 -0.7592616806 0.538325131058 +1403715944284058112.0000000000 -0.0481203267 0.0049093990 1.3872781908 0.2200283760 0.3005115499 -0.7773696343 0.506928765996 +1403715944334057984.0000000000 -0.0874316093 0.0415498568 1.4000788661 0.2143019866 0.3146143128 -0.7897385534 0.481046266008 +1403715944384058112.0000000000 -0.1252458239 0.0757025975 1.4106346276 0.2095483288 0.3294667425 -0.7979143533 0.459210026262 +1403715944434057984.0000000000 -0.1600575972 0.1067269789 1.4195754005 0.2067430259 0.3441508244 -0.8037315496 0.439127689325 +1403715944484058112.0000000000 -0.1917420039 0.1341057062 1.4262062910 0.2044894427 0.3594871674 -0.8072518444 0.421067101501 +1403715944534057984.0000000000 -0.2189912203 0.1571094921 1.4330206619 0.2044640303 0.3740813625 -0.8082913377 0.406106769186 +1403715944584058112.0000000000 -0.2405202742 0.1749959357 1.4410648802 0.2074613400 0.3871020055 -0.8079645009 0.392816999509 +1403715944634057984.0000000000 -0.2556641483 0.1869950988 1.4496653531 0.2112674153 0.4000963935 -0.8055715962 0.382548504748 +1403715944684058112.0000000000 -0.2636949593 0.1927848365 1.4594778822 0.2169647685 0.4117082965 -0.8025164124 0.373349669519 +1403715944734057984.0000000000 -0.2644300281 0.1922609201 1.4701852501 0.2226038706 0.4237928951 -0.7981604913 0.365768955712 +1403715944784058112.0000000000 -0.2579159279 0.1854321512 1.4817115687 0.2269610228 0.4379133618 -0.7911428073 0.361681683638 +1403715944834057984.0000000000 -0.2436880144 0.1726402481 1.4950422470 0.2336972050 0.4510302902 -0.7810506390 0.363204065276 +1403715944884058112.0000000000 -0.2212736330 0.1539384515 1.5103807720 0.2419093540 0.4640233188 -0.7646531291 0.376122076245 +1403715944934057984.0000000000 -0.1913400680 0.1307132056 1.5276206043 0.2539451917 0.4748380494 -0.7433120962 0.396897712425 +1403715944984058112.0000000000 -0.1561752397 0.1051397336 1.5455878993 0.2692937110 0.4820111221 -0.7191990363 0.421780655729 +1403715945034057984.0000000000 -0.1172640230 0.0784279778 1.5638417416 0.2869635851 0.4854373898 -0.6921244012 0.450517762785 +1403715945084058112.0000000000 -0.0760759282 0.0519762164 1.5826085037 0.3049823271 0.4850003190 -0.6654850435 0.478424631106 +1403715945134057984.0000000000 -0.0340620538 0.0266111821 1.6007166608 0.3202062935 0.4823424332 -0.6431703407 0.501144310052 +1403715945184058112.0000000000 0.0066105878 0.0031085962 1.6171464649 0.3313562064 0.4800329624 -0.6247646396 0.51907664619 +1403715945234057984.0000000000 0.0446403243 -0.0178746140 1.6330708799 0.3414100857 0.4762097715 -0.6096996189 0.533788143016 +1403715945284058112.0000000000 0.0795372953 -0.0361161665 1.6488499676 0.3495253828 0.4719019982 -0.5973395191 0.54619228278 +1403715945334057984.0000000000 0.1101714564 -0.0510272969 1.6655669734 0.3580123886 0.4658763870 -0.5861054565 0.557912820683 +1403715945384058112.0000000000 0.1357005313 -0.0619863743 1.6829773293 0.3652906958 0.4592845911 -0.5749275691 0.570156699722 +1403715945434057984.0000000000 0.1550721824 -0.0686217169 1.7013924586 0.3729335602 0.4516640885 -0.5654201268 0.580706630808 +1403715945484058112.0000000000 0.1673479604 -0.0704505427 1.7211681068 0.3818371241 0.4430220353 -0.5570243686 0.589623388025 +1403715945534057984.0000000000 0.1712698883 -0.0677731547 1.7406043067 0.3878120081 0.4361369304 -0.5521789305 0.595386305708 +1403715945584058112.0000000000 0.1665402067 -0.0602238803 1.7572700286 0.3887211052 0.4355539580 -0.5606577165 0.587240646597 +1403715945634057984.0000000000 0.1537324639 -0.0485821043 1.7708576248 0.3817550150 0.4419629344 -0.5788638951 0.569076852596 +1403715945684058112.0000000000 0.1340691201 -0.0334873006 1.7838724331 0.3727704285 0.4499086163 -0.5989635172 0.547601268861 +1403715945734057984.0000000000 0.1090408073 -0.0162271487 1.7967396128 0.3616116864 0.4582275847 -0.6174930151 0.527225611264 +1403715945784058112.0000000000 0.0799599877 0.0028910032 1.8090287489 0.3487722688 0.4672690909 -0.6350540183 0.506679282161 +1403715945834057984.0000000000 0.0478846167 0.0231998668 1.8205700807 0.3329855480 0.4776937675 -0.6518763697 0.485784404853 +1403715945884058112.0000000000 0.0148975418 0.0443489743 1.8323665243 0.3179944771 0.4867095020 -0.6680369870 0.464456625838 +1403715945934057984.0000000000 -0.0171356214 0.0656717175 1.8433916727 0.3028091019 0.4957029217 -0.6824336181 0.443699918975 +1403715945984058112.0000000000 -0.0466391351 0.0870366760 1.8548737610 0.2916231562 0.5027704796 -0.6941982041 0.424578182445 +1403715946034057984.0000000000 -0.0726359855 0.1078412972 1.8661083632 0.2817295047 0.5107906153 -0.7023509984 0.407951600799 +1403715946084058112.0000000000 -0.0935956528 0.1276289232 1.8778729890 0.2745457802 0.5184071996 -0.7076050445 0.393920919582 +1403715946134057984.0000000000 -0.1091817614 0.1466135602 1.8891316718 0.2689917413 0.5257390014 -0.7124016627 0.379111878606 +1403715946184058112.0000000000 -0.1185426000 0.1640215231 1.9003300225 0.2635209948 0.5347429464 -0.7147336643 0.3657354996 +1403715946234057984.0000000000 -0.1205170287 0.1799368128 1.9122312633 0.2603761786 0.5429840305 -0.7157695390 0.353619223587 +1403715946284058112.0000000000 -0.1139492599 0.1937685415 1.9251509056 0.2594502726 0.5503749416 -0.7146694623 0.344993535114 +1403715946334057984.0000000000 -0.0987628895 0.2056371815 1.9391465373 0.2620914323 0.5575175862 -0.7092496613 0.342705617338 +1403715946384058112.0000000000 -0.0736081919 0.2151778247 1.9551059747 0.2690312760 0.5636072218 -0.6986300541 0.349120494383 +1403715946434057984.0000000000 -0.0392671693 0.2229520371 1.9732983317 0.2812243464 0.5665233944 -0.6840755646 0.363324555276 +1403715946484058112.0000000000 0.0021223795 0.2300188627 1.9925015073 0.2974148471 0.5659542459 -0.6671456626 0.382304675859 +1403715946534057984.0000000000 0.0490036691 0.2372971550 2.0118041758 0.3163616901 0.5617745679 -0.6513599104 0.400068597923 +1403715946584058112.0000000000 0.1000318039 0.2448374830 2.0322764386 0.3373887788 0.5542241279 -0.6351717078 0.419000393296 +1403715946634057984.0000000000 0.1523220131 0.2524963534 2.0528524302 0.3575030574 0.5457175141 -0.6184853523 0.438018067866 +1403715946684058112.0000000000 0.2044507892 0.2606014810 2.0736739021 0.3770272590 0.5362570076 -0.6036507722 0.453745096983 +1403715946734057984.0000000000 0.2547641647 0.2692671952 2.0933343290 0.3911959304 0.5290464506 -0.5910092964 0.466672914078 +1403715946784058112.0000000000 0.3021025241 0.2789999959 2.1116718893 0.4041054500 0.5220266827 -0.5811819755 0.475830262934 +1403715946834057984.0000000000 0.3463731179 0.2888429386 2.1281324449 0.4126918353 0.5176043601 -0.5741051533 0.481844838522 +1403715946884058112.0000000000 0.3870316217 0.2990344162 2.1433139912 0.4199347887 0.5135031341 -0.5677321890 0.487493042156 +1403715946934057984.0000000000 0.4228341858 0.3097304969 2.1576392256 0.4262769048 0.5095967289 -0.5614792156 0.493295311952 +1403715946984058112.0000000000 0.4534564448 0.3205719144 2.1706837917 0.4301919158 0.5063639321 -0.5558631178 0.499546472461 +1403715947034057984.0000000000 0.4789962173 0.3320349597 2.1834275213 0.4360274604 0.5013412244 -0.5504587810 0.505501890103 +1403715947084058112.0000000000 0.4988631315 0.3441481604 2.1959834912 0.4431456520 0.4947524331 -0.5453635054 0.511293074514 +1403715947134057984.0000000000 0.5121079535 0.3567932526 2.2098658585 0.4543381689 0.4831550000 -0.5360677200 0.522273370785 +1403715947184058112.0000000000 0.5177752777 0.3697878799 2.2229704608 0.4648515778 0.4709635638 -0.5257466382 0.53450613156 +1403715947234057984.0000000000 0.5149735028 0.3833696712 2.2338918234 0.4726414513 0.4610392113 -0.5195521455 0.542326905359 +1403715947284058112.0000000000 0.5031263141 0.3974762888 2.2414700921 0.4761757687 0.4551102130 -0.5177584634 0.545946430415 +1403715947334057984.0000000000 0.4819262361 0.4122574241 2.2451118636 0.4742732523 0.4551929584 -0.5229515774 0.542573405622 +1403715947384058112.0000000000 0.4521653463 0.4272212480 2.2443546508 0.4652858486 0.4618447747 -0.5339748379 0.533928230777 +1403715947434057984.0000000000 0.4144664658 0.4428705611 2.2387960927 0.4504965855 0.4740240831 -0.5497922998 0.519694546934 +1403715947484058112.0000000000 0.3697219080 0.4592382473 2.2310001425 0.4362103739 0.4863944475 -0.5668776940 0.501787436219 +1403715947534057984.0000000000 0.3195457255 0.4760385918 2.2208370398 0.4226183571 0.4979852805 -0.5832358700 0.482949588117 +1403715947584058112.0000000000 0.2651254761 0.4931099039 2.2078632672 0.4118113220 0.5074117908 -0.5991732294 0.462532324053 +1403715947634057984.0000000000 0.2086517606 0.5093832341 2.1911145492 0.3972359026 0.5187539963 -0.6159257610 0.440151548755 +1403715947684058112.0000000000 0.1514741027 0.5251901976 2.1721306810 0.3844324260 0.5280306216 -0.6314463249 0.417936491809 +1403715947734057984.0000000000 0.0950470987 0.5396445541 2.1502345819 0.3713679966 0.5369396152 -0.6443798714 0.398191212803 +1403715947784058112.0000000000 0.0408043870 0.5524550349 2.1260418775 0.3580827933 0.5457017782 -0.6528113420 0.384478392339 +1403715947834057984.0000000000 -0.0106194221 0.5636330501 2.0997378899 0.3452625765 0.5546214221 -0.6579143020 0.374616607502 +1403715947884058112.0000000000 -0.0581925801 0.5730326124 2.0710403843 0.3319010411 0.5638772291 -0.6620441074 0.365488398385 +1403715947934057984.0000000000 -0.1012320100 0.5814856841 2.0408543082 0.3200544032 0.5723164228 -0.6658279211 0.355938577122 +1403715947984058112.0000000000 -0.1385052754 0.5887997173 2.0102442041 0.3084563627 0.5807890024 -0.6689198937 0.346532802037 +1403715948034057984.0000000000 -0.1689790666 0.5951504958 1.9803638963 0.2978949741 0.5884294346 -0.6721384570 0.336510445083 +1403715948084058112.0000000000 -0.1917748395 0.6005768116 1.9511977642 0.2886339097 0.5950223992 -0.6753128315 0.32648336916 +1403715948134057984.0000000000 -0.2049577450 0.6047580392 1.9234791998 0.2812680963 0.6007083406 -0.6765440040 0.319884288768 +1403715948184058112.0000000000 -0.2082307740 0.6080821847 1.8975863094 0.2759093126 0.6051024893 -0.6772029976 0.314835081722 +1403715948234057984.0000000000 -0.2007584312 0.6106897617 1.8749192817 0.2766862692 0.6058054254 -0.6763109402 0.314718933595 +1403715948284058112.0000000000 -0.1821755142 0.6124073253 1.8552320446 0.2822502818 0.6038334600 -0.6731198978 0.320358446282 +1403715948334057984.0000000000 -0.1529565520 0.6135294944 1.8382074554 0.2940538723 0.5987203660 -0.6671526858 0.331622582518 +1403715948384058112.0000000000 -0.1148096060 0.6138146999 1.8231963650 0.3101261331 0.5906116819 -0.6588865306 0.347660988036 +1403715948434057984.0000000000 -0.0702119037 0.6134388246 1.8093145991 0.3273661777 0.5808970553 -0.6492241906 0.36592068425 +1403715948484058112.0000000000 -0.0207992153 0.6123036925 1.7961620397 0.3433584923 0.5710665345 -0.6378159385 0.386236698786 +1403715948534057984.0000000000 0.0310786751 0.6107669611 1.7832067965 0.3573714755 0.5611632035 -0.6270516908 0.405200770766 +1403715948584058112.0000000000 0.0853261722 0.6088202597 1.7704706819 0.3706129692 0.5506181176 -0.6155634552 0.42490863526 +1403715948634057984.0000000000 0.1394074792 0.6067285251 1.7564014757 0.3812922370 0.5410192966 -0.6065255463 0.4405009788 +1403715948684058112.0000000000 0.1924053081 0.6045775746 1.7418341406 0.3907339664 0.5316936620 -0.5974177504 0.455764027472 +1403715948734057984.0000000000 0.2433678100 0.6027423468 1.7269082976 0.4000803958 0.5219050455 -0.5884645327 0.470383135331 +1403715948784058112.0000000000 0.2904972197 0.6012125198 1.7109857254 0.4065499974 0.5140865267 -0.5813370546 0.482161147012 +1403715948834057984.0000000000 0.3333430663 0.6001589883 1.6945336865 0.4123063056 0.5075058187 -0.5758778089 0.490719984973 +1403715948884058112.0000000000 0.3717686678 0.5998122218 1.6783921429 0.4180712767 0.5019484789 -0.5707104822 0.497547663713 +1403715948934057984.0000000000 0.4050117381 0.6001384132 1.6631803206 0.4252238279 0.4974186972 -0.5658367058 0.501585643968 +1403715948984058112.0000000000 0.4324296200 0.6012227390 1.6491758733 0.4328370614 0.4940028402 -0.5593265727 0.505734176417 +1403715949034057984.0000000000 0.4536485983 0.6034385878 1.6361124304 0.4406632986 0.4917467850 -0.5526181762 0.50854115665 +1403715949084058112.0000000000 0.4680914671 0.6061459089 1.6235834975 0.4468530683 0.4921765510 -0.5470810765 0.508710992424 +1403715949134057984.0000000000 0.4754046367 0.6094795805 1.6116526447 0.4514677286 0.4955422773 -0.5441023600 0.504546690864 +1403715949184058112.0000000000 0.4753246818 0.6135491014 1.5994206426 0.4515893721 0.5042239034 -0.5447348099 0.495064926165 +1403715949234057984.0000000000 0.4682864536 0.6178268105 1.5858478260 0.4446759685 0.5194491949 -0.5496888170 0.479872922169 +1403715949284058112.0000000000 0.4561532122 0.6220312139 1.5729389710 0.4369834054 0.5358379596 -0.5557081555 0.461640152447 +1403715949334057984.0000000000 0.4395627863 0.6258841404 1.5602457268 0.4258886173 0.5545589543 -0.5626091651 0.441082961813 +1403715949384058112.0000000000 0.4205278497 0.6294145280 1.5483463997 0.4121589449 0.5735442980 -0.5702694247 0.41948149614 +1403715949434057984.0000000000 0.4004162218 0.6326083888 1.5369616454 0.3978339085 0.5914137289 -0.5778442970 0.39755999664 +1403715949484058112.0000000000 0.3810799858 0.6354347673 1.5275940785 0.3851971130 0.6071221210 -0.5824132633 0.379237003698 +1403715949534057984.0000000000 0.3640153790 0.6384051743 1.5193887920 0.3751709708 0.6208381120 -0.5851053283 0.362572111533 +1403715949584058112.0000000000 0.3502445945 0.6412648585 1.5120271998 0.3671329504 0.6336655573 -0.5842414808 0.349776000111 +1403715949634057984.0000000000 0.3406982188 0.6448496717 1.5056912388 0.3622248940 0.6446858917 -0.5828864496 0.336773832066 +1403715949684058112.0000000000 0.3359398254 0.6490496903 1.4999146451 0.3576673164 0.6555803812 -0.5805780992 0.324372510074 +1403715949734057984.0000000000 0.3366305546 0.6539831569 1.4946353836 0.3535763718 0.6663179906 -0.5771027229 0.312980082348 +1403715949784058112.0000000000 0.3433412295 0.6597017685 1.4898870476 0.3496346168 0.6771562575 -0.5716532485 0.304019080277 +1403715949834057984.0000000000 0.3574539459 0.6665920704 1.4864410790 0.3482188315 0.6866256595 -0.5637859067 0.299055681308 +1403715949884058112.0000000000 0.3784758241 0.6749684390 1.4839651202 0.3475607869 0.6959011752 -0.5541820572 0.296319593178 +1403715949934057984.0000000000 0.4070584738 0.6853377806 1.4830994583 0.3493575693 0.7040089580 -0.5422182053 0.29718696747 +1403715949984058112.0000000000 0.4426220399 0.6976412098 1.4835417536 0.3514736771 0.7117147853 -0.5281402899 0.30165568603 +1403715950034057984.0000000000 0.4845004186 0.7129500940 1.4848814613 0.3551422027 0.7185201915 -0.5136926993 0.306141406716 +1403715950084058112.0000000000 0.5324454855 0.7319031793 1.4874636727 0.3644663902 0.7220387929 -0.4968464347 0.314591564151 +1403715950134057984.0000000000 0.5855350748 0.7549005709 1.4920660725 0.3814229644 0.7200068198 -0.4788794946 0.326773822957 +1403715950184058112.0000000000 0.6420732116 0.7820004893 1.4980343663 0.4023161632 0.7134171340 -0.4640055434 0.337456002351 +1403715950234057984.0000000000 0.7005406823 0.8120930881 1.5055238791 0.4283036011 0.7014718985 -0.4499095465 0.349391758463 +1403715950284058112.0000000000 0.7583427085 0.8444902653 1.5128988313 0.4540930092 0.6875508390 -0.4402757481 0.356694054442 +1403715950334057984.0000000000 0.8142564010 0.8779635226 1.5198033621 0.4769978417 0.6738932912 -0.4317950958 0.363171979008 +1403715950384058112.0000000000 0.8675533429 0.9115389650 1.5257625851 0.4975490845 0.6602849490 -0.4249202592 0.368661725682 +1403715950434057984.0000000000 0.9174141030 0.9442982255 1.5311154617 0.5146182337 0.6477324342 -0.4181421364 0.375190513027 +1403715950484058112.0000000000 0.9626711188 0.9758517244 1.5364665500 0.5299330023 0.6354910629 -0.4111885769 0.382421333419 +1403715950534057984.0000000000 1.0027083354 1.0057404329 1.5418368037 0.5426369149 0.6240774837 -0.4051176966 0.389810370327 +1403715950584058112.0000000000 1.0365892502 1.0335059958 1.5464254208 0.5502274168 0.6165093969 -0.4012554730 0.395170847554 +1403715950634057984.0000000000 1.0634140741 1.0591601522 1.5517643468 0.5569369898 0.6099463564 -0.3987944816 0.398433925637 +1403715950684058112.0000000000 1.0828382516 1.0822093524 1.5579993333 0.5630238204 0.6038909230 -0.3959465819 0.401928146544 +1403715950734057984.0000000000 1.0944931989 1.1025332966 1.5652127463 0.5693453968 0.5973124226 -0.3929332358 0.405792017118 +1403715950784058112.0000000000 1.0978461321 1.1201504533 1.5729556969 0.5749051886 0.5918732947 -0.3896727857 0.409053966226 +1403715950834057984.0000000000 1.0922104626 1.1348026101 1.5816561083 0.5802778688 0.5870619915 -0.3871422760 0.410800038075 +1403715950884058112.0000000000 1.0775021993 1.1460818524 1.5910111957 0.5828870589 0.5848170046 -0.3850885292 0.412236063887 +1403715950934057984.0000000000 1.0536221109 1.1540843383 1.5998105561 0.5816880158 0.5872864973 -0.3871207450 0.408498655058 +1403715950984058112.0000000000 1.0205728051 1.1587011854 1.6070342210 0.5742893999 0.5968376876 -0.3951520849 0.397279862981 +1403715951034057984.0000000000 0.9793628553 1.1596214415 1.6129172261 0.5598212230 0.6123078513 -0.4065386618 0.382629860318 +1403715951084058112.0000000000 0.9318580787 1.1576932408 1.6187193061 0.5426781184 0.6291451950 -0.4179737156 0.367389107773 +1403715951134057984.0000000000 0.8793199136 1.1535443511 1.6244930061 0.5246594320 0.6465384535 -0.4275955770 0.35196950303 +1403715951184058112.0000000000 0.8233696367 1.1474854478 1.6297812914 0.5035400170 0.6658158876 -0.4354872250 0.336879105673 +1403715951234057984.0000000000 0.7652689879 1.1405567038 1.6350367114 0.4813713385 0.6854493981 -0.4427967428 0.319955937029 +1403715951284058112.0000000000 0.7075536885 1.1338983579 1.6408871872 0.4617430821 0.7028177662 -0.4478678827 0.30373487332 +1403715951334057984.0000000000 0.6508906108 1.1277344255 1.6467882908 0.4451902575 0.7175655260 -0.4518399957 0.28765599035 +1403715951384058112.0000000000 0.5970170095 1.1228286576 1.6533318201 0.4306745855 0.7309154920 -0.4532281975 0.273616786615 +1403715951434057984.0000000000 0.5469640582 1.1199310241 1.6600993658 0.4179610128 0.7431267353 -0.4530083446 0.260489321669 +1403715951484058112.0000000000 0.5018792908 1.1194142617 1.6673287771 0.4059576372 0.7545927623 -0.4522244031 0.247550498238 +1403715951534057984.0000000000 0.4623305150 1.1218489629 1.6751889442 0.3964179576 0.7644450755 -0.4508868873 0.234899008686 +1403715951584058112.0000000000 0.4290696997 1.1273656849 1.6834350800 0.3879647583 0.7738584195 -0.4474005938 0.224631256994 +1403715951634057984.0000000000 0.4024140934 1.1366449341 1.6925358469 0.3819541604 0.7817541716 -0.4438568570 0.21438872392 +1403715951684058112.0000000000 0.3836480887 1.1499490807 1.7020131664 0.3770826406 0.7893086122 -0.4381401300 0.206963337998 +1403715951734057984.0000000000 0.3725826526 1.1680630638 1.7125448616 0.3745312272 0.7952107328 -0.4334158554 0.19878869841 +1403715951784058112.0000000000 0.3693578319 1.1904271716 1.7232954608 0.3733099037 0.8006421346 -0.4270011368 0.19308525904 +1403715951834057984.0000000000 0.3751910037 1.2184763239 1.7352450765 0.3765979526 0.8036469837 -0.4205932266 0.188220204567 +1403715951884058112.0000000000 0.3902162268 1.2521058116 1.7490901585 0.3879267258 0.8029621072 -0.4114601695 0.188322167513 +1403715951934057984.0000000000 0.4135416585 1.2912570146 1.7662314418 0.4109741959 0.7960262875 -0.4003232828 0.192830570971 +1403715951984058112.0000000000 0.4430572868 1.3343117902 1.7845690602 0.4384041938 0.7863314947 -0.3865517728 0.200155615172 +1403715952034057984.0000000000 0.4771933363 1.3803086070 1.8029570434 0.4677615030 0.7746209046 -0.3716035501 0.207538989044 +1403715952084058112.0000000000 0.5140034340 1.4276381238 1.8216989259 0.4994592954 0.7599147716 -0.3565536816 0.214334841206 +1403715952134057984.0000000000 0.5518212202 1.4749066875 1.8401628018 0.5290102965 0.7453199308 -0.3404988853 0.22069620767 +1403715952184058112.0000000000 0.5888049223 1.5208579975 1.8575689732 0.5530416447 0.7334286143 -0.3255084601 0.224213401337 +1403715952234057984.0000000000 0.6248635896 1.5644886328 1.8741221488 0.5733514192 0.7227293807 -0.3132297338 0.225427430176 +1403715952284058112.0000000000 0.6598251866 1.6049844572 1.8895702086 0.5893735436 0.7142399006 -0.3025713261 0.225722801442 +1403715952334057984.0000000000 0.6928720339 1.6416938296 1.9043173505 0.6025449952 0.7071844422 -0.2931250559 0.225626672095 +1403715952384058112.0000000000 0.7235922957 1.6740253409 1.9187707167 0.6137868151 0.7009367532 -0.2846160620 0.225714666795 +1403715952434057984.0000000000 0.7515557473 1.7014261418 1.9329752311 0.6246742838 0.6941722612 -0.2771209139 0.226077221237 +1403715952484058112.0000000000 0.7760870648 1.7237692067 1.9464048231 0.6324532393 0.6903809770 -0.2700588011 0.224600201718 +1403715952534057984.0000000000 0.7971580253 1.7404275200 1.9597298824 0.6391045317 0.6874545649 -0.2619280782 0.224377585108 +1403715952584058112.0000000000 0.8144213293 1.7514911275 1.9737293594 0.6464496545 0.6840099044 -0.2542349332 0.222705845473 +1403715952634057984.0000000000 0.8278524760 1.7563055932 1.9884462867 0.6551815366 0.6788653689 -0.2473066577 0.220722409662 +1403715952684058112.0000000000 0.8372884650 1.7541986181 2.0039758113 0.6653202471 0.6714155916 -0.2405041933 0.220698448628 +1403715952734057984.0000000000 0.8421466861 1.7444169117 2.0200463589 0.6766350338 0.6620702956 -0.2334072936 0.222146325771 +1403715952784058112.0000000000 0.8420056591 1.7267816095 2.0360507789 0.6868935162 0.6531084864 -0.2268951302 0.223931244559 +1403715952834057984.0000000000 0.8369210658 1.7010900792 2.0518371259 0.6940355584 0.6467560965 -0.2222263942 0.225025831961 +1403715952884058112.0000000000 0.8262673645 1.6664891447 2.0646106267 0.6905605149 0.6515077083 -0.2215998438 0.222614892974 +1403715952934057984.0000000000 0.8099186107 1.6229978971 2.0744542114 0.6748784212 0.6688267235 -0.2250345128 0.215799440645 +1403715952984058112.0000000000 0.7889794842 1.5721807020 2.0815742927 0.6513980496 0.6929421583 -0.2297650822 0.206687573896 +1403715953034057984.0000000000 0.7645416503 1.5161722305 2.0863423250 0.6252197787 0.7182764623 -0.2342787756 0.195684969716 +1403715953084058112.0000000000 0.7374493250 1.4558340474 2.0878957704 0.5967616944 0.7436470509 -0.2390030329 0.183690212129 +1403715953134057984.0000000000 0.7089830708 1.3927479554 2.0853143236 0.5665369339 0.7681383172 -0.2430846802 0.17294295701 +1403715953184058112.0000000000 0.6804323972 1.3288446334 2.0803857136 0.5381184911 0.7892277637 -0.2477576002 0.16175351049 +1403715953234057984.0000000000 0.6528984905 1.2653475869 2.0736854544 0.5131721787 0.8062602642 -0.2511116151 0.153432910568 +1403715953284058112.0000000000 0.6272144602 1.2043010493 2.0651727144 0.4931185451 0.8192521227 -0.2534942531 0.14628986151 +1403715953334057984.0000000000 0.6037534007 1.1468559708 2.0545734531 0.4769166464 0.8294581812 -0.2549018269 0.139909601859 +1403715953384058112.0000000000 0.5823068821 1.0925756739 2.0413354363 0.4607666935 0.8397095731 -0.2543716698 0.133704676766 +1403715953434057984.0000000000 0.5635537832 1.0429556384 2.0262823453 0.4469552883 0.8485446109 -0.2536873418 0.125879887703 +1403715953484058112.0000000000 0.5486674591 0.9994158277 2.0109781365 0.4353454638 0.8565240500 -0.2505876448 0.118518822492 +1403715953534057984.0000000000 0.5378657081 0.9626209953 1.9966509337 0.4252786885 0.8640311563 -0.2454303489 0.11114019017 +1403715953584058112.0000000000 0.5315994398 0.9329659003 1.9837592835 0.4162343422 0.8712350589 -0.2385299653 0.103932190144 +1403715953634057984.0000000000 0.5302527850 0.9116120527 1.9728415031 0.4090585888 0.8777273214 -0.2298428585 0.0971497842862 +1403715953684058112.0000000000 0.5338319928 0.8992225624 1.9636053196 0.4031153442 0.8835949055 -0.2203041375 0.0906870948729 +1403715953734057984.0000000000 0.5424414929 0.8960999964 1.9560904017 0.3983619931 0.8885057992 -0.2112232962 0.0851462650322 +1403715953784058112.0000000000 0.5566062769 0.9031440213 1.9502443742 0.3955472926 0.8922391344 -0.2015229891 0.0827052066774 +1403715953834057984.0000000000 0.5760469329 0.9205295006 1.9468432180 0.3975296576 0.8937138073 -0.1902859514 0.0838871785003 +1403715953884058112.0000000000 0.6004254035 0.9480967326 1.9454198791 0.4039931374 0.8931291915 -0.1755990576 0.0909657253186 +1403715953934057984.0000000000 0.6284729982 0.9851711466 1.9441098830 0.4156944477 0.8898118194 -0.1571850568 0.103565970301 +1403715953984058112.0000000000 0.6589993383 1.0309462455 1.9425638128 0.4348697254 0.8818808211 -0.1359744674 0.121183676807 +1403715954034057984.0000000000 0.6895259065 1.0836980373 1.9397036073 0.4567517890 0.8709007422 -0.1146743203 0.140568491128 +1403715954084058112.0000000000 0.7179103024 1.1429291462 1.9351676442 0.4812177018 0.8571880948 -0.1008806820 0.153235705796 +1403715954134057984.0000000000 0.7435054838 1.2068832544 1.9292776343 0.5072812724 0.8413132102 -0.0899085274 0.163628389381 +1403715954184058112.0000000000 0.7654934903 1.2743065176 1.9231609979 0.5341044476 0.8238921707 -0.0831849450 0.170336123496 +1403715954234057984.0000000000 0.7828611553 1.3436333111 1.9174691914 0.5599785088 0.8061560637 -0.0808520824 0.173203381625 +1403715954284058112.0000000000 0.7955426014 1.4131328519 1.9118706579 0.5831981130 0.7895306910 -0.0820082810 0.172614862923 +1403715954334057984.0000000000 0.8032965962 1.4812088914 1.9065098045 0.6042709899 0.7741746201 -0.0870222378 0.167144722924 +1403715954384058112.0000000000 0.8063068789 1.5467739310 1.9013226345 0.6238032326 0.7597714731 -0.0954583212 0.156539274914 +1403715954434057984.0000000000 0.8051504201 1.6082206823 1.8963561299 0.6424377911 0.7451140938 -0.1030831747 0.146466825099 +1403715954484058112.0000000000 0.8005424498 1.6644560928 1.8919104357 0.6601455199 0.7301006544 -0.1089004716 0.138930249398 +1403715954534057984.0000000000 0.7928234601 1.7138653848 1.8878982336 0.6762012344 0.7155224428 -0.1117090196 0.135279781861 +1403715954584058112.0000000000 0.7822744962 1.7556292592 1.8844066087 0.6908031260 0.7016009390 -0.1124386481 0.133808497519 +1403715954634057984.0000000000 0.7683145805 1.7885903285 1.8810052732 0.7022786725 0.6903295508 -0.1128239999 0.132365110557 +1403715954684058112.0000000000 0.7508047075 1.8120649511 1.8775610042 0.7112965824 0.6813411752 -0.1129122513 0.130698884335 +1403715954734057984.0000000000 0.7299793931 1.8250402911 1.8726283636 0.7133714800 0.6793239899 -0.1128968925 0.129901270116 +1403715954784058112.0000000000 0.7060070316 1.8280869772 1.8671030001 0.7103541038 0.6826119655 -0.1131074855 0.129014140565 +1403715954834057984.0000000000 0.6789101733 1.8214482322 1.8611838347 0.7014808393 0.6918272122 -0.1145127963 0.127226412472 +1403715954884058112.0000000000 0.6492123107 1.8054044216 1.8553901682 0.6896348195 0.7035786177 -0.1158087593 0.126369599683 +1403715954934057984.0000000000 0.6167799404 1.7809549146 1.8495392941 0.6724028334 0.7200817542 -0.1184991484 0.123752368681 +1403715954984058112.0000000000 0.5819323934 1.7492775468 1.8439393993 0.6514944870 0.7388341812 -0.1209959617 0.12263345075 +1403715955034057984.0000000000 0.5449078761 1.7123201217 1.8394979748 0.6310963430 0.7562184494 -0.1241409318 0.120166932236 +1403715955084058112.0000000000 0.5064024921 1.6712976479 1.8357073056 0.6104571758 0.7727829723 -0.1278139281 0.117524950273 +1403715955134057984.0000000000 0.4664188623 1.6274735739 1.8322436596 0.5888522083 0.7892896194 -0.1336378139 0.111426694513 +1403715955184058112.0000000000 0.4257860284 1.5823888625 1.8289721846 0.5666062789 0.8052448820 -0.1405235745 0.103880362489 +1403715955234057984.0000000000 0.3855527117 1.5372790179 1.8256626108 0.5434878101 0.8207562414 -0.1473747332 0.0962334688947 +1403715955284058112.0000000000 0.3467639627 1.4937943617 1.8232147956 0.5228578966 0.8337349598 -0.1523646100 0.0910530746123 +1403715955334057984.0000000000 0.3098619419 1.4531050388 1.8215360798 0.5045105080 0.8446582347 -0.1558273910 0.087974076237 +1403715955384058112.0000000000 0.2747872276 1.4161660933 1.8207116292 0.4887987529 0.8534603632 -0.1597292234 0.0846626412941 +1403715955434057984.0000000000 0.2416443015 1.3836552720 1.8204425336 0.4739576335 0.8615449425 -0.1628190448 0.0812061102733 +1403715955484058112.0000000000 0.2107024548 1.3562139622 1.8210493580 0.4604235040 0.8686994914 -0.1664373774 0.0752993364067 +1403715955534057984.0000000000 0.1825222364 1.3348798532 1.8226842483 0.4471801571 0.8755130968 -0.1706056333 0.0663358296972 +1403715955584058112.0000000000 0.1579358034 1.3204688248 1.8255607253 0.4354479022 0.8815140257 -0.1733016528 0.0573121626465 +1403715955634057984.0000000000 0.1375536637 1.3137319900 1.8293951528 0.4253657040 0.8869722292 -0.1728612735 0.049631266334 +1403715955684058112.0000000000 0.1222612018 1.3157344689 1.8344260441 0.4186022878 0.8912757915 -0.1686939589 0.0440674067852 +1403715955734057984.0000000000 0.1124110544 1.3275666040 1.8414036138 0.4203017140 0.8923785462 -0.1584684228 0.0435288238005 +1403715955784058112.0000000000 0.1071987350 1.3493656598 1.8517917979 0.4345795726 0.8876975810 -0.1451264657 0.0455182243529 +1403715955834057984.0000000000 0.1058483326 1.3802907368 1.8657972069 0.4605244784 0.8764973940 -0.1323617510 0.0463669070917 +1403715955884058112.0000000000 0.1069973896 1.4167172801 1.8802800506 0.4894810083 0.8627687435 -0.1172636979 0.0478295189193 +1403715955934057984.0000000000 0.1093381992 1.4563332296 1.8952189439 0.5180716549 0.8478607587 -0.1028724601 0.0463805050967 +1403715955984058112.0000000000 0.1125130119 1.4981867548 1.9103326819 0.5472017590 0.8312875213 -0.0862130377 0.045810521446 +1403715956034057984.0000000000 0.1160713092 1.5410286098 1.9256061977 0.5748642382 0.8141790639 -0.0668277061 0.0466649459168 +1403715956084058112.0000000000 0.1192881779 1.5832715215 1.9406587397 0.5980538234 0.7987020866 -0.0470025077 0.0468760649255 +1403715956134057984.0000000000 0.1217822133 1.6236718485 1.9546062471 0.6152362260 0.7865520671 -0.0279069825 0.0451822117566 +1403715956184058112.0000000000 0.1231522883 1.6611327209 1.9677405745 0.6294973445 0.7758034209 -0.0092467529 0.042150242349 +1403715956234057984.0000000000 0.1229038638 1.6944141069 1.9799360006 0.6394620671 0.7678840566 0.0084834848 0.0370185203835 +1403715956284058112.0000000000 0.1210502404 1.7228856477 1.9916728983 0.6452609263 0.7630011002 0.0245702677 0.0293931979907 +1403715956334057984.0000000000 0.1172844169 1.7461985873 2.0044964140 0.6529807673 0.7560925446 0.0396278030 0.0192306737874 +1403715956384058112.0000000000 0.1117475299 1.7636859713 2.0182645097 0.6626722536 0.7469434197 0.0537073922 0.00751851622914 +1403715956434057984.0000000000 0.1048708106 1.7748187112 2.0333255110 0.6752221589 0.7345721225 0.0666770628 -0.00574476463561 +1403715956484058112.0000000000 0.0970478613 1.7787317463 2.0489782153 0.6885422375 0.7206282356 0.0789343308 -0.0193366139821 +1403715956534057984.0000000000 0.0890964931 1.7748629355 2.0643075880 0.6988724541 0.7088128937 0.0901741437 -0.0320967051135 +1403715956584058112.0000000000 0.0816246212 1.7626950027 2.0796369952 0.7062872172 0.6995055095 0.0997074243 -0.0436902561801 +1403715956634057984.0000000000 0.0750345575 1.7414222689 2.0946764817 0.7101425453 0.6937608618 0.1068044602 -0.0546464936966 +1403715956684058112.0000000000 0.0695876882 1.7109659359 2.1078197034 0.7074995501 0.6948787776 0.1131122969 -0.0615912287795 +1403715956734057984.0000000000 0.0652781696 1.6710844817 2.1200602980 0.6986634866 0.7023984875 0.1168472970 -0.0696592170841 +1403715956784058112.0000000000 0.0625168874 1.6231567754 2.1318868462 0.6863729847 0.7133003387 0.1198378362 -0.075720840419 +1403715956834057984.0000000000 0.0611857240 1.5680040930 2.1430780626 0.6718300185 0.7262166477 0.1213001002 -0.0808708388207 +1403715956884058112.0000000000 0.0610256610 1.5071144879 2.1535223721 0.6545396955 0.7412813778 0.1226622526 -0.0838670238999 +1403715956934057984.0000000000 0.0620910572 1.4415744796 2.1629703801 0.6357657431 0.7571387536 0.1240483105 -0.0845863138117 +1403715956984058112.0000000000 0.0640601691 1.3724274506 2.1704527226 0.6141944723 0.7746191123 0.1253149651 -0.0838244629999 +1403715957034057984.0000000000 0.0667366036 1.3009157184 2.1751348351 0.5924992106 0.7913903735 0.1267226630 -0.0811623617646 +1403715957084058112.0000000000 0.0694496162 1.2283741116 2.1770906062 0.5723209477 0.8063023524 0.1273302209 -0.0781809701525 +1403715957134057984.0000000000 0.0716736496 1.1562291639 2.1763677218 0.5527360915 0.8200971543 0.1269814264 -0.0761524002788 +1403715957184058112.0000000000 0.0730935367 1.0850001764 2.1722662738 0.5331490765 0.8332039375 0.1262124355 -0.0747909215113 +1403715957234057984.0000000000 0.0737842894 1.0157168682 2.1648741342 0.5135168198 0.8457284478 0.1251223031 -0.0734048887561 +1403715957284058112.0000000000 0.0732280191 0.9498700773 2.1542524355 0.4931267165 0.8580822117 0.1231981678 -0.0730969966613 +1403715957334057984.0000000000 0.0715762763 0.8883078220 2.1405491318 0.4716387454 0.8703803736 0.1213669558 -0.072560051227 +1403715957384058112.0000000000 0.0687536685 0.8319020882 2.1244497452 0.4511683657 0.8814441148 0.1205574195 -0.0704931694535 +1403715957434057984.0000000000 0.0643288577 0.7822999407 2.1070714025 0.4336858300 0.8904172819 0.1202364673 -0.0679474565183 +1403715957484058112.0000000000 0.0579666582 0.7406852389 2.0884155941 0.4169980751 0.8985834123 0.1198537029 -0.0655404184926 +1403715957534057984.0000000000 0.0492644758 0.7081243055 2.0690283022 0.4032950986 0.9050216362 0.1194416334 -0.0634239510547 +1403715957584058112.0000000000 0.0384005901 0.6853811246 2.0486907657 0.3917037128 0.9101064842 0.1210453073 -0.0601865626906 +1403715957634057984.0000000000 0.0247921412 0.6732373874 2.0281607483 0.3824977194 0.9140546109 0.1217561641 -0.05809560702 +1403715957684058112.0000000000 0.0084884006 0.6723399862 2.0076315301 0.3792469563 0.9152241299 0.1246293404 -0.0548093584725 +1403715957734057984.0000000000 -0.0112745469 0.6837880705 1.9880794200 0.3850198591 0.9125884284 0.1269414970 -0.0531782359366 +1403715957784058112.0000000000 -0.0348545947 0.7074004332 1.9705316582 0.3998812360 0.9060366463 0.1274455742 -0.0543159124546 +1403715957834057984.0000000000 -0.0623112173 0.7433288704 1.9567450610 0.4263458141 0.8936514924 0.1276767906 -0.0575751164603 +1403715957884058112.0000000000 -0.0930822995 0.7883161011 1.9457548490 0.4576352230 0.8776439552 0.1277103231 -0.0632547542167 +1403715957934057984.0000000000 -0.1260896195 0.8388522667 1.9360156698 0.4894321117 0.8595398465 0.1299083248 -0.069074507354 +1403715957984058112.0000000000 -0.1608310940 0.8927123655 1.9272002036 0.5203985676 0.8401171673 0.1330393622 -0.0754254873852 +1403715958034057984.0000000000 -0.1968426527 0.9478500138 1.9187775594 0.5494338767 0.8200617201 0.1365137085 -0.0835774950341 +1403715958084058112.0000000000 -0.2333318580 1.0027019293 1.9098759753 0.5773359021 0.7989263829 0.1421554646 -0.0905080918306 +1403715958134057984.0000000000 -0.2700460674 1.0556091305 1.9000209560 0.6002818901 0.7798390041 0.1465280696 -0.100211301576 +1403715958184058112.0000000000 -0.3063051078 1.1056082415 1.8896758180 0.6212287413 0.7609828168 0.1510474028 -0.110293633388 +1403715958234057984.0000000000 -0.3411909644 1.1512366097 1.8781844424 0.6385121466 0.7440277046 0.1568880532 -0.118790370332 +1403715958284058112.0000000000 -0.3742858862 1.1918992434 1.8659206959 0.6516988163 0.7297266227 0.1635761224 -0.126611852071 +1403715958334057984.0000000000 -0.4052060471 1.2267941595 1.8531335985 0.6629150129 0.7165277179 0.1699132135 -0.135134063548 +1403715958384058112.0000000000 -0.4337523468 1.2551935956 1.8400152542 0.6730473747 0.7039143312 0.1763447969 -0.142878823609 +1403715958434057984.0000000000 -0.4597756055 1.2759650051 1.8280948024 0.6837123763 0.6899962923 0.1806381789 -0.154312512348 +1403715958484058112.0000000000 -0.4818416621 1.2886766451 1.8161747916 0.6932561299 0.6766284546 0.1855369804 -0.164760133839 +1403715958534057984.0000000000 -0.4996328104 1.2924929976 1.8038407939 0.6982294047 0.6673176614 0.1902241754 -0.176004546048 +1403715958584058112.0000000000 -0.5128563584 1.2870236478 1.7901346341 0.6968084649 0.6642443018 0.1962782279 -0.186312447053 +1403715958634057984.0000000000 -0.5208355435 1.2722887920 1.7762940530 0.6917463879 0.6646436759 0.2024079182 -0.196892746157 +1403715958684058112.0000000000 -0.5234798743 1.2488834984 1.7623724941 0.6821396640 0.6690070929 0.2086934378 -0.208715206526 +1403715958734057984.0000000000 -0.5205510558 1.2179307718 1.7481807406 0.6687173659 0.6767213470 0.2164824855 -0.219090475496 +1403715958784058112.0000000000 -0.5121803915 1.1798937296 1.7337010036 0.6502531387 0.6883887137 0.2252166357 -0.229279963087 +1403715958834057984.0000000000 -0.4987432336 1.1358139991 1.7194094143 0.6278019369 0.7023169987 0.2331356164 -0.241378014138 +1403715958884058112.0000000000 -0.4803352453 1.0877108036 1.7049922486 0.6024329681 0.7176902746 0.2412550716 -0.252569156989 +1403715958934057984.0000000000 -0.4571675696 1.0373685227 1.6910214058 0.5778881589 0.7314045525 0.2494992178 -0.262379108832 +1403715958984058112.0000000000 -0.4298031467 0.9862683700 1.6769086994 0.5539551008 0.7438394154 0.2587728020 -0.26995056451 +1403715959034057984.0000000000 -0.3986265801 0.9357752002 1.6614962288 0.5295759281 0.7562051342 0.2725356645 -0.270974986056 +1403715959084058112.0000000000 -0.3643818184 0.8871143111 1.6463073578 0.5086133985 0.7654598347 0.2873908190 -0.26979653365 +1403715959134057984.0000000000 -0.3283230881 0.8416952606 1.6312339602 0.4929692408 0.7708448779 0.3047428505 -0.264407444812 +1403715959184058112.0000000000 -0.2913733433 0.7996370755 1.6161051511 0.4805828505 0.7734988492 0.3246140848 -0.255666482046 +1403715959234057984.0000000000 -0.2547002131 0.7609991733 1.6017452992 0.4698277961 0.7746410950 0.3440298193 -0.246650561278 +1403715959284058112.0000000000 -0.2190348435 0.7250702584 1.5872342527 0.4574059796 0.7762417265 0.3623985346 -0.238528518049 +1403715959334057984.0000000000 -0.1853237229 0.6921540651 1.5723625980 0.4406184165 0.7801247627 0.3801780998 -0.229620073369 +1403715959384058112.0000000000 -0.1550447475 0.6631038709 1.5576590105 0.4218740263 0.7854901120 0.3951643194 -0.221071822046 +1403715959434057984.0000000000 -0.1297162474 0.6385888950 1.5439222943 0.4053514892 0.7900098913 0.4072847218 -0.213760841117 +1403715959484058112.0000000000 -0.1098416687 0.6185468612 1.5309583686 0.3900166594 0.7944303908 0.4170254518 -0.207019641657 +1403715959534057984.0000000000 -0.0974854076 0.6037058146 1.5199521906 0.3774390872 0.7974536331 0.4250721958 -0.202289562074 +1403715959584058112.0000000000 -0.0940772686 0.5949929765 1.5124211597 0.3701122593 0.7968520095 0.4346173731 -0.197867454165 +1403715959634057984.0000000000 -0.1006691450 0.5924444889 1.5101242889 0.3670962169 0.7942945632 0.4419268946 -0.197578172564 +1403715959684058112.0000000000 -0.1181438042 0.5961163274 1.5138424848 0.3719773442 0.7876145594 0.4480792127 -0.201298734248 +1403715959734057984.0000000000 -0.1464007636 0.6053095985 1.5237370328 0.3850689625 0.7774190925 0.4493269457 -0.213182421087 +1403715959784058112.0000000000 -0.1833713644 0.6190868175 1.5383559625 0.4057168131 0.7627521345 0.4477217611 -0.230539093157 +1403715959834057984.0000000000 -0.2266478368 0.6357856199 1.5548917061 0.4286066573 0.7460498067 0.4440712388 -0.250013507868 +1403715959884058112.0000000000 -0.2736395525 0.6542154499 1.5718325378 0.4541837692 0.7264490560 0.4394569567 -0.269937874502 +1403715959934057984.0000000000 -0.3226100097 0.6735301872 1.5884131624 0.4799501467 0.7059246833 0.4330911098 -0.289396421365 +1403715959984058112.0000000000 -0.3719043732 0.6927747285 1.6039714904 0.5048977298 0.6850706856 0.4250104854 -0.308419398604 +1403715960034057984.0000000000 -0.4194489166 0.7112590950 1.6171542779 0.5267127704 0.6657682327 0.4174980806 -0.324070471521 +1403715960084058112.0000000000 -0.4641372286 0.7280536949 1.6291871072 0.5451541296 0.6483304030 0.4095140104 -0.338781550276 +1403715960134057984.0000000000 -0.5048254091 0.7428892377 1.6394686304 0.5594011307 0.6342476826 0.4035741152 -0.349182166876 +1403715960184058112.0000000000 -0.5403550822 0.7551992189 1.6494739330 0.5723826404 0.6213396618 0.3982685802 -0.357347555925 +1403715960234057984.0000000000 -0.5693257927 0.7642353714 1.6592115769 0.5838694708 0.6098270034 0.3937031907 -0.363600418926 +1403715960284058112.0000000000 -0.5911086285 0.7697684008 1.6687700879 0.5923865790 0.6011304774 0.3899398163 -0.368330326998 +1403715960334057984.0000000000 -0.6054089583 0.7716143176 1.6786354324 0.6011105145 0.5926297283 0.3860056152 -0.372096519157 +1403715960384058112.0000000000 -0.6119071331 0.7695307280 1.6887040706 0.6088105117 0.5845523995 0.3815532806 -0.376915570428 +1403715960434057984.0000000000 -0.6096583132 0.7630127444 1.6989613407 0.6148775917 0.5782650244 0.3778847932 -0.38044472907 +1403715960484058112.0000000000 -0.5981347706 0.7517028025 1.7083526226 0.6160899675 0.5772316923 0.3771437737 -0.380787735361 +1403715960534057984.0000000000 -0.5775042422 0.7356565534 1.7169282193 0.6119987401 0.5821425476 0.3802336028 -0.37681560972 +1403715960584058112.0000000000 -0.5481853818 0.7152260823 1.7240717162 0.6008284202 0.5945823819 0.3882561117 -0.367061564862 +1403715960634057984.0000000000 -0.5108456434 0.6903475842 1.7296752913 0.5833229517 0.6124322092 0.3993519365 -0.353806661857 +1403715960684058112.0000000000 -0.4673490305 0.6622192406 1.7358114679 0.5645532784 0.6304752695 0.4095764575 -0.340628325035 +1403715960734057984.0000000000 -0.4195445451 0.6314718602 1.7419514432 0.5468544857 0.6465632953 0.4204041524 -0.325831897256 +1403715960784058112.0000000000 -0.3682734684 0.5983310881 1.7479178387 0.5263282232 0.6642542969 0.4309409128 -0.309894756612 +1403715960834057984.0000000000 -0.3151511778 0.5633257631 1.7528141180 0.5001922589 0.6849591956 0.4430421774 -0.290434559818 +1403715960884058112.0000000000 -0.2621515365 0.5271642749 1.7585279533 0.4758977009 0.7026536344 0.4542271408 -0.271066325854 +1403715960934057984.0000000000 -0.2112476530 0.4904389384 1.7649593116 0.4513149165 0.7194537722 0.4629394799 -0.253748209575 +1403715960984058112.0000000000 -0.1647090513 0.4545444043 1.7725345193 0.4325838398 0.7315623712 0.4696571117 -0.238976810648 +1403715961034057984.0000000000 -0.1231916422 0.4196504379 1.7801384651 0.4148842536 0.7424431725 0.4751897572 -0.225485889557 +1403715961084058112.0000000000 -0.0882659382 0.3864438526 1.7880568222 0.3986984791 0.7518650803 0.4798425127 -0.213282879651 +1403715961134057984.0000000000 -0.0610140237 0.3551747435 1.7968050816 0.3822552062 0.7613499794 0.4828921621 -0.202589057036 +1403715961184058112.0000000000 -0.0433011943 0.3267806906 1.8069804013 0.3666093002 0.7703756004 0.4841908577 -0.194108909384 +1403715961234057984.0000000000 -0.0360267600 0.3020673739 1.8190152815 0.3548527737 0.7778438630 0.4823966868 -0.190609208498 +1403715961284058112.0000000000 -0.0399726015 0.2816310811 1.8334668122 0.3488131942 0.7829484763 0.4774009132 -0.193415116008 +1403715961334057984.0000000000 -0.0554422393 0.2659654330 1.8510949799 0.3512211239 0.7834979409 0.4705278403 -0.203416445396 +1403715961384058112.0000000000 -0.0814677816 0.2551319749 1.8713146030 0.3600049474 0.7798976973 0.4631624091 -0.218258109647 +1403715961434057984.0000000000 -0.1162945804 0.2489201097 1.8935952415 0.3730486926 0.7726115110 0.4565067070 -0.23560083294 +1403715961484058112.0000000000 -0.1580746028 0.2467202854 1.9172902809 0.3881744415 0.7617601601 0.4523822188 -0.253756555859 +1403715961534057984.0000000000 -0.2051171296 0.2482043565 1.9423344882 0.4047321288 0.7481878966 0.4496095013 -0.272503342269 +1403715961584058112.0000000000 -0.2556628021 0.2529721322 1.9677601478 0.4227317836 0.7315459977 0.4492191173 -0.290414319646 +1403715961634057984.0000000000 -0.3085725832 0.2598001205 1.9933701378 0.4403542175 0.7131034080 0.4502015374 -0.308042640495 +1403715961684058112.0000000000 -0.3626936662 0.2679198256 2.0185963005 0.4576098385 0.6934203030 0.4511970626 -0.325856916125 +1403715961734057984.0000000000 -0.4166814552 0.2767436801 2.0420022187 0.4753901523 0.6721877856 0.4532315822 -0.341685406319 +1403715961784058112.0000000000 -0.4688767044 0.2856625561 2.0626188324 0.4934154146 0.6502273051 0.4553870383 -0.35548322841 +1403715961834057984.0000000000 -0.5187858043 0.2942561288 2.0800452057 0.5082526621 0.6301306165 0.4562282000 -0.369419094231 +1403715961884058112.0000000000 -0.5654304075 0.3020239130 2.0932034572 0.5210159011 0.6119528281 0.4573289349 -0.380665748682 +1403715961934057984.0000000000 -0.6080019388 0.3088371423 2.1026915555 0.5317034219 0.5959022933 0.4580673493 -0.390341173115 +1403715961984058112.0000000000 -0.6457126846 0.3137933316 2.1110486990 0.5433606488 0.5783601906 0.4548041007 -0.404242409032 +1403715962034057984.0000000000 -0.6773427860 0.3165288736 2.1176282093 0.5545390293 0.5598732295 0.4494623226 -0.420728002947 +1403715962084058112.0000000000 -0.7009098173 0.3167758222 2.1222546531 0.5632602355 0.5422914405 0.4433487472 -0.438291899284 +1403715962134057984.0000000000 -0.7153072341 0.3147147158 2.1238511623 0.5683968759 0.5277889745 0.4400302769 -0.452478889289 +1403715962184058112.0000000000 -0.7201577306 0.3103870447 2.1223566742 0.5694747929 0.5166817656 0.4395057696 -0.464298494308 +1403715962234057984.0000000000 -0.7146753768 0.3039118234 2.1180046287 0.5656189832 0.5101919143 0.4419170585 -0.473802374235 +1403715962284058112.0000000000 -0.6985610731 0.2954353862 2.1110512348 0.5568684583 0.5082104043 0.4476337618 -0.480878072259 +1403715962334057984.0000000000 -0.6724569908 0.2854951023 2.1020739380 0.5434091266 0.5105902248 0.4545294478 -0.487244419689 +1403715962384058112.0000000000 -0.6360165639 0.2750044714 2.0918614001 0.5286359320 0.5154419579 0.4617647333 -0.491565835457 +1403715962434057984.0000000000 -0.5895531638 0.2641335290 2.0799674687 0.5101352859 0.5232086711 0.4698781938 -0.495206178803 +1403715962484058112.0000000000 -0.5347483368 0.2536395398 2.0662274612 0.4888055108 0.5325630361 0.4787685751 -0.498223279902 +1403715962534057984.0000000000 -0.4724977585 0.2443775603 2.0496928975 0.4638168615 0.5446034949 0.4895630404 -0.498607041507 +1403715962584058112.0000000000 -0.4041172154 0.2370486374 2.0303927148 0.4347791663 0.5589429671 0.5023703395 -0.496159125783 +1403715962634057984.0000000000 -0.3314417053 0.2330179954 2.0088641741 0.4084443823 0.5707658156 0.5145786416 -0.492552933117 +1403715962684058112.0000000000 -0.2559108636 0.2324891829 1.9854907191 0.3842863937 0.5805136329 0.5250904031 -0.489497659121 +1403715962734057984.0000000000 -0.1784954045 0.2361593304 1.9592350841 0.3628693617 0.5880644006 0.5355175378 -0.485517305327 +1403715962784058112.0000000000 -0.0998097010 0.2442214685 1.9299475260 0.3431380409 0.5941158961 0.5478773898 -0.47865744806 +1403715962834057984.0000000000 -0.0211424625 0.2570072860 1.8978290891 0.3283924112 0.5969451853 0.5620197569 -0.468986847305 +1403715962884058112.0000000000 0.0564215546 0.2741910666 1.8636184196 0.3170406760 0.5971235719 0.5769996627 -0.458257611802 +1403715962934057984.0000000000 0.1328343482 0.2955354033 1.8259821946 0.3085254400 0.5945883827 0.5965158032 -0.442092303188 +1403715962984058112.0000000000 0.2068580300 0.3205963990 1.7842611447 0.3047791337 0.5880239708 0.6195034269 -0.421370375618 +1403715963034057984.0000000000 0.2771346901 0.3473510282 1.7391843651 0.2979840427 0.5823194110 0.6417764617 -0.400290628222 +1403715963084058112.0000000000 0.3422140167 0.3747160587 1.6906743606 0.2895657499 0.5766553479 0.6623042834 -0.380753624427 +1403715963134057984.0000000000 0.4020692028 0.4018570877 1.6398663178 0.2784987943 0.5718984048 0.6808164120 -0.363124839823 +1403715963184058112.0000000000 0.4557784648 0.4284279005 1.5868640990 0.2665063639 0.5674314856 0.6967465317 -0.348626071615 +1403715963234057984.0000000000 0.5020661032 0.4535686459 1.5317225226 0.2550502700 0.5619616794 0.7110703782 -0.336938195976 +1403715963284058112.0000000000 0.5404439947 0.4765057363 1.4741596138 0.2424739205 0.5573006024 0.7235203467 -0.327323608048 +1403715963334057984.0000000000 0.5689193714 0.4967614181 1.4156282557 0.2344025662 0.5494851711 0.7337596378 -0.323602035708 +1403715963384058112.0000000000 0.5847409353 0.5129001232 1.3596069035 0.2339121799 0.5385421826 0.7377124603 -0.333223251949 +1403715963434057984.0000000000 0.5882968144 0.5249117267 1.3067928036 0.2451965558 0.5207719650 0.7362818254 -0.355758742753 +1403715963484058112.0000000000 0.5831041774 0.5331338749 1.2563681536 0.2593893963 0.5009026311 0.7305151088 -0.384917356125 +1403715963534057984.0000000000 0.5716577278 0.5383664721 1.2083145296 0.2759700996 0.4785176421 0.7213197040 -0.417802889964 +1403715963584058112.0000000000 0.5563683203 0.5409372049 1.1618277854 0.2887526152 0.4579955604 0.7114251527 -0.448035987487 +1403715963634057984.0000000000 0.5396294474 0.5422649913 1.1173881369 0.2992297446 0.4382418105 0.7031583000 -0.473258999438 +1403715963684058112.0000000000 0.5231052318 0.5428227519 1.0761052405 0.3071924778 0.4206125776 0.6964957539 -0.493570163264 +1403715963734057984.0000000000 0.5080855343 0.5430887353 1.0380712624 0.3115313660 0.4061891734 0.6920751248 -0.508911176031 +1403715963784058112.0000000000 0.4956009290 0.5433597843 1.0032216696 0.3110297206 0.3966788678 0.6897419490 -0.519771519463 +1403715963834057984.0000000000 0.4855446826 0.5438659444 0.9720637677 0.3091747540 0.3891447403 0.6885454529 -0.528093270075 +1403715963884058112.0000000000 0.4784451027 0.5449034865 0.9443276616 0.3061604676 0.3843329656 0.6894506073 -0.532176474166 +1403715963934057984.0000000000 0.4744650739 0.5468517321 0.9191323456 0.3009220201 0.3823862416 0.6929885071 -0.531971455082 +1403715963984058112.0000000000 0.4727201208 0.5494016616 0.8977480325 0.2931045067 0.3831337750 0.6971068897 -0.530415161004 +1403715964034057984.0000000000 0.4730436021 0.5532754079 0.8785951500 0.2886596600 0.3822110558 0.7043346704 -0.523930321292 +1403715964084058112.0000000000 0.4745343362 0.5574640965 0.8620819696 0.2820984802 0.3832211788 0.7170324198 -0.509339262665 +1403715964134057984.0000000000 0.4765546667 0.5616704593 0.8499843569 0.2810750936 0.3802638194 0.7325508328 -0.489658551111 +1403715964184058112.0000000000 0.4792006010 0.5638328480 0.8456598870 0.2761707950 0.3803633124 0.7438680216 -0.475093473996 +1403715964234057984.0000000000 0.4810374572 0.5629989835 0.8496249283 0.2736329473 0.3799665535 0.7494058034 -0.468125378642 +1403715964284058112.0000000000 0.4814653180 0.5583158173 0.8626287409 0.2693936373 0.3823644715 0.7466391682 -0.473026882588 +1403715964334057984.0000000000 0.4800867655 0.5511962158 0.8796922194 0.2676547689 0.3830171767 0.7430194435 -0.479145983596 +1403715964384058112.0000000000 0.4777010781 0.5422250166 0.8977350015 0.2665723230 0.3835997620 0.7376627579 -0.487487512442 +1403715964434057984.0000000000 0.4749417555 0.5320937379 0.9142349372 0.2651568910 0.3845933191 0.7346723112 -0.491971947507 +1403715964484058112.0000000000 0.4717167418 0.5207822007 0.9293931095 0.2653207338 0.3839552594 0.7331128456 -0.49470074048 +1403715964534057984.0000000000 0.4678995836 0.5082867879 0.9436634521 0.2676622338 0.3818648418 0.7323656205 -0.496162039138 +1403715964584058112.0000000000 0.4640159670 0.4946679709 0.9574185855 0.2675470813 0.3819363096 0.7326974779 -0.495678949092 +1403715964634057984.0000000000 0.4599353838 0.4796361911 0.9734602138 0.2655928280 0.3832591387 0.7303718372 -0.499129103341 +1403715964684058112.0000000000 0.4554281136 0.4638326366 0.9918020903 0.2616930417 0.3861490451 0.7266243009 -0.5044034023 +1403715964734057984.0000000000 0.4505012301 0.4479745168 1.0125105968 0.2580055159 0.3888429513 0.7225092394 -0.510112450246 +1403715964784058112.0000000000 0.4454332313 0.4321413264 1.0375514393 0.2527420291 0.3921965993 0.7164467651 -0.51865916263 +1403715964834057984.0000000000 0.4393501030 0.4165001938 1.0662498434 0.2474192928 0.3948820655 0.7100480693 -0.52790490357 +1403715964884058112.0000000000 0.4325642959 0.4023402816 1.0959353684 0.2457054937 0.3945341185 0.7039220905 -0.537089685422 +1403715964934057984.0000000000 0.4253573778 0.3899790625 1.1231895462 0.2472969306 0.3915914811 0.6993778801 -0.544399596643 +1403715964984058112.0000000000 0.4179960060 0.3794373835 1.1481374163 0.2489132866 0.3880996163 0.6946157293 -0.552204538354 +1403715965034057984.0000000000 0.4107542362 0.3712909457 1.1697407968 0.2537270247 0.3820054867 0.6899569625 -0.560048029131 +1403715965084058112.0000000000 0.4044467774 0.3651959299 1.1874405553 0.2591212763 0.3752880982 0.6847287135 -0.568473039321 +1403715965134057984.0000000000 0.3998301566 0.3616377736 1.2014077841 0.2639885429 0.3694483641 0.6795369524 -0.576235616558 +1403715965184058112.0000000000 0.3973640039 0.3611705936 1.2094223775 0.2658866778 0.3662343094 0.6848069118 -0.571153393302 +1403715965234057984.0000000000 0.3972218544 0.3638610365 1.2140543166 0.2638775888 0.3662558500 0.6980686297 -0.555810632061 +1403715965284058112.0000000000 0.3990049063 0.3695426827 1.2166205587 0.2604296327 0.3678589758 0.7155887642 -0.53365616352 +1403715965334057984.0000000000 0.4019519396 0.3763604431 1.2187203969 0.2522427740 0.3733076277 0.7349208319 -0.50685931862 +1403715965384058112.0000000000 0.4046216208 0.3829993344 1.2215543787 0.2419344795 0.3801696865 0.7526694257 -0.4800285957 +1403715965434057984.0000000000 0.4054857808 0.3884347580 1.2263747385 0.2324259869 0.3871997407 0.7670040897 -0.455806151562 +1403715965484058112.0000000000 0.4030192561 0.3912689973 1.2328742808 0.2250450100 0.3929530457 0.7784582232 -0.434678550314 +1403715965534057984.0000000000 0.3963996893 0.3904668670 1.2411745706 0.2203694772 0.3969976791 0.7866150908 -0.418409888991 +1403715965584058112.0000000000 0.3843062540 0.3849736972 1.2514623579 0.2179749350 0.3996958774 0.7910793635 -0.408562815184 +1403715965634057984.0000000000 0.3662494859 0.3744031370 1.2650603639 0.2205871273 0.3993716850 0.7901039769 -0.409364485643 +1403715965684058112.0000000000 0.3418220238 0.3583942948 1.2823378381 0.2297715478 0.3951743786 0.7823498572 -0.423049580172 +1403715965734057984.0000000000 0.3123111201 0.3376146043 1.3024367802 0.2427142710 0.3881033990 0.7690235994 -0.446170637684 +1403715965784058112.0000000000 0.2801792066 0.3134943050 1.3236393322 0.2558536634 0.3801561693 0.7524722424 -0.473081086468 +1403715965834057984.0000000000 0.2475993185 0.2881743389 1.3449926877 0.2685884987 0.3717664347 0.7333121735 -0.50189958427 +1403715965884058112.0000000000 0.2157917639 0.2626655798 1.3655167589 0.2798917875 0.3633677318 0.7146293381 -0.528137659978 +1403715965934057984.0000000000 0.1862825583 0.2382266242 1.3846307429 0.2895084031 0.3554402127 0.6977780201 -0.550411640855 +1403715965984058112.0000000000 0.1596187913 0.2157012693 1.4017673620 0.2988539875 0.3473345225 0.6839371384 -0.567692711211 +1403715966034057984.0000000000 0.1368474857 0.1950703735 1.4172305493 0.3041682496 0.3414256473 0.6736929106 -0.580558408423 +1403715966084058112.0000000000 0.1187712815 0.1771020674 1.4333711622 0.3110789788 0.3337213249 0.6610846531 -0.595673591509 +1403715966134057984.0000000000 0.1068499207 0.1625915465 1.4506882288 0.3166152614 0.3264611429 0.6470801987 -0.611935547948 +1403715966184058112.0000000000 0.1016369104 0.1526925645 1.4670538223 0.3197554257 0.3214769898 0.6389149653 -0.621447246264 +1403715966234057984.0000000000 0.1035142175 0.1479239214 1.4822380030 0.3198530382 0.3203622705 0.6389754768 -0.621910274589 +1403715966284058112.0000000000 0.1124511143 0.1482956242 1.4960207110 0.3163181585 0.3241246987 0.6480507424 -0.612304040147 +1403715966334057984.0000000000 0.1277654270 0.1530082233 1.5085855847 0.3072249951 0.3331259273 0.6650912469 -0.593543218508 +1403715966384058112.0000000000 0.1484942856 0.1615618779 1.5217811004 0.2981569058 0.3427069597 0.6825668196 -0.572500599203 +1403715966434057984.0000000000 0.1730151029 0.1724661578 1.5348895405 0.2891099291 0.3526116134 0.7006534400 -0.548785254925 +1403715966484058112.0000000000 0.2004232706 0.1850002059 1.5472690034 0.2775629836 0.3645760354 0.7201982611 -0.520919926034 +1403715966534057984.0000000000 0.2292289267 0.1978648565 1.5590194774 0.2642184744 0.3773603750 0.7399285030 -0.490197465867 +1403715966584058112.0000000000 0.2573402201 0.2094757149 1.5716366217 0.2528809913 0.3882472107 0.7551696423 -0.46371771475 +1403715966634057984.0000000000 0.2834130424 0.2186368106 1.5849184954 0.2431613698 0.3981228206 0.7670803072 -0.440407277785 +1403715966684058112.0000000000 0.3057220842 0.2243758611 1.5987961379 0.2357800375 0.4060647148 0.7751753718 -0.422637391075 +1403715966734057984.0000000000 0.3237742177 0.2265627359 1.6127458457 0.2303172761 0.4125033867 0.7805818408 -0.409251631776 +1403715966784058112.0000000000 0.3371072371 0.2247756979 1.6259027018 0.2252344621 0.4180487783 0.7854473786 -0.396959785724 +1403715966834057984.0000000000 0.3442696357 0.2181978746 1.6397856793 0.2236108634 0.4210052030 0.7880750446 -0.389474678117 +1403715966884058112.0000000000 0.3444056575 0.2064499858 1.6553705023 0.2276598570 0.4202559642 0.7865620609 -0.390993655198 +1403715966934057984.0000000000 0.3375779767 0.1889521587 1.6738030603 0.2371388806 0.4168008655 0.7781280102 -0.405658710691 +1403715966984058112.0000000000 0.3257077384 0.1672396976 1.6932971500 0.2491095483 0.4113686981 0.7663741340 -0.425900121951 +1403715967034057984.0000000000 0.3098525999 0.1420096172 1.7135091273 0.2646698935 0.4024461810 0.7526804128 -0.448841971117 +1403715967084058112.0000000000 0.2921690822 0.1140482570 1.7346848705 0.2785774437 0.3942973957 0.7351982767 -0.475823145247 +1403715967134057984.0000000000 0.2742249456 0.0852688317 1.7555120364 0.2929097120 0.3848941591 0.7174105708 -0.501380553923 +1403715967184058112.0000000000 0.2574981890 0.0564698611 1.7757065127 0.3059107346 0.3758953385 0.6998927402 -0.52466319591 +1403715967234057984.0000000000 0.2432683888 0.0283883990 1.7958415891 0.3191981195 0.3662646363 0.6810688829 -0.547821096153 +1403715967284058112.0000000000 0.2331717231 0.0019843170 1.8158867738 0.3306264063 0.3569369741 0.6616692931 -0.570504971549 +1403715967334057984.0000000000 0.2284806177 -0.0216304199 1.8357236359 0.3413777105 0.3482114159 0.6431916500 -0.590351225951 +1403715967384058112.0000000000 0.2306907136 -0.0415482420 1.8544133764 0.3459773543 0.3437730002 0.6301722282 -0.604154580729 +1403715967434057984.0000000000 0.2399922020 -0.0572853349 1.8715960891 0.3488638130 0.3419777193 0.6241263853 -0.609763507196 +1403715967484058112.0000000000 0.2569617790 -0.0688824682 1.8876097932 0.3455094967 0.3445160291 0.6242778495 -0.610089386897 +1403715967534057984.0000000000 0.2820167096 -0.0760869917 1.9030579204 0.3366521999 0.3489647272 0.6286567215 -0.608012863326 +1403715967584058112.0000000000 0.3143608918 -0.0789780849 1.9177649833 0.3231621177 0.3549418319 0.6373317727 -0.602819005307 +1403715967634057984.0000000000 0.3526183391 -0.0775922988 1.9315460500 0.3061427417 0.3614936417 0.6506755199 -0.593481538537 +1403715967684058112.0000000000 0.3959973777 -0.0721319004 1.9450628221 0.2860141578 0.3678575566 0.6663989485 -0.582055977541 +1403715967734057984.0000000000 0.4425920973 -0.0634277584 1.9591881456 0.2631951371 0.3741962784 0.6812253052 -0.571522133042 +1403715967784058112.0000000000 0.4910349165 -0.0510834633 1.9720658237 0.2396988792 0.3796859752 0.6979510219 -0.557895490812 +1403715967834057984.0000000000 0.5400686112 -0.0351475463 1.9839936477 0.2151360382 0.3847614250 0.7147698800 -0.542935677119 +1403715967884058112.0000000000 0.5873675590 -0.0169975958 1.9949119368 0.1944663473 0.3865415377 0.7286798877 -0.530842821124 +1403715967934057984.0000000000 0.6315214338 0.0028676288 2.0030526536 0.1778534511 0.3862392122 0.7419814775 -0.518315452142 +1403715967984058112.0000000000 0.6718238590 0.0242441812 2.0074519694 0.1679065051 0.3824417615 0.7564409875 -0.5033316372 +1403715968034057984.0000000000 0.7079603946 0.0467517765 2.0082444744 0.1630042022 0.3759618662 0.7723583230 -0.485329708748 +1403715968084058112.0000000000 0.7384536954 0.0687777469 2.0064888944 0.1617887253 0.3681211350 0.7873736025 -0.467283691557 +1403715968134057984.0000000000 0.7631271906 0.0888931802 2.0033572817 0.1617150312 0.3604591366 0.8000854290 -0.451420830078 +1403715968184058112.0000000000 0.7823151066 0.1062183227 1.9992788280 0.1632379960 0.3534621673 0.8081190400 -0.441997138152 +1403715968234057984.0000000000 0.7952594297 0.1192693492 1.9952401891 0.1675429679 0.3468122794 0.8094355704 -0.443243335195 +1403715968284058112.0000000000 0.8027389275 0.1283081964 1.9908911988 0.1758960829 0.3390869309 0.8039198328 -0.455843749266 +1403715968334057984.0000000000 0.8068169748 0.1345843225 1.9848263078 0.1843641483 0.3325523334 0.7946697693 -0.473200553865 +1403715968384058112.0000000000 0.8080463199 0.1385019039 1.9764155411 0.1939276106 0.3257224812 0.7840900554 -0.491426222456 +1403715968434057984.0000000000 0.8077707846 0.1411492324 1.9652419646 0.2016065963 0.3204787728 0.7712541608 -0.511678762505 +1403715968484058112.0000000000 0.8060841837 0.1436037103 1.9504169872 0.2100065899 0.3147447842 0.7585270264 -0.530537183715 +1403715968534057984.0000000000 0.8036799160 0.1461964753 1.9335347604 0.2169470366 0.3101435179 0.7453303046 -0.548842161949 +1403715968584058112.0000000000 0.8008571161 0.1492139758 1.9134213023 0.2249987125 0.3044788352 0.7325693350 -0.565694606365 +1403715968634057984.0000000000 0.7986516981 0.1533938564 1.8909784177 0.2324634068 0.2990602557 0.7201160324 -0.581340371756 +1403715968684058112.0000000000 0.7981863432 0.1601759318 1.8678614929 0.2396326894 0.2935558349 0.7085193344 -0.59531630148 +1403715968734057984.0000000000 0.8002177809 0.1705432756 1.8444373424 0.2465551262 0.2883420449 0.6981143191 -0.607211521925 +1403715968784058112.0000000000 0.8060751304 0.1851259784 1.8212595307 0.2513597383 0.2839608243 0.6888910980 -0.61774880596 +1403715968834057984.0000000000 0.8160530721 0.2044240117 1.7986772940 0.2562304453 0.2797908196 0.6808603899 -0.626491967699 +1403715968884058112.0000000000 0.8306593072 0.2286287761 1.7762776758 0.2586642487 0.2773064977 0.6756040626 -0.632260281418 +1403715968934057984.0000000000 0.8500196625 0.2579516648 1.7539677003 0.2591518060 0.2762912129 0.6737191623 -0.634512409176 +1403715968984058112.0000000000 0.8744154085 0.2927717562 1.7303734013 0.2563998710 0.2780016086 0.6783698552 -0.629911542502 +1403715969034057984.0000000000 0.9034939274 0.3326528672 1.7049909166 0.2500862321 0.2824927056 0.6912464753 -0.616305977729 +1403715969084058112.0000000000 0.9365774703 0.3770694761 1.6786151746 0.2408963812 0.2896088690 0.7102980242 -0.594619503024 +1403715969134057984.0000000000 0.9725748679 0.4250054142 1.6509140549 0.2299330829 0.2983803658 0.7346755512 -0.56422670018 +1403715969184058112.0000000000 1.0103904873 0.4749022090 1.6229640817 0.2161681038 0.3082581951 0.7608885312 -0.528485457912 +1403715969234057984.0000000000 1.0476275060 0.5248783815 1.5967348713 0.2039682269 0.3169152014 0.7830166472 -0.49481981343 +1403715969284058112.0000000000 1.0827743470 0.5728362749 1.5724534819 0.1932055580 0.3245450382 0.8010799860 -0.464341454731 +1403715969334057984.0000000000 1.1144052462 0.6171519976 1.5501778334 0.1847964484 0.3303695900 0.8143272782 -0.439974193172 +1403715969384058112.0000000000 1.1415209701 0.6568430721 1.5289855295 0.1788718486 0.3344841822 0.8255206994 -0.41790042888 +1403715969434057984.0000000000 1.1634045046 0.6905277007 1.5090256924 0.1736736478 0.3381058153 0.8345297932 -0.39885078161 +1403715969484058112.0000000000 1.1787922473 0.7173851401 1.4902973055 0.1732003833 0.3381577317 0.8418810248 -0.383258810425 +1403715969534057984.0000000000 1.1874443637 0.7369047782 1.4726433801 0.1781684078 0.3337871807 0.8476929224 -0.371831744003 +1403715969584058112.0000000000 1.1885651529 0.7471031685 1.4565034675 0.1901220189 0.3235344944 0.8512337435 -0.366851690438 +1403715969634057984.0000000000 1.1835270443 0.7468798058 1.4431116368 0.2050620218 0.3109754673 0.8517923694 -0.368366102349 +1403715969684058112.0000000000 1.1740456933 0.7369965251 1.4312845895 0.2203300886 0.2983324035 0.8501017525 -0.373870886003 +1403715969734057984.0000000000 1.1606429085 0.7171441317 1.4218283290 0.2368090444 0.2849974424 0.8458439672 -0.383726357471 +1403715969784058112.0000000000 1.1451193111 0.6873162352 1.4149442211 0.2503010675 0.2743943528 0.8382029229 -0.399340675058 +1403715969834057984.0000000000 1.1287423139 0.6480988107 1.4105970168 0.2609094036 0.2665061146 0.8267078953 -0.421253878154 +1403715969884058112.0000000000 1.1131563051 0.6014231660 1.4083124195 0.2639203526 0.2649717189 0.8126511123 -0.446916329253 +1403715969934057984.0000000000 1.0991885329 0.5492865488 1.4076363065 0.2610600669 0.2679514414 0.7955877222 -0.476539445201 +1403715969984058112.0000000000 1.0871793163 0.4938548363 1.4083583468 0.2573411329 0.2706521470 0.7761590484 -0.508035518645 +1403715970034057984.0000000000 1.0772309549 0.4373358124 1.4083585943 0.2543950637 0.2718008790 0.7590810006 -0.534044444105 +1403715970084058112.0000000000 1.0699054061 0.3810716363 1.4083123037 0.2524034427 0.2716349919 0.7430780011 -0.557083492412 +1403715970134057984.0000000000 1.0653654004 0.3265275458 1.4076047113 0.2522140105 0.2696822023 0.7288463007 -0.576578418398 +1403715970184058112.0000000000 1.0641623730 0.2745279718 1.4071766264 0.2528160562 0.2671808099 0.7143244272 -0.595347855601 +1403715970234057984.0000000000 1.0666462880 0.2258622245 1.4078372329 0.2530806417 0.2643823699 0.6982187556 -0.615258255197 +1403715970284058112.0000000000 1.0736056003 0.1821314689 1.4086975440 0.2530202070 0.2616372538 0.6831548674 -0.633108323545 +1403715970334057984.0000000000 1.0854438787 0.1443317910 1.4098224081 0.2521278036 0.2598763929 0.6703360749 -0.64772322625 +1403715970384058112.0000000000 1.1020290319 0.1131095166 1.4111851687 0.2527020177 0.2577541400 0.6612303133 -0.657631330072 +1403715970434057984.0000000000 1.1242762561 0.0890626009 1.4134417745 0.2485622455 0.2584326699 0.6554391926 -0.664702061089 +1403715970484058112.0000000000 1.1521488296 0.0730801206 1.4155274222 0.2416917270 0.2616551203 0.6560174423 -0.665404254968 +1403715970534057984.0000000000 1.1857633598 0.0650249522 1.4171174498 0.2293810398 0.2686670980 0.6630629582 -0.659962000844 +1403715970584058112.0000000000 1.2237547255 0.0645123969 1.4184988162 0.2128629185 0.2789497340 0.6760788623 -0.647914960336 +1403715970634057984.0000000000 1.2644070299 0.0712562125 1.4191839641 0.1984656012 0.2891425945 0.6936703464 -0.629149756148 +1403715970684058112.0000000000 1.3065605508 0.0843449701 1.4200310045 0.1847217030 0.2996609032 0.7126542255 -0.606799135138 +1403715970734057984.0000000000 1.3492094213 0.1027328808 1.4206924574 0.1699821997 0.3112352170 0.7331396637 -0.58029727295 +1403715970784058112.0000000000 1.3907129437 0.1253098865 1.4217759293 0.1536407236 0.3242469290 0.7541191723 -0.550057025333 +1403715970834057984.0000000000 1.4290379202 0.1499897199 1.4239619265 0.1380596553 0.3368426275 0.7734292810 -0.518925546904 +1403715970884058112.0000000000 1.4625478820 0.1749913066 1.4279937847 0.1239832461 0.3485129613 0.7898218691 -0.489232343076 +1403715970934057984.0000000000 1.4899418508 0.1990754628 1.4336417339 0.1120895822 0.3574923248 0.8034967718 -0.462631712 +1403715970984058112.0000000000 1.5096045552 0.2211173111 1.4406959694 0.1035188245 0.3627543717 0.8153273206 -0.43924307521 +1403715971034057984.0000000000 1.5201628058 0.2401904534 1.4488361106 0.1008148431 0.3625496454 0.8263214234 -0.419031057659 +1403715971084058112.0000000000 1.5209397930 0.2547528005 1.4587741284 0.1025029745 0.3570927933 0.8372409974 -0.40125476877 +1403715971134057984.0000000000 1.5117231789 0.2636071323 1.4715667978 0.1098674469 0.3457699233 0.8459929468 -0.390727831391 +1403715971184058112.0000000000 1.4927396232 0.2648437288 1.4873650803 0.1202375903 0.3315247696 0.8515358546 -0.387970278893 +1403715971234057984.0000000000 1.4648210502 0.2576968447 1.5054872054 0.1357619065 0.3109700611 0.8544085362 -0.393512870363 +1403715971284058112.0000000000 1.4296832257 0.2418270837 1.5268450883 0.1518059545 0.2884169006 0.8529593879 -0.407714270377 +1403715971334057984.0000000000 1.3896863159 0.2177048816 1.5501579940 0.1684773398 0.2634603220 0.8485372349 -0.426835572108 +1403715971384058112.0000000000 1.3476743941 0.1866712205 1.5747822491 0.1831373870 0.2377639417 0.8415476738 -0.449139753522 +1403715971434057984.0000000000 1.3052174973 0.1494318612 1.6007413467 0.1944197592 0.2132876657 0.8323115870 -0.473251255683 +1403715971484058112.0000000000 1.2638487019 0.1080009036 1.6261134283 0.2033051068 0.1890367341 0.8218694248 -0.497456324898 +1403715971534057984.0000000000 1.2253011250 0.0631461753 1.6510806281 0.2086040154 0.1660811312 0.8110005084 -0.520749073887 +1403715971584058112.0000000000 1.1908936799 0.0160556917 1.6759127317 0.2096319857 0.1453869027 0.8007365470 -0.541976070902 +1403715971634057984.0000000000 1.1612828830 -0.0321681476 1.7006789036 0.2070449053 0.1274067520 0.7912574350 -0.561080741378 +1403715971684058112.0000000000 1.1369930222 -0.0803550162 1.7248939904 0.2005863191 0.1123685665 0.7832994296 -0.577564228036 +1403715971734057984.0000000000 1.1183690820 -0.1280874640 1.7486039964 0.1886223949 0.1011042328 0.7754368108 -0.594051579138 +1403715971784058112.0000000000 1.1047712455 -0.1740071792 1.7712870734 0.1745013656 0.0922123411 0.7687394350 -0.608346807907 +1403715971834057984.0000000000 1.0959598112 -0.2171120204 1.7931702839 0.1555943016 0.0865899525 0.7639460091 -0.620225030655 +1403715971884058112.0000000000 1.0911723575 -0.2570074917 1.8134819723 0.1361025051 0.0820594513 0.7614404975 -0.62845105083 +1403715971934057984.0000000000 1.0895197407 -0.2929221496 1.8317992607 0.1188657495 0.0767708901 0.7605505401 -0.633671870927 +1403715971984058112.0000000000 1.0906555124 -0.3246832326 1.8489229756 0.1031780571 0.0711796905 0.7611945692 -0.636294403514 +1403715972034057984.0000000000 1.0938716173 -0.3525518925 1.8648288908 0.0907164351 0.0645377705 0.7621936620 -0.637703870245 +1403715972084058112.0000000000 1.0987784948 -0.3760772964 1.8805871439 0.0797402518 0.0580477210 0.7606381181 -0.641639780253 +1403715972134057984.0000000000 1.1047255836 -0.3953761785 1.8968072601 0.0722499850 0.0515434890 0.7560497909 -0.648468906074 +1403715972184058112.0000000000 1.1116902072 -0.4098051167 1.9139786858 0.0666200165 0.0455922807 0.7482390643 -0.658499369807 +1403715972234057984.0000000000 1.1196464519 -0.4186967574 1.9316904954 0.0620993596 0.0408428617 0.7385430179 -0.670096814571 +1403715972284058112.0000000000 1.1285800275 -0.4210360740 1.9490308684 0.0592285304 0.0365826801 0.7297888089 -0.680119094767 +1403715972334057984.0000000000 1.1386404614 -0.4163198193 1.9660754991 0.0572928166 0.0331435404 0.7223470478 -0.688355853745 +1403715972384058112.0000000000 1.1498313856 -0.4041610380 1.9824778567 0.0542541955 0.0318968793 0.7179744777 -0.693218378817 +1403715972434057984.0000000000 1.1620680713 -0.3841347257 1.9976389285 0.0527096483 0.0308005250 0.7175898932 -0.693785100619 +1403715972484058112.0000000000 1.1752235517 -0.3563647872 2.0114168243 0.0516459028 0.0304126480 0.7208882291 -0.690454873786 +1403715972534057984.0000000000 1.1892925222 -0.3210328906 2.0233872819 0.0507416971 0.0310031910 0.7300189194 -0.680835119284 +1403715972584058112.0000000000 1.2044810446 -0.2788039884 2.0337659818 0.0470369743 0.0338348461 0.7454042096 -0.664089821182 +1403715972634057984.0000000000 1.2201607005 -0.2309587228 2.0431658443 0.0436792345 0.0372406980 0.7615390267 -0.645572277693 +1403715972684058112.0000000000 1.2363355094 -0.1788015332 2.0507254008 0.0389179198 0.0417647043 0.7787829195 -0.624690538873 +1403715972734057984.0000000000 1.2526187905 -0.1238935456 2.0559976468 0.0339780451 0.0468269380 0.7957472625 -0.602859042039 +1403715972784058112.0000000000 1.2685690245 -0.0675762973 2.0585152267 0.0302018766 0.0518071968 0.8113037290 -0.581541159539 +1403715972834057984.0000000000 1.2838309042 -0.0114783805 2.0592573442 0.0270710158 0.0564461463 0.8229173936 -0.56470165223 +1403715972884058112.0000000000 1.2979005342 0.0437513985 2.0587935581 0.0258315438 0.0600496500 0.8287812274 -0.555741349955 +1403715972934057984.0000000000 1.3106769669 0.0969016309 2.0577462207 0.0253570286 0.0638899879 0.8278108544 -0.556780279684 +1403715972984058112.0000000000 1.3223774520 0.1485263556 2.0551130373 0.0246001428 0.0677057446 0.8245511664 -0.561182803661 +1403715973034057984.0000000000 1.3329523984 0.1987792841 2.0522053127 0.0206792484 0.0740809555 0.8191599340 -0.568384890121 +1403715973084058112.0000000000 1.3416215960 0.2483307702 2.0487051207 0.0178548674 0.0796610670 0.8145227634 -0.574358760741 +1403715973134057984.0000000000 1.3481344525 0.2979787958 2.0448139430 0.0189862575 0.0820903359 0.8112338223 -0.578619377745 +1403715973184058112.0000000000 1.3525154667 0.3481436002 2.0404808007 0.0221599703 0.0824668798 0.8096406124 -0.580680831619 +1403715973234057984.0000000000 1.3552282481 0.3986084797 2.0365785363 0.0234603877 0.0839164035 0.8089440649 -0.581392421116 +1403715973284058112.0000000000 1.3565557284 0.4493548349 2.0329616126 0.0241696053 0.0854351681 0.8090224017 -0.581033059104 +1403715973334057984.0000000000 1.3561934625 0.5007863938 2.0292901734 0.0238208354 0.0873524399 0.8114360526 -0.577385184698 +1403715973384058112.0000000000 1.3540471804 0.5525748589 2.0254161541 0.0240999777 0.0884308423 0.8155936925 -0.571319618025 +1403715973434057984.0000000000 1.3499416642 0.6040810559 2.0214545963 0.0258910671 0.0884044428 0.8211342263 -0.563252065702 +1403715973484058112.0000000000 1.3441875482 0.6548387185 2.0176894386 0.0272001441 0.0884936363 0.8266409462 -0.555061955597 +1403715973534057984.0000000000 1.3368538610 0.7041802741 2.0147545217 0.0270763564 0.0893142449 0.8322415687 -0.546501425333 +1403715973584058112.0000000000 1.3281038114 0.7513613564 2.0131317434 0.0251127474 0.0911495533 0.8370004433 -0.538972510153 +1403715973634057984.0000000000 1.3176930329 0.7962210920 2.0122162068 0.0218341056 0.0934113629 0.8412320928 -0.532096001816 +1403715973684058112.0000000000 1.3054309676 0.8386398038 2.0113136093 0.0169859529 0.0966865363 0.8453457194 -0.525122657815 +1403715973734057984.0000000000 1.2908940928 0.8781253498 2.0104644074 0.0125386814 0.0994070582 0.8487716553 -0.519179829541 +1403715973784058112.0000000000 1.2737296080 0.9139033094 2.0097793731 0.0085958799 0.1015532700 0.8513678571 -0.514573431246 +1403715973834057984.0000000000 1.2533805440 0.9460340491 2.0094199004 0.0065338157 0.1024057614 0.8531515691 -0.511471181469 +1403715973884058112.0000000000 1.2300360897 0.9745847547 2.0091227889 0.0059339739 0.1019131206 0.8550780510 -0.508350303016 +1403715973934057984.0000000000 1.2037722886 0.9993102337 2.0089567703 0.0054340549 0.1011307909 0.8564508366 -0.506196600815 +1403715973984058112.0000000000 1.1743802217 1.0198181277 2.0090328393 0.0095697965 0.0969690521 0.8559684900 -0.50776310025 +1403715974034057984.0000000000 1.1421918199 1.0361925003 2.0099039417 0.0155387622 0.0914928389 0.8534762242 -0.512802049572 +1403715974084058112.0000000000 1.1081509702 1.0489892832 2.0113413133 0.0212966502 0.0860998505 0.8501798289 -0.518967751432 +1403715974134057984.0000000000 1.0722931826 1.0585699176 2.0131551991 0.0264401154 0.0811892161 0.8456767763 -0.526820673082 +1403715974184058112.0000000000 1.0352184745 1.0653571241 2.0150807447 0.0296327692 0.0777123359 0.8411941992 -0.534298616 +1403715974234057984.0000000000 0.9971648420 1.0699197368 2.0162013795 0.0320233079 0.0748259544 0.8374701683 -0.540388102629 +1403715974284058112.0000000000 0.9585231063 1.0726736936 2.0158739386 0.0345794133 0.0717995919 0.8355272679 -0.543638912683 +1403715974334057984.0000000000 0.9195973481 1.0742151925 2.0136356812 0.0362926991 0.0692193191 0.8352918749 -0.544223308641 +1403715974384058112.0000000000 0.8803718916 1.0743115853 2.0093852570 0.0366844680 0.0675450307 0.8356497669 -0.543857872717 +1403715974434057984.0000000000 0.8405785454 1.0729348716 2.0034652119 0.0372142461 0.0661271192 0.8364802860 -0.542718191328 +1403715974484058112.0000000000 0.8004019963 1.0697307484 1.9970807373 0.0373315960 0.0650328032 0.8363090261 -0.543106158485 +1403715974534057984.0000000000 0.7597629581 1.0646759789 1.9906180457 0.0379484926 0.0638696196 0.8346151785 -0.545800409941 +1403715974584058112.0000000000 0.7188971052 1.0578719721 1.9839354429 0.0381661436 0.0630743320 0.8323765758 -0.549285181152 +1403715974634057984.0000000000 0.6780353896 1.0497882309 1.9767955268 0.0390555584 0.0617784273 0.8299436500 -0.553038540385 +1403715974684058112.0000000000 0.6372133045 1.0404189725 1.9695041749 0.0385213666 0.0616313699 0.8276770905 -0.556478492296 +1403715974734057984.0000000000 0.5961714150 1.0304139690 1.9613856834 0.0391949748 0.0607029004 0.8259452747 -0.559100451648 +1403715974784058112.0000000000 0.5553295497 1.0197275947 1.9528003741 0.0395126116 0.0600234259 0.8246313326 -0.561087432724 +1403715974834057984.0000000000 0.5146758718 1.0085790741 1.9437153519 0.0385952711 0.0597651652 0.8244813466 -0.561399179957 +1403715974884058112.0000000000 0.4739933274 0.9966827413 1.9345550431 0.0386955171 0.0589259304 0.8238353187 -0.562428448218 +1403715974934057984.0000000000 0.4336114381 0.9844623889 1.9250523778 0.0383314006 0.0579421916 0.8233073257 -0.563328016015 +1403715974984058112.0000000000 0.3933367732 0.9719387175 1.9156625718 0.0378722388 0.0568287819 0.8226970802 -0.564363089899 +1403715975034057984.0000000000 0.3531342884 0.9593243194 1.9062774478 0.0389271461 0.0544912584 0.8221931754 -0.565255484211 +1403715975084058112.0000000000 0.3134181768 0.9462099492 1.8972924688 0.0390758383 0.0521165161 0.8217198762 -0.566156685666 +1403715975134057984.0000000000 0.2739182248 0.9327501740 1.8886306460 0.0406423232 0.0491832490 0.8216159983 -0.56645949624 +1403715975184058112.0000000000 0.2349709701 0.9188709283 1.8804870407 0.0415680828 0.0466888966 0.8214327919 -0.56686895299 +1403715975234057984.0000000000 0.1967208894 0.9046161447 1.8727344266 0.0430782398 0.0435502310 0.8217161575 -0.566595269197 +1403715975284058112.0000000000 0.1592777879 0.8897875136 1.8663365480 0.0437605616 0.0411113420 0.8214522775 -0.567107597044 +1403715975334057984.0000000000 0.1228588375 0.8741954376 1.8616100884 0.0443326465 0.0384593048 0.8197432001 -0.569716231362 +1403715975384058112.0000000000 0.0872728490 0.8583285668 1.8582965892 0.0451122350 0.0360095421 0.8178531252 -0.572524641122 +1403715975434057984.0000000000 0.0529140384 0.8425591608 1.8564746508 0.0464814948 0.0332658755 0.8154359546 -0.576018277625 +1403715975484058112.0000000000 0.0198231634 0.8271201142 1.8557553508 0.0490263098 0.0297749709 0.8128893502 -0.579586728996 +1403715975534057984.0000000000 -0.0115460117 0.8125302293 1.8565778859 0.0490923344 0.0282638877 0.8119703194 -0.580943453119 +1403715975584058112.0000000000 -0.0412909058 0.7987977675 1.8581383868 0.0481722241 0.0275865029 0.8130361403 -0.579560744208 +1403715975634057984.0000000000 -0.0696208748 0.7854665370 1.8612110501 0.0461289212 0.0279925364 0.8145085916 -0.577636819038 +1403715975684058112.0000000000 -0.0965283012 0.7722713821 1.8653100461 0.0442729687 0.0284548087 0.8157146661 -0.576055389343 +1403715975734057984.0000000000 -0.1222541565 0.7589770987 1.8703822532 0.0439124551 0.0283358834 0.8166985242 -0.574693217829 +1403715975784058112.0000000000 -0.1466075138 0.7455122811 1.8759987122 0.0426645180 0.0289933301 0.8176013655 -0.573469382631 +1403715975834057984.0000000000 -0.1700381684 0.7317380220 1.8820226621 0.0426217216 0.0291046621 0.8179754488 -0.572933218293 +1403715975884058112.0000000000 -0.1923420647 0.7179576967 1.8876968298 0.0426957356 0.0291174634 0.8191657100 -0.571223937712 +1403715975934057984.0000000000 -0.2134755723 0.7037525756 1.8937136341 0.0426978138 0.0293231757 0.8199804263 -0.570043111156 +1403715975984058112.0000000000 -0.2335078097 0.6889247566 1.8998861973 0.0427975071 0.0295212193 0.8208337833 -0.568795895923 +1403715976034057984.0000000000 -0.2526048539 0.6738769962 1.9055048311 0.0440723354 0.0292036510 0.8219999107 -0.567028149974 +1403715976084058112.0000000000 -0.2704132436 0.6587137755 1.9113506227 0.0440557357 0.0297936866 0.8224102526 -0.566403394026 +1403715976134057984.0000000000 -0.2870108633 0.6428837556 1.9174909306 0.0447946995 0.0304411413 0.8221047665 -0.566754377741 +1403715976184058112.0000000000 -0.3025359003 0.6266845859 1.9235426851 0.0466237415 0.0306210894 0.8212536961 -0.567830029422 +1403715976234057984.0000000000 -0.3169868147 0.6102123184 1.9297604541 0.0485129196 0.0306579171 0.8202421651 -0.569130371118 +1403715976284058112.0000000000 -0.3301897928 0.5933390276 1.9357733220 0.0492659238 0.0316429124 0.8196687603 -0.569837449002 +1403715976334057984.0000000000 -0.3425548872 0.5760919234 1.9414378765 0.0523624722 0.0309790117 0.8190362677 -0.570506848803 +1403715976384058112.0000000000 -0.3534686018 0.5584221525 1.9469589580 0.0552965602 0.0298443149 0.8178733834 -0.571956935395 +1403715976434057984.0000000000 -0.3623915889 0.5405627234 1.9517006680 0.0577381987 0.0268831435 0.8178380973 -0.571912968608 +1403715976484058112.0000000000 -0.3693219436 0.5226672490 1.9556702528 0.0589724677 0.0223793750 0.8179015460 -0.571890262744 +1403715976534057984.0000000000 -0.3741864988 0.5044746804 1.9591599491 0.0587577447 0.0176609271 0.8177432997 -0.572303691105 +1403715976584058112.0000000000 -0.3766104313 0.4863914299 1.9620030846 0.0575336219 0.0110381562 0.8175964975 -0.5728036389 +1403715976634057984.0000000000 -0.3765841060 0.4683407562 1.9640947334 0.0531006116 0.0050239044 0.8181764429 -0.572487898311 +1403715976684058112.0000000000 -0.3741996754 0.4501658258 1.9661043996 0.0460590465 -0.0000943908 0.8180303819 -0.573327872696 +1403715976734057984.0000000000 -0.3700312639 0.4322182762 1.9672211241 0.0386174119 -0.0044881574 0.8188929743 -0.572628019457 +1403715976784058112.0000000000 -0.3644473659 0.4138273053 1.9682066929 0.0324542269 -0.0084083181 0.8189939050 -0.572821967929 +1403715976834057984.0000000000 -0.3576412267 0.3951269277 1.9685661245 0.0276411781 -0.0125362153 0.8192326098 -0.572657611229 +1403715976884058112.0000000000 -0.3496226804 0.3761908442 1.9687732793 0.0235947059 -0.0160466740 0.8188767071 -0.573259742792 +1403715976934057984.0000000000 -0.3404564249 0.3573026069 1.9684437050 0.0206844772 -0.0193884841 0.8191988462 -0.572808423006 +1403715976984058112.0000000000 -0.3298974958 0.3383204620 1.9684166045 0.0171018846 -0.0230654893 0.8190381711 -0.573020054672 +1403715977034057984.0000000000 -0.3180445796 0.3193879690 1.9678739240 0.0140833133 -0.0281369414 0.8187957148 -0.57322207757 +1403715977084058112.0000000000 -0.3047857548 0.3006823972 1.9670625299 0.0098834024 -0.0334823314 0.8185167697 -0.573420918245 +1403715977134057984.0000000000 -0.2900585377 0.2823371861 1.9661055902 0.0054911051 -0.0404739585 0.8184250932 -0.573159727486 +1403715977184058112.0000000000 -0.2738005227 0.2641876488 1.9651276866 0.0005669509 -0.0491210792 0.8177777643 -0.573433803017 +1403715977234057984.0000000000 -0.2558083288 0.2462575198 1.9637229050 0.0062601830 0.0583745228 -0.8172747235 0.573249728742 +1403715977284058112.0000000000 -0.2364818104 0.2289316265 1.9615300077 0.0133414580 0.0693673020 -0.8168270176 0.572541532318 +1403715977334057984.0000000000 -0.2155116889 0.2117119592 1.9600328850 0.0209250811 0.0821036096 -0.8152711086 0.572847412351 +1403715977384058112.0000000000 -0.1930091169 0.1952426635 1.9586679087 0.0300994347 0.0953640008 -0.8136988347 0.572620238666 +1403715977434057984.0000000000 -0.1690433506 0.1794112824 1.9569094604 0.0410807779 0.1084862509 -0.8122241907 0.571694819927 +1403715977484058112.0000000000 -0.1440696225 0.1641059148 1.9545609726 0.0503073826 0.1241193847 -0.8097908604 0.571228770267 +1403715977534057984.0000000000 -0.1175215174 0.1494575658 1.9525287930 0.0613080716 0.1393890969 -0.8077908920 0.569461038942 +1403715977584058112.0000000000 -0.0896249919 0.1349632068 1.9508173031 0.0727469167 0.1552915532 -0.8043889767 0.568815254491 +1403715977634057984.0000000000 -0.0602849740 0.1209616081 1.9492523911 0.0854424313 0.1711648715 -0.8007227582 0.567666488509 +1403715977684058112.0000000000 -0.0299962183 0.1078140824 1.9471404190 0.0980929843 0.1871304111 -0.7970856760 0.56569815343 +1403715977734057984.0000000000 0.0007444006 0.0961726916 1.9444358071 0.1112402835 0.2035187097 -0.7935541700 0.562563341719 +1403715977784058112.0000000000 0.0322577381 0.0849264226 1.9421133006 0.1231399027 0.2207875230 -0.7886662972 0.560441705851 +1403715977834057984.0000000000 0.0645589975 0.0743735131 1.9397385373 0.1354660432 0.2380392147 -0.7830145954 0.558457184373 +1403715977884058112.0000000000 0.0973026287 0.0645378356 1.9370960240 0.1459623103 0.2566529398 -0.7757228472 0.557743970706 +1403715977934057984.0000000000 0.1309198586 0.0557342611 1.9345326651 0.1559304154 0.2756048368 -0.7674519888 0.557445176066 +1403715977984058112.0000000000 0.1651440225 0.0487871276 1.9319005437 0.1647897493 0.2959310031 -0.7579159865 0.55752357554 +1403715978034057984.0000000000 0.2002314695 0.0437137079 1.9294007426 0.1744185340 0.3159466325 -0.7483204159 0.556572057871 +1403715978084058112.0000000000 0.2359260095 0.0410042318 1.9269280930 0.1845679017 0.3363945798 -0.7367582865 0.556741056236 +1403715978134057984.0000000000 0.2722090458 0.0404969620 1.9239101660 0.1932508233 0.3573305596 -0.7252855994 0.555814528259 +1403715978184058112.0000000000 0.3093220239 0.0422475209 1.9204428141 0.2012517161 0.3775877233 -0.7136631017 0.554626212251 +1403715978234057984.0000000000 0.3474904680 0.0468834689 1.9163520849 0.2093888271 0.3970132965 -0.7026956000 0.552046787247 +1403715978284058112.0000000000 0.3864536408 0.0547334009 1.9127121334 0.2187959001 0.4149116600 -0.6910316525 0.549956292622 +1403715978334057984.0000000000 0.4258189347 0.0666571160 1.9098992688 0.2313728387 0.4298266381 -0.6812545307 0.54553454063 +1403715978384058112.0000000000 0.4660250739 0.0823396720 1.9073739406 0.2462186517 0.4424415766 -0.6716064951 0.540894206526 +1403715978434057984.0000000000 0.5067870652 0.1014790800 1.9041550862 0.2611220696 0.4542649968 -0.6641333389 0.53327805649 +1403715978484058112.0000000000 0.5480954303 0.1237535081 1.9008532723 0.2779637570 0.4643410747 -0.6578032665 0.523849576441 +1403715978534057984.0000000000 0.5889312387 0.1492332356 1.8971905716 0.2968483992 0.4736592052 -0.6510995904 0.513417285057 +1403715978584058112.0000000000 0.6294942068 0.1770960728 1.8935086212 0.3159409764 0.4824332919 -0.6432509122 0.503654328111 +1403715978634057984.0000000000 0.6688820647 0.2071075332 1.8890440664 0.3333164624 0.4926011972 -0.6340496533 0.494191494886 +1403715978684058112.0000000000 0.7067665386 0.2387147798 1.8840466909 0.3486272269 0.5038937535 -0.6252563834 0.483326594339 +1403715978734057984.0000000000 0.7428159214 0.2713416561 1.8786164180 0.3611720057 0.5169147831 -0.6148680200 0.473593926543 +1403715978784058112.0000000000 0.7768775550 0.3048851134 1.8730047070 0.3712948339 0.5310571027 -0.6034700257 0.464696059791 +1403715978834057984.0000000000 0.8089784299 0.3394492355 1.8674488551 0.3798878801 0.5463151192 -0.5923277364 0.454282777264 +1403715978884058112.0000000000 0.8399747396 0.3746734475 1.8624383925 0.3870539623 0.5624028058 -0.5800135032 0.444383449751 +1403715978934057984.0000000000 0.8699860582 0.4106236916 1.8583398655 0.3947243282 0.5781687656 -0.5671598911 0.433870074049 +1403715978984058112.0000000000 0.8988469711 0.4473308160 1.8547639390 0.4013136074 0.5944126447 -0.5531064372 0.423903603962 +1403715979034057984.0000000000 0.9264846727 0.4851364426 1.8519516699 0.4097776542 0.6092477737 -0.5375859909 0.414609125137 +1403715979084058112.0000000000 0.9537224950 0.5244142740 1.8504941112 0.4209752209 0.6219039861 -0.5211225732 0.405520109437 +1403715979134057984.0000000000 0.9791557529 0.5649205431 1.8506189645 0.4348687358 0.6323847861 -0.5050211225 0.394882679637 +1403715979184058112.0000000000 1.0031219441 0.6062885690 1.8529430573 0.4498661675 0.6416901638 -0.4865117159 0.386213043941 +1403715979234057984.0000000000 1.0252191486 0.6481881883 1.8571714968 0.4680529735 0.6483154586 -0.4669439717 0.37759344205 +1403715979284058112.0000000000 1.0452307757 0.6900985847 1.8626358797 0.4854771970 0.6547174403 -0.4456853159 0.370164238902 +1403715979334057984.0000000000 1.0625128234 0.7315180074 1.8672303813 0.4972403799 0.6641513334 -0.4225722436 0.364811882967 +1403715979384058112.0000000000 1.0764789525 0.7726897805 1.8716192867 0.5064558855 0.6744743802 -0.4002153783 0.358349546537 +1403715979434057984.0000000000 1.0870256123 0.8133676109 1.8748756681 0.5109997836 0.6867613861 -0.3791921874 0.351356378447 +1403715979484058112.0000000000 1.0939811015 0.8540633177 1.8784743869 0.5155130980 0.6978755860 -0.3598675404 0.343090754255 +1403715979534057984.0000000000 1.0973780296 0.8950810829 1.8827016397 0.5198737646 0.7080692425 -0.3417927405 0.333986435697 +1403715979584058112.0000000000 1.0968718813 0.9364598136 1.8874649296 0.5242524295 0.7176176641 -0.3258111635 0.322538934214 +1403715979634057984.0000000000 1.0926996697 0.9781408881 1.8926483698 0.5284242690 0.7265904121 -0.3098626695 0.311157983883 +1403715979684058112.0000000000 1.0846240145 1.0203317350 1.8984199721 0.5333948167 0.7348859227 -0.2940117621 0.2983114711 +1403715979734057984.0000000000 1.0729213160 1.0626375222 1.9046702445 0.5395379568 0.7418522598 -0.2763100073 0.286717278366 +1403715979784058112.0000000000 1.0574756558 1.1052581079 1.9112920616 0.5469682430 0.7474982856 -0.2586024778 0.274220372382 +1403715979834057984.0000000000 1.0383233516 1.1477403209 1.9180035987 0.5548258745 0.7521264426 -0.2407199913 0.261778435256 +1403715979884058112.0000000000 1.0152960365 1.1899032857 1.9252116273 0.5637266137 0.7556635968 -0.2227105653 0.248162925332 +1403715979934057984.0000000000 0.9886480290 1.2312746430 1.9322855198 0.5720301280 0.7588180743 -0.2039896523 0.235297438326 +1403715979984058112.0000000000 0.9581984692 1.2716392420 1.9398855918 0.5809913809 0.7610016133 -0.1847144616 0.221824542235 +1403715980034057984.0000000000 0.9239027472 1.3104925096 1.9476469432 0.5898043860 0.7625759098 -0.1655491209 0.207851525301 +1403715980084058112.0000000000 0.8860116537 1.3475048902 1.9549062153 0.5967927944 0.7646723776 -0.1461565026 0.19430077808 +1403715980134057984.0000000000 0.8443204582 1.3824611718 1.9614570410 0.6026461219 0.7668977200 -0.1269420889 0.180475053297 +1403715980184058112.0000000000 0.7989921315 1.4150284994 1.9676086096 0.6075177521 0.7693968948 -0.1084228604 0.164909316315 +1403715980234057984.0000000000 0.7502802684 1.4451952517 1.9734769173 0.6115426344 0.7720042792 -0.0914599294 0.147173640878 +1403715980284058112.0000000000 0.6982028602 1.4724894568 1.9785700613 0.6134271491 0.7755930652 -0.0751583085 0.128505870096 +1403715980334057984.0000000000 0.6433512044 1.4969752195 1.9830032268 0.6146945834 0.7788003600 -0.0579622823 0.110729138571 +1403715980384058112.0000000000 0.5858271406 1.5186978876 1.9874026226 0.6163651137 0.7809700587 -0.0406665850 0.0923365736352 +1403715980434057984.0000000000 0.5262264247 1.5375912249 1.9919384265 0.6192732900 0.7814058732 -0.0232214582 0.0732544713366 +1403715980484058112.0000000000 0.4649799745 1.5531990062 1.9965231566 0.6228132791 0.7804596717 -0.0051415357 0.054404823242 +1403715980534057984.0000000000 0.4018946358 1.5652178011 2.0009612081 0.6263900976 0.7787428942 0.0115287459 0.032588931079 +1403715980584058112.0000000000 0.3380435267 1.5736822006 2.0046589142 0.6279533349 0.7776275922 0.0289494223 0.0114833820038 +1403715980634057984.0000000000 0.2738518384 1.5784863787 2.0075261223 0.6279640307 0.7767640178 0.0471897915 -0.00848294267204 +1403715980684058112.0000000000 0.2097775278 1.5799569279 2.0098259936 0.6271466881 0.7755922067 0.0662318124 -0.0275155876651 +1403715980734057984.0000000000 0.1462874248 1.5777630896 2.0114699866 0.6255750703 0.7741028196 0.0852757405 -0.0463541166199 +1403715980784058112.0000000000 0.0833577838 1.5719137972 2.0123420755 0.6220707414 0.7732016318 0.1038829157 -0.0662990880352 +1403715980834057984.0000000000 0.0216526945 1.5630043064 2.0126714474 0.6176129393 0.7721060902 0.1234225572 -0.0846954255911 +1403715980884058112.0000000000 -0.0390284483 1.5508428653 2.0132338201 0.6135155499 0.7696904498 0.1425332589 -0.104209172858 +1403715980934057984.0000000000 -0.0980626941 1.5360381684 2.0136359847 0.6093666968 0.7663026659 0.1625540558 -0.122591321478 +1403715980984058112.0000000000 -0.1553390515 1.5184074307 2.0144385297 0.6058901055 0.7612016538 0.1824954182 -0.142002269644 +1403715981034057984.0000000000 -0.2102427122 1.4979094601 2.0152709415 0.6025998681 0.7549262400 0.2020588580 -0.161653917366 +1403715981084058112.0000000000 -0.2625759279 1.4748305845 2.0161767374 0.5993470455 0.7474571191 0.2219660396 -0.181168572006 +1403715981134057984.0000000000 -0.3121388112 1.4495024880 2.0167731873 0.5947816911 0.7398387194 0.2423494066 -0.200350129178 +1403715981184058112.0000000000 -0.3585435526 1.4221155246 2.0173457543 0.5910432951 0.7307305317 0.2641671426 -0.216602017853 +1403715981234057984.0000000000 -0.4016648922 1.3917297319 2.0181164022 0.5851194260 0.7217438840 0.2854460939 -0.235035211797 +1403715981284058112.0000000000 -0.4414096141 1.3590552848 2.0195648823 0.5782082249 0.7121710769 0.3065744543 -0.253967930649 +1403715981334057984.0000000000 -0.4774116773 1.3248508042 2.0213321702 0.5710334565 0.7016040660 0.3278724658 -0.27234568517 +1403715981384058112.0000000000 -0.5098993153 1.2891632976 2.0236602040 0.5624638850 0.6906356834 0.3486001094 -0.291778502514 +1403715981434057984.0000000000 -0.5383596299 1.2521226066 2.0263550990 0.5540387534 0.6783220714 0.3690951807 -0.310948508058 +1403715981484058112.0000000000 -0.5626155175 1.2136091476 2.0298686213 0.5450907365 0.6648485296 0.3884337405 -0.331619889283 +1403715981534057984.0000000000 -0.5824821007 1.1742041166 2.0341349262 0.5377367501 0.6491550759 0.4071329282 -0.351681182099 +1403715981584058112.0000000000 -0.5974177918 1.1340971858 2.0386306800 0.5305981822 0.6324004709 0.4253506324 -0.370960985845 +1403715981634057984.0000000000 -0.6069113628 1.0934782173 2.0430247670 0.5224035611 0.6154008483 0.4444343594 -0.388399813849 +1403715981684058112.0000000000 -0.6108154089 1.0524261562 2.0470856939 0.5134018688 0.5985651824 0.4637610949 -0.403811701692 +1403715981734057984.0000000000 -0.6091264760 1.0110370758 2.0498523444 0.5025059861 0.5828848935 0.4849291131 -0.415423507033 +1403715981784058112.0000000000 -0.6019706803 0.9693568530 2.0514449119 0.4875995509 0.5698645536 0.5069198055 -0.424892197285 +1403715981834057984.0000000000 -0.5890859500 0.9275578832 2.0518501077 0.4692727298 0.5593411017 0.5309079275 -0.430182995424 +1403715981884058112.0000000000 -0.5721948889 0.8861379229 2.0524671817 0.4513444360 0.5481508080 0.5534895942 -0.43527940543 +1403715981934057984.0000000000 -0.5519617086 0.8449453128 2.0534013938 0.4342919596 0.5361107230 0.5737859184 -0.441299791945 +1403715981984058112.0000000000 -0.5290485105 0.8043165075 2.0548290578 0.4204745128 0.5217787814 0.5918682449 -0.447928641707 +1403715982034057984.0000000000 -0.5035605025 0.7640685289 2.0566156818 0.4069830263 0.5076569180 0.6077782286 -0.455252561399 +1403715982084058112.0000000000 -0.4756838434 0.7241388702 2.0589219163 0.3949409296 0.4925278335 0.6217945306 -0.463475519328 +1403715982134057984.0000000000 -0.4454566353 0.6847124274 2.0610311160 0.3832883829 0.4772593257 0.6348797160 -0.471424753112 +1403715982184058112.0000000000 -0.4133125468 0.6458096902 2.0635271843 0.3722719818 0.4615574899 0.6469781246 -0.479372048991 +1403715982234057984.0000000000 -0.3790906368 0.6072853670 2.0663410058 0.3610273870 0.4460326312 0.6580860659 -0.487480099702 +1403715982284058112.0000000000 -0.3427441959 0.5690240953 2.0691969897 0.3482580531 0.4314704872 0.6688201781 -0.495206135369 +1403715982334057984.0000000000 -0.3047280836 0.5311880828 2.0721301646 0.3370101647 0.4158439550 0.6789593267 -0.502505907038 +1403715982384058112.0000000000 -0.2648743701 0.4937821119 2.0751436478 0.3245133120 0.4009776657 0.6884062372 -0.509906731138 +1403715982434057984.0000000000 -0.2231547358 0.4572981141 2.0778447831 0.3127942385 0.3846536669 0.6979529347 -0.516781406311 +1403715982484058112.0000000000 -0.1794801139 0.4215185292 2.0802469920 0.3002014638 0.3681428006 0.7073366563 -0.523473795037 +1403715982534057984.0000000000 -0.1339300606 0.3868246945 2.0823908867 0.2892275763 0.3499467761 0.7160568128 -0.53023325421 +1403715982584058112.0000000000 -0.0861806533 0.3530511517 2.0839160804 0.2764494027 0.3319517614 0.7244918052 -0.537117659474 +1403715982634057984.0000000000 -0.0364530726 0.3203602456 2.0853485739 0.2633210617 0.3129916043 0.7323208438 -0.544430395845 +1403715982684058112.0000000000 0.0149945092 0.2884158012 2.0865681923 0.2486735620 0.2944678836 0.7402055535 -0.550949964802 +1403715982734057984.0000000000 0.0679621689 0.2574608050 2.0872239902 0.2339448457 0.2752390999 0.7477622488 -0.557103999493 +1403715982784058112.0000000000 0.1226308593 0.2277287432 2.0880712053 0.2190122240 0.2551222324 0.7550350598 -0.562910606414 +1403715982834057984.0000000000 0.1787475207 0.1998884662 2.0889421627 0.2030611365 0.2355757204 0.7617949006 -0.568277031255 +1403715982884058112.0000000000 0.2360483895 0.1740568225 2.0898660657 0.1882135633 0.2148761652 0.7683759153 -0.572714886269 +1403715982934057984.0000000000 0.2944877427 0.1500046014 2.0906982253 0.1743052298 0.1940417780 0.7746581906 -0.576081732876 +1403715982984058112.0000000000 0.3540651742 0.1273922502 2.0917914847 0.1586449416 0.1747060931 0.7791051458 -0.580779420585 +1403715983034057984.0000000000 0.4146095331 0.1065758376 2.0921721915 0.1430515978 0.1553531683 0.7832245428 -0.584774271838 +1403715983084058112.0000000000 0.4759349523 0.0875176077 2.0923989485 0.1279340728 0.1354817348 0.7870311771 -0.58809820505 +1403715983134057984.0000000000 0.5380734682 0.0701249047 2.0927906319 0.1116782468 0.1161432292 0.7901944656 -0.591296394469 +1403715983184058112.0000000000 0.6010069487 0.0547835395 2.0932360065 0.0953699456 0.0958100172 0.7925387410 -0.59464893681 +1403715983234057984.0000000000 0.6643346363 0.0413794851 2.0936626533 0.0778612936 0.0759116269 0.7942619021 -0.597765066534 +1403715983284058112.0000000000 0.7278834127 0.0298296440 2.0937580456 0.0608507935 0.0548389894 0.7959098077 -0.599847850812 +1403715983334057984.0000000000 0.7913429987 0.0202857825 2.0936301941 0.0454358403 0.0322033522 0.7961330676 -0.602553455893 +1403715983384058112.0000000000 0.8550905939 0.0133747014 2.0932808165 0.0282395168 0.0099868739 0.7971063244 -0.603095597479 +1403715983434057984.0000000000 0.9187769118 0.0088526460 2.0933661446 0.0099441896 -0.0123794908 0.7959818357 -0.605112203321 +1403715983484058112.0000000000 0.9821751866 0.0062386846 2.0944011301 0.0099223087 0.0338778439 -0.7920032352 0.609495459242 +1403715983534057984.0000000000 1.0449876623 0.0061128770 2.0960167994 0.0309249928 0.0545537415 -0.7865020806 0.614395647279 +1403715983584058112.0000000000 1.1068857601 0.0085157319 2.0981682483 0.0519268975 0.0745764494 -0.7796420267 0.619596853353 +1403715983634057984.0000000000 1.1673408470 0.0139431297 2.1004500961 0.0733406284 0.0939421741 -0.7723660619 0.623896374899 +1403715983684058112.0000000000 1.2257272635 0.0229457587 2.1021623484 0.0940893154 0.1128963183 -0.7657912048 0.626071443783 +1403715983734057984.0000000000 1.2818611861 0.0355343302 2.1041939869 0.1142284981 0.1308672918 -0.7584099339 0.628203768196 +1403715983784058112.0000000000 1.3352140001 0.0518035252 2.1056752792 0.1329553479 0.1488203019 -0.7526767690 0.627417783218 +1403715983834057984.0000000000 1.3854624176 0.0716824518 2.1071285314 0.1503706229 0.1668607545 -0.7468770893 0.62587600841 +1403715983884058112.0000000000 1.4322836928 0.0951622944 2.1090099338 0.1677699691 0.1843680957 -0.7410303198 0.623486734348 +1403715983934057984.0000000000 1.4752370133 0.1219866992 2.1108421928 0.1832052176 0.2020115369 -0.7357072323 0.619969398912 +1403715983984058112.0000000000 1.5144934453 0.1521603077 2.1129814233 0.1993092855 0.2183946153 -0.7306697166 0.615387167497 +1403715984034057984.0000000000 1.5496667814 0.1854873612 2.1149729009 0.2135585001 0.2351765600 -0.7267004299 0.609090500479 +1403715984084058112.0000000000 1.5806810935 0.2218838752 2.1172019057 0.2278939417 0.2511659898 -0.7235437293 0.601219151949 +1403715984134057984.0000000000 1.6074903595 0.2606418645 2.1194985093 0.2399637049 0.2678393366 -0.7207098377 0.592669250065 +1403715984184058112.0000000000 1.6304070026 0.3013820732 2.1222036322 0.2537185558 0.2828055161 -0.7178551051 0.58337979271 +1403715984234057984.0000000000 1.6491878121 0.3436821837 2.1251337119 0.2661016230 0.2980801702 -0.7142936078 0.574563121198 +1403715984284058112.0000000000 1.6638437396 0.3871839562 2.1286229028 0.2774532488 0.3131687316 -0.7094589030 0.567109429611 +1403715984334057984.0000000000 1.6745412952 0.4317572177 2.1331729396 0.2901528705 0.3268146550 -0.7032901851 0.560701710884 +1403715984384058112.0000000000 1.6811783921 0.4772383699 2.1377946467 0.3015226557 0.3410645721 -0.6965834804 0.554554326053 +1403715984434057984.0000000000 1.6837174375 0.5233869330 2.1425249883 0.3109360187 0.3562360681 -0.6885175386 0.549871125954 +1403715984484058112.0000000000 1.6820624597 0.5702686805 2.1472304403 0.3195855574 0.3718996409 -0.6811899877 0.543632163553 +1403715984534057984.0000000000 1.6763562879 0.6178323384 2.1515958823 0.3273171478 0.3884567407 -0.6749829773 0.535128793575 +1403715984584058112.0000000000 1.6669336141 0.6658399110 2.1551274049 0.3320428927 0.4072678390 -0.6699804507 0.524410736409 +1403715984634057984.0000000000 1.6544520659 0.7141898524 2.1583395739 0.3354279458 0.4272297859 -0.6642112049 0.513601283512 +1403715984684058112.0000000000 1.6394210986 0.7633255991 2.1615623256 0.3411042254 0.4464943941 -0.6577621725 0.501636908372 +1403715984734057984.0000000000 1.6221231703 0.8129293870 2.1648574860 0.3495262707 0.4645486030 -0.6502849612 0.489035224439 +1403715984784058112.0000000000 1.6032239602 0.8628774483 2.1683436122 0.3623276148 0.4798651379 -0.6416214339 0.476203826686 +1403715984834057984.0000000000 1.5831695871 0.9123521725 2.1724819074 0.3768918522 0.4931757008 -0.6319047003 0.464140829629 +1403715984884058112.0000000000 1.5612108206 0.9608031491 2.1766062653 0.3907512193 0.5064321121 -0.6211392197 0.452798045737 +1403715984934057984.0000000000 1.5377691167 1.0077404226 2.1804714531 0.4031914802 0.5194524968 -0.6094416147 0.442929624269 +1403715984984058112.0000000000 1.5128414709 1.0529341672 2.1839932476 0.4137254119 0.5321179401 -0.5968384252 0.435276550703 +1403715985034057984.0000000000 1.4863076227 1.0963714579 2.1871482544 0.4215528288 0.5450397083 -0.5834529459 0.429892531746 +1403715985084058112.0000000000 1.4580501221 1.1381095699 2.1900289075 0.4271848558 0.5563504653 -0.5716614878 0.425664659126 +1403715985134057984.0000000000 1.4282491451 1.1781751010 2.1927401375 0.4304105332 0.5662195036 -0.5626713573 0.421358743062 +1403715985184058112.0000000000 1.3971389924 1.2169016376 2.1960598005 0.4331157316 0.5736621068 -0.5545736233 0.419250100309 +1403715985234057984.0000000000 1.3647393116 1.2544843258 2.1992941941 0.4333988053 0.5800906362 -0.5475083526 0.419398299012 +1403715985284058112.0000000000 1.3309830567 1.2910258967 2.2022512203 0.4290819115 0.5875125993 -0.5398514845 0.423412368196 +1403715985334057984.0000000000 1.2959951043 1.3273790122 2.2055538014 0.4251581086 0.5925778596 -0.5343497746 0.427273192951 +1403715985384058112.0000000000 1.2597883445 1.3639953765 2.2091624488 0.4215610630 0.5952009401 -0.5315090748 0.430720575829 +1403715985434057984.0000000000 1.2219349313 1.4014797089 2.2132752373 0.4212386049 0.5933855004 -0.5341334004 0.430294313484 +1403715985484058112.0000000000 1.1827260460 1.4392415508 2.2166832650 0.4193020593 0.5902419348 -0.5407831006 0.428198411496 +1403715985534057984.0000000000 1.1421419472 1.4774436974 2.2193824351 0.4150745025 0.5871691098 -0.5504190790 0.424245720517 +1403715985584058112.0000000000 1.1008035916 1.5159050406 2.2215399504 0.4080878297 0.5845274732 -0.5621451526 0.419266960023 +1403715985634057984.0000000000 1.0586475882 1.5544646194 2.2228014994 0.3986998007 0.5826759041 -0.5752051984 0.413117706408 +1403715985684058112.0000000000 1.0167338259 1.5933652517 2.2229592228 0.3888902456 0.5814288909 -0.5880200769 0.406124624811 +1403715985734057984.0000000000 0.9754733445 1.6323367957 2.2214536419 0.3793734664 0.5803730388 -0.6008457478 0.397777948235 +1403715985784058112.0000000000 0.9361809003 1.6716065039 2.2189967101 0.3739345742 0.5766610657 -0.6138837570 0.388306170945 +1403715985834057984.0000000000 0.8992201117 1.7100916431 2.2146398243 0.3706284254 0.5718009077 -0.6248539800 0.381098144706 +1403715985884058112.0000000000 0.8647886626 1.7473676875 2.2073610969 0.3695189447 0.5659362151 -0.6326917066 0.377985653617 +1403715985934057984.0000000000 0.8332488944 1.7833838202 2.1972317071 0.3710746402 0.5591809078 -0.6376782796 0.378135869028 +1403715985984058112.0000000000 0.8043667841 1.8177617311 2.1840171486 0.3733390379 0.5528703670 -0.6403482881 0.380665719421 +1403715986034057984.0000000000 0.7771861974 1.8508897572 2.1672887886 0.3760914893 0.5470484969 -0.6419645177 0.383633538387 +1403715986084058112.0000000000 0.7521139282 1.8824304352 2.1476354981 0.3792336150 0.5415691382 -0.6422054060 0.387887806374 +1403715986134057984.0000000000 0.7290841278 1.9122082893 2.1256858590 0.3827083668 0.5365118820 -0.6430831100 0.390042843857 +1403715986184058112.0000000000 0.7078096678 1.9398440589 2.1023242539 0.3860979236 0.5324954556 -0.6429957567 0.392343522908 +1403715986234057984.0000000000 0.6878798252 1.9648227639 2.0785686365 0.3878288326 0.5300975126 -0.6424249419 0.394810863389 +1403715986284058112.0000000000 0.6695640446 1.9872829188 2.0547301180 0.3873483577 0.5297829334 -0.6407527525 0.398405827579 +1403715986334057984.0000000000 0.6521377143 2.0073610158 2.0311561034 0.3857878667 0.5308558984 -0.6357207743 0.406471197283 +1403715986384058112.0000000000 0.6353903369 2.0257798074 2.0085080902 0.3859761465 0.5309369070 -0.6291553664 0.416283485222 +1403715986434057984.0000000000 0.6187473586 2.0430554277 1.9854699152 0.3855723248 0.5314162143 -0.6239071009 0.42387582959 +1403715986484058112.0000000000 0.6021583532 2.0597023389 1.9614301188 0.3833607666 0.5338594515 -0.6214694414 0.42638520386 +1403715986534057984.0000000000 0.5850663008 2.0758225951 1.9356219935 0.3777785686 0.5388251422 -0.6220213028 0.424311581357 +1403715986584058112.0000000000 0.5676661144 2.0915915419 1.9087675780 0.3701947117 0.5448750792 -0.6250803750 0.418738042543 +1403715986634057984.0000000000 0.5509358003 2.1069973751 1.8812255463 0.3617979815 0.5517605960 -0.6292169600 0.410790071086 +1403715986684058112.0000000000 0.5359326959 2.1219554335 1.8534997456 0.3542797346 0.5576551183 -0.6335408416 0.402656976472 +1403715986734057984.0000000000 0.5235723288 2.1365155445 1.8267255145 0.3491165218 0.5618151178 -0.6364974475 0.396676728533 +1403715986784058112.0000000000 0.5149544143 2.1506311572 1.8014034017 0.3466732292 0.5643605513 -0.6370400794 0.394328261032 +1403715986834057984.0000000000 0.5102049196 2.1641341149 1.7778097173 0.3470365198 0.5646557927 -0.6362581373 0.394848163649 +1403715986884058112.0000000000 0.5086454753 2.1771830796 1.7554676453 0.3494526258 0.5637480356 -0.6338127492 0.397935187697 +1403715986934057984.0000000000 0.5100292938 2.1896488109 1.7341159747 0.3538057545 0.5602566698 -0.6319341049 0.401986615567 +1403715986984058112.0000000000 0.5137645472 2.2013432400 1.7136000260 0.3594109290 0.5544964061 -0.6292384660 0.409165580949 +1403715987034057984.0000000000 0.5194545940 2.2125532356 1.6942380886 0.3687028024 0.5441184033 -0.6286073974 0.415747695849 +1403715987084058112.0000000000 0.5261353209 2.2229268833 1.6750560348 0.3756505312 0.5340386051 -0.6279977333 0.423448100318 +1403715987134057984.0000000000 0.5329684602 2.2327166897 1.6564474083 0.3840710687 0.5213607004 -0.6315280974 0.426432522711 +1403715987184058112.0000000000 0.5394289720 2.2410656669 1.6379942695 0.3904719995 0.5093606452 -0.6345899479 0.43055655692 +1403715987234057984.0000000000 0.5449457496 2.2477601450 1.6196142251 0.3947081428 0.4986083727 -0.6376327750 0.434763863441 +1403715987284058112.0000000000 0.5490327698 2.2524395282 1.6014165650 0.3973560312 0.4888117334 -0.6407917750 0.438813371274 +1403715987334057984.0000000000 0.5514238970 2.2551920241 1.5828442525 0.3959019394 0.4830822247 -0.6435391705 0.442437062932 +1403715987384058112.0000000000 0.5520280684 2.2557828940 1.5640151372 0.3901177502 0.4819281076 -0.6443028017 0.447691120918 +1403715987434057984.0000000000 0.5506684504 2.2550615241 1.5452709220 0.3830501457 0.4830954062 -0.6443304907 0.452470588097 +1403715987484058112.0000000000 0.5477961930 2.2534307336 1.5269252853 0.3748128462 0.4859472168 -0.6441247848 0.456589415561 +1403715987534057984.0000000000 0.5436851870 2.2515956864 1.5092312178 0.3674745227 0.4892819641 -0.6450729746 0.45765324448 +1403715987584058112.0000000000 0.5385653001 2.2493038435 1.4921606080 0.3615309700 0.4924643197 -0.6461571246 0.45744422806 +1403715987634057984.0000000000 0.5327030117 2.2466983702 1.4758513121 0.3573491506 0.4948808374 -0.6467546530 0.457277771347 +1403715987684058112.0000000000 0.5265162901 2.2441369613 1.4605573200 0.3548045635 0.4968021390 -0.6463118316 0.457801674049 +1403715987734057984.0000000000 0.5200458832 2.2417668477 1.4454873713 0.3521280979 0.4993530294 -0.6461342301 0.457343318856 +1403715987784058112.0000000000 0.5133842930 2.2393365818 1.4303018216 0.3483747410 0.5027469482 -0.6466205603 0.455809605936 +1403715987834057984.0000000000 0.5066267249 2.2373671250 1.4146579083 0.3438306865 0.5071699249 -0.6489472218 0.451028413296 +1403715987884058112.0000000000 0.5000310370 2.2355481594 1.3993667512 0.3389710217 0.5117169074 -0.6513170828 0.446128356764 +1403715987934057984.0000000000 0.4943433818 2.2338416863 1.3845531469 0.3357690774 0.5153984074 -0.6536632823 0.440849091843 +1403715987984058112.0000000000 0.4899253063 2.2319915715 1.3701542049 0.3325650833 0.5190960206 -0.6548823603 0.437114265302 +1403715988034057984.0000000000 0.4873586205 2.2301708141 1.3571208659 0.3322040259 0.5208396398 -0.6546639777 0.435639335944 +1403715988084058112.0000000000 0.4867215880 2.2284668243 1.3453212980 0.3346753777 0.5208896801 -0.6526553666 0.436700475266 +1403715988134057984.0000000000 0.4878403012 2.2265734508 1.3346058498 0.3384245517 0.5196139460 -0.6492157269 0.440441948304 +1403715988184058112.0000000000 0.4900486275 2.2246704716 1.3245543707 0.3420799266 0.5186854825 -0.6451768262 0.444627436203 +1403715988234057984.0000000000 0.4930235596 2.2228342566 1.3147228293 0.3454217764 0.5175467508 -0.6413495569 0.448887405617 +1403715988284058112.0000000000 0.4960400610 2.2213953522 1.3054689871 0.3488825615 0.5160371063 -0.6372577165 0.453750224222 +1403715988334057984.0000000000 0.4988927060 2.2206621629 1.2967997161 0.3514466326 0.5151242522 -0.6337532834 0.457699732375 +1403715988384058112.0000000000 0.5019484317 2.2207061442 1.2894173283 0.3557319896 0.5128257535 -0.6314396368 0.460161366425 +1403715988434057984.0000000000 0.5047282236 2.2212805280 1.2824378886 0.3591843844 0.5107432348 -0.6309887121 0.460414130159 +1403715988484058112.0000000000 0.5067568760 2.2222727667 1.2760615817 0.3633172524 0.5080270627 -0.6311996574 0.459887018955 +1403715988534057984.0000000000 0.5079279126 2.2237435328 1.2699791826 0.3678908488 0.5045926651 -0.6335027791 0.456855332243 +1403715988584058112.0000000000 0.5082686715 2.2251807454 1.2643205038 0.3709944517 0.5020439295 -0.6355100199 0.454358915743 +1403715988634057984.0000000000 0.5076761458 2.2262765150 1.2591552500 0.3746010487 0.4991580157 -0.6384906140 0.450383242861 +1403715988684058112.0000000000 0.5057840326 2.2268639926 1.2542749835 0.3778187728 0.4963996714 -0.6423863373 0.445174274683 +1403715988734057984.0000000000 0.5028989382 2.2263808639 1.2496517912 0.3783414644 0.4954855334 -0.6454057043 0.441365267526 +1403715988784058112.0000000000 0.4992721960 2.2245015589 1.2451359107 0.3764726114 0.4963732883 -0.6485770582 0.437298217505 +1403715988834057984.0000000000 0.4949929007 2.2209701617 1.2406575670 0.3719447062 0.4992582691 -0.6502523120 0.43539665471 +1403715988884058112.0000000000 0.4904882098 2.2161237414 1.2367186276 0.3665479057 0.5026808129 -0.6509792259 0.434949055236 +1403715988934057984.0000000000 0.4861734157 2.2100155632 1.2336268294 0.3618399647 0.5054176220 -0.6512459149 0.435320141579 +1403715988984058112.0000000000 0.4822116467 2.2029311562 1.2315689828 0.3583730553 0.5072745050 -0.6508730486 0.436584017589 +1403715989034057984.0000000000 0.4786250372 2.1950595474 1.2300515904 0.3549170295 0.5091655585 -0.6499881562 0.438519934538 +1403715989084058112.0000000000 0.4752632085 2.1869035574 1.2287554129 0.3527071346 0.5100020304 -0.6502161727 0.438992636653 +1403715989134057984.0000000000 0.4724667553 2.1781571587 1.2280158131 0.3513525057 0.5103079768 -0.6493374682 0.441019316964 +1403715989184058112.0000000000 0.4701963282 2.1692556436 1.2275665934 0.3505246446 0.5103093157 -0.6495451438 0.441370572266 +1403715989234057984.0000000000 0.4686000220 2.1600380551 1.2271519934 0.3491848357 0.5106790204 -0.6496049890 0.441916560996 +1403715989284058112.0000000000 0.4676588527 2.1506766920 1.2268646596 0.3492087341 0.5099511956 -0.6497401383 0.442539027495 +1403715989334057984.0000000000 0.4670436764 2.1410977865 1.2264028880 0.3489137825 0.5097300277 -0.6494809425 0.443406107964 +1403715989384058112.0000000000 0.4670055424 2.1313070209 1.2261418118 0.3491215183 0.5091239507 -0.6490856234 0.44451639097 +1403715989434057984.0000000000 0.4674100909 2.1215687041 1.2255487348 0.3480021435 0.5096079751 -0.6493612025 0.444437001699 +1403715989484058112.0000000000 0.4682416859 2.1119178603 1.2255427596 0.3482519914 0.5091412898 -0.6497285270 0.444239280935 +1403715989534057984.0000000000 0.4693907459 2.1021360554 1.2250942988 0.3478058638 0.5091686689 -0.6502757568 0.443756451016 +1403715989584058112.0000000000 0.4713870579 2.0919544539 1.2249686619 0.3481939977 0.5087289549 -0.6491674323 0.445575397904 +1403715989634057984.0000000000 0.4742932372 2.0813341096 1.2252650033 0.3496668046 0.5074868520 -0.6468727288 0.449161322318 +1403715989684058112.0000000000 0.4771955388 2.0710718870 1.2252553155 0.3514180157 0.5063077970 -0.6441016800 0.453090298733 +1403715989734057984.0000000000 0.4803159050 2.0610804753 1.2244292896 0.3533798149 0.5050093481 -0.6416788451 0.456438960278 +1403715989784058112.0000000000 0.4833992245 2.0512392691 1.2225738877 0.3543508097 0.5045821190 -0.6393752266 0.459381876528 +1403715989834057984.0000000000 0.4862404612 2.0417280524 1.2196502800 0.3546267104 0.5047837602 -0.6376255665 0.46137499791 +1403715989884058112.0000000000 0.4885096190 2.0326996099 1.2158255747 0.3546919293 0.5052195073 -0.6359759864 0.46312139819 +1403715989934057984.0000000000 0.4903088637 2.0240647853 1.2112488871 0.3531682369 0.5067300028 -0.6340104194 0.465325357959 +1403715989984058112.0000000000 0.4914325602 2.0165167866 1.2066491485 0.3526516243 0.5077757505 -0.6334192822 0.465382242899 +1403715990034057984.0000000000 0.4920431077 2.0094990508 1.2022578848 0.3518861520 0.5091001498 -0.6327077047 0.465482689099 +1403715990084058112.0000000000 0.4924671904 2.0032115311 1.1976825489 0.3517828972 0.5098771448 -0.6324478230 0.465063266219 +1403715990134057984.0000000000 0.4922971832 1.9974801728 1.1923864092 0.3511261130 0.5108303447 -0.6325042429 0.464436426733 +1403715990184058112.0000000000 0.4919037920 1.9924613177 1.1861672226 0.3508976293 0.5118841084 -0.6326280125 0.463278869706 +1403715990234057984.0000000000 0.4912582474 1.9880807474 1.1789522038 0.3495425836 0.5133452171 -0.6325485840 0.462794726856 +1403715990284058112.0000000000 0.4903830495 1.9846915041 1.1715609162 0.3492533710 0.5141521381 -0.6322787267 0.462485971169 +1403715990334057984.0000000000 0.4894402435 1.9821500569 1.1640125374 0.3485290218 0.5151086723 -0.6318590660 0.462541562851 +1403715990384058112.0000000000 0.4884537509 1.9803185202 1.1554506056 0.3478142552 0.5160666423 -0.6314450538 0.462577137977 +1403715990434057984.0000000000 0.4874332066 1.9793414272 1.1449923645 0.3468999561 0.5172197606 -0.6314864499 0.461918827557 +1403715990484058112.0000000000 0.4866054633 1.9792006244 1.1324689789 0.3453155030 0.5186204566 -0.6312779850 0.46182045333 +1403715990534057984.0000000000 0.4858902906 1.9801190031 1.1184268672 0.3450509325 0.5190793816 -0.6315835605 0.46108421755 +1403715990584058112.0000000000 0.4854599253 1.9820907493 1.1026160414 0.3438488593 0.5201352371 -0.6320235392 0.460188594991 +1403715990634057984.0000000000 0.4852526550 1.9850573436 1.0857948949 0.3422276014 0.5213956890 -0.6328961213 0.458769336332 +1403715990684058112.0000000000 0.4853578402 1.9890634222 1.0683854310 0.3402189012 0.5229756611 -0.6338081344 0.457203243656 +1403715990734057984.0000000000 0.4860457049 1.9941157886 1.0506253729 0.3390092964 0.5240614761 -0.6349970734 0.455204331042 +1403715990784058112.0000000000 0.4876220030 1.9998949908 1.0331482921 0.3379630617 0.5248191033 -0.6353855858 0.454566865358 +1403715990834057984.0000000000 0.4897115286 2.0067291530 1.0162321794 0.3366077398 0.5260919796 -0.6365408910 0.452480002366 +1403715990884058112.0000000000 0.4927940836 2.0145015573 1.0002991155 0.3349558148 0.5273069027 -0.6369983520 0.451647132201 +1403715990934057984.0000000000 0.4971475371 2.0234361272 0.9856261691 0.3340608593 0.5280748650 -0.6375413102 0.450645489289 +1403715990984058112.0000000000 0.5029294163 2.0333262372 0.9723537318 0.3336154913 0.5287238520 -0.6366998168 0.451403517511 +1403715991034057984.0000000000 0.5100363603 2.0444385758 0.9615898323 0.3348679777 0.5281655529 -0.6353145747 0.453078334648 +1403715991084058112.0000000000 0.5182305131 2.0565838653 0.9527652926 0.3371277635 0.5269426312 -0.6332658044 0.45568712464 +1403715991134057984.0000000000 0.5260491384 2.0678607835 0.9494551144 0.3462115650 0.5202246775 -0.6327151908 0.457356889644 +1403715991184058112.0000000000 0.5292482684 2.0738490315 0.9500868319 0.3436784600 0.5224687112 -0.6307056340 0.459480103155 +1403715991234057984.0000000000 0.5300530120 2.0764089158 0.9521918676 0.3389632089 0.5264796439 -0.6278057780 0.462366772849 +1403715991284058112.0000000000 0.5301698974 2.0776886366 0.9520617582 0.3377333784 0.5270332864 -0.6257602936 0.465398898895 +1403715991334057984.0000000000 0.5295337389 2.0764551057 0.9504757293 0.3425239302 0.5231743507 -0.6269985022 0.464584582461 +1403715991384058112.0000000000 0.5284551714 2.0741813694 0.9474804678 0.3501189322 0.5178653144 -0.6324415314 0.457438475393 +1403715991434057984.0000000000 0.5285486955 2.0746069045 0.9477379394 0.3474625729 0.5198734297 -0.6305897538 0.459736815984 +1403715991484058112.0000000000 0.5288202165 2.0756148471 0.9484402991 0.3486912370 0.5189673515 -0.6311967571 0.458996691923 +1403715991534057984.0000000000 0.5282101945 2.0744713643 0.9469509245 0.3484637395 0.5191997094 -0.6312645099 0.458813472524 +1403715991584058112.0000000000 0.5280758853 2.0748208264 0.9472676596 0.3495330802 0.5184672148 -0.6309121948 0.459312720744 +1403715991634057984.0000000000 0.5282601434 2.0747579831 0.9473675575 0.3489869563 0.5187720375 -0.6315522910 0.45850341458 +1403715991684058112.0000000000 0.5283004940 2.0747816694 0.9465108997 0.3485686186 0.5190873930 -0.6314258000 0.458638916468 +1403715991734057984.0000000000 0.5282217395 2.0750212693 0.9468171251 0.3497297040 0.5182748002 -0.6313805323 0.45873629584 +1403715991784058112.0000000000 0.5283465581 2.0748004700 0.9468611189 0.3487342667 0.5189405597 -0.6313042224 0.45884647283 +1403715991834057984.0000000000 0.5283991288 2.0749576427 0.9466085885 0.3494798490 0.5183980451 -0.6317253612 0.458312524438 +1403715991884058112.0000000000 0.5283537215 2.0748500734 0.9466692302 0.3491323190 0.5186452337 -0.6312075595 0.459010634074 +1403715991934057984.0000000000 0.5283533271 2.0748006744 0.9467583644 0.3492502013 0.5185416005 -0.6316664241 0.458406407264 +1403715991984058112.0000000000 0.5283192962 2.0747641353 0.9466431844 0.3492013668 0.5186184788 -0.6313718887 0.458762266349 +1403715992034057984.0000000000 0.5284034268 2.0748294262 0.9467454950 0.3493238368 0.5184812379 -0.6315800015 0.458537637066 +1403715992084058112.0000000000 0.5283392514 2.0747666347 0.9467666082 0.3491449195 0.5186415959 -0.6316122819 0.458448083917 +1403715992134057984.0000000000 0.5282755717 2.0748243926 0.9468594031 0.3493086494 0.5184948343 -0.6314449157 0.458719841071 +1403715992184058112.0000000000 0.5283276292 2.0749799590 0.9468538660 0.3492297276 0.5186042986 -0.6316462159 0.458378922713 +1403715992234057984.0000000000 0.5282799900 2.0749634708 0.9469204409 0.3490981963 0.5186630930 -0.6315509269 0.4585438606 +1403715992284058112.0000000000 0.5282910444 2.0750055052 0.9469279684 0.3493331372 0.5184832585 -0.6315224814 0.458607485136 +1403715992334057984.0000000000 0.5283796926 2.0750968234 0.9468251591 0.3491500152 0.5186158199 -0.6316290180 0.458450304644 +1403715992384058112.0000000000 0.5283875556 2.0750806849 0.9468381357 0.3492586363 0.5184998646 -0.6315946972 0.458545999711 +1403715992434057984.0000000000 0.5284115832 2.0750746994 0.9468478921 0.3492577434 0.5184843652 -0.6316545713 0.45848172741 +1403715992484058112.0000000000 0.5284218129 2.0750721843 0.9468235395 0.3492164255 0.5185053184 -0.6316604800 0.458481363736 +1403715992534057984.0000000000 0.5283951169 2.0750080522 0.9468122005 0.3493415535 0.5184216010 -0.6316779021 0.458456705318 +1403715992584058112.0000000000 0.5283370055 2.0749423376 0.9467566626 0.3492776544 0.5184469041 -0.6317335632 0.458400079394 +1403715992634057984.0000000000 0.5283120408 2.0748834996 0.9466928671 0.3492355324 0.5184379112 -0.6317108020 0.458473704621 +1403715992684058112.0000000000 0.5283235330 2.0748265476 0.9466536820 0.3492983145 0.5184608369 -0.6317193427 0.458388176234 +1403715992734057984.0000000000 0.5283806583 2.0747942639 0.9466122894 0.3493493957 0.5183982976 -0.6317842050 0.458330582688 +1403715992784058112.0000000000 0.5283731983 2.0747836712 0.9465596750 0.3493205201 0.5183632762 -0.6318486916 0.458303304699 +1403715992834057984.0000000000 0.5283660810 2.0747567779 0.9465261779 0.3492242880 0.5183625617 -0.6319096228 0.458293442906 +1403715992884058112.0000000000 0.5283252852 2.0747799224 0.9465473880 0.3492551589 0.5183391187 -0.6319426494 0.458250891818 +1403715992934057984.0000000000 0.5282533591 2.0748493346 0.9465938900 0.3492574870 0.5183429795 -0.6319436463 0.458243375622 +1403715992984058112.0000000000 0.5281824301 2.0749275528 0.9467025946 0.3492327825 0.5183722325 -0.6319992040 0.458152483744 +1403715993034057984.0000000000 0.5281265467 2.0750304730 0.9468108270 0.3492099886 0.5183848862 -0.6320291445 0.458114237085 diff --git a/data/euroc_groundtruth/V2_01_easy.txt b/data/euroc_groundtruth/V2_01_easy.txt new file mode 100755 index 00000000..2d37a8d4 --- /dev/null +++ b/data/euroc_groundtruth/V2_01_easy.txt @@ -0,0 +1,2241 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1413393213505760512.0000000000 -1.0805520923 0.4272539299 1.3077239102 0.4340338472 0.5668555860 0.5560183037 -0.425597239215 +1413393213555760384.0000000000 -1.0818362344 0.4271738049 1.3075269095 0.4340269706 0.5668909070 0.5559887051 -0.42559587414 +1413393213605760512.0000000000 -1.0827582610 0.4271218722 1.3073925543 0.4339999222 0.5669556090 0.5559333401 -0.425609593765 +1413393213655760384.0000000000 -1.0833468104 0.4270903424 1.3073260358 0.4340064265 0.5669887467 0.5559014958 -0.425600410938 +1413393213705760512.0000000000 -1.0836815634 0.4270210800 1.3072699609 0.4339531497 0.5670011669 0.5558911148 -0.425651746225 +1413393213755760384.0000000000 -1.0838215671 0.4269766590 1.3072619064 0.4338671409 0.5670360002 0.5559042586 -0.425675855264 +1413393213805760512.0000000000 -1.0838427606 0.4269659294 1.3071936351 0.4338748089 0.5670543975 0.5558931866 -0.42565799141 +1413393213855760384.0000000000 -1.0837980369 0.4269336509 1.3072017875 0.4338701315 0.5670693422 0.5558668007 -0.425677307328 +1413393213905760512.0000000000 -1.0836660433 0.4269000753 1.3072289116 0.4337524706 0.5671400686 0.5559162393 -0.425638428462 +1413393213955760384.0000000000 -1.0835189941 0.4268026346 1.3073096465 0.4336432103 0.5671484807 0.5559856856 -0.425647840799 +1413393214005760512.0000000000 -1.0834673236 0.4267965040 1.3075277790 0.4334920450 0.5672226280 0.5560400413 -0.425632012058 +1413393214055760384.0000000000 -1.0833864065 0.4269143662 1.3074919164 0.4337779712 0.5673547272 0.5558013904 -0.425476320775 +1413393214105760512.0000000000 -1.0833093800 0.4269814763 1.3075714677 0.4334948485 0.5675069359 0.5559143266 -0.425414333891 +1413393214155760384.0000000000 -1.0832362302 0.4269947222 1.3075344194 0.4335965389 0.5674042077 0.5558702795 -0.4255052749 +1413393214205760512.0000000000 -1.0831150302 0.4269364770 1.3075835202 0.4333725687 0.5675167425 0.5558485675 -0.425611717053 +1413393214255760384.0000000000 -1.0831404480 0.4270055863 1.3075213271 0.4335557183 0.5673786539 0.5559041627 -0.42553667771 +1413393214305760512.0000000000 -1.0830906000 0.4268867899 1.3074635006 0.4334626367 0.5674634781 0.5558566890 -0.425580409455 +1413393214355760384.0000000000 -1.0830453377 0.4268671210 1.3074224895 0.4334422053 0.5674672406 0.5558053352 -0.425663264716 +1413393214405760512.0000000000 -1.0830525035 0.4268792002 1.3073977778 0.4334629979 0.5674402703 0.5558743357 -0.425587936748 +1413393214455760384.0000000000 -1.0830122896 0.4268638912 1.3074088938 0.4334012344 0.5674383974 0.5557994161 -0.425751152995 +1413393214505760512.0000000000 -1.0829995601 0.4269309007 1.3073674297 0.4334497028 0.5674314454 0.5558475204 -0.425648263203 +1413393214555760384.0000000000 -1.0829379888 0.4269039954 1.3073921917 0.4333340751 0.5674813620 0.5557587287 -0.425815357435 +1413393214605760512.0000000000 -1.0828938491 0.4269072140 1.3073438279 0.4333704501 0.5674730114 0.5558053075 -0.425728663078 +1413393214655760384.0000000000 -1.0828553864 0.4268626309 1.3073771738 0.4333176904 0.5674966139 0.5557631335 -0.425805955572 +1413393214705760512.0000000000 -1.0828332511 0.4267989358 1.3073699465 0.4332858446 0.5675006672 0.5557236752 -0.425884451929 +1413393214755760384.0000000000 -1.0828353008 0.4267854846 1.3073348892 0.4333191039 0.5675008579 0.5557370955 -0.425832844098 +1413393214805760512.0000000000 -1.0828251845 0.4267529226 1.3073045093 0.4332431308 0.5675604492 0.5556659634 -0.42592354143 +1413393214855760384.0000000000 -1.0828168470 0.4267637437 1.3072708732 0.4332783523 0.5675651555 0.5556609071 -0.425888036901 +1413393214905760512.0000000000 -1.0828046704 0.4267812342 1.3072570903 0.4332842255 0.5675512474 0.5556898504 -0.425862831938 +1413393214955760384.0000000000 -1.0827778435 0.4267739326 1.3073209192 0.4332416330 0.5675851873 0.5556571863 -0.425903549929 +1413393215005760512.0000000000 -1.0827527069 0.4267790700 1.3074221515 0.4332413185 0.5676195303 0.5556454754 -0.425873378451 +1413393215055760384.0000000000 -1.0827627160 0.4268520382 1.3075236758 0.4333306578 0.5677054647 0.5557656469 -0.425510977643 +1413393215105760512.0000000000 -1.0827694502 0.4268106428 1.3075738635 0.4329515930 0.5677993072 0.5557424350 -0.425801844503 +1413393215155760384.0000000000 -1.0828128926 0.4267997095 1.3074968751 0.4331195830 0.5676568278 0.5557177510 -0.425853183377 +1413393215205760512.0000000000 -1.0828451156 0.4268325310 1.3074818968 0.4330456406 0.5676539106 0.5558567865 -0.425750800154 +1413393215255760384.0000000000 -1.0828908908 0.4267974347 1.3074335051 0.4330517665 0.5676838152 0.5557561135 -0.425836113815 +1413393215305760512.0000000000 -1.0829122985 0.4268325807 1.3074305312 0.4330712848 0.5676948327 0.5557721877 -0.425780594478 +1413393215355760384.0000000000 -1.0829049253 0.4268206880 1.3074204099 0.4330754561 0.5677369309 0.5557120082 -0.425798767653 +1413393215405760512.0000000000 -1.0827963978 0.4268420018 1.3075139815 0.4329184124 0.5678667205 0.5557771133 -0.425700406764 +1413393215455760384.0000000000 -1.0828033518 0.4268708502 1.3075877444 0.4328332775 0.5678780230 0.5559427360 -0.425555612298 +1413393215505760512.0000000000 -1.0828634367 0.4268548333 1.3076682902 0.4326959068 0.5680572241 0.5558987762 -0.425513563856 +1413393215555760384.0000000000 -1.0829841078 0.4269053259 1.3078268144 0.4326405036 0.5680960642 0.5559729642 -0.425421108513 +1413393215605760512.0000000000 -1.0832777849 0.4269262720 1.3078929066 0.4326793435 0.5680721778 0.5560380320 -0.425328453603 +1413393215655760384.0000000000 -1.0835861753 0.4269080846 1.3080416842 0.4323705641 0.5683270854 0.5560092953 -0.425339491269 +1413393215705760512.0000000000 -1.0837540263 0.4269697466 1.3081247730 0.4319169812 0.5686589021 0.5563416521 -0.42492204059 +1413393215755760384.0000000000 -1.0836644442 0.4269669760 1.3081051975 0.4316269966 0.5688937321 0.5566246599 -0.42453155986 +1413393215805760512.0000000000 -1.0834218098 0.4269596555 1.3081933282 0.4313833752 0.5690061855 0.5568978683 -0.424270089491 +1413393215855760384.0000000000 -1.0831927050 0.4270278344 1.3081553480 0.4311269476 0.5691694265 0.5570545860 -0.424106009467 +1413393215905760512.0000000000 -1.0831000770 0.4270291368 1.3081091303 0.4309666125 0.5692336044 0.5570911312 -0.42413483006 +1413393215955760384.0000000000 -1.0830998860 0.4270229793 1.3081836752 0.4307834798 0.5693623978 0.5570170206 -0.42424532079 +1413393216005760512.0000000000 -1.0829252420 0.4270245999 1.3082812275 0.4310151322 0.5691864590 0.5570473791 -0.424206256763 +1413393216055760384.0000000000 -1.0829511362 0.4269258692 1.3083536600 0.4312135493 0.5690177926 0.5571826608 -0.424053191334 +1413393216105760512.0000000000 -1.0830211396 0.4269187106 1.3082270060 0.4311597962 0.5690934060 0.5572259258 -0.423949517067 +1413393216155760384.0000000000 -1.0831647735 0.4267859313 1.3081528412 0.4313871700 0.5688433790 0.5570675821 -0.424261745379 +1413393216205760512.0000000000 -1.0832169731 0.4266568173 1.3082068371 0.4313146630 0.5688819464 0.5573056680 -0.423970971781 +1413393216255760384.0000000000 -1.0834716705 0.4267247085 1.3083560026 0.4304888456 0.5693449432 0.5578549436 -0.423466115951 +1413393216305760512.0000000000 -1.0837909291 0.4268240813 1.3084776323 0.4295746985 0.5699985710 0.5583479070 -0.422865016547 +1413393216355760384.0000000000 -1.0838860112 0.4270628645 1.3083509299 0.4292148155 0.5704396164 0.5584109131 -0.422552408881 +1413393216405760512.0000000000 -1.0835605908 0.4270659546 1.3082195150 0.4286948923 0.5706840594 0.5587773361 -0.422265653696 +1413393216455760384.0000000000 -1.0836449687 0.4270113583 1.3086239947 0.4289594518 0.5704120396 0.5589462109 -0.422141003812 +1413393216505760512.0000000000 -1.0836635030 0.4273069916 1.3084448912 0.4279402003 0.5716150414 0.5597094780 -0.42053386265 +1413393216555760384.0000000000 -1.0835685469 0.4278807966 1.3084198996 0.4280652202 0.5723419860 0.5597030479 -0.419424983158 +1413393216605760512.0000000000 -1.0834307885 0.4284221393 1.3083468183 0.4275494497 0.5734661467 0.5590012154 -0.41935150869 +1413393216655760384.0000000000 -1.0837075318 0.4289965403 1.3089934750 0.4287019902 0.5732646155 0.5584181962 -0.419227148922 +1413393216705760512.0000000000 -1.0835403970 0.4296675636 1.3103210707 0.4310916762 0.5725834285 0.5583096717 -0.417849846967 +1413393216755760384.0000000000 -1.0830214422 0.4305898635 1.3115702771 0.4334131631 0.5723343178 0.5583203577 -0.415770173237 +1413393216805760512.0000000000 -1.0823327517 0.4313704669 1.3144443749 0.4357973830 0.5716789976 0.5583211847 -0.414175348605 +1413393216855760384.0000000000 -1.0813902441 0.4318974856 1.3187701123 0.4379924483 0.5710414127 0.5579707199 -0.413210595092 +1413393216905760512.0000000000 -1.0800141965 0.4322670612 1.3244894800 0.4407466347 0.5700685726 0.5570987821 -0.412801615212 +1413393216955760384.0000000000 -1.0781515326 0.4323498610 1.3305808069 0.4429857569 0.5692332165 0.5578141102 -0.41058565841 +1413393217005760512.0000000000 -1.0758244621 0.4320747088 1.3384751256 0.4440367753 0.5693405900 0.5582532661 -0.40870028835 +1413393217055760384.0000000000 -1.0726201019 0.4310094681 1.3483766273 0.4432032502 0.5703622801 0.5593584171 -0.406664369872 +1413393217105760512.0000000000 -1.0687948180 0.4291543897 1.3610226825 0.4428610995 0.5711485464 0.5595743068 -0.405635279161 +1413393217155760384.0000000000 -1.0642930568 0.4265552581 1.3749294652 0.4418408869 0.5723721664 0.5597211078 -0.404819731745 +1413393217205760512.0000000000 -1.0591715166 0.4233033803 1.3887412835 0.4414978318 0.5729765136 0.5598697797 -0.404132910273 +1413393217255760384.0000000000 -1.0539143201 0.4195340910 1.4013986269 0.4426665781 0.5726518091 0.5599502620 -0.403202071295 +1413393217305760512.0000000000 -1.0482770694 0.4151309385 1.4121524007 0.4430594691 0.5727874204 0.5603230077 -0.402058459561 +1413393217355760384.0000000000 -1.0419796505 0.4098454965 1.4216631986 0.4423416727 0.5731715463 0.5607924978 -0.401646607712 +1413393217405760512.0000000000 -1.0350684134 0.4039491444 1.4301216846 0.4421009596 0.5737071147 0.5612387386 -0.400522117192 +1413393217455760384.0000000000 -1.0275168963 0.3973211937 1.4376670954 0.4416671182 0.5742209530 0.5616653001 -0.399665540765 +1413393217505760512.0000000000 -1.0195815455 0.3896760972 1.4444353846 0.4416699211 0.5739964751 0.5621292574 -0.399332474676 +1413393217555760384.0000000000 -1.0113345445 0.3813409278 1.4501744125 0.4419904201 0.5743148243 0.5617519800 -0.399050954293 +1413393217605760512.0000000000 -1.0021357857 0.3721497518 1.4547029126 0.4423515926 0.5739231069 0.5620059623 -0.398856658756 +1413393217655760384.0000000000 -0.9927690613 0.3618970262 1.4590606382 0.4421220180 0.5738217748 0.5622219791 -0.398952551264 +1413393217705760512.0000000000 -0.9830792487 0.3508759533 1.4650279529 0.4424194773 0.5738746316 0.5621413557 -0.398660268214 +1413393217755760384.0000000000 -0.9730882733 0.3387413500 1.4730978735 0.4424080353 0.5736546602 0.5620189947 -0.399161760088 +1413393217805760512.0000000000 -0.9627910654 0.3257988289 1.4829801197 0.4420202661 0.5738779948 0.5620217960 -0.399266367596 +1413393217855760384.0000000000 -0.9521787000 0.3120200560 1.4945676189 0.4415429930 0.5745024639 0.5613556913 -0.399833080498 +1413393217905760512.0000000000 -0.9414238312 0.2974897488 1.5077924753 0.4413947197 0.5743626141 0.5611994950 -0.400416552725 +1413393217955760384.0000000000 -0.9304516342 0.2822880266 1.5223933202 0.4417069791 0.5741958546 0.5606215410 -0.401120372106 +1413393218005760512.0000000000 -0.9190460370 0.2665903258 1.5367245367 0.4407541482 0.5750402703 0.5601041747 -0.401681194372 +1413393218055760384.0000000000 -0.9073339582 0.2501550042 1.5494816645 0.4389435475 0.5762204850 0.5585988513 -0.404061676194 +1413393218105760512.0000000000 -0.8954847841 0.2334147674 1.5602615073 0.4364963521 0.5782198998 0.5569695599 -0.406100469699 +1413393218155760384.0000000000 -0.8833414451 0.2163587578 1.5694315006 0.4327784369 0.5808883021 0.5543506232 -0.409837762567 +1413393218205760512.0000000000 -0.8708232278 0.1991630202 1.5764367756 0.4287346472 0.5832396837 0.5516713363 -0.414339004188 +1413393218255760384.0000000000 -0.8577702902 0.1826558480 1.5810006615 0.4237974330 0.5869889930 0.5487230527 -0.418022331133 +1413393218305760512.0000000000 -0.8444519815 0.1670308288 1.5828556004 0.4194803011 0.5901595152 0.5468608635 -0.42034654695 +1413393218355760384.0000000000 -0.8309823709 0.1526585796 1.5825448438 0.4192231456 0.5900262221 0.5472101544 -0.420335649635 +1413393218405760512.0000000000 -0.8174148748 0.1398817332 1.5800220927 0.4230293534 0.5880490547 0.5485115120 -0.417587830885 +1413393218455760384.0000000000 -0.8034269996 0.1280075931 1.5759587011 0.4269456235 0.5856938346 0.5506925751 -0.41402639331 +1413393218505760512.0000000000 -0.7890345115 0.1166922843 1.5711325312 0.4311566510 0.5827269920 0.5528971960 -0.410898875503 +1413393218555760384.0000000000 -0.7744945248 0.1058025318 1.5664524702 0.4353689310 0.5804823302 0.5546439789 -0.407264305927 +1413393218605760512.0000000000 -0.7596503394 0.0946186494 1.5626385890 0.4385550341 0.5780753548 0.5558657935 -0.405600278376 +1413393218655760384.0000000000 -0.7444938303 0.0827973290 1.5595361991 0.4404815862 0.5765148061 0.5566807727 -0.404614838929 +1413393218705760512.0000000000 -0.7290223749 0.0707052282 1.5574865005 0.4407269939 0.5768927392 0.5562657826 -0.4043796031 +1413393218755760384.0000000000 -0.7130638548 0.0580894672 1.5555841271 0.4401409673 0.5769322636 0.5578802299 -0.402734082373 +1413393218805760512.0000000000 -0.6966373710 0.0449454585 1.5538455189 0.4362270353 0.5796139452 0.5596542581 -0.400675379407 +1413393218855760384.0000000000 -0.6800777890 0.0314626918 1.5527515883 0.4286623569 0.5854661200 0.5609300560 -0.398541689589 +1413393218905760512.0000000000 -0.6638095384 0.0178116186 1.5520208783 0.4212664707 0.5904782519 0.5629229880 -0.396216739012 +1413393218955760384.0000000000 -0.6482655187 0.0043700340 1.5517880768 0.4153207318 0.5944928323 0.5647686235 -0.393857034976 +1413393219005760512.0000000000 -0.6340715003 -0.0085079698 1.5526210299 0.4115738687 0.5975342607 0.5654215307 -0.392247690235 +1413393219055760384.0000000000 -0.6214314823 -0.0209701309 1.5546728273 0.4087865416 0.5990972814 0.5658005444 -0.392231761573 +1413393219105760512.0000000000 -0.6104268712 -0.0328139758 1.5578789197 0.4089937403 0.5986253085 0.5658484999 -0.39266695244 +1413393219155760384.0000000000 -0.6010684461 -0.0440899610 1.5617766324 0.4093414109 0.5983032504 0.5651226062 -0.393839142184 +1413393219205760512.0000000000 -0.5929663467 -0.0549445400 1.5661450663 0.4094407323 0.5976860295 0.5650437523 -0.394785074258 +1413393219255760384.0000000000 -0.5861263665 -0.0652169166 1.5713790155 0.4102802899 0.5963995236 0.5648149747 -0.396183967856 +1413393219305760512.0000000000 -0.5805364948 -0.0748281151 1.5772139666 0.4107231327 0.5955120177 0.5646172905 -0.397340232507 +1413393219355760384.0000000000 -0.5761097332 -0.0838746755 1.5831216181 0.4104512110 0.5949975006 0.5648772650 -0.398021925418 +1413393219405760512.0000000000 -0.5728983554 -0.0924853566 1.5892966724 0.4097254239 0.5948837673 0.5643691351 -0.39965717765 +1413393219455760384.0000000000 -0.5710263148 -0.1002865106 1.5940369687 0.4105336413 0.5940771901 0.5640741377 -0.400443240318 +1413393219505760512.0000000000 -0.5706133581 -0.1075799194 1.5968400716 0.4113314372 0.5932496763 0.5638326940 -0.401190682214 +1413393219555760384.0000000000 -0.5713265577 -0.1143033276 1.5980542829 0.4123485985 0.5921001176 0.5632759337 -0.402624274767 +1413393219605760512.0000000000 -0.5728134207 -0.1203829444 1.5982328874 0.4137894224 0.5909614761 0.5627516715 -0.403550992982 +1413393219655760384.0000000000 -0.5750879639 -0.1259408582 1.5993336343 0.4150938578 0.5896761962 0.5617879630 -0.405429842824 +1413393219705760512.0000000000 -0.5781298242 -0.1309184350 1.6025777240 0.4175960073 0.5877242468 0.5609186427 -0.406895638521 +1413393219755760384.0000000000 -0.5819904334 -0.1352100005 1.6088706994 0.4205280169 0.5854571546 0.5600979840 -0.408272403494 +1413393219805760512.0000000000 -0.5855547568 -0.1389727651 1.6187271491 0.4244845602 0.5824939256 0.5600256612 -0.40851553647 +1413393219855760384.0000000000 -0.5893156625 -0.1425012384 1.6321565422 0.4257315619 0.5816672304 0.5599089504 -0.408555794945 +1413393219905760512.0000000000 -0.5923112971 -0.1457925119 1.6484563840 0.4276555872 0.5801568148 0.5599712838 -0.408608529487 +1413393219955760384.0000000000 -0.5955696827 -0.1489695603 1.6654440026 0.4298131178 0.5785246980 0.5602423030 -0.40828717781 +1413393220005760512.0000000000 -0.5988311054 -0.1522463888 1.6807399818 0.4310036747 0.5776558968 0.5599633104 -0.408644819178 +1413393220055760384.0000000000 -0.6015346989 -0.1556038975 1.6938045136 0.4325531273 0.5766838864 0.5595522788 -0.408943436805 +1413393220105760512.0000000000 -0.6034444983 -0.1591696788 1.7049586963 0.4332609903 0.5763951138 0.5592299755 -0.40904207812 +1413393220155760384.0000000000 -0.6052210909 -0.1627874630 1.7154601188 0.4340945074 0.5759663806 0.5591443267 -0.40887933306 +1413393220205760512.0000000000 -0.6068713801 -0.1665544911 1.7262980538 0.4352648623 0.5750936216 0.5592512158 -0.40871738837 +1413393220255760384.0000000000 -0.6083018016 -0.1705799394 1.7374442147 0.4356194314 0.5751518216 0.5587021097 -0.40900861324 +1413393220305760512.0000000000 -0.6093502820 -0.1747308040 1.7487383823 0.4368856880 0.5743915668 0.5589300496 -0.408414523704 +1413393220355760384.0000000000 -0.6098833491 -0.1793998390 1.7603809129 0.4369745177 0.5742261443 0.5586173292 -0.408979566247 +1413393220405760512.0000000000 -0.6100182071 -0.1842443939 1.7722391554 0.4370765575 0.5745287308 0.5583428992 -0.408820287156 +1413393220455760384.0000000000 -0.6095139000 -0.1894146150 1.7842274924 0.4367414987 0.5748507870 0.5587269276 -0.408200509876 +1413393220505760512.0000000000 -0.6084820681 -0.1949464739 1.7959663357 0.4351752699 0.5760125317 0.5594866793 -0.407193692901 +1413393220555760384.0000000000 -0.6069952310 -0.2005827916 1.8063523617 0.4337199193 0.5774651407 0.5597968969 -0.406261587021 +1413393220605760512.0000000000 -0.6053321416 -0.2063835334 1.8143041793 0.4330975777 0.5782009382 0.5599597429 -0.405654100976 +1413393220655760384.0000000000 -0.6039614788 -0.2123218200 1.8194437223 0.4335031267 0.5776568953 0.5598007977 -0.406214989139 +1413393220705760512.0000000000 -0.6024317628 -0.2184862686 1.8221733297 0.4333789172 0.5781164450 0.5588256387 -0.407035619654 +1413393220755760384.0000000000 -0.6008463156 -0.2247789596 1.8220126926 0.4313277576 0.5797288273 0.5576232709 -0.408567179326 +1413393220805760512.0000000000 -0.5987134703 -0.2312300986 1.8209273296 0.4268663910 0.5824492456 0.5572793551 -0.409850803335 +1413393220855760384.0000000000 -0.5967305848 -0.2371630966 1.8216604226 0.4232398494 0.5856636624 0.5556011921 -0.411306965461 +1413393220905760512.0000000000 -0.5944535318 -0.2422765151 1.8252607322 0.4208539049 0.5872024283 0.5551063601 -0.412228368591 +1413393220955760384.0000000000 -0.5925009942 -0.2468386028 1.8322739106 0.4192394534 0.5882438569 0.5551915334 -0.412273946388 +1413393221005760512.0000000000 -0.5905544265 -0.2500241797 1.8418242180 0.4204599874 0.5886530980 0.5543920806 -0.41152199227 +1413393221055760384.0000000000 -0.5889253913 -0.2525397392 1.8535628994 0.4206706134 0.5889695790 0.5546899879 -0.410451077882 +1413393221105760512.0000000000 -0.5874200488 -0.2544965315 1.8662669159 0.4202189184 0.5895327289 0.5553026850 -0.409275152208 +1413393221155760384.0000000000 -0.5861131201 -0.2555414581 1.8798078929 0.4208115426 0.5901102490 0.5552255607 -0.407936412204 +1413393221205760512.0000000000 -0.5849368993 -0.2560575811 1.8936662877 0.4209726303 0.5904809439 0.5563648985 -0.405675238598 +1413393221255760384.0000000000 -0.5840846141 -0.2561973539 1.9080332454 0.4203936798 0.5910290627 0.5570762928 -0.404499449919 +1413393221305760512.0000000000 -0.5836833384 -0.2553731998 1.9219425078 0.4210976430 0.5913320538 0.5585762451 -0.401242763934 +1413393221355760384.0000000000 -0.5839073519 -0.2541942448 1.9362891867 0.4203578133 0.5921121308 0.5595357743 -0.399527534286 +1413393221405760512.0000000000 -0.5847275611 -0.2527586281 1.9509481399 0.4203802852 0.5919679494 0.5610658201 -0.397566985779 +1413393221455760384.0000000000 -0.5864380715 -0.2509076310 1.9656073721 0.4218087575 0.5913816490 0.5621185672 -0.395433728584 +1413393221505760512.0000000000 -0.5887222147 -0.2490446303 1.9783141886 0.4221943668 0.5910498041 0.5632015364 -0.393974713812 +1413393221555760384.0000000000 -0.5917260098 -0.2471484714 1.9876111376 0.4236491166 0.5899756565 0.5650206911 -0.391409975957 +1413393221605760512.0000000000 -0.5959272881 -0.2453954912 1.9951694362 0.4250664683 0.5889906628 0.5659092166 -0.390070833557 +1413393221655760384.0000000000 -0.6009962649 -0.2440820159 2.0024465053 0.4262449690 0.5877624600 0.5664818212 -0.389806186801 +1413393221705760512.0000000000 -0.6069081622 -0.2431389802 2.0102762282 0.4288386859 0.5856298851 0.5654435299 -0.391674142137 +1413393221755760384.0000000000 -0.6132076786 -0.2425493839 2.0184670678 0.4309521590 0.5839261895 0.5634627313 -0.394740664755 +1413393221805760512.0000000000 -0.6195516767 -0.2425460236 2.0265163197 0.4327395461 0.5816567354 0.5625194072 -0.397471815229 +1413393221855760384.0000000000 -0.6259026754 -0.2427479718 2.0344617145 0.4343605326 0.5799904414 0.5621330555 -0.398683387567 +1413393221905760512.0000000000 -0.6321649974 -0.2431919891 2.0424389522 0.4344883256 0.5795385151 0.5614629938 -0.400142863311 +1413393221955760384.0000000000 -0.6381829683 -0.2441095883 2.0498812155 0.4342704013 0.5786386562 0.5608613029 -0.402518475449 +1413393222005760512.0000000000 -0.6438695148 -0.2450374267 2.0548071032 0.4339520252 0.5785552596 0.5609459906 -0.40286355877 +1413393222055760384.0000000000 -0.6494525853 -0.2460332440 2.0567963490 0.4338792905 0.5782145644 0.5606286359 -0.403871528393 +1413393222105760512.0000000000 -0.6548837915 -0.2475383340 2.0560207230 0.4332455081 0.5775736727 0.5605975547 -0.40550877182 +1413393222155760384.0000000000 -0.6607077047 -0.2490616301 2.0522433273 0.4332242457 0.5769928801 0.5610639884 -0.405713162392 +1413393222205760512.0000000000 -0.6661793960 -0.2506017774 2.0454424382 0.4329853627 0.5766753181 0.5615023019 -0.405813279901 +1413393222255760384.0000000000 -0.6711859158 -0.2523553143 2.0356586033 0.4315168653 0.5770135726 0.5623563038 -0.405714086035 +1413393222305760512.0000000000 -0.6758620980 -0.2541031480 2.0235025769 0.4299457189 0.5777566464 0.5640691481 -0.403942981847 +1413393222355760384.0000000000 -0.6804310058 -0.2559297774 2.0108752337 0.4270346874 0.5797080684 0.5662690666 -0.401147448525 +1413393222405760512.0000000000 -0.6851120767 -0.2580990615 1.9990657908 0.4234825222 0.5815198812 0.5686857187 -0.398865559386 +1413393222455760384.0000000000 -0.6904359992 -0.2602037721 1.9883562987 0.4221365013 0.5821962621 0.5711926927 -0.395710998585 +1413393222505760512.0000000000 -0.6963893005 -0.2626649285 1.9792433140 0.4194061781 0.5837494139 0.5722965790 -0.394729914199 +1413393222555760384.0000000000 -0.7029959226 -0.2655133194 1.9726794749 0.4167192466 0.5848816353 0.5722921041 -0.395904394743 +1413393222605760512.0000000000 -0.7103508039 -0.2681178816 1.9676864002 0.4155234389 0.5853785671 0.5729310727 -0.395502453587 +1413393222655760384.0000000000 -0.7188125531 -0.2707008937 1.9649756589 0.4138294353 0.5860864020 0.5737287301 -0.395073755129 +1413393222705760512.0000000000 -0.7288275099 -0.2731012846 1.9648148953 0.4145430554 0.5848482764 0.5747748734 -0.394639574456 +1413393222755760384.0000000000 -0.7397747007 -0.2756518146 1.9670068701 0.4123896342 0.5859503726 0.5751829062 -0.394666409636 +1413393222805760512.0000000000 -0.7519173647 -0.2780824095 1.9709988080 0.4106705567 0.5866346780 0.5762675685 -0.393859287019 +1413393222855760384.0000000000 -0.7650966330 -0.2805726954 1.9771572507 0.4087541673 0.5873341313 0.5775555281 -0.392922716158 +1413393222905760512.0000000000 -0.7798222985 -0.2831801917 1.9855670286 0.4069110508 0.5876857835 0.5782171981 -0.393336609635 +1413393222955760384.0000000000 -0.7959631706 -0.2856727800 1.9954291932 0.4051502277 0.5877992512 0.5798143135 -0.392633028558 +1413393223005760512.0000000000 -0.8136774129 -0.2880254156 2.0068018941 0.4063322538 0.5860135735 0.5804391024 -0.393157270733 +1413393223055760384.0000000000 -0.8325470634 -0.2904403141 2.0188070966 0.4073173604 0.5843127081 0.5799816428 -0.395338489177 +1413393223105760512.0000000000 -0.8525661306 -0.2926660398 2.0309425171 0.4080135009 0.5830001889 0.5794133867 -0.397386323498 +1413393223155760384.0000000000 -0.8737925537 -0.2945497702 2.0428364856 0.4098281028 0.5811742179 0.5798240410 -0.397594688066 +1413393223205760512.0000000000 -0.8959645268 -0.2965316917 2.0545314098 0.4120989901 0.5786802766 0.5805735904 -0.397791234268 +1413393223255760384.0000000000 -0.9191063168 -0.2986591625 2.0655745798 0.4136468354 0.5771752399 0.5810367775 -0.397694985274 +1413393223305760512.0000000000 -0.9429829173 -0.3012259088 2.0755901824 0.4146066440 0.5761352559 0.5804868435 -0.399004413734 +1413393223355760384.0000000000 -0.9676005368 -0.3041254912 2.0822075896 0.4157808255 0.5749356808 0.5806516515 -0.399272998981 +1413393223405760512.0000000000 -0.9928934211 -0.3073102359 2.0843451521 0.4171001285 0.5738346412 0.5800870408 -0.400300277843 +1413393223455760384.0000000000 -1.0187052796 -0.3106481762 2.0810834138 0.4192961820 0.5722289822 0.5796170412 -0.400984774419 +1413393223505760512.0000000000 -1.0448740820 -0.3144459778 2.0726122406 0.4216387648 0.5707141476 0.5783820643 -0.402467764434 +1413393223555760384.0000000000 -1.0713004232 -0.3186596196 2.0598510703 0.4235660367 0.5697041133 0.5765791652 -0.404457046073 +1413393223605760512.0000000000 -1.0978750871 -0.3229880528 2.0435854402 0.4261235399 0.5686370308 0.5748955285 -0.405667089169 +1413393223655760384.0000000000 -1.1237978305 -0.3275125899 2.0244757699 0.4284303761 0.5680694236 0.5734339839 -0.406100983639 +1413393223705760512.0000000000 -1.1494914754 -0.3324857254 2.0050651035 0.4296887130 0.5686083632 0.5720540602 -0.405963411368 +1413393223755760384.0000000000 -1.1748742745 -0.3379020161 1.9880059546 0.4310592263 0.5691467643 0.5708242018 -0.405486910732 +1413393223805760512.0000000000 -1.1997530867 -0.3439036141 1.9748485314 0.4321859341 0.5699553991 0.5690611909 -0.40562978485 +1413393223855760384.0000000000 -1.2243644786 -0.3505822460 1.9660759121 0.4321200826 0.5715341846 0.5686779515 -0.404012744328 +1413393223905760512.0000000000 -1.2485576260 -0.3576045774 1.9597708114 0.4340967734 0.5720327869 0.5680311056 -0.402093453216 +1413393223955760384.0000000000 -1.2728154643 -0.3653972597 1.9581165977 0.4346482970 0.5730865530 0.5673823865 -0.40091132214 +1413393224005760512.0000000000 -1.2971073458 -0.3738405398 1.9588409644 0.4358091792 0.5735357960 0.5659979684 -0.400965521983 +1413393224055760384.0000000000 -1.3212630091 -0.3828489263 1.9596783387 0.4352347693 0.5754420952 0.5649693826 -0.400308240474 +1413393224105760512.0000000000 -1.3451349786 -0.3923773184 1.9591826477 0.4362226519 0.5757964362 0.5634982967 -0.400796621337 +1413393224155760384.0000000000 -1.3680796329 -0.4022815116 1.9561396444 0.4370611825 0.5762044740 0.5626597809 -0.400474590677 +1413393224205760512.0000000000 -1.3904281067 -0.4127301804 1.9508259375 0.4377833592 0.5765487281 0.5617618735 -0.400450860943 +1413393224255760384.0000000000 -1.4125858487 -0.4234828595 1.9430359250 0.4395272946 0.5759415221 0.5613454868 -0.399997956026 +1413393224305760512.0000000000 -1.4339903540 -0.4349379837 1.9329967348 0.4406712518 0.5755708203 0.5601850668 -0.400898702439 +1413393224355760384.0000000000 -1.4551757244 -0.4466858019 1.9192301705 0.4414357805 0.5754100110 0.5598357222 -0.400776415354 +1413393224405760512.0000000000 -1.4763799442 -0.4585504320 1.9031622523 0.4419057550 0.5770232139 0.5582308237 -0.400177288032 +1413393224455760384.0000000000 -1.4977511631 -0.4707681774 1.8850063212 0.4430527324 0.5788863327 0.5550464182 -0.400647430822 +1413393224505760512.0000000000 -1.5187561142 -0.4831376480 1.8646665832 0.4440263383 0.5820268573 0.5512655718 -0.400239450408 +1413393224555760384.0000000000 -1.5393631965 -0.4955926026 1.8423253003 0.4438044823 0.5870704734 0.5461489858 -0.400133885132 +1413393224605760512.0000000000 -1.5598406141 -0.5079621960 1.8194467753 0.4453089830 0.5916483665 0.5400858741 -0.399949207678 +1413393224655760384.0000000000 -1.5800731165 -0.5200567758 1.7971438857 0.4464400965 0.5973189641 0.5334158312 -0.399210278483 +1413393224705760512.0000000000 -1.5983602397 -0.5318647100 1.7757372582 0.4461686266 0.6040404008 0.5281858799 -0.396343824302 +1413393224755760384.0000000000 -1.6159030889 -0.5430708566 1.7543939430 0.4459182001 0.6108747488 0.5225641361 -0.39359334813 +1413393224805760512.0000000000 -1.6322535538 -0.5536359594 1.7337005598 0.4471344394 0.6171293394 0.5175225451 -0.389092003062 +1413393224855760384.0000000000 -1.6471934458 -0.5633964010 1.7149215562 0.4477810104 0.6235312630 0.5122183143 -0.3851406618 +1413393224905760512.0000000000 -1.6619265705 -0.5726531484 1.6994793110 0.4495655232 0.6274684530 0.5079872317 -0.382260582923 +1413393224955760384.0000000000 -1.6754373217 -0.5813062770 1.6860941046 0.4503330138 0.6319833062 0.5045777025 -0.37841593441 +1413393225005760512.0000000000 -1.6885541061 -0.5892962263 1.6763932123 0.4519467357 0.6345083780 0.5028706780 -0.374518821421 +1413393225055760384.0000000000 -1.7021144150 -0.5968373481 1.6696058100 0.4534333150 0.6361296068 0.5023796526 -0.370610357121 +1413393225105760512.0000000000 -1.7166655002 -0.6034583943 1.6658484830 0.4550435193 0.6376793943 0.5011087725 -0.367682449498 +1413393225155760384.0000000000 -1.7307425041 -0.6097583761 1.6626308073 0.4567313659 0.6383668030 0.5002101020 -0.365614740095 +1413393225205760512.0000000000 -1.7447389965 -0.6159947265 1.6594722921 0.4560819788 0.6400234462 0.4991261657 -0.365009982791 +1413393225255760384.0000000000 -1.7586655621 -0.6214774654 1.6560118120 0.4566544677 0.6409736800 0.4989524235 -0.362857985635 +1413393225305760512.0000000000 -1.7727078724 -0.6265295978 1.6527467219 0.4565818715 0.6427102874 0.4978625080 -0.361371559881 +1413393225355760384.0000000000 -1.7870441872 -0.6306644232 1.6507413461 0.4580946415 0.6444601496 0.4954977438 -0.359586430298 +1413393225405760512.0000000000 -1.8014098284 -0.6340702837 1.6492343962 0.4579663616 0.6488980651 0.4907597287 -0.358263871285 +1413393225455760384.0000000000 -1.8167042569 -0.6364406035 1.6490939099 0.4584808220 0.6536228579 0.4856957799 -0.355910248425 +1413393225505760512.0000000000 -1.8321911884 -0.6377827219 1.6502503860 0.4598420643 0.6594004480 0.4778189555 -0.354154444928 +1413393225555760384.0000000000 -1.8474438368 -0.6378237142 1.6514248559 0.4609735925 0.6664179478 0.4699139233 -0.350101943047 +1413393225605760512.0000000000 -1.8628377518 -0.6363991922 1.6536114699 0.4630932420 0.6734868466 0.4606548061 -0.34605962809 +1413393225655760384.0000000000 -1.8783239642 -0.6333074641 1.6570160053 0.4668071492 0.6801722484 0.4504947169 -0.341337527962 +1413393225705760512.0000000000 -1.8932745799 -0.6285968039 1.6607989196 0.4713815636 0.6869895921 0.4404286469 -0.334465736294 +1413393225755760384.0000000000 -1.9081000312 -0.6224090097 1.6651406221 0.4778220530 0.6924597672 0.4312719696 -0.325868140019 +1413393225805760512.0000000000 -1.9225551259 -0.6148306398 1.6698783056 0.4851058095 0.6975715940 0.4216772626 -0.31662992746 +1413393225855760384.0000000000 -1.9360766196 -0.6063094072 1.6737286125 0.4935129576 0.7021208774 0.4127043931 -0.305198817327 +1413393225905760512.0000000000 -1.9493330340 -0.5974575428 1.6734927954 0.5018032707 0.7061494792 0.4036513281 -0.29429916063 +1413393225955760384.0000000000 -1.9624539318 -0.5882432620 1.6681272336 0.5097364977 0.7101194711 0.3953341830 -0.282152305433 +1413393226005760512.0000000000 -1.9757124114 -0.5791796560 1.6589132611 0.5177233797 0.7135330244 0.3861535221 -0.271511661855 +1413393226055760384.0000000000 -1.9890877595 -0.5706253069 1.6479116946 0.5239916759 0.7177725784 0.3758198685 -0.262668375988 +1413393226105760512.0000000000 -2.0022646476 -0.5632737706 1.6370951135 0.5280591481 0.7225659687 0.3654449244 -0.25593351527 +1413393226155760384.0000000000 -2.0157191319 -0.5564333771 1.6275365010 0.5314758455 0.7271625101 0.3547697581 -0.250811738556 +1413393226205760512.0000000000 -2.0290299045 -0.5503346641 1.6205949453 0.5340323526 0.7317813409 0.3451334209 -0.245333318552 +1413393226255760384.0000000000 -2.0427395307 -0.5448132431 1.6180031350 0.5348306304 0.7364032074 0.3365291339 -0.241691238955 +1413393226305760512.0000000000 -2.0562428743 -0.5396125801 1.6180568998 0.5355471432 0.7403548160 0.3288432610 -0.238591939304 +1413393226355760384.0000000000 -2.0694886336 -0.5349526184 1.6197215286 0.5334458534 0.7453981376 0.3221737293 -0.236688035669 +1413393226405760512.0000000000 -2.0822503840 -0.5303179681 1.6212137790 0.5311733995 0.7499450081 0.3180761194 -0.232948249029 +1413393226455760384.0000000000 -2.0949696123 -0.5256563392 1.6213141624 0.5275239271 0.7549231806 0.3143887729 -0.230150379355 +1413393226505760512.0000000000 -2.1078984341 -0.5206862746 1.6188513224 0.5241941932 0.7590797829 0.3117386300 -0.22767818855 +1413393226555760384.0000000000 -2.1210976107 -0.5151614131 1.6144086542 0.5217060560 0.7621823268 0.3093703170 -0.226254058259 +1413393226605760512.0000000000 -2.1343627095 -0.5088949692 1.6071746342 0.5193044378 0.7649585778 0.3076089949 -0.224806542278 +1413393226655760384.0000000000 -2.1478821217 -0.5013793204 1.5995787846 0.5190307279 0.7660901597 0.3065310947 -0.223050798388 +1413393226705760512.0000000000 -2.1618854244 -0.4924801241 1.5920365252 0.5227889085 0.7639526241 0.3082789367 -0.219162593716 +1413393226755760384.0000000000 -2.1763623076 -0.4825221442 1.5853136088 0.5277149481 0.7610239825 0.3094296241 -0.215899836394 +1413393226805760512.0000000000 -2.1911757413 -0.4722284961 1.5786974601 0.5312553521 0.7586187320 0.3118310567 -0.21219510477 +1413393226855760384.0000000000 -2.2067152197 -0.4619104275 1.5726344931 0.5337816024 0.7566190750 0.3137962827 -0.210087289848 +1413393226905760512.0000000000 -2.2227938070 -0.4514869768 1.5670655582 0.5360715547 0.7547683342 0.3164134901 -0.20696510141 +1413393226955760384.0000000000 -2.2396763169 -0.4414122688 1.5621256180 0.5368521166 0.7538506922 0.3180885357 -0.205714905238 +1413393227005760512.0000000000 -2.2573254085 -0.4317069215 1.5576036099 0.5373501968 0.7530153446 0.3195919447 -0.205142988392 +1413393227055760384.0000000000 -2.2758028978 -0.4221767563 1.5537660737 0.5377899942 0.7524293646 0.3197259461 -0.205930310722 +1413393227105760512.0000000000 -2.2949968075 -0.4130092934 1.5506041978 0.5387408291 0.7514588450 0.3193311432 -0.207594663197 +1413393227155760384.0000000000 -2.3147767514 -0.4043016404 1.5479863705 0.5385382306 0.7514078591 0.3178818418 -0.210508760197 +1413393227205760512.0000000000 -2.3349374578 -0.3957693751 1.5459225635 0.5382781657 0.7512553179 0.3168023993 -0.213326752653 +1413393227255760384.0000000000 -2.3553906032 -0.3874793060 1.5449523851 0.5375057994 0.7516824900 0.3139755785 -0.217899715152 +1413393227305760512.0000000000 -2.3756419334 -0.3791611685 1.5438248545 0.5363291943 0.7525802600 0.3128214777 -0.219355124715 +1413393227355760384.0000000000 -2.3959767540 -0.3707949084 1.5433007620 0.5363934161 0.7526477811 0.3115326085 -0.220795956924 +1413393227405760512.0000000000 -2.4161168325 -0.3624295562 1.5426066436 0.5349837937 0.7537747493 0.3106636894 -0.221594313512 +1413393227455760384.0000000000 -2.4361464436 -0.3538079999 1.5423219378 0.5339613152 0.7547004424 0.3093790379 -0.222704213946 +1413393227505760512.0000000000 -2.4560099949 -0.3448693966 1.5422515535 0.5337523077 0.7550453571 0.3085415820 -0.223197390011 +1413393227555760384.0000000000 -2.4756951108 -0.3352615975 1.5426362305 0.5345069846 0.7553747822 0.3060731371 -0.223674890457 +1413393227605760512.0000000000 -2.4950825810 -0.3250838044 1.5432366675 0.5353043103 0.7562306897 0.3025482976 -0.223671560294 +1413393227655760384.0000000000 -2.5138934580 -0.3143164703 1.5436058757 0.5362602161 0.7575202477 0.2989842827 -0.221802735698 +1413393227705760512.0000000000 -2.5320918112 -0.3028162497 1.5438119839 0.5368448192 0.7598086183 0.2942293406 -0.218900887885 +1413393227755760384.0000000000 -2.5497104113 -0.2906985612 1.5437276340 0.5380093762 0.7621785053 0.2882538376 -0.215730300045 +1413393227805760512.0000000000 -2.5666014574 -0.2779831264 1.5434684898 0.5397047850 0.7644573145 0.2825258330 -0.210957135781 +1413393227855760384.0000000000 -2.5830223850 -0.2647976555 1.5431406112 0.5411215585 0.7674269808 0.2737820030 -0.208054567149 +1413393227905760512.0000000000 -2.5988821163 -0.2509406102 1.5424877870 0.5430364216 0.7702198887 0.2657505569 -0.203099505834 +1413393227955760384.0000000000 -2.6140390416 -0.2366048293 1.5419617809 0.5458251810 0.7726592520 0.2564464927 -0.198261817737 +1413393228005760512.0000000000 -2.6280423903 -0.2215022321 1.5408815196 0.5479609755 0.7759586372 0.2462702353 -0.192296474068 +1413393228055760384.0000000000 -2.6410830432 -0.2057253763 1.5395307939 0.5511563508 0.7785884565 0.2366157410 -0.184498464637 +1413393228105760512.0000000000 -2.6535158793 -0.1896508268 1.5381086580 0.5533477934 0.7817563219 0.2260991298 -0.177601960251 +1413393228155760384.0000000000 -2.6650061921 -0.1729343301 1.5362906863 0.5553459513 0.7850423704 0.2166626138 -0.168394366836 +1413393228205760512.0000000000 -2.6759269201 -0.1560754327 1.5346594535 0.5563198726 0.7885332458 0.2071713040 -0.160634897936 +1413393228255760384.0000000000 -2.6862090309 -0.1389766526 1.5330218422 0.5579983697 0.7908393936 0.2002452515 -0.152028655947 +1413393228305760512.0000000000 -2.6961940314 -0.1217542320 1.5317297854 0.5594980924 0.7928619292 0.1934610949 -0.144584406204 +1413393228355760384.0000000000 -2.7058981643 -0.1043054897 1.5310239727 0.5611744715 0.7943760043 0.1873390399 -0.137673746501 +1413393228405760512.0000000000 -2.7153681584 -0.0864310548 1.5305970728 0.5629285415 0.7958729836 0.1808792819 -0.130308620391 +1413393228455760384.0000000000 -2.7245491678 -0.0682605082 1.5304827343 0.5647879702 0.7973273124 0.1730693295 -0.12381725532 +1413393228505760512.0000000000 -2.7337546851 -0.0500908403 1.5308487291 0.5678627184 0.7975646862 0.1655688289 -0.118361595456 +1413393228555760384.0000000000 -2.7427770334 -0.0319843556 1.5310487325 0.5700866127 0.7983012572 0.1579570878 -0.112986349631 +1413393228605760512.0000000000 -2.7515225817 -0.0139842634 1.5307481134 0.5706566283 0.8000835830 0.1507206793 -0.107240615334 +1413393228655760384.0000000000 -2.7604169133 0.0036193396 1.5308401306 0.5709221692 0.8015677955 0.1441813945 -0.10367579922 +1413393228705760512.0000000000 -2.7690834446 0.0210612760 1.5308639607 0.5708240731 0.8030204672 0.1396872975 -0.0990225518966 +1413393228755760384.0000000000 -2.7778566171 0.0383462761 1.5312265157 0.5701993522 0.8045524555 0.1354426905 -0.0960381319164 +1413393228805760512.0000000000 -2.7869400614 0.0556462164 1.5312695420 0.5673330964 0.8073243539 0.1317459022 -0.0948871047174 +1413393228855760384.0000000000 -2.7961189415 0.0735623451 1.5305429583 0.5645886083 0.8098576525 0.1284991741 -0.0941182679415 +1413393228905760512.0000000000 -2.8050176403 0.0916839715 1.5291919175 0.5603510405 0.8132439782 0.1261206362 -0.0934586991438 +1413393228955760384.0000000000 -2.8138115258 0.1106279423 1.5276569639 0.5589637703 0.8144508350 0.1247070067 -0.0931531179722 +1413393229005760512.0000000000 -2.8224761096 0.1305493391 1.5254535011 0.5590402676 0.8146158887 0.1252265940 -0.0905164802414 +1413393229055760384.0000000000 -2.8309462067 0.1517323468 1.5223814007 0.5603267061 0.8138305113 0.1281872602 -0.0853340945058 +1413393229105760512.0000000000 -2.8398276782 0.1734583741 1.5184417864 0.5630688403 0.8118613944 0.1311717603 -0.081415764801 +1413393229155760384.0000000000 -2.8490534705 0.1954026163 1.5139194875 0.5652835061 0.8102477034 0.1335803501 -0.0781633352452 +1413393229205760512.0000000000 -2.8588558925 0.2175444280 1.5088919927 0.5672599231 0.8086882370 0.1364631489 -0.0749488088239 +1413393229255760384.0000000000 -2.8696684990 0.2399215333 1.5030374064 0.5690677378 0.8071556754 0.1392001990 -0.072697524655 +1413393229305760512.0000000000 -2.8812368690 0.2622566969 1.4964171478 0.5710018693 0.8056211503 0.1409014927 -0.0712614674299 +1413393229355760384.0000000000 -2.8939096259 0.2844701243 1.4891746141 0.5727457702 0.8041920025 0.1420445566 -0.0711396495055 +1413393229405760512.0000000000 -2.9077291776 0.3066642191 1.4813397095 0.5742331553 0.8029753082 0.1418885628 -0.0731749520616 +1413393229455760384.0000000000 -2.9227006289 0.3286310553 1.4738141467 0.5756239882 0.8019414697 0.1397461658 -0.0775752053224 +1413393229505760512.0000000000 -2.9381916714 0.3503600990 1.4666541605 0.5760969002 0.8015625631 0.1365679475 -0.0834207096382 +1413393229555760384.0000000000 -2.9539789763 0.3717570824 1.4596074304 0.5748495624 0.8022532374 0.1346523550 -0.0883542133736 +1413393229605760512.0000000000 -2.9695654860 0.3930358462 1.4529499501 0.5727837221 0.8036574415 0.1317740028 -0.0932155388478 +1413393229655760384.0000000000 -2.9848600108 0.4142931860 1.4467262050 0.5695798559 0.8057590129 0.1298930867 -0.0972573233285 +1413393229705760512.0000000000 -2.9995111708 0.4357639061 1.4409969511 0.5664064180 0.8078581367 0.1295845802 -0.0987767041043 +1413393229755760384.0000000000 -3.0136704018 0.4576604328 1.4361148194 0.5633195427 0.8098826232 0.1295460312 -0.0998952210756 +1413393229805760512.0000000000 -3.0273769379 0.4801787960 1.4316527741 0.5592125995 0.8125965841 0.1298703605 -0.10050746052 +1413393229855760384.0000000000 -3.0406193386 0.5036371608 1.4279268698 0.5548918155 0.8154173751 0.1311347393 -0.099966282056 +1413393229905760512.0000000000 -3.0535291368 0.5282365045 1.4252560656 0.5514961503 0.8176272557 0.1320041689 -0.0995618721449 +1413393229955760384.0000000000 -3.0662175009 0.5542941892 1.4238436966 0.5501412174 0.8183890760 0.1336940259 -0.0985386659639 +1413393230005760512.0000000000 -3.0786448092 0.5818526658 1.4231860393 0.5502824049 0.8181708422 0.1366945098 -0.0953958008124 +1413393230055760384.0000000000 -3.0911225005 0.6110773190 1.4231376094 0.5537246041 0.8156046891 0.1410062016 -0.0910785654486 +1413393230105760512.0000000000 -3.1040970936 0.6412443017 1.4231961819 0.5571353023 0.8130050853 0.1448610522 -0.0873971499119 +1413393230155760384.0000000000 -3.1176500605 0.6720681657 1.4230104673 0.5600299413 0.8107666260 0.1477235734 -0.0848627651534 +1413393230205760512.0000000000 -3.1319962900 0.7031931769 1.4221227499 0.5620989907 0.8090210532 0.1505414269 -0.0828669955305 +1413393230255760384.0000000000 -3.1474017264 0.7346177531 1.4208224698 0.5646300586 0.8069905637 0.1522216263 -0.0823875202629 +1413393230305760512.0000000000 -3.1637619973 0.7661100751 1.4188847096 0.5669102454 0.8051639731 0.1526794372 -0.0837421007241 +1413393230355760384.0000000000 -3.1808288559 0.7972511957 1.4157769171 0.5666119582 0.8052508530 0.1516632494 -0.0867191520881 +1413393230405760512.0000000000 -3.1984744563 0.8284864648 1.4124388801 0.5673987357 0.8046262679 0.1499938160 -0.0902058695961 +1413393230455760384.0000000000 -3.2163878772 0.8599234705 1.4086849574 0.5669835672 0.8051083184 0.1475243299 -0.0925570219652 +1413393230505760512.0000000000 -3.2343223698 0.8916269962 1.4051894622 0.5662955199 0.8061513116 0.1431532003 -0.094533635495 +1413393230555760384.0000000000 -3.2518960529 0.9237204818 1.4021658043 0.5654835548 0.8076732313 0.1373596395 -0.0949980532584 +1413393230605760512.0000000000 -3.2688712199 0.9560778900 1.3997651051 0.5652327076 0.8091529288 0.1296461821 -0.0947385432453 +1413393230655760384.0000000000 -3.2853643182 0.9894314912 1.3981497248 0.5643743545 0.8112392237 0.1214419927 -0.0928673910838 +1413393230705760512.0000000000 -3.3013696643 1.0239901196 1.3976195695 0.5648377074 0.8125506500 0.1125335450 -0.0897552603401 +1413393230755760384.0000000000 -3.3162592682 1.0590661983 1.3991813030 0.5652016247 0.8139941451 0.1028785279 -0.085887506361 +1413393230805760512.0000000000 -3.3301229944 1.0944794713 1.4010911813 0.5657515164 0.8152500307 0.0933007077 -0.0811639519993 +1413393230855760384.0000000000 -3.3430659015 1.1309251808 1.4031008040 0.5663719231 0.8164974262 0.0835437963 -0.0746674750956 +1413393230905760512.0000000000 -3.3548153794 1.1682015726 1.4057864746 0.5673023215 0.8174684052 0.0746031849 -0.0659382083395 +1413393230955760384.0000000000 -3.3656535433 1.2059005980 1.4092552157 0.5684130180 0.8181153007 0.0675958813 -0.0549981144316 +1413393231005760512.0000000000 -3.3758527487 1.2439537002 1.4130444239 0.5694673253 0.8185196033 0.0624426877 -0.0428197988586 +1413393231055760384.0000000000 -3.3858346346 1.2822403064 1.4171651599 0.5704852798 0.8186324877 0.0584997584 -0.0310672491272 +1413393231105760512.0000000000 -3.3963990606 1.3207021276 1.4218735974 0.5722011697 0.8179777868 0.0552052952 -0.0212258603689 +1413393231155760384.0000000000 -3.4077998575 1.3591916798 1.4269282084 0.5733122544 0.8175407453 0.0526490509 -0.0129717480233 +1413393231205760512.0000000000 -3.4204626391 1.3976934310 1.4322803461 0.5732736080 0.8178578214 0.0490628436 -0.00766757151337 +1413393231255760384.0000000000 -3.4341316749 1.4363692247 1.4377340203 0.5735842915 0.8177936150 0.0469900129 -0.00256954307916 +1413393231305760512.0000000000 -3.4492666467 1.4746396277 1.4426700111 0.5743105245 0.8174936466 0.0432345018 -0.00152878831228 +1413393231355760384.0000000000 -3.4653040729 1.5126975733 1.4447740518 0.5746714549 0.8174548210 0.0389190577 -0.00237518321997 +1413393231405760512.0000000000 -3.4823139662 1.5509994327 1.4445857076 0.5757258522 0.8168914280 0.0346969310 -0.0049255347306 +1413393231455760384.0000000000 -3.4999435885 1.5894439314 1.4424981493 0.5785590776 0.8150495287 0.0297401856 -0.00889836236366 +1413393231505760512.0000000000 -3.5178112586 1.6278905276 1.4391383895 0.5837078707 0.8114677106 0.0248883701 -0.0136325138581 +1413393231555760384.0000000000 -3.5357472675 1.6658917517 1.4338087468 0.5910848655 0.8061227425 0.0211027209 -0.0184250089182 +1413393231605760512.0000000000 -3.5531506685 1.7029720820 1.4266958899 0.5979678644 0.8010068459 0.0176106281 -0.0226347451544 +1413393231655760384.0000000000 -3.5695562722 1.7386301178 1.4181664708 0.6026291994 0.7974971027 0.0142621709 -0.0251596826367 +1413393231705760512.0000000000 -3.5846896246 1.7727460810 1.4088270415 0.6046477826 0.7960102453 0.0120169005 -0.0249868451894 +1413393231755760384.0000000000 -3.5984039501 1.8053987158 1.3994866338 0.6038897287 0.7966793911 0.0085922952 -0.0233519993647 +1413393231805760512.0000000000 -3.6110554381 1.8365574702 1.3912714971 0.6014728024 0.7985775535 0.0042286852 -0.0220562275485 +1413393231855760384.0000000000 -3.6226896595 1.8660742291 1.3842057745 0.5980551299 0.8011375473 -0.0019378761 -0.022470794852 +1413393231905760512.0000000000 -3.6326959079 1.8945745689 1.3776856944 0.5926048475 0.8051520215 -0.0094394414 -0.0214619183316 +1413393231955760384.0000000000 -3.6409803442 1.9221914831 1.3725057833 0.5882865771 0.8081995402 -0.0175768413 -0.0205781690735 +1413393232005760512.0000000000 -3.6472701023 1.9492947099 1.3684420632 0.5847690896 0.8105701405 -0.0261040508 -0.0184319739865 +1413393232055760384.0000000000 -3.6511464077 1.9761964695 1.3649189237 0.5816644226 0.8126506260 -0.0331251909 -0.012968471323 +1413393232105760512.0000000000 -3.6530743420 2.0029193640 1.3630686487 0.5797122737 0.8138077765 -0.0401261596 -0.00636191932565 +1413393232155760384.0000000000 -3.6530776404 2.0292846674 1.3614772759 0.5781103397 0.8145792622 -0.0474075660 0.00125829618738 +1413393232205760512.0000000000 -3.6512013500 2.0555689495 1.3598211833 0.5783911607 0.8139265961 -0.0534373593 0.0114721430464 +1413393232255760384.0000000000 -3.6480853120 2.0816226399 1.3572394355 0.5783005530 0.8133171635 -0.0605550652 0.0204143582903 +1413393232305760512.0000000000 -3.6437454963 2.1074705700 1.3533175250 0.5783866577 0.8123831502 -0.0682544147 0.0290486896508 +1413393232355760384.0000000000 -3.6383980424 2.1332900215 1.3482153385 0.5778899788 0.8115967764 -0.0780247445 0.0355806711447 +1413393232405760512.0000000000 -3.6319295911 2.1587352652 1.3414239983 0.5757925740 0.8118692137 -0.0868790755 0.0422293491692 +1413393232455760384.0000000000 -3.6243657102 2.1841282129 1.3329629519 0.5741775464 0.8116201025 -0.0959073481 0.0489360291472 +1413393232505760512.0000000000 -3.6159276522 2.2095040499 1.3229608375 0.5721186760 0.8116079308 -0.1048134160 0.0546528605172 +1413393232555760384.0000000000 -3.6067141634 2.2349811284 1.3117908762 0.5709208480 0.8110905335 -0.1123667705 0.0596258393877 +1413393232605760512.0000000000 -3.5969369785 2.2602670326 1.2984117698 0.5698990928 0.8106951473 -0.1180052602 0.0637429269106 +1413393232655760384.0000000000 -3.5863139660 2.2853440534 1.2850391647 0.5692519150 0.8100577752 -0.1236899358 0.0667791723594 +1413393232705760512.0000000000 -3.5746709606 2.3103907492 1.2724381341 0.5692375119 0.8091926375 -0.1277924154 0.0696062430151 +1413393232755760384.0000000000 -3.5620447277 2.3352789168 1.2602172605 0.5687132673 0.8089026680 -0.1300001707 0.0730865847073 +1413393232805760512.0000000000 -3.5483678649 2.3602148120 1.2486461574 0.5678593578 0.8089117865 -0.1321777787 0.0756736832266 +1413393232855760384.0000000000 -3.5336884940 2.3858962519 1.2380429787 0.5681364219 0.8083000052 -0.1336765840 0.077476955516 +1413393232905760512.0000000000 -3.5182706250 2.4112283750 1.2274638354 0.5665047642 0.8091956878 -0.1341942530 0.0791618176362 +1413393232955760384.0000000000 -3.5016336135 2.4368097879 1.2184034105 0.5656278168 0.8096381790 -0.1326083215 0.0834639149412 +1413393233005760512.0000000000 -3.4843649728 2.4627233076 1.2109640707 0.5641620842 0.8105932831 -0.1309466805 0.0866754803394 +1413393233055760384.0000000000 -3.4666014658 2.4890272516 1.2057122788 0.5630091627 0.8114682543 -0.1282143964 0.0900056862269 +1413393233105760512.0000000000 -3.4484635823 2.5155952769 1.2021059034 0.5611112650 0.8127992267 -0.1265655568 0.0921559828529 +1413393233155760384.0000000000 -3.4301049111 2.5426918971 1.2005841998 0.5606235866 0.8131772571 -0.1253197559 0.0934820917906 +1413393233205760512.0000000000 -3.4114988739 2.5706006504 1.2011840793 0.5608184929 0.8130410600 -0.1239789831 0.0952683817551 +1413393233255760384.0000000000 -3.3922727488 2.5993800379 1.2045700142 0.5634863470 0.8107713257 -0.1241651899 0.0985697712006 +1413393233305760512.0000000000 -3.3728612761 2.6284938592 1.2099141957 0.5662058446 0.8082629048 -0.1252675867 0.102127615908 +1413393233355760384.0000000000 -3.3534378936 2.6580589959 1.2173571115 0.5701578172 0.8046131041 -0.1273422077 0.106309822187 +1413393233405760512.0000000000 -3.3339498854 2.6875559982 1.2265676614 0.5742914071 0.8004022869 -0.1318807129 0.110240810945 +1413393233455760384.0000000000 -3.3149411452 2.7167322732 1.2377524595 0.5776840053 0.7964970931 -0.1381952275 0.113029420215 +1413393233505760512.0000000000 -3.2959671919 2.7452715394 1.2511669821 0.5789760941 0.7937790522 -0.1435156881 0.118763403587 +1413393233555760384.0000000000 -3.2774740841 2.7726373926 1.2658600265 0.5788894940 0.7917508500 -0.1513654099 0.122906704242 +1413393233605760512.0000000000 -3.2589020607 2.7994119363 1.2809415208 0.5756976061 0.7915957243 -0.1581304521 0.130166185212 +1413393233655760384.0000000000 -3.2409410815 2.8252156746 1.2972539466 0.5705665728 0.7924960224 -0.1658759598 0.137437282263 +1413393233705760512.0000000000 -3.2235539890 2.8508486718 1.3154086913 0.5645874718 0.7936567068 -0.1747466981 0.1442692275 +1413393233755760384.0000000000 -3.2062223650 2.8770129868 1.3365069330 0.5622195778 0.7919896957 -0.1815054700 0.154004001798 +1413393233805760512.0000000000 -3.1901523187 2.9027371552 1.3593327983 0.5623301799 0.7888065883 -0.1895745148 0.160095091677 +1413393233855760384.0000000000 -3.1749878530 2.9281984130 1.3824104899 0.5639669965 0.7848543884 -0.1954230242 0.166597291475 +1413393233905760512.0000000000 -3.1610928516 2.9533351424 1.4055792417 0.5666681270 0.7804178252 -0.2026310871 0.169634591231 +1413393233955760384.0000000000 -3.1476040863 2.9777505434 1.4282285308 0.5683727216 0.7762781740 -0.2094440712 0.174578999072 +1413393234005760512.0000000000 -3.1351286200 3.0013423816 1.4506879976 0.5681481119 0.7734081313 -0.2190633287 0.17623519367 +1413393234055760384.0000000000 -3.1233837587 3.0240412978 1.4733535514 0.5669901815 0.7710269410 -0.2292871209 0.17738942038 +1413393234105760512.0000000000 -3.1119679605 3.0456151014 1.4951976374 0.5640062379 0.7696973025 -0.2393236067 0.179408019138 +1413393234155760384.0000000000 -3.1007617802 3.0662389453 1.5149922625 0.5601675528 0.7690280968 -0.2483952925 0.181955703037 +1413393234205760512.0000000000 -3.0896664765 3.0862196230 1.5330773161 0.5587220206 0.7670301221 -0.2566837792 0.183324665554 +1413393234255760384.0000000000 -3.0784018959 3.1056332575 1.5497027583 0.5634899183 0.7601568379 -0.2661420261 0.183872552629 +1413393234305760512.0000000000 -3.0668892421 3.1240841449 1.5645579594 0.5713565337 0.7507643834 -0.2765248591 0.182862118619 +1413393234355760384.0000000000 -3.0551033607 3.1408187158 1.5782737832 0.5806686510 0.7399151851 -0.2879856765 0.180038014866 +1413393234405760512.0000000000 -3.0425335208 3.1547167286 1.5898366082 0.5884839028 0.7295891454 -0.2988514202 0.179092723721 +1413393234455760384.0000000000 -3.0295106225 3.1652131997 1.5990756077 0.5936581019 0.7213107483 -0.3090118309 0.178304657034 +1413393234505760512.0000000000 -3.0158166944 3.1717272753 1.6059609851 0.5959453251 0.7151747578 -0.3168219803 0.181653703504 +1413393234555760384.0000000000 -3.0010546994 3.1736912104 1.6123070066 0.5957943968 0.7107119585 -0.3230893301 0.188496243037 +1413393234605760512.0000000000 -2.9853925083 3.1707535442 1.6181043023 0.5914525741 0.7095248267 -0.3246811814 0.203323641841 +1413393234655760384.0000000000 -2.9685052650 3.1640707378 1.6265444673 0.5817780476 0.7121614054 -0.3230023159 0.223673735516 +1413393234705760512.0000000000 -2.9533365496 3.1525472777 1.6395055971 0.5692476333 0.7163228527 -0.3208339488 0.244753508472 +1413393234755760384.0000000000 -2.9402967266 3.1379723627 1.6569940799 0.5557691582 0.7207431073 -0.3221711969 0.260491335779 +1413393234805760512.0000000000 -2.9288417656 3.1221872763 1.6754759093 0.5406784532 0.7259069799 -0.3248095102 0.274271123011 +1413393234855760384.0000000000 -2.9193948543 3.1061864437 1.6924452652 0.5276279007 0.7294198906 -0.3320759544 0.281568787501 +1413393234905760512.0000000000 -2.9112051588 3.0908672423 1.7066422816 0.5195905001 0.7291058502 -0.3426450719 0.284648425599 +1413393234955760384.0000000000 -2.9040981448 3.0761056110 1.7163444926 0.5141522621 0.7268260534 -0.3539982437 0.286455202242 +1413393235005760512.0000000000 -2.8979230672 3.0618754916 1.7212163304 0.5111990583 0.7225077101 -0.3676873414 0.285419254176 +1413393235055760384.0000000000 -2.8921100906 3.0478620485 1.7211973174 0.5098735704 0.7165873381 -0.3816029458 0.284448098412 +1413393235105760512.0000000000 -2.8863592461 3.0337107419 1.7161564761 0.5083431187 0.7103107626 -0.3948433605 0.284858938544 +1413393235155760384.0000000000 -2.8804807774 3.0191914330 1.7065247043 0.5051366075 0.7049126175 -0.4068313714 0.287094835728 +1413393235205760512.0000000000 -2.8737161603 3.0042141315 1.6942490965 0.5003466618 0.7005165295 -0.4150982434 0.294318294251 +1413393235255760384.0000000000 -2.8669424210 2.9885456162 1.6808785083 0.4920896822 0.6986278459 -0.4215023039 0.303484242513 +1413393235305760512.0000000000 -2.8600604619 2.9728386973 1.6679154962 0.4827303931 0.6976514076 -0.4262146043 0.313998395212 +1413393235355760384.0000000000 -2.8535940008 2.9576940598 1.6558976181 0.4733863273 0.6975450675 -0.4307560368 0.322157571171 +1413393235405760512.0000000000 -2.8474056335 2.9435026127 1.6450574450 0.4642292828 0.6984042251 -0.4346384894 0.328347521377 +1413393235455760384.0000000000 -2.8410767479 2.9308492810 1.6355161316 0.4566826226 0.6989801854 -0.4380297871 0.333163005449 +1413393235505760512.0000000000 -2.8345018173 2.9199715971 1.6269317457 0.4490823750 0.7004975460 -0.4404325254 0.337116299002 +1413393235555760384.0000000000 -2.8268830614 2.9111778738 1.6200136191 0.4436936025 0.7004822504 -0.4388007018 0.346286800344 +1413393235605760512.0000000000 -2.8189362382 2.9046203917 1.6135491022 0.4389044527 0.6999755644 -0.4354430282 0.357472320333 +1413393235655760384.0000000000 -2.8110319985 2.9010930223 1.6077734436 0.4361152707 0.6978346780 -0.4343719412 0.366266637252 +1413393235705760512.0000000000 -2.8036088280 2.9010605962 1.6027633859 0.4359310946 0.6948806934 -0.4334839805 0.37309052709 +1413393235755760384.0000000000 -2.7971568760 2.9045790961 1.5982025430 0.4373455608 0.6915494946 -0.4355022450 0.375267839825 +1413393235805760512.0000000000 -2.7917615797 2.9114485163 1.5943654400 0.4407090198 0.6878085217 -0.4387701691 0.374400502107 +1413393235855760384.0000000000 -2.7873276933 2.9215934742 1.5918052805 0.4487581054 0.6816947952 -0.4450991543 0.368503883205 +1413393235905760512.0000000000 -2.7835144327 2.9336538595 1.5897508188 0.4573478370 0.6745535955 -0.4531931282 0.361145941965 +1413393235955760384.0000000000 -2.7799561404 2.9466737935 1.5878798363 0.4648744511 0.6673474689 -0.4616339315 0.354165517482 +1413393236005760512.0000000000 -2.7763993473 2.9595966098 1.5866594088 0.4704116705 0.6602072617 -0.4684921808 0.35121832014 +1413393236055760384.0000000000 -2.7729548723 2.9721010608 1.5856482606 0.4745506922 0.6529474632 -0.4765808636 0.348327333617 +1413393236105760512.0000000000 -2.7686857003 2.9836439074 1.5849432433 0.4759008333 0.6466799979 -0.4842796752 0.347558014337 +1413393236155760384.0000000000 -2.7646753835 2.9935861294 1.5869968653 0.4753177852 0.6405900289 -0.4919176816 0.3489045892 +1413393236205760512.0000000000 -2.7617463120 3.0012180571 1.5880972061 0.4693092938 0.6372365200 -0.4984154749 0.353921486605 +1413393236255760384.0000000000 -2.7597011411 3.0074544664 1.5912172344 0.4608371215 0.6353257892 -0.5034028750 0.361352784067 +1413393236305760512.0000000000 -2.7584519547 3.0124293922 1.5936990611 0.4506333075 0.6335960080 -0.5077711832 0.371017717002 +1413393236355760384.0000000000 -2.7565571083 3.0172337622 1.5974650868 0.4421235183 0.6299953388 -0.5135106942 0.379393508859 +1413393236405760512.0000000000 -2.7548802372 3.0224930131 1.6021124202 0.4353944750 0.6255027530 -0.5208620115 0.384552625805 +1413393236455760384.0000000000 -2.7530376927 3.0279110884 1.6075615864 0.4302232690 0.6197460000 -0.5284922988 0.389254061503 +1413393236505760512.0000000000 -2.7512381612 3.0335588743 1.6129009221 0.4240609700 0.6146086122 -0.5380238744 0.391099550048 +1413393236555760384.0000000000 -2.7490505647 3.0392813293 1.6184128756 0.4167504587 0.6102008797 -0.5476736947 0.392463330349 +1413393236605760512.0000000000 -2.7464739083 3.0451311692 1.6236604151 0.4080530134 0.6067377772 -0.5583687098 0.391900997587 +1413393236655760384.0000000000 -2.7429185568 3.0511890730 1.6278964095 0.4007269091 0.6027050930 -0.5683706789 0.391304595594 +1413393236705760512.0000000000 -2.7383937639 3.0575083004 1.6296285629 0.3967303549 0.5975956649 -0.5764448126 0.391402382313 +1413393236755760384.0000000000 -2.7330269032 3.0638145764 1.6290395798 0.3959483523 0.5906585623 -0.5842597380 0.391136707208 +1413393236805760512.0000000000 -2.7261143087 3.0699216957 1.6263569742 0.3976368090 0.5823699748 -0.5913586617 0.391184245287 +1413393236855760384.0000000000 -2.7177140397 3.0751884761 1.6226590013 0.3986261389 0.5753458325 -0.5961119611 0.393350866619 +1413393236905760512.0000000000 -2.7079154121 3.0794328947 1.6205791711 0.3988773466 0.5700149781 -0.5988805404 0.396638230013 +1413393236955760384.0000000000 -2.6972308845 3.0823552608 1.6207171924 0.3992555190 0.5657841255 -0.5988313491 0.402348566816 +1413393237005760512.0000000000 -2.6852529431 3.0840316431 1.6253443451 0.3987656416 0.5634581316 -0.5966621455 0.409261751293 +1413393237055760384.0000000000 -2.6739852618 3.0847978842 1.6329110970 0.3968411022 0.5629142919 -0.5940373759 0.415649173712 +1413393237105760512.0000000000 -2.6622233671 3.0849546102 1.6434876391 0.3936485284 0.5639614602 -0.5901375269 0.422759987241 +1413393237155760384.0000000000 -2.6503961693 3.0848492029 1.6553856382 0.3906375770 0.5654815959 -0.5845074589 0.43125848233 +1413393237205760512.0000000000 -2.6387015872 3.0851850425 1.6657692354 0.3868495329 0.5681087815 -0.5791235970 0.438424122014 +1413393237255760384.0000000000 -2.6266966132 3.0863682557 1.6729574903 0.3842843889 0.5700161791 -0.5752170143 0.443319806183 +1413393237305760512.0000000000 -2.6148344487 3.0885122467 1.6767504049 0.3810626514 0.5725038545 -0.5728641337 0.44593416184 +1413393237355760384.0000000000 -2.6034904822 3.0921209256 1.6776504945 0.3791788391 0.5748357344 -0.5707343505 0.447269032629 +1413393237405760512.0000000000 -2.5922421115 3.0971608315 1.6752486389 0.3794678544 0.5754442981 -0.5690810922 0.448346649125 +1413393237455760384.0000000000 -2.5812952743 3.1039813952 1.6707603963 0.3818686698 0.5751186807 -0.5689761082 0.446856812008 +1413393237505760512.0000000000 -2.5706849270 3.1126311262 1.6661480704 0.3873834892 0.5730448498 -0.5705110124 0.442798845051 +1413393237555760384.0000000000 -2.5606321176 3.1224726821 1.6616867821 0.3937304396 0.5704251352 -0.5737464169 0.436355995853 +1413393237605760512.0000000000 -2.5510659050 3.1328312048 1.6578464157 0.4006700470 0.5672156980 -0.5766944632 0.430294505501 +1413393237655760384.0000000000 -2.5422606186 3.1432004476 1.6537657850 0.4057984484 0.5652037056 -0.5808273698 0.422506753781 +1413393237705760512.0000000000 -2.5337497225 3.1530733341 1.6500011631 0.4105229170 0.5633935211 -0.5834230563 0.416744780912 +1413393237755760384.0000000000 -2.5257044479 3.1620698771 1.6463130936 0.4132616513 0.5629685203 -0.5852732251 0.411990903608 +1413393237805760512.0000000000 -2.5177605458 3.1698048534 1.6429443836 0.4144783743 0.5633976582 -0.5863031342 0.408704527506 +1413393237855760384.0000000000 -2.5095718256 3.1761045878 1.6395566138 0.4130874582 0.5655207032 -0.5862374671 0.407272290098 +1413393237905760512.0000000000 -2.5008076973 3.1811979034 1.6371106076 0.4099961616 0.5687517965 -0.5856545999 0.406734841197 +1413393237955760384.0000000000 -2.4920269959 3.1852574320 1.6349797981 0.4074048719 0.5710508254 -0.5848464237 0.407279861788 +1413393238005760512.0000000000 -2.4833870189 3.1879439645 1.6308188836 0.3992477582 0.5771082124 -0.5830610635 0.409374077048 +1413393238055760384.0000000000 -2.4741027348 3.1902455136 1.6273177186 0.3921365421 0.5823607336 -0.5809068011 0.411864294059 +1413393238105760512.0000000000 -2.4642185474 3.1925810965 1.6249711558 0.3860824560 0.5863792885 -0.5800018753 0.413155529818 +1413393238155760384.0000000000 -2.4533291034 3.1951038415 1.6243420613 0.3819975979 0.5881192500 -0.5786621645 0.416345628401 +1413393238205760512.0000000000 -2.4415517047 3.1982596275 1.6246394974 0.3783769383 0.5894712297 -0.5781468764 0.418450416567 +1413393238255760384.0000000000 -2.4288123925 3.2023585698 1.6273072225 0.3759883147 0.5901476947 -0.5776251785 0.420366077043 +1413393238305760512.0000000000 -2.4147878612 3.2074556369 1.6316223830 0.3735019017 0.5898619902 -0.5785237390 0.421745711685 +1413393238355760384.0000000000 -2.3987589069 3.2138825379 1.6391968466 0.3723974709 0.5890598840 -0.5799329180 0.421908031735 +1413393238405760512.0000000000 -2.3802204731 3.2214876476 1.6493277250 0.3727048960 0.5875410495 -0.5809076173 0.422413205111 +1413393238455760384.0000000000 -2.3599050780 3.2304396483 1.6623026071 0.3761500435 0.5838223890 -0.5828577542 0.421828639546 +1413393238505760512.0000000000 -2.3389644532 3.2404179518 1.6751232334 0.3816515041 0.5786914153 -0.5867048335 0.418611769573 +1413393238555760384.0000000000 -2.3176611974 3.2508297708 1.6864259780 0.3895211480 0.5719602357 -0.5902841200 0.415571199311 +1413393238605760512.0000000000 -2.2960948379 3.2609890755 1.6951974626 0.3977453974 0.5650574658 -0.5942864923 0.411499968679 +1413393238655760384.0000000000 -2.2741132377 3.2701867230 1.7010689740 0.4045998665 0.5589684479 -0.5983839127 0.407173077797 +1413393238705760512.0000000000 -2.2518835647 3.2780400567 1.7039334281 0.4098624750 0.5542798167 -0.6014914321 0.403726012864 +1413393238755760384.0000000000 -2.2299336972 3.2842221112 1.7040480157 0.4137543526 0.5505572617 -0.6038721336 0.401288529031 +1413393238805760512.0000000000 -2.2076064085 3.2883405972 1.7024652971 0.4153807176 0.5486876985 -0.6044052476 0.401366373421 +1413393238855760384.0000000000 -2.1852341900 3.2903026047 1.7001393551 0.4141260232 0.5489815113 -0.6037323160 0.403269423195 +1413393238905760512.0000000000 -2.1627773833 3.2901286408 1.6977294003 0.4106450870 0.5509217445 -0.6017592482 0.40711380612 +1413393238955760384.0000000000 -2.1402574257 3.2880786742 1.6964322068 0.4046987577 0.5548966665 -0.5980294940 0.413121446078 +1413393239005760512.0000000000 -2.1174638513 3.2847075387 1.6958108000 0.3986084009 0.5582500736 -0.5940534869 0.420200729161 +1413393239055760384.0000000000 -2.0948157049 3.2809515886 1.6950083242 0.3925461370 0.5623503974 -0.5904006043 0.425554564557 +1413393239105760512.0000000000 -2.0719126946 3.2771964668 1.6945547185 0.3879630670 0.5650954302 -0.5874549911 0.430172577945 +1413393239155760384.0000000000 -2.0489611905 3.2737482921 1.6944411781 0.3847019372 0.5668016053 -0.5854589826 0.433564458131 +1413393239205760512.0000000000 -2.0259664253 3.2710850069 1.6942409909 0.3816250254 0.5690392536 -0.5836397922 0.43579956498 +1413393239255760384.0000000000 -2.0027207213 3.2692336924 1.6945961290 0.3804804504 0.5692611954 -0.5828235663 0.437599141712 +1413393239305760512.0000000000 -1.9793826733 3.2681492770 1.6948345843 0.3784730183 0.5700508967 -0.5823967082 0.438878370185 +1413393239355760384.0000000000 -1.9559217255 3.2684009489 1.6953632698 0.3771667346 0.5709940993 -0.5823488375 0.438840317634 +1413393239405760512.0000000000 -1.9320694263 3.2695733275 1.6964802680 0.3766743053 0.5708203789 -0.5826975018 0.439026404797 +1413393239455760384.0000000000 -1.9078747737 3.2720295448 1.6984439710 0.3766820091 0.5706353353 -0.5835943615 0.438068030475 +1413393239505760512.0000000000 -1.8832572822 3.2753241424 1.7010993987 0.3752246091 0.5717681063 -0.5822586324 0.439616435526 +1413393239555760384.0000000000 -1.8583291934 3.2802148620 1.7046254085 0.3764123697 0.5709566355 -0.5836043261 0.437867832516 +1413393239605760512.0000000000 -1.8331898525 3.2863353193 1.7089642699 0.3790404316 0.5697384438 -0.5854966700 0.434649406224 +1413393239655760384.0000000000 -1.8075162034 3.2936067946 1.7142213065 0.3846638347 0.5663270886 -0.5888784935 0.429568950055 +1413393239705760512.0000000000 -1.7814686247 3.3012220421 1.7201734037 0.3925185929 0.5608971836 -0.5942825191 0.422080313679 +1413393239755760384.0000000000 -1.7552189455 3.3083979784 1.7262659562 0.3988976369 0.5569250523 -0.5979837035 0.416089715911 +1413393239805760512.0000000000 -1.7287333087 3.3144309544 1.7319601165 0.4026290080 0.5544228610 -0.6005068384 0.412185286206 +1413393239855760384.0000000000 -1.7022716833 3.3189463816 1.7368289032 0.4035601342 0.5536969768 -0.6026542931 0.409104728571 +1413393239905760512.0000000000 -1.6754235850 3.3219934182 1.7410350471 0.4015442466 0.5553354898 -0.6020971584 0.409687348724 +1413393239955760384.0000000000 -1.6480478789 3.3238035925 1.7453946516 0.4004086268 0.5562214732 -0.6013718529 0.410661051013 +1413393240005760512.0000000000 -1.6200959979 3.3243406122 1.7499551373 0.3981530997 0.5580087636 -0.5985159407 0.414582920116 +1413393240055760384.0000000000 -1.5916558930 3.3241023786 1.7549888222 0.3953853368 0.5603666963 -0.5950591438 0.419003838226 +1413393240105760512.0000000000 -1.5628556126 3.3231551296 1.7603575018 0.3917317108 0.5631185529 -0.5901343160 0.425658608642 +1413393240155760384.0000000000 -1.5339459295 3.3222875551 1.7652389512 0.3884535326 0.5657422794 -0.5858351126 0.431087864742 +1413393240205760512.0000000000 -1.5052985797 3.3220340976 1.7685614341 0.3866570336 0.5675559456 -0.5825086547 0.434810595729 +1413393240255760384.0000000000 -1.4771626420 3.3224246531 1.7694200522 0.3844041675 0.5695233611 -0.5809774665 0.4362817445 +1413393240305760512.0000000000 -1.4494928336 3.3237618968 1.7678431026 0.3847878505 0.5697273555 -0.5811027414 0.435509648991 +1413393240355760384.0000000000 -1.4218018189 3.3259514365 1.7639939636 0.3864064162 0.5689001663 -0.5819521374 0.434021188526 +1413393240405760512.0000000000 -1.3940022606 3.3289061442 1.7579485163 0.3898518679 0.5667706295 -0.5840851079 0.430849348737 +1413393240455760384.0000000000 -1.3660943834 3.3321552148 1.7497134410 0.3935741405 0.5644757593 -0.5854987763 0.428553025952 +1413393240505760512.0000000000 -1.3386206609 3.3355532416 1.7396521473 0.3979313810 0.5615452983 -0.5884160493 0.424363107327 +1413393240555760384.0000000000 -1.3115333807 3.3385614710 1.7300561716 0.4014703408 0.5589261031 -0.5903510955 0.421792319445 +1413393240605760512.0000000000 -1.2849267799 3.3409458217 1.7228003160 0.4042232656 0.5567743350 -0.5921178082 0.419526390908 +1413393240655760384.0000000000 -1.2578296060 3.3422817381 1.7174278950 0.4045270127 0.5559433851 -0.5932341045 0.418757860681 +1413393240705760512.0000000000 -1.2287589137 3.3425227526 1.7168998592 0.4034575128 0.5557378610 -0.5937700259 0.419302541796 +1413393240755760384.0000000000 -1.1988129953 3.3418284341 1.7218125695 0.4014634420 0.5559258419 -0.5921821793 0.423194789137 +1413393240805760512.0000000000 -1.1693152912 3.3405791251 1.7281659526 0.3998791660 0.5558286161 -0.5900156384 0.427823267996 +1413393240855760384.0000000000 -1.1404590634 3.3390435076 1.7339286409 0.3976744856 0.5561677583 -0.5870858503 0.433431231554 +1413393240905760512.0000000000 -1.1123261646 3.3375805500 1.7381010726 0.3980933204 0.5542852604 -0.5850114380 0.438236438184 +1413393240955760384.0000000000 -1.0860116647 3.3362051941 1.7387381137 0.3983463938 0.5524615660 -0.5828990303 0.443097155323 +1413393241005760512.0000000000 -1.0609581804 3.3352029550 1.7361874230 0.3990173765 0.5506842959 -0.5810429375 0.447125311625 +1413393241055760384.0000000000 -1.0363916936 3.3345173117 1.7313691844 0.4010142191 0.5478470813 -0.5806829673 0.449286615789 +1413393241105760512.0000000000 -1.0129768974 3.3343549126 1.7235399427 0.4035934506 0.5447456279 -0.5828024620 0.448002028871 +1413393241155760384.0000000000 -0.9909463866 3.3344741385 1.7135239542 0.4065658214 0.5413368602 -0.5863285322 0.444834226368 +1413393241205760512.0000000000 -0.9702097743 3.3345510843 1.7013513473 0.4090951898 0.5385081149 -0.5903367776 0.440627535297 +1413393241255760384.0000000000 -0.9506571294 3.3342022453 1.6888083709 0.4105794320 0.5362541020 -0.5944620802 0.436429723225 +1413393241305760512.0000000000 -0.9322504071 3.3330394855 1.6763662631 0.4102001214 0.5353448559 -0.5986693676 0.432130459377 +1413393241355760384.0000000000 -0.9148275014 3.3307111509 1.6634230079 0.4048025305 0.5380517006 -0.6034421763 0.427191782184 +1413393241405760512.0000000000 -0.8976996643 3.3275179353 1.6518755982 0.4012041551 0.5396190378 -0.6070122818 0.423535842334 +1413393241455760384.0000000000 -0.8805588400 3.3228946670 1.6409843207 0.3962685124 0.5418336004 -0.6085956139 0.423082727585 +1413393241505760512.0000000000 -0.8632481284 3.3173630914 1.6312046328 0.3917955195 0.5443584075 -0.6076886189 0.425305463859 +1413393241555760384.0000000000 -0.8455728922 3.3110350803 1.6224731737 0.3886909211 0.5458553291 -0.6052785968 0.429650029489 +1413393241605760512.0000000000 -0.8276534254 3.3042408907 1.6143210927 0.3862862393 0.5470637313 -0.6015908979 0.435422331473 +1413393241655760384.0000000000 -0.8098851730 3.2977129132 1.6064031717 0.3842746139 0.5484382133 -0.5986053731 0.439568145574 +1413393241705760512.0000000000 -0.7923349013 3.2913640514 1.5986733870 0.3824471476 0.5496381078 -0.5953213391 0.444099800669 +1413393241755760384.0000000000 -0.7750427600 3.2856777888 1.5912221576 0.3811035579 0.5504343914 -0.5942336025 0.445722430004 +1413393241805760512.0000000000 -0.7580111441 3.2807338454 1.5839959355 0.3788340091 0.5524563998 -0.5932187913 0.446506646663 +1413393241855760384.0000000000 -0.7410026203 3.2767190818 1.5774538583 0.3776152771 0.5539156680 -0.5926199012 0.446526357556 +1413393241905760512.0000000000 -0.7238631127 3.2736000041 1.5722251260 0.3781340317 0.5538096437 -0.5913156562 0.447945674548 +1413393241955760384.0000000000 -0.7070787030 3.2715756292 1.5677610908 0.3801246899 0.5536237125 -0.5883038966 0.450449253898 +1413393242005760512.0000000000 -0.6905186769 3.2706871983 1.5631534739 0.3821097182 0.5531627549 -0.5865758817 0.451588158489 +1413393242055760384.0000000000 -0.6743356930 3.2708381677 1.5593045392 0.3850157130 0.5522534891 -0.5835825083 0.454103997553 +1413393242105760512.0000000000 -0.6588278382 3.2721997025 1.5557876737 0.3879114128 0.5515717440 -0.5807540653 0.456089972133 +1413393242155760384.0000000000 -0.6441634135 3.2746387609 1.5533260061 0.3931255316 0.5487163307 -0.5787544034 0.457609052945 +1413393242205760512.0000000000 -0.6308957081 3.2781391623 1.5516730103 0.3993921778 0.5454528156 -0.5766351859 0.458758080744 +1413393242255760384.0000000000 -0.6192750609 3.2821007815 1.5500430637 0.4031150768 0.5435838317 -0.5750888063 0.459660437285 +1413393242305760512.0000000000 -0.6094708088 3.2865265594 1.5487474449 0.4058040548 0.5421011921 -0.5750833341 0.459051767766 +1413393242355760384.0000000000 -0.6017029910 3.2916458894 1.5475499256 0.4076286321 0.5415227337 -0.5774377769 0.455145735919 +1413393242405760512.0000000000 -0.5957574694 3.2971210116 1.5466550563 0.4085580759 0.5417149353 -0.5820699765 0.448129188779 +1413393242455760384.0000000000 -0.5914197490 3.3026361721 1.5459182963 0.4083122501 0.5425520399 -0.5885555722 0.438771841425 +1413393242505760512.0000000000 -0.5883466331 3.3076581175 1.5453602834 0.4073919864 0.5437143978 -0.5961138237 0.427848959708 +1413393242555760384.0000000000 -0.5858041891 3.3117418729 1.5450558496 0.4058026469 0.5454043055 -0.6021208089 0.418699040915 +1413393242605760512.0000000000 -0.5832582454 3.3144962525 1.5452827681 0.4041409738 0.5466629636 -0.6068775619 0.411739362287 +1413393242655760384.0000000000 -0.5801010608 3.3157458317 1.5460336691 0.4025125098 0.5481111550 -0.6093820743 0.407690236271 +1413393242705760512.0000000000 -0.5761434675 3.3153892290 1.5477690714 0.4028388657 0.5477044888 -0.6111680243 0.40523362067 +1413393242755760384.0000000000 -0.5715549720 3.3135878672 1.5504193251 0.4056002854 0.5464229168 -0.6122160124 0.402618875156 +1413393242805760512.0000000000 -0.5663999104 3.3100931832 1.5533411119 0.4071443498 0.5470277014 -0.6107178142 0.402514501194 +1413393242855760384.0000000000 -0.5606866821 3.3050132861 1.5566991197 0.4076939777 0.5498983972 -0.6069646511 0.403721792427 +1413393242905760512.0000000000 -0.5544861074 3.2983788274 1.5598412894 0.4048126868 0.5568474874 -0.5992442852 0.408599866651 +1413393242955760384.0000000000 -0.5482365450 3.2909122627 1.5630814975 0.4013159436 0.5647295059 -0.5929015634 0.410480005121 +1413393243005760512.0000000000 -0.5418634444 3.2831485052 1.5669381830 0.3983025290 0.5734286089 -0.5864701366 0.410594087488 +1413393243055760384.0000000000 -0.5349762454 3.2755844921 1.5711811871 0.3972818640 0.5824202881 -0.5791272507 0.409347476005 +1413393243105760512.0000000000 -0.5273991331 3.2684012366 1.5755816347 0.3973541072 0.5910212705 -0.5725323124 0.406214626214 +1413393243155760384.0000000000 -0.5191932560 3.2619664278 1.5811337141 0.4008150325 0.5985064473 -0.5648809676 0.402550412684 +1413393243205760512.0000000000 -0.5101823243 3.2563596495 1.5877064424 0.4076087437 0.6044864061 -0.5551265321 0.400357128399 +1413393243255760384.0000000000 -0.5002075434 3.2509337003 1.5952099914 0.4158762258 0.6074643074 -0.5453510071 0.400782184186 +1413393243305760512.0000000000 -0.4899667995 3.2457022335 1.6013078797 0.4239073934 0.6098264240 -0.5358233761 0.401631129254 +1413393243355760384.0000000000 -0.4797626039 3.2407851591 1.6045798856 0.4310958150 0.6114987354 -0.5288068353 0.400735605832 +1413393243405760512.0000000000 -0.4699439140 3.2357910065 1.6058792464 0.4371188157 0.6123731904 -0.5226361791 0.400970872962 +1413393243455760384.0000000000 -0.4611314730 3.2310685036 1.6048757663 0.4416413743 0.6140256527 -0.5177329285 0.399847482401 +1413393243505760512.0000000000 -0.4529634732 3.2264385972 1.6014231286 0.4456202089 0.6150417780 -0.5139222927 0.39878580445 +1413393243555760384.0000000000 -0.4456953944 3.2218792615 1.5949795861 0.4482263407 0.6164823928 -0.5111940143 0.397143911734 +1413393243605760512.0000000000 -0.4396311946 3.2172753475 1.5874431526 0.4495585834 0.6181271451 -0.5092746240 0.395544270566 +1413393243655760384.0000000000 -0.4347355367 3.2127555234 1.5796654070 0.4498625042 0.6199544905 -0.5078135840 0.394215069411 +1413393243705760512.0000000000 -0.4312148399 3.2083665248 1.5722931748 0.4486961290 0.6225236682 -0.5069187499 0.392644173904 +1413393243755760384.0000000000 -0.4287830715 3.2043655107 1.5661861444 0.4473621701 0.6247399079 -0.5069225657 0.390636210106 +1413393243805760512.0000000000 -0.4272587411 3.2005695423 1.5611964362 0.4455348351 0.6268275606 -0.5068259259 0.389504044722 +1413393243855760384.0000000000 -0.4269491984 3.1973199472 1.5576327099 0.4457898038 0.6274470032 -0.5071046837 0.387848615743 +1413393243905760512.0000000000 -0.4273419995 3.1941460147 1.5547260525 0.4449776974 0.6283228618 -0.5068062327 0.387753365791 +1413393243955760384.0000000000 -0.4283454881 3.1914232727 1.5527692470 0.4449889632 0.6286606837 -0.5064515629 0.387656267576 +1413393244005760512.0000000000 -0.4300777044 3.1890773226 1.5514693426 0.4446249589 0.6291036121 -0.5063778449 0.387451634901 +1413393244055760384.0000000000 -0.4322350349 3.1870484096 1.5510784421 0.4441086993 0.6293109624 -0.5055555190 0.388778591238 +1413393244105760512.0000000000 -0.4351754110 3.1855462570 1.5511577095 0.4429606338 0.6300575783 -0.5052990455 0.389212280885 +1413393244155760384.0000000000 -0.4389138392 3.1847294048 1.5515138866 0.4425270759 0.6310907340 -0.5043566796 0.389253917616 +1413393244205760512.0000000000 -0.4436591979 3.1850001538 1.5519879419 0.4439317825 0.6325430234 -0.5024673391 0.387737629202 +1413393244255760384.0000000000 -0.4491599749 3.1861221255 1.5525123899 0.4449334146 0.6358152828 -0.4992326446 0.385408808016 +1413393244305760512.0000000000 -0.4554656104 3.1882430122 1.5531161556 0.4462090375 0.6399164346 -0.4950686784 0.382506804132 +1413393244355760384.0000000000 -0.4624403301 3.1913362735 1.5537578856 0.4486722830 0.6444826588 -0.4901920040 0.378215658385 +1413393244405760512.0000000000 -0.4693775305 3.1951565392 1.5536992974 0.4525380814 0.6472629000 -0.4854240998 0.374997955318 +1413393244455760384.0000000000 -0.4769837418 3.1991980698 1.5523546796 0.4574507355 0.6485920612 -0.4814040020 0.371910405302 +1413393244505760512.0000000000 -0.4855505113 3.2034337174 1.5479484260 0.4616276968 0.6502097823 -0.4783196348 0.36788236642 +1413393244555760384.0000000000 -0.4947127680 3.2076111222 1.5402110552 0.4656427043 0.6508343070 -0.4760999245 0.364582553955 +1413393244605760512.0000000000 -0.5043901439 3.2118840174 1.5306245685 0.4681102725 0.6524123805 -0.4745675863 0.360577959014 +1413393244655760384.0000000000 -0.5143783777 3.2162579636 1.5214148954 0.4703135474 0.6537122343 -0.4734408009 0.356818286956 +1413393244705760512.0000000000 -0.5248769954 3.2203450410 1.5156304400 0.4727502861 0.6543385165 -0.4715062244 0.355007258054 +1413393244755760384.0000000000 -0.5378441960 3.2235869194 1.5102071331 0.4748980012 0.6545446094 -0.4725885526 0.350290312023 +1413393244805760512.0000000000 -0.5511279729 3.2262735531 1.5076095141 0.4779927951 0.6536434725 -0.4736905647 0.346251855724 +1413393244855760384.0000000000 -0.5648134493 3.2282387494 1.5083585651 0.4793334976 0.6537568245 -0.4749252359 0.34247252849 +1413393244905760512.0000000000 -0.5773373545 3.2298029005 1.5139833778 0.4809576372 0.6529854312 -0.4757308527 0.340543585505 +1413393244955760384.0000000000 -0.5889602813 3.2303488266 1.5233465935 0.4813807691 0.6528818127 -0.4754232575 0.340573956862 +1413393245005760512.0000000000 -0.6015058744 3.2295468767 1.5323717521 0.4781735398 0.6552011611 -0.4749938551 0.341236489632 +1413393245055760384.0000000000 -0.6141577651 3.2279898295 1.5411883308 0.4744936908 0.6573688717 -0.4759564763 0.340862635914 +1413393245105760512.0000000000 -0.6269107402 3.2258454447 1.5481193087 0.4700414837 0.6602986320 -0.4765473059 0.340542780581 +1413393245155760384.0000000000 -0.6393329504 3.2232241955 1.5525592473 0.4658361500 0.6627653192 -0.4782210810 0.339180498676 +1413393245205760512.0000000000 -0.6515411713 3.2201013570 1.5546604366 0.4615418585 0.6652493968 -0.4798802702 0.337842092099 +1413393245255760384.0000000000 -0.6634028876 3.2167632152 1.5542409693 0.4588264772 0.6668781594 -0.4798112734 0.338427135813 +1413393245305760512.0000000000 -0.6743710744 3.2134709945 1.5507983369 0.4565816552 0.6680819094 -0.4795545829 0.339451257724 +1413393245355760384.0000000000 -0.6845623060 3.2104016258 1.5447798265 0.4555953330 0.6686063106 -0.4781660028 0.34169543135 +1413393245405760512.0000000000 -0.6940513575 3.2074204141 1.5369139646 0.4551197367 0.6686792766 -0.4768811322 0.343974470148 +1413393245455760384.0000000000 -0.7030635418 3.2046326873 1.5271914072 0.4552014483 0.6683768684 -0.4747942618 0.347324649628 +1413393245505760512.0000000000 -0.7120718800 3.2022779627 1.5154427935 0.4553417507 0.6680260736 -0.4732487764 0.34991520499 +1413393245555760384.0000000000 -0.7207509451 3.2004257659 1.5036171832 0.4560604839 0.6671159276 -0.4711565110 0.353520460935 +1413393245605760512.0000000000 -0.7292487375 3.1990505198 1.4921250767 0.4566152052 0.6660644494 -0.4695395122 0.356922050427 +1413393245655760384.0000000000 -0.7377597875 3.1982705145 1.4813180342 0.4569020412 0.6652149965 -0.4682234007 0.359856054827 +1413393245705760512.0000000000 -0.7463646170 3.1980442726 1.4709397737 0.4560681236 0.6648488058 -0.4673007838 0.362778044482 +1413393245755760384.0000000000 -0.7552738764 3.1985196748 1.4611995143 0.4543593487 0.6647108336 -0.4681614779 0.364063072193 +1413393245805760512.0000000000 -0.7644370243 3.1998077550 1.4523470302 0.4530435815 0.6642132361 -0.4698486575 0.364437277615 +1413393245855760384.0000000000 -0.7738538613 3.2018970766 1.4447324848 0.4534216837 0.6625781457 -0.4724390283 0.363593649862 +1413393245905760512.0000000000 -0.7836228188 3.2046434653 1.4376343956 0.4532714358 0.6613321600 -0.4762957460 0.361008506731 +1413393245955760384.0000000000 -0.7935526516 3.2080696741 1.4313356440 0.4543790221 0.6593926368 -0.4808826282 0.35706155303 +1413393246005760512.0000000000 -0.8034931807 3.2118539349 1.4252676319 0.4553184291 0.6576095801 -0.4869323186 0.350901247257 +1413393246055760384.0000000000 -0.8129705616 3.2154464130 1.4197039986 0.4567548841 0.6555354968 -0.4930447089 0.34431831703 +1413393246105760512.0000000000 -0.8216745445 3.2184333858 1.4140917748 0.4567432027 0.6541279937 -0.4989383867 0.338471122632 +1413393246155760384.0000000000 -0.8295108319 3.2206735095 1.4088992976 0.4578396853 0.6530801230 -0.5025142943 0.333689315792 +1413393246205760512.0000000000 -0.8361189951 3.2221773723 1.4042235715 0.4598448771 0.6532551376 -0.5016521746 0.331881770969 +1413393246255760384.0000000000 -0.8415782577 3.2226093487 1.3993607474 0.4613696963 0.6552154569 -0.4971608273 0.332658714314 +1413393246305760512.0000000000 -0.8462577128 3.2223097093 1.3944322478 0.4625389892 0.6592208085 -0.4883847303 0.336104097396 +1413393246355760384.0000000000 -0.8501452779 3.2216034222 1.3895348496 0.4640796350 0.6636270215 -0.4780486426 0.340145210143 +1413393246405760512.0000000000 -0.8533841698 3.2206423171 1.3852387871 0.4666187897 0.6669186263 -0.4686864909 0.34324834184 +1413393246455760384.0000000000 -0.8563625331 3.2197287696 1.3820381864 0.4700164607 0.6692803427 -0.4599775055 0.345787570516 +1413393246505760512.0000000000 -0.8594286183 3.2188708017 1.3788776892 0.4732184090 0.6711429918 -0.4532853937 0.346646468079 +1413393246555760384.0000000000 -0.8628755021 3.2180416600 1.3755831972 0.4752670971 0.6731724092 -0.4477665533 0.347080981387 +1413393246605760512.0000000000 -0.8668797931 3.2172058367 1.3720952735 0.4758635668 0.6758125629 -0.4436293893 0.346445104647 +1413393246655760384.0000000000 -0.8715863077 3.2164462539 1.3683472264 0.4751395525 0.6785043081 -0.4418836697 0.344402572586 +1413393246705760512.0000000000 -0.8767172796 3.2158890905 1.3648965913 0.4744623745 0.6806714545 -0.4401111814 0.343327794064 +1413393246755760384.0000000000 -0.8821308113 3.2158346484 1.3617825356 0.4744508837 0.6820211054 -0.4389416059 0.342160543119 +1413393246805760512.0000000000 -0.8878612887 3.2160237112 1.3581290606 0.4746261528 0.6827786954 -0.4375596948 0.342176535817 +1413393246855760384.0000000000 -0.8940310626 3.2166215053 1.3534673615 0.4747512867 0.6836182732 -0.4363565409 0.341862898711 +1413393246905760512.0000000000 -0.9005968638 3.2178111086 1.3480122652 0.4757321385 0.6839589412 -0.4345847996 0.342074774143 +1413393246955760384.0000000000 -0.9077224194 3.2196321865 1.3418359201 0.4781963654 0.6833676189 -0.4329335592 0.341914414449 +1413393247005760512.0000000000 -0.9156389727 3.2217945917 1.3343569822 0.4787790126 0.6840467548 -0.4317174470 0.341278098227 +1413393247055760384.0000000000 -0.9243285578 3.2243519825 1.3260269283 0.4792245333 0.6847240339 -0.4309246736 0.340295121583 +1413393247105760512.0000000000 -0.9336627611 3.2273962810 1.3169483089 0.4798093851 0.6853811506 -0.4299936028 0.339324526004 +1413393247155760384.0000000000 -0.9436624204 3.2310502772 1.3071230220 0.4802190960 0.6862415837 -0.4300507451 0.336925014401 +1413393247205760512.0000000000 -0.9543323722 3.2350509505 1.2961635125 0.4798217260 0.6878351994 -0.4312462615 0.332686807217 +1413393247255760384.0000000000 -0.9653729739 3.2392298444 1.2841482137 0.4776745499 0.6904758833 -0.4339360013 0.326756217469 +1413393247305760512.0000000000 -0.9764460251 3.2435589609 1.2712852509 0.4743718090 0.6938207429 -0.4373067230 0.319917166732 +1413393247355760384.0000000000 -0.9870214972 3.2481036722 1.2579090681 0.4701109263 0.6976337720 -0.4406933366 0.313196775408 +1413393247405760512.0000000000 -0.9965049726 3.2530331915 1.2450742661 0.4680563951 0.6998196288 -0.4439843248 0.306681622303 +1413393247455760384.0000000000 -1.0044789768 3.2582106862 1.2323551395 0.4660510020 0.7022253166 -0.4457740556 0.30159834147 +1413393247505760512.0000000000 -1.0106654096 3.2637276660 1.2206470581 0.4663596173 0.7025035737 -0.4486874761 0.29610299733 +1413393247555760384.0000000000 -1.0149177127 3.2688984003 1.2090439654 0.4658677063 0.7036075505 -0.4496225497 0.292819497154 +1413393247605760512.0000000000 -1.0172282839 3.2742422446 1.1983415114 0.4670134184 0.7035952331 -0.4517342754 0.28772966371 +1413393247655760384.0000000000 -1.0175110797 3.2791536430 1.1875122154 0.4685043461 0.7035251993 -0.4523001147 0.284570866263 +1413393247705760512.0000000000 -1.0151716741 3.2835406803 1.1760281660 0.4696623641 0.7037371749 -0.4514073633 0.283553601268 +1413393247755760384.0000000000 -1.0106110481 3.2878087062 1.1652603607 0.4729041901 0.7028076731 -0.4511726976 0.280831263461 +1413393247805760512.0000000000 -1.0040074586 3.2913796492 1.1541947537 0.4742961376 0.7030969785 -0.4513393995 0.27747172685 +1413393247855760384.0000000000 -0.9950703560 3.2942332530 1.1445222144 0.4787390060 0.7011069703 -0.4507655851 0.27580494493 +1413393247905760512.0000000000 -0.9826608688 3.2968890033 1.1382639772 0.4886656133 0.6956297378 -0.4480337514 0.276714553101 +1413393247955760384.0000000000 -0.9675795745 3.2982521092 1.1342011538 0.4978535761 0.6905639263 -0.4409629343 0.284279740884 +1413393248005760512.0000000000 -0.9514185177 3.2983823253 1.1289234047 0.5053198377 0.6860658403 -0.4343993989 0.291997750929 +1413393248055760384.0000000000 -0.9360558739 3.2966382539 1.1234003707 0.5108015578 0.6831904167 -0.4276249075 0.299114629356 +1413393248105760512.0000000000 -0.9211556025 3.2932141409 1.1179312770 0.5126477234 0.6824020521 -0.4224533803 0.305045721782 +1413393248155760384.0000000000 -0.9075480273 3.2878661020 1.1128650028 0.5139522753 0.6818261219 -0.4191146338 0.308721755024 +1413393248205760512.0000000000 -0.8938044553 3.2816018487 1.1091117210 0.5122427304 0.6834413206 -0.4162114751 0.311902796545 +1413393248255760384.0000000000 -0.8817219179 3.2736377381 1.1068582155 0.5084947336 0.6858773406 -0.4165176233 0.312279440743 +1413393248305760512.0000000000 -0.8697595071 3.2649873031 1.1064398644 0.5027329980 0.6897004801 -0.4164976068 0.313213224541 +1413393248355760384.0000000000 -0.8589905716 3.2556085927 1.1072751479 0.5010015280 0.6905928819 -0.4166207811 0.31385675899 +1413393248405760512.0000000000 -0.8490967364 3.2455276411 1.1090137984 0.5003817718 0.6899271815 -0.4166807135 0.316221045559 +1413393248455760384.0000000000 -0.8402287319 3.2353780190 1.1126518991 0.5030889636 0.6871767435 -0.4159988273 0.318801809096 +1413393248505760512.0000000000 -0.8326157740 3.2247617391 1.1176279501 0.5074625742 0.6830596787 -0.4155342741 0.321313675656 +1413393248555760384.0000000000 -0.8254494729 3.2137757832 1.1234116088 0.5107648141 0.6791834399 -0.4157785893 0.323971178301 +1413393248605760512.0000000000 -0.8191850234 3.2024080307 1.1316698693 0.5136154884 0.6759708335 -0.4155202694 0.326504927962 +1413393248655760384.0000000000 -0.8149648860 3.1900343486 1.1404569386 0.5148795785 0.6740023168 -0.4165238268 0.32730383178 +1413393248705760512.0000000000 -0.8128116502 3.1760059208 1.1488050909 0.5124054302 0.6743561115 -0.4178250190 0.328795929808 +1413393248755760384.0000000000 -0.8124408631 3.1611715449 1.1575205036 0.5080872446 0.6762700841 -0.4197003767 0.329177336712 +1413393248805760512.0000000000 -0.8136696424 3.1455865316 1.1668166558 0.5025779859 0.6788371008 -0.4224339341 0.328854268778 +1413393248855760384.0000000000 -0.8160585234 3.1294771319 1.1758249185 0.4940412685 0.6833716413 -0.4259095950 0.327913771792 +1413393248905760512.0000000000 -0.8194872080 3.1132065398 1.1835807675 0.4840729909 0.6888910186 -0.4312367405 0.324248943795 +1413393248955760384.0000000000 -0.8230755826 3.0969896534 1.1893857920 0.4743724041 0.6937511969 -0.4364293571 0.321262377543 +1413393249005760512.0000000000 -0.8261931226 3.0814983168 1.1935029472 0.4669340952 0.6971534799 -0.4409479583 0.318613361684 +1413393249055760384.0000000000 -0.8287799532 3.0667056638 1.1956291074 0.4617901760 0.6989231092 -0.4443539646 0.317499409343 +1413393249105760512.0000000000 -0.8307138254 3.0528458877 1.1959736514 0.4589542976 0.6991710965 -0.4469973834 0.317354800983 +1413393249155760384.0000000000 -0.8315898051 3.0400367752 1.1942420181 0.4581050899 0.6980771443 -0.4488537251 0.318368278375 +1413393249205760512.0000000000 -0.8315245420 3.0282101054 1.1912388893 0.4592643432 0.6958614044 -0.4494355669 0.320719254287 +1413393249255760384.0000000000 -0.8305537200 3.0172118014 1.1879802259 0.4602147853 0.6938061826 -0.4494651023 0.323753693706 +1413393249305760512.0000000000 -0.8289746601 3.0069998281 1.1850733285 0.4614912226 0.6916199878 -0.4499481606 0.325936031712 +1413393249355760384.0000000000 -0.8268750586 2.9975262116 1.1825290455 0.4615002595 0.6909294929 -0.4489267581 0.328783686109 +1413393249405760512.0000000000 -0.8242310156 2.9889214360 1.1805158873 0.4614115209 0.6903996663 -0.4476493613 0.331749541912 +1413393249455760384.0000000000 -0.8214261544 2.9810148960 1.1780821974 0.4596655302 0.6913524410 -0.4449406572 0.335808299805 +1413393249505760512.0000000000 -0.8186620650 2.9742479835 1.1754554909 0.4578492750 0.6929103195 -0.4411848577 0.340007723156 +1413393249555760384.0000000000 -0.8158793847 2.9686169799 1.1717517025 0.4540603442 0.6956934375 -0.4362783065 0.345689288524 +1413393249605760512.0000000000 -0.8135290965 2.9647058159 1.1668611127 0.4515197432 0.6980854439 -0.4312977705 0.35041242503 +1413393249655760384.0000000000 -0.8117728215 2.9629450853 1.1611957819 0.4519769204 0.6986577521 -0.4272906857 0.353577260108 +1413393249705760512.0000000000 -0.8105205009 2.9638387587 1.1550703954 0.4551890893 0.6975522364 -0.4267543659 0.352284660002 +1413393249755760384.0000000000 -0.8099184492 2.9665633837 1.1475079850 0.4583133756 0.6965373219 -0.4273815613 0.349470470746 +1413393249805760512.0000000000 -0.8101696680 2.9709181105 1.1390313153 0.4624090063 0.6948986623 -0.4284035182 0.346069625282 +1413393249855760384.0000000000 -0.8109791317 2.9764331288 1.1300680531 0.4663150527 0.6929181426 -0.4290979864 0.343932605881 +1413393249905760512.0000000000 -0.8126117597 2.9829401383 1.1208780155 0.4695000543 0.6915871265 -0.4296889377 0.341532373631 +1413393249955760384.0000000000 -0.8150636472 2.9902945776 1.1116432552 0.4706526686 0.6915683754 -0.4302552369 0.339263435714 +1413393250005760512.0000000000 -0.8179415761 2.9981591988 1.1026281145 0.4695031115 0.6923031260 -0.4326969595 0.336238830721 +1413393250055760384.0000000000 -0.8211246547 3.0065551004 1.0937022432 0.4664897998 0.6942341167 -0.4346921731 0.333869693962 +1413393250105760512.0000000000 -0.8243831782 3.0158028348 1.0852163892 0.4632677844 0.6961451437 -0.4365390303 0.331961705451 +1413393250155760384.0000000000 -0.8273068253 3.0259960805 1.0775060987 0.4613548678 0.6966485718 -0.4386476509 0.330787985994 +1413393250205760512.0000000000 -0.8299132943 3.0371942963 1.0700990790 0.4605294446 0.6964933069 -0.4407138134 0.329516370907 +1413393250255760384.0000000000 -0.8318257700 3.0492141656 1.0632993120 0.4616201050 0.6946757816 -0.4414926817 0.330781875444 +1413393250305760512.0000000000 -0.8334043090 3.0620106339 1.0565836427 0.4624555737 0.6928131605 -0.4421786639 0.332600054326 +1413393250355760384.0000000000 -0.8346613656 3.0756544485 1.0505933903 0.4652717073 0.6894372826 -0.4431411888 0.334401492939 +1413393250405760512.0000000000 -0.8360541135 3.0898601223 1.0450378430 0.4689944972 0.6854840821 -0.4448966200 0.334996615483 +1413393250455760384.0000000000 -0.8377286174 3.1048970608 1.0404549345 0.4748806606 0.6806057889 -0.4459601695 0.335236700851 +1413393250505760512.0000000000 -0.8398616297 3.1201420717 1.0364342352 0.4818347572 0.6750439973 -0.4477483464 0.334174036574 +1413393250555760384.0000000000 -0.8424906887 3.1350219630 1.0329321972 0.4892970454 0.6694786509 -0.4492437841 0.332515803804 +1413393250605760512.0000000000 -0.8459778246 3.1489857642 1.0291012076 0.4943328683 0.6658054350 -0.4507440436 0.330405728255 +1413393250655760384.0000000000 -0.8501074030 3.1614785505 1.0246283105 0.4951864174 0.6651105345 -0.4513709053 0.3296705851 +1413393250705760512.0000000000 -0.8549081095 3.1727313161 1.0203751751 0.4948062104 0.6655302675 -0.4528530944 0.327353558177 +1413393250755760384.0000000000 -0.8604232293 3.1827908777 1.0167143760 0.4932206427 0.6672360724 -0.4536165196 0.325209893018 +1413393250805760512.0000000000 -0.8666485277 3.1915321620 1.0127907576 0.4894059646 0.6704298016 -0.4562442956 0.320697405212 +1413393250855760384.0000000000 -0.8729019247 3.1992064512 1.0093604087 0.4856148032 0.6736577164 -0.4580282928 0.31713345309 +1413393250905760512.0000000000 -0.8785590868 3.2057638715 1.0066304347 0.4812965895 0.6770230211 -0.4583458188 0.316089437097 +1413393250955760384.0000000000 -0.8835233132 3.2112390692 1.0046940194 0.4767804824 0.6796413044 -0.4595612997 0.315549490298 +1413393251005760512.0000000000 -0.8874039219 3.2159146932 1.0034135975 0.4718743200 0.6813340634 -0.4616608278 0.316208475986 +1413393251055760384.0000000000 -0.8898422573 3.2199411997 1.0033983679 0.4683284703 0.6808002333 -0.4637843443 0.31950519277 +1413393251105760512.0000000000 -0.8906171615 3.2235032585 1.0043345712 0.4657013169 0.6777704322 -0.4677278666 0.324006431222 +1413393251155760384.0000000000 -0.8900279965 3.2266350783 1.0069266165 0.4638565631 0.6726993788 -0.4724350270 0.330329804746 +1413393251205760512.0000000000 -0.8886153205 3.2291291156 1.0097756882 0.4620375897 0.6654883886 -0.4791757786 0.337693712691 +1413393251255760384.0000000000 -0.8868389301 3.2308450908 1.0135310491 0.4595071378 0.6572106842 -0.4866115307 0.346607162325 +1413393251305760512.0000000000 -0.8842564770 3.2322798503 1.0166590828 0.4560587157 0.6486186930 -0.4947450614 0.355712753685 +1413393251355760384.0000000000 -0.8811897714 3.2332051818 1.0214416279 0.4531320699 0.6382404217 -0.5034275696 0.365897763701 +1413393251405760512.0000000000 -0.8789924000 3.2336207713 1.0267474675 0.4491931615 0.6282016935 -0.5122925727 0.375691969506 +1413393251455760384.0000000000 -0.8774579399 3.2335232535 1.0321920306 0.4463406297 0.6170444459 -0.5209245000 0.385582493559 +1413393251505760512.0000000000 -0.8762253719 3.2329148579 1.0379071069 0.4431996779 0.6057998681 -0.5293962176 0.395373507079 +1413393251555760384.0000000000 -0.8758448835 3.2317848562 1.0444226706 0.4392705403 0.5953839786 -0.5367146790 0.405581883021 +1413393251605760512.0000000000 -0.8768384608 3.2304562527 1.0514004391 0.4359519377 0.5849207289 -0.5441722248 0.414355208312 +1413393251655760384.0000000000 -0.8790381770 3.2288330012 1.0587895922 0.4324817060 0.5745222241 -0.5512653263 0.423072485482 +1413393251705760512.0000000000 -0.8828926802 3.2267821559 1.0661082089 0.4281970131 0.5647817443 -0.5583037968 0.43123748644 +1413393251755760384.0000000000 -0.8885966776 3.2243868071 1.0733886810 0.4226118730 0.5561272478 -0.5657624018 0.438217518734 +1413393251805760512.0000000000 -0.8960907455 3.2217132577 1.0804447455 0.4150988335 0.5487109894 -0.5742971568 0.443612425673 +1413393251855760384.0000000000 -0.9052807432 3.2190310663 1.0875123774 0.4060004641 0.5428163890 -0.5843757728 0.446115396612 +1413393251905760512.0000000000 -0.9158793124 3.2163373348 1.0942694421 0.3945591811 0.5387341689 -0.5955555652 0.446544641281 +1413393251955760384.0000000000 -0.9272791481 3.2134234842 1.1012019663 0.3818807017 0.5352064214 -0.6059806119 0.447781993966 +1413393252005760512.0000000000 -0.9389320819 3.2104765456 1.1086544190 0.3695525100 0.5315458370 -0.6143562735 0.451061342542 +1413393252055760384.0000000000 -0.9505830004 3.2079498710 1.1166257909 0.3586258266 0.5271898169 -0.6225829223 0.453705761876 +1413393252105760512.0000000000 -0.9617863927 3.2059107724 1.1258713024 0.3511270490 0.5204777192 -0.6304851891 0.456400225205 +1413393252155760384.0000000000 -0.9725553183 3.2042071094 1.1360536678 0.3454153614 0.5129597557 -0.6371977776 0.45993424467 +1413393252205760512.0000000000 -0.9826758877 3.2027772462 1.1461917435 0.3405659976 0.5049619855 -0.6440532382 0.462842976491 +1413393252255760384.0000000000 -0.9921034376 3.2012263842 1.1561907100 0.3355547253 0.4963901821 -0.6498112830 0.467701945677 +1413393252305760512.0000000000 -1.0009587640 3.1999000035 1.1663938312 0.3309923617 0.4880838134 -0.6548735101 0.472608647148 +1413393252355760384.0000000000 -1.0093381811 3.1988385056 1.1764476509 0.3264614027 0.4796817016 -0.6603652588 0.476703411611 +1413393252405760512.0000000000 -1.0174267802 3.1977618639 1.1858879332 0.3218495206 0.4704375085 -0.6672300372 0.479484633879 +1413393252455760384.0000000000 -1.0253009846 3.1969133623 1.1936170090 0.3168656048 0.4626628114 -0.6750929709 0.479362902323 +1413393252505760512.0000000000 -1.0328127901 3.1964759240 1.1996235773 0.3144413049 0.4550754541 -0.6816009702 0.4790126453 +1413393252555760384.0000000000 -1.0396885962 3.1956374641 1.2028327328 0.3115651502 0.4490716951 -0.6857637001 0.480614104455 +1413393252605760512.0000000000 -1.0458100743 3.1943581586 1.2036247041 0.3093092486 0.4446722820 -0.6884524383 0.482314825045 +1413393252655760384.0000000000 -1.0512212074 3.1924882111 1.2024990117 0.3067621844 0.4408115566 -0.6905439101 0.484490703673 +1413393252705760512.0000000000 -1.0561927983 3.1902133506 1.1993025870 0.3031623230 0.4373841365 -0.6928201094 0.486608691999 +1413393252755760384.0000000000 -1.0606734214 3.1872662571 1.1957275528 0.2993028803 0.4341497304 -0.6936389052 0.490710573197 +1413393252805760512.0000000000 -1.0647753455 3.1840112873 1.1924800760 0.2946902697 0.4309189334 -0.6943464996 0.4953276252 +1413393252855760384.0000000000 -1.0684761776 3.1805033732 1.1898269058 0.2895559628 0.4275713592 -0.6949870374 0.500332984123 +1413393252905760512.0000000000 -1.0717757560 3.1772383884 1.1879665834 0.2853960920 0.4239593751 -0.6955356244 0.505012588014 +1413393252955760384.0000000000 -1.0747632718 3.1742345692 1.1869258035 0.2808709702 0.4215392255 -0.6953533420 0.509803794916 +1413393253005760512.0000000000 -1.0774073172 3.1718246605 1.1864617727 0.2760896822 0.4198730137 -0.6959747507 0.512933023058 +1413393253055760384.0000000000 -1.0795128820 3.1702518948 1.1869921452 0.2711369389 0.4192669824 -0.6967370812 0.515031452925 +1413393253105760512.0000000000 -1.0809533921 3.1696485180 1.1882592983 0.2664554752 0.4187518653 -0.6985737130 0.515405784392 +1413393253155760384.0000000000 -1.0816835713 3.1704694845 1.1895414245 0.2630700359 0.4186547284 -0.7028904179 0.511338865154 +1413393253205760512.0000000000 -1.0812683218 3.1719430923 1.1909131538 0.2606468538 0.4181896774 -0.7073439058 0.506798983948 +1413393253255760384.0000000000 -1.0798027257 3.1739316849 1.1924398393 0.2595064832 0.4169895257 -0.7125072152 0.501108360486 +1413393253305760512.0000000000 -1.0767176457 3.1760422125 1.1943430137 0.2590653606 0.4164440922 -0.7162262995 0.496466861924 +1413393253355760384.0000000000 -1.0718881221 3.1778822360 1.1967421514 0.2592743522 0.4157108517 -0.7186362011 0.493480808758 +1413393253405760512.0000000000 -1.0653830908 3.1791575770 1.1996950943 0.2606963732 0.4134809636 -0.7204727251 0.491924736189 +1413393253455760384.0000000000 -1.0572838540 3.1799588005 1.2031527485 0.2623703910 0.4122791532 -0.7209386449 0.491360507288 +1413393253505760512.0000000000 -1.0477391267 3.1800384038 1.2073271926 0.2640848080 0.4108137729 -0.7204510833 0.492383483373 +1413393253555760384.0000000000 -1.0367655631 3.1793012564 1.2121844855 0.2658420689 0.4091361175 -0.7199640349 0.493545763068 +1413393253605760512.0000000000 -1.0244975344 3.1781966621 1.2182817413 0.2687483339 0.4080147411 -0.7174047417 0.496617297937 +1413393253655760384.0000000000 -1.0111649604 3.1764649171 1.2248748332 0.2705558430 0.4072160033 -0.7145846453 0.500343329222 +1413393253705760512.0000000000 -0.9971205543 3.1742268684 1.2319361627 0.2723815922 0.4066123335 -0.7123471217 0.503027093465 +1413393253755760384.0000000000 -0.9824783127 3.1716984527 1.2392595570 0.2731239361 0.4076394706 -0.7093700083 0.505991668771 +1413393253805760512.0000000000 -0.9675417049 3.1687605434 1.2469781593 0.2737259168 0.4066277278 -0.7082931506 0.507985064979 +1413393253855760384.0000000000 -0.9523717974 3.1658166111 1.2551871437 0.2736910358 0.4053237198 -0.7086937477 0.508487041225 +1413393253905760512.0000000000 -0.9370535872 3.1626971595 1.2637572280 0.2730587346 0.4031223373 -0.7095383058 0.509398371847 +1413393253955760384.0000000000 -0.9214914175 3.1594420515 1.2725789002 0.2714995846 0.3996237841 -0.7115410967 0.510194153661 +1413393254005760512.0000000000 -0.9056155608 3.1558841225 1.2822052627 0.2706623843 0.3946724571 -0.7137257703 0.511440172564 +1413393254055760384.0000000000 -0.8897016793 3.1518967575 1.2924236967 0.2675898867 0.3898743592 -0.7163759835 0.513029323556 +1413393254105760512.0000000000 -0.8738450871 3.1476291271 1.3032420979 0.2647189524 0.3837189789 -0.7194521951 0.514851590719 +1413393254155760384.0000000000 -0.8577571397 3.1428154308 1.3143905053 0.2617044211 0.3766435783 -0.7222459405 0.517697993288 +1413393254205760512.0000000000 -0.8416882784 3.1375415931 1.3256090101 0.2572214407 0.3692735314 -0.7256744921 0.520452419535 +1413393254255760384.0000000000 -0.8260398288 3.1325600803 1.3376141194 0.2535082636 0.3620167212 -0.7287252002 0.523103275146 +1413393254305760512.0000000000 -0.8106858063 3.1272399360 1.3497463229 0.2466885975 0.3571244667 -0.7306628951 0.527009093795 +1413393254355760384.0000000000 -0.7954792500 3.1220339367 1.3617409629 0.2388861443 0.3539623829 -0.7325950521 0.530045782184 +1413393254405760512.0000000000 -0.7803005455 3.1172091748 1.3735550019 0.2299535057 0.3530893589 -0.7342721859 0.532253367212 +1413393254455760384.0000000000 -0.7648268669 3.1127823190 1.3851914335 0.2214681996 0.3521077194 -0.7374870002 0.532057247877 +1413393254505760512.0000000000 -0.7484511347 3.1088773955 1.3969235551 0.2137664815 0.3518286625 -0.7399323657 0.531996783599 +1413393254555760384.0000000000 -0.7307941023 3.1057609436 1.4092164787 0.2107885963 0.3495685152 -0.7426631897 0.530868540748 +1413393254605760512.0000000000 -0.7119287222 3.1031369334 1.4209512225 0.2085790275 0.3473452193 -0.7455725797 0.529119661667 +1413393254655760384.0000000000 -0.6915251832 3.1007469187 1.4327066667 0.2094231461 0.3442998305 -0.7474578804 0.528115791853 +1413393254705760512.0000000000 -0.6696028062 3.0984584801 1.4452143974 0.2127344225 0.3407126247 -0.7465522224 0.530394901984 +1413393254755760384.0000000000 -0.6468338461 3.0960844239 1.4578406197 0.2167736633 0.3366363112 -0.7448967528 0.533679679695 +1413393254805760512.0000000000 -0.6236978643 3.0938917099 1.4699383014 0.2203132264 0.3341747687 -0.7430127062 0.536396704604 +1413393254855760384.0000000000 -0.6004277531 3.0921117561 1.4812899094 0.2233544356 0.3328480755 -0.7415338206 0.538007943806 +1413393254905760512.0000000000 -0.5771931436 3.0902945658 1.4923782841 0.2263635636 0.3310939665 -0.7396168827 0.540465715203 +1413393254955760384.0000000000 -0.5542950730 3.0888653040 1.5025704672 0.2285879803 0.3307015225 -0.7385054070 0.541289019054 +1413393255005760512.0000000000 -0.5318839951 3.0877114822 1.5121170931 0.2298343017 0.3311315688 -0.7377746559 0.54149481531 +1413393255055760384.0000000000 -0.5097546291 3.0868043981 1.5216591267 0.2326263263 0.3302598917 -0.7373575026 0.541403093425 +1413393255105760512.0000000000 -0.4880479000 3.0860911697 1.5309873637 0.2358310625 0.3291976800 -0.7371188036 0.540988416463 +1413393255155760384.0000000000 -0.4669709585 3.0854779809 1.5399057302 0.2400658425 0.3273617436 -0.7375162634 0.539696619639 +1413393255205760512.0000000000 -0.4466959908 3.0847538778 1.5482218313 0.2443018486 0.3255670916 -0.7382033977 0.537939047853 +1413393255255760384.0000000000 -0.4273313124 3.0836355192 1.5558313782 0.2476126877 0.3242763160 -0.7386369652 0.536608107819 +1413393255305760512.0000000000 -0.4091003529 3.0822338652 1.5622882796 0.2502305971 0.3235034989 -0.7391895800 0.535097093357 +1413393255355760384.0000000000 -0.3920548982 3.0801970383 1.5677858739 0.2516545352 0.3229560459 -0.7398550329 0.533838849927 +1413393255405760512.0000000000 -0.3761252146 3.0774348856 1.5725238307 0.2530878543 0.3221892980 -0.7400120270 0.53340678122 +1413393255455760384.0000000000 -0.3614505805 3.0740197584 1.5766429857 0.2536994402 0.3217561390 -0.7403414065 0.532920428269 +1413393255505760512.0000000000 -0.3480080639 3.0697247445 1.5807713260 0.2537385508 0.3210220307 -0.7406199265 0.532957529365 +1413393255555760384.0000000000 -0.3359342439 3.0645078865 1.5847238652 0.2522049456 0.3209599920 -0.7410325652 0.533149215818 +1413393255605760512.0000000000 -0.3250074751 3.0584987196 1.5886065397 0.2500019308 0.3208638883 -0.7416740417 0.533352618542 +1413393255655760384.0000000000 -0.3151566845 3.0517017679 1.5922261808 0.2476525120 0.3205921026 -0.7422885459 0.533757109236 +1413393255705760512.0000000000 -0.3062897486 3.0443720770 1.5951138571 0.2448604629 0.3204689676 -0.7433091902 0.533698831078 +1413393255755760384.0000000000 -0.2984258026 3.0365417136 1.5970647266 0.2410857527 0.3208604058 -0.7452651526 0.532452920088 +1413393255805760512.0000000000 -0.2913363310 3.0281324739 1.5985820171 0.2371906387 0.3209419873 -0.7467995683 0.532003051179 +1413393255855760384.0000000000 -0.2848928348 3.0193514712 1.5990239960 0.2323131049 0.3218833756 -0.7496733574 0.529539017394 +1413393255905760512.0000000000 -0.2788781186 3.0099981448 1.5995044920 0.2261180732 0.3242542680 -0.7513770033 0.528358198125 +1413393255955760384.0000000000 -0.2725542107 2.9999111276 1.6000805822 0.2197665259 0.3267671732 -0.7513671285 0.529502905396 +1413393256005760512.0000000000 -0.2657011783 2.9895731296 1.6003211415 0.2147391868 0.3286182132 -0.7514585564 0.530289722391 +1413393256055760384.0000000000 -0.2579834434 2.9789022018 1.6001242076 0.2108503650 0.3299332628 -0.7508763697 0.531856036016 +1413393256105760512.0000000000 -0.2495226671 2.9680395238 1.5988192179 0.2082162763 0.3300016067 -0.7507687191 0.533002112744 +1413393256155760384.0000000000 -0.2403270164 2.9574604057 1.5967892668 0.2067700844 0.3298020005 -0.7507809808 0.53367095812 +1413393256205760512.0000000000 -0.2302106718 2.9471095769 1.5945626003 0.2070176626 0.3287748362 -0.7511707826 0.533660238116 +1413393256255760384.0000000000 -0.2191920685 2.9367543253 1.5923237345 0.2074691328 0.3273867775 -0.7522423292 0.532828241657 +1413393256305760512.0000000000 -0.2072615037 2.9264429805 1.5906611373 0.2083991986 0.3262785297 -0.7530397639 0.532018053376 +1413393256355760384.0000000000 -0.1945772493 2.9161446986 1.5892846420 0.2101646465 0.3250096811 -0.7542850879 0.530333418422 +1413393256405760512.0000000000 -0.1811694565 2.9055109968 1.5885173373 0.2113419771 0.3239912949 -0.7560946934 0.527906264619 +1413393256455760384.0000000000 -0.1669026920 2.8945518784 1.5896505874 0.2148976715 0.3217542846 -0.7577584889 0.525447660279 +1413393256505760512.0000000000 -0.1520686952 2.8829058450 1.5923485608 0.2183070559 0.3201131895 -0.7587639262 0.523590373872 +1413393256555760384.0000000000 -0.1369588160 2.8702751523 1.5964922427 0.2197232731 0.3201458243 -0.7594870459 0.521926969494 +1413393256605760512.0000000000 -0.1214938570 2.8565943728 1.6016489824 0.2187041025 0.3229054829 -0.7581005147 0.522670234792 +1413393256655760384.0000000000 -0.1054791649 2.8419449029 1.6070661240 0.2162338398 0.3265573539 -0.7555117616 0.525171590242 +1413393256705760512.0000000000 -0.0888770697 2.8269034905 1.6112948480 0.2142268749 0.3299188429 -0.7532503992 0.527137780206 +1413393256755760384.0000000000 -0.0714451576 2.8116199976 1.6135138936 0.2128466410 0.3330168430 -0.7513268840 0.528492197757 +1413393256805760512.0000000000 -0.0530480585 2.7960343381 1.6131921028 0.2121157558 0.3355033142 -0.7492190536 0.530203019665 +1413393256855760384.0000000000 -0.0341446476 2.7807535550 1.6103270317 0.2120026664 0.3377253747 -0.7475633485 0.531173682301 +1413393256905760512.0000000000 -0.0149272588 2.7660743424 1.6057893973 0.2142152728 0.3384070507 -0.7467065426 0.531057270124 +1413393256955760384.0000000000 0.0048664610 2.7514987595 1.6000238920 0.2169729360 0.3381431420 -0.7466559622 0.530176229835 +1413393257005760512.0000000000 0.0254480904 2.7369141461 1.5939287619 0.2205521148 0.3373796267 -0.7466448391 0.529200563518 +1413393257055760384.0000000000 0.0464017043 2.7220998065 1.5875069921 0.2221583519 0.3375200737 -0.7461452994 0.529143703217 +1413393257105760512.0000000000 0.0678087498 2.7075014380 1.5810170602 0.2251324035 0.3364794112 -0.7457389549 0.529122308994 +1413393257155760384.0000000000 0.0894535554 2.6926882615 1.5742851465 0.2268807293 0.3357999665 -0.7464583970 0.527791037016 +1413393257205760512.0000000000 0.1113126856 2.6774456647 1.5679394082 0.2279065984 0.3353216660 -0.7463438595 0.527815124894 +1413393257255760384.0000000000 0.1332865621 2.6620908662 1.5616363410 0.2284726133 0.3349344721 -0.7471171178 0.52672115652 +1413393257305760512.0000000000 0.1555395028 2.6462665554 1.5560972025 0.2292830048 0.3342370619 -0.7462554353 0.528031926587 +1413393257355760384.0000000000 0.1778481260 2.6302163315 1.5502459229 0.2292046435 0.3341732805 -0.7462000749 0.528184530551 +1413393257405760512.0000000000 0.2002314507 2.6137985655 1.5446253479 0.2290981419 0.3336813025 -0.7459985793 0.528826010499 +1413393257455760384.0000000000 0.2226443276 2.5973465614 1.5387021458 0.2285009410 0.3335334899 -0.7464782894 0.528500609761 +1413393257505760512.0000000000 0.2449638225 2.5807152036 1.5329271022 0.2293404268 0.3320675140 -0.7472277193 0.528000824141 +1413393257555760384.0000000000 0.2671457116 2.5635829336 1.5269351668 0.2287378441 0.3313155879 -0.7471143043 0.528894314694 +1413393257605760512.0000000000 0.2894274182 2.5461513202 1.5209010920 0.2293664260 0.3294456456 -0.7472251479 0.529633068741 +1413393257655760384.0000000000 0.3116544327 2.5283605870 1.5145245108 0.2296372075 0.3275267115 -0.7479142855 0.529733166508 +1413393257705760512.0000000000 0.3337318618 2.5102543925 1.5075185295 0.2283807158 0.3267237436 -0.7486613477 0.529716934321 +1413393257755760384.0000000000 0.3557323007 2.4917838631 1.5007703477 0.2275445988 0.3255350405 -0.7485862277 0.530913413537 +1413393257805760512.0000000000 0.3773370219 2.4730949947 1.4937229070 0.2248203080 0.3258059906 -0.7484134846 0.5321499241 +1413393257855760384.0000000000 0.3988446465 2.4541532845 1.4868896567 0.2204488885 0.3273566192 -0.7480084072 0.533594747107 +1413393257905760512.0000000000 0.4205713378 2.4350916741 1.4809058699 0.2163057154 0.3285658272 -0.7473433581 0.535475713581 +1413393257955760384.0000000000 0.4427578771 2.4161371967 1.4759192996 0.2129554994 0.3298030990 -0.7464661493 0.537278474378 +1413393258005760512.0000000000 0.4654396273 2.3973934633 1.4717959563 0.2108839977 0.3300775086 -0.7457317124 0.538944330127 +1413393258055760384.0000000000 0.4885961101 2.3791333394 1.4680078687 0.2091612814 0.3304583747 -0.7452800420 0.540005999957 +1413393258105760512.0000000000 0.5124099263 2.3614915249 1.4647996501 0.2094696990 0.3300010596 -0.7450000780 0.540552152647 +1413393258155760384.0000000000 0.5367383202 2.3447235535 1.4618608716 0.2104419260 0.3311048319 -0.7442330323 0.540556176317 +1413393258205760512.0000000000 0.5616691135 2.3288326862 1.4593022934 0.2124520940 0.3331289167 -0.7433504618 0.539740051834 +1413393258255760384.0000000000 0.5872673953 2.3135906924 1.4577863673 0.2164962981 0.3352588107 -0.7403463588 0.540941911632 +1413393258305760512.0000000000 0.6130889677 2.2991810620 1.4569789691 0.2215121658 0.3382082294 -0.7351336831 0.544174624512 +1413393258355760384.0000000000 0.6391536406 2.2859370960 1.4568724050 0.2286183924 0.3412328042 -0.7284936268 0.548261652614 +1413393258405760512.0000000000 0.6650911755 2.2741119626 1.4566177954 0.2367047702 0.3450444021 -0.7234750742 0.549089272645 +1413393258455760384.0000000000 0.6902227798 2.2638858951 1.4558436409 0.2446533609 0.3503200294 -0.7192265229 0.547844703079 +1413393258505760512.0000000000 0.7142181882 2.2554469830 1.4550479636 0.2555660831 0.3550744027 -0.7152545395 0.544994577382 +1413393258555760384.0000000000 0.7372442458 2.2480963455 1.4542646599 0.2659644057 0.3621653901 -0.7102531502 0.541885253297 +1413393258605760512.0000000000 0.7592397253 2.2415780309 1.4537701560 0.2748735957 0.3717085254 -0.7046410230 0.538292027823 +1413393258655760384.0000000000 0.7797200663 2.2360318099 1.4534069107 0.2819190312 0.3830726799 -0.7000798082 0.532602331907 +1413393258705760512.0000000000 0.7986675746 2.2315425617 1.4525948869 0.2879792436 0.3961761251 -0.6960479917 0.525004406009 +1413393258755760384.0000000000 0.8165777224 2.2274904506 1.4520632820 0.2937264908 0.4088035112 -0.6927096813 0.516485948809 +1413393258805760512.0000000000 0.8339169652 2.2238038710 1.4521340389 0.3010871893 0.4205759951 -0.6890281535 0.507644108046 +1413393258855760384.0000000000 0.8506920074 2.2203268453 1.4527151222 0.3095521770 0.4319614438 -0.6845453117 0.498983443599 +1413393258905760512.0000000000 0.8667586595 2.2167128547 1.4530121534 0.3156066556 0.4444221169 -0.6792177165 0.491471987501 +1413393258955760384.0000000000 0.8822600523 2.2130225258 1.4533406374 0.3208932508 0.4576064613 -0.6731404662 0.484257948715 +1413393259005760512.0000000000 0.8977685995 2.2093692711 1.4541565151 0.3270142676 0.4702303053 -0.6661400538 0.477705513426 +1413393259055760384.0000000000 0.9130341686 2.2055883834 1.4551125282 0.3333954273 0.4820858912 -0.6588585905 0.47153583136 +1413393259105760512.0000000000 0.9281650251 2.2020265314 1.4563263991 0.3408102110 0.4937994091 -0.6514079664 0.464411676099 +1413393259155760384.0000000000 0.9434677507 2.1982091595 1.4578481707 0.3474647423 0.5054072757 -0.6432110747 0.458378939211 +1413393259205760512.0000000000 0.9590242261 2.1942090470 1.4596668076 0.3550503451 0.5157618548 -0.6350250806 0.452407016586 +1413393259255760384.0000000000 0.9745561067 2.1903188698 1.4613067890 0.3621158909 0.5267560089 -0.6264382993 0.446066414112 +1413393259305760512.0000000000 0.9905585160 2.1863089230 1.4631826048 0.3696577765 0.5370916871 -0.6182136369 0.438973287368 +1413393259355760384.0000000000 1.0068757052 2.1821361623 1.4648777521 0.3761859915 0.5473231416 -0.6102176351 0.431921192338 +1413393259405760512.0000000000 1.0234466272 2.1779135498 1.4670707347 0.3837267694 0.5573961460 -0.6011583011 0.425055290324 +1413393259455760384.0000000000 1.0405460352 2.1734529275 1.4695137160 0.3914459074 0.5667231859 -0.5920639481 0.418396000803 +1413393259505760512.0000000000 1.0580306210 2.1688497299 1.4720636206 0.3978968151 0.5767806201 -0.5825793028 0.411829572458 +1413393259555760384.0000000000 1.0759540238 2.1643271449 1.4750138049 0.4046808398 0.5871468030 -0.5724902629 0.404656580968 +1413393259605760512.0000000000 1.0940305591 2.1597457584 1.4783646519 0.4112672516 0.5974793610 -0.5616675042 0.398004115077 +1413393259655760384.0000000000 1.1123263651 2.1551214639 1.4817471799 0.4176320655 0.6077234015 -0.5514134783 0.390126775763 +1413393259705760512.0000000000 1.1308201111 2.1505191758 1.4854972847 0.4244083748 0.6179121684 -0.5403606826 0.382194212603 +1413393259755760384.0000000000 1.1496236245 2.1457004059 1.4894892710 0.4309236438 0.6274036789 -0.5297067241 0.374272926225 +1413393259805760512.0000000000 1.1687468077 2.1407120759 1.4938854673 0.4374686759 0.6363506173 -0.5185391191 0.367146062774 +1413393259855760384.0000000000 1.1881702731 2.1358226571 1.4987375427 0.4441395607 0.6447840108 -0.5074887079 0.359789996257 +1413393259905760512.0000000000 1.2082189618 2.1308572991 1.5037404813 0.4501610432 0.6526982241 -0.4968185493 0.352861718731 +1413393259955760384.0000000000 1.2284464476 2.1258933364 1.5084520121 0.4557845448 0.6604125778 -0.4864632764 0.345643105746 +1413393260005760512.0000000000 1.2489091690 2.1208827830 1.5131591998 0.4616935265 0.6675427046 -0.4761114056 0.338443133414 +1413393260055760384.0000000000 1.2696814566 2.1157820858 1.5176886579 0.4662307240 0.6746238303 -0.4662585080 0.33183520496 +1413393260105760512.0000000000 1.2906485645 2.1109204185 1.5229443863 0.4724592681 0.6805951152 -0.4560240196 0.324984034493 +1413393260155760384.0000000000 1.3117207465 2.1059808633 1.5278888061 0.4776413233 0.6868900345 -0.4460946766 0.31786850469 +1413393260205760512.0000000000 1.3330978965 2.1009465992 1.5328476345 0.4828419198 0.6926010234 -0.4362766016 0.311175560992 +1413393260255760384.0000000000 1.3545186387 2.0958556451 1.5371289124 0.4877060794 0.6986126858 -0.4259019406 0.304451362854 +1413393260305760512.0000000000 1.3764951381 2.0908346199 1.5410306729 0.4954558896 0.7020393071 -0.4142534084 0.300097294817 +1413393260355760384.0000000000 1.3988307858 2.0854057148 1.5437346086 0.5042148980 0.7035631513 -0.4006024125 0.300472853871 +1413393260405760512.0000000000 1.4207426354 2.0794669960 1.5444183527 0.5115441095 0.7047176114 -0.3865581205 0.303757356744 +1413393260455760384.0000000000 1.4420302326 2.0730208513 1.5436344747 0.5184857400 0.7044631705 -0.3718681565 0.310834768167 +1413393260505760512.0000000000 1.4617533212 2.0662272131 1.5413094730 0.5249147797 0.7030976830 -0.3581830102 0.319097247544 +1413393260555760384.0000000000 1.4787437967 2.0589246594 1.5369624582 0.5282658569 0.7025137077 -0.3460778562 0.328085038369 +1413393260605760512.0000000000 1.4925488956 2.0518565645 1.5313478052 0.5306676325 0.7020754280 -0.3358584533 0.335679991237 +1413393260655760384.0000000000 1.5021534209 2.0449499434 1.5244446897 0.5288043065 0.7048307536 -0.3274357472 0.341123798115 +1413393260705760512.0000000000 1.5071681697 2.0389031462 1.5180679610 0.5268469586 0.7081088557 -0.3199835955 0.344419263884 +1413393260755760384.0000000000 1.5072527712 2.0340295252 1.5115076810 0.5202605272 0.7148848818 -0.3197275686 0.340650659115 +1413393260805760512.0000000000 1.5029041385 2.0304947423 1.5054939856 0.5123008348 0.7225257475 -0.3231186050 0.333314815179 +1413393260855760384.0000000000 1.4945736796 2.0291582196 1.5015199994 0.5077837739 0.7279689849 -0.3307851988 0.320621191064 +1413393260905760512.0000000000 1.4835629278 2.0295164221 1.4990119646 0.5050956091 0.7315213193 -0.3389809990 0.307972185923 +1413393260955760384.0000000000 1.4706789268 2.0311849341 1.4972831863 0.5030277912 0.7340146922 -0.3476774277 0.295475682754 +1413393261005760512.0000000000 1.4569643361 2.0339829985 1.4962767287 0.5013350996 0.7356316381 -0.3552039039 0.285200626947 +1413393261055760384.0000000000 1.4431574807 2.0375545593 1.4955805774 0.4993390878 0.7368653621 -0.3614676291 0.277544711147 +1413393261105760512.0000000000 1.4296745426 2.0419266671 1.4949500575 0.4968028765 0.7381618354 -0.3669490088 0.271389814712 +1413393261155760384.0000000000 1.4170501241 2.0470232486 1.4941244331 0.4932481901 0.7399134636 -0.3703977605 0.268402288312 +1413393261205760512.0000000000 1.4052000198 2.0530201848 1.4930752412 0.4900928440 0.7415621885 -0.3728655509 0.266206321851 +1413393261255760384.0000000000 1.3946299183 2.0600789801 1.4923665342 0.4885682002 0.7419249697 -0.3744410376 0.265786309607 +1413393261305760512.0000000000 1.3850589335 2.0684157294 1.4924549976 0.4902851186 0.7411743134 -0.3730932409 0.266613152557 +1413393261355760384.0000000000 1.3761612953 2.0779688073 1.4932360440 0.4941557927 0.7402507948 -0.3697176944 0.266735149177 +1413393261405760512.0000000000 1.3678227674 2.0883995827 1.4940753626 0.4978088315 0.7400208122 -0.3655616548 0.266308545352 +1413393261455760384.0000000000 1.3599162659 2.0998364317 1.4949605083 0.5014643641 0.7408432283 -0.3596763470 0.265174900851 +1413393261505760512.0000000000 1.3519191464 2.1124384737 1.4965547256 0.5054628919 0.7423244711 -0.3557210779 0.258697041522 +1413393261555760384.0000000000 1.3445737883 2.1259853937 1.4988869842 0.5102771055 0.7436209089 -0.3525583401 0.24969548691 +1413393261605760512.0000000000 1.3373613638 2.1396934127 1.5006554629 0.5149306918 0.7454542766 -0.3499727240 0.238040745691 +1413393261655760384.0000000000 1.3305363462 2.1532129952 1.5022384023 0.5183852255 0.7488186162 -0.3454378401 0.226318661683 +1413393261705760512.0000000000 1.3247854424 2.1665719127 1.5041963060 0.5211171100 0.7529683431 -0.3399473855 0.214269472968 +1413393261755760384.0000000000 1.3206799335 2.1798382078 1.5061541603 0.5238103702 0.7573939202 -0.3328767934 0.202904376807 +1413393261805760512.0000000000 1.3183536678 2.1927924785 1.5078954587 0.5262731856 0.7623460884 -0.3236101071 0.192721234582 +1413393261855760384.0000000000 1.3182749865 2.2052579263 1.5100744276 0.5297856829 0.7664119193 -0.3120794812 0.185866343241 +1413393261905760512.0000000000 1.3210020586 2.2172654279 1.5126869455 0.5342649555 0.7689264392 -0.2986514203 0.184717128699 +1413393261955760384.0000000000 1.3255174601 2.2289779367 1.5159126476 0.5390969297 0.7704928926 -0.2866313591 0.18318751813 +1413393262005760512.0000000000 1.3314875669 2.2401752280 1.5189101381 0.5420538940 0.7724728197 -0.2757005158 0.182900367662 +1413393262055760384.0000000000 1.3385425045 2.2513058783 1.5223281338 0.5454733482 0.7733250529 -0.2667986746 0.182333913963 +1413393262105760512.0000000000 1.3463518131 2.2621592470 1.5257557905 0.5476807167 0.7745088395 -0.2593109817 0.181492988415 +1413393262155760384.0000000000 1.3549067181 2.2728433314 1.5298382264 0.5497943467 0.7750272065 -0.2541662613 0.180162474091 +1413393262205760512.0000000000 1.3640777228 2.2831760901 1.5343580859 0.5502924724 0.7761403229 -0.2495917851 0.180245207438 +1413393262255760384.0000000000 1.3734944990 2.2934932041 1.5397591712 0.5509084382 0.7767917211 -0.2468164656 0.17937710846 +1413393262305760512.0000000000 1.3830086729 2.3034289623 1.5447709384 0.5495701065 0.7785825330 -0.2447267169 0.178579874304 +1413393262355760384.0000000000 1.3929480197 2.3133434509 1.5496642675 0.5486580785 0.7797409293 -0.2425132341 0.179348062037 +1413393262405760512.0000000000 1.4027516503 2.3234561779 1.5546743028 0.5487278459 0.7800391637 -0.2421619240 0.17830944118 +1413393262455760384.0000000000 1.4128061004 2.3338152943 1.5597714232 0.5481416403 0.7806942189 -0.2417304708 0.17783041967 +1413393262505760512.0000000000 1.4229576063 2.3443894825 1.5643240211 0.5480027603 0.7809263132 -0.2412544058 0.177885861294 +1413393262555760384.0000000000 1.4331600618 2.3550282384 1.5667327380 0.5475712611 0.7813626185 -0.2406319547 0.178141614606 +1413393262605760512.0000000000 1.4434786454 2.3658359453 1.5659920068 0.5470228779 0.7818328358 -0.2398435767 0.178825184637 +1413393262655760384.0000000000 1.4538091022 2.3770360836 1.5626973937 0.5468019693 0.7819794230 -0.2398408452 0.178863516065 +1413393262705760512.0000000000 1.4639389896 2.3881234217 1.5568485564 0.5470228885 0.7818806135 -0.2396912024 0.178820561076 +1413393262755760384.0000000000 1.4738585919 2.3992377403 1.5485098701 0.5466867989 0.7821999458 -0.2392271747 0.179073023311 +1413393262805760512.0000000000 1.4836174326 2.4105989883 1.5386730927 0.5464175617 0.7824623757 -0.2392089207 0.178772400076 +1413393262855760384.0000000000 1.4934220465 2.4225399348 1.5284758814 0.5463776789 0.7825611995 -0.2395711718 0.177974870778 +1413393262905760512.0000000000 1.5030617693 2.4348876744 1.5185552469 0.5469165248 0.7824147523 -0.2395811451 0.176947295009 +1413393262955760384.0000000000 1.5126846627 2.4474112173 1.5089928776 0.5463516266 0.7829314680 -0.2406553093 0.174937813778 +1413393263005760512.0000000000 1.5220456778 2.4598530381 1.4999907733 0.5464918206 0.7830840461 -0.2410504658 0.173264940419 +1413393263055760384.0000000000 1.5317423553 2.4726257973 1.4917719490 0.5473835256 0.7825723541 -0.2428141480 0.170273532721 +1413393263105760512.0000000000 1.5417565280 2.4855631468 1.4838018964 0.5468026439 0.7831999712 -0.2437741497 0.167865534273 +1413393263155760384.0000000000 1.5525775040 2.4992723188 1.4771977808 0.5476230553 0.7827855134 -0.2449835848 0.165344708288 +1413393263205760512.0000000000 1.5637042063 2.5126717861 1.4714101870 0.5476768752 0.7829613090 -0.2458623676 0.163013267184 +1413393263255760384.0000000000 1.5753926700 2.5258427056 1.4666979713 0.5486857214 0.7823538114 -0.2463271227 0.161831522247 +1413393263305760512.0000000000 1.5878974219 2.5390232197 1.4628316889 0.5495584490 0.7818017944 -0.2463791673 0.161458265009 +1413393263355760384.0000000000 1.6007053854 2.5516728202 1.4595186223 0.5498682372 0.7816460324 -0.2468176838 0.16048499201 +1413393263405760512.0000000000 1.6143244627 2.5642306037 1.4563168728 0.5495996776 0.7816148790 -0.2480998286 0.159577098577 +1413393263455760384.0000000000 1.6288564820 2.5768479759 1.4519895616 0.5493795044 0.7816892327 -0.2471429169 0.161444982057 +1413393263505760512.0000000000 1.6439231960 2.5893954763 1.4458015483 0.5495587999 0.7814847629 -0.2459772332 0.163590621625 +1413393263555760384.0000000000 1.6596349759 2.6020009961 1.4377113278 0.5517281338 0.7796660868 -0.2446634795 0.166903089598 +1413393263605760512.0000000000 1.6752886554 2.6143768851 1.4275151625 0.5545853506 0.7775417365 -0.2425138349 0.170443470856 +1413393263655760384.0000000000 1.6909576077 2.6266144796 1.4155267901 0.5592578338 0.7740585666 -0.2400637595 0.174451718622 +1413393263705760512.0000000000 1.7059318653 2.6384590081 1.4019100494 0.5641326543 0.7706477506 -0.2380227508 0.176639641369 +1413393263755760384.0000000000 1.7197848433 2.6493926443 1.3865416498 0.5676834070 0.7689509243 -0.2339028160 0.178155825224 +1413393263805760512.0000000000 1.7323918985 2.6594617794 1.3711933643 0.5711207512 0.7677994575 -0.2285885752 0.179031683829 +1413393263855760384.0000000000 1.7434429398 2.6685053572 1.3559320069 0.5736227767 0.7680359062 -0.2231730313 0.176837651272 +1413393263905760512.0000000000 1.7531288365 2.6763323663 1.3411437567 0.5755407221 0.7689602446 -0.2166756080 0.17465594863 +1413393263955760384.0000000000 1.7613983398 2.6831196799 1.3272582830 0.5780768386 0.7696791664 -0.2101429027 0.171058791148 +1413393264005760512.0000000000 1.7683747146 2.6887629142 1.3137089699 0.5780338616 0.7721438174 -0.2043862935 0.16702401946 +1413393264055760384.0000000000 1.7739771101 2.6932253567 1.3011304039 0.5772445607 0.7748760709 -0.2010606556 0.161029204289 +1413393264105760512.0000000000 1.7787248414 2.6967436725 1.2891837032 0.5732670091 0.7795537313 -0.1980949120 0.156266829941 +1413393264155760384.0000000000 1.7827698440 2.6992939476 1.2779261886 0.5686600288 0.7841306758 -0.1969372349 0.151593470771 +1413393264205760512.0000000000 1.7862707504 2.7010547587 1.2669964919 0.5630184841 0.7891308766 -0.1964753017 0.147241644851 +1413393264255760384.0000000000 1.7898469094 2.7027757495 1.2568288830 0.5574217413 0.7936565288 -0.1951430514 0.145977759248 +1413393264305760512.0000000000 1.7932487514 2.7043874206 1.2471751169 0.5529571450 0.7970533943 -0.1955238678 0.143926021034 +1413393264355760384.0000000000 1.7970127626 2.7066662854 1.2377202118 0.5486016393 0.8000107739 -0.1950565840 0.144816891602 +1413393264405760512.0000000000 1.8007244100 2.7096196638 1.2292112270 0.5448571077 0.8024658149 -0.1952170269 0.145153920193 +1413393264455760384.0000000000 1.8046136758 2.7139837433 1.2218545878 0.5440020558 0.8028487803 -0.1957648109 0.145505113086 +1413393264505760512.0000000000 1.8086177895 2.7192147735 1.2148664441 0.5436627110 0.8026407091 -0.1972619012 0.145898906773 +1413393264555760384.0000000000 1.8126988510 2.7254046386 1.2082733748 0.5437972509 0.8020936347 -0.1982618960 0.147046154807 +1413393264605760512.0000000000 1.8166276269 2.7327279520 1.2026518033 0.5463599607 0.7998800099 -0.2001250847 0.147080636287 +1413393264655760384.0000000000 1.8205816071 2.7407942173 1.1970733460 0.5476520159 0.7984938706 -0.2023037929 0.14682637172 +1413393264705760512.0000000000 1.8242488908 2.7497144259 1.1919920298 0.5501919928 0.7967022928 -0.2035637209 0.145313589277 +1413393264755760384.0000000000 1.8276503417 2.7589221098 1.1863772366 0.5509584424 0.7965920139 -0.2036243808 0.14290930588 +1413393264805760512.0000000000 1.8315007508 2.7684851901 1.1809473740 0.5525367917 0.7957929170 -0.2025307142 0.14282169632 +1413393264855760384.0000000000 1.8354023929 2.7782022200 1.1749184600 0.5524882566 0.7962477215 -0.2006080941 0.143187586364 +1413393264905760512.0000000000 1.8396446567 2.7881804903 1.1687945960 0.5526208981 0.7964043534 -0.1987101295 0.144445606514 +1413393264955760384.0000000000 1.8438712180 2.7985369033 1.1623972536 0.5519759448 0.7969303770 -0.1976201427 0.145501923637 +1413393265005760512.0000000000 1.8479704818 2.8092380622 1.1557707085 0.5515466991 0.7973628401 -0.1962047042 0.146671244602 +1413393265055760384.0000000000 1.8520693587 2.8204413705 1.1496521116 0.5528227785 0.7964439431 -0.1951711136 0.148230419987 +1413393265105760512.0000000000 1.8561392358 2.8320126477 1.1437014586 0.5542588405 0.7953255992 -0.1946700313 0.149525609354 +1413393265155760384.0000000000 1.8598956721 2.8442590715 1.1389914930 0.5597912887 0.7914012998 -0.1931009846 0.151755413726 +1413393265205760512.0000000000 1.8633559620 2.8568022228 1.1353188604 0.5679293347 0.7853161294 -0.1920653225 0.154420722546 +1413393265255760384.0000000000 1.8661540601 2.8686341399 1.1313937792 0.5745623764 0.7802262893 -0.1906627402 0.157393559776 +1413393265305760512.0000000000 1.8675239862 2.8795769286 1.1281856697 0.5813761920 0.7751921649 -0.1908565993 0.157011430581 +1413393265355760384.0000000000 1.8677609719 2.8890999690 1.1253121212 0.5859962837 0.7716149360 -0.1945293461 0.152895649152 +1413393265405760512.0000000000 1.8670884101 2.8967567424 1.1223858637 0.5869656124 0.7706747046 -0.1990136714 0.148072374806 +1413393265455760384.0000000000 1.8656996541 2.9025160225 1.1192000371 0.5844526652 0.7725105260 -0.2027868107 0.143248311395 +1413393265505760512.0000000000 1.8639868366 2.9065076684 1.1167296483 0.5808080824 0.7752565725 -0.2066758970 0.13756559083 +1413393265555760384.0000000000 1.8622738817 2.9089833555 1.1142766492 0.5760589771 0.7793016443 -0.2063278023 0.135180768159 +1413393265605760512.0000000000 1.8607563433 2.9100914667 1.1128528344 0.5722068959 0.7834014497 -0.2010007620 0.135868063047 +1413393265655760384.0000000000 1.8592501034 2.9101753714 1.1116219680 0.5686874378 0.7874806784 -0.1932812068 0.138243098284 +1413393265705760512.0000000000 1.8574282767 2.9100747309 1.1116121067 0.5669907015 0.7906324320 -0.1852066709 0.13827650139 +1413393265755760384.0000000000 1.8551629985 2.9098682245 1.1122973594 0.5656143589 0.7938655165 -0.1762742227 0.137059611616 +1413393265805760512.0000000000 1.8526387488 2.9095790679 1.1142924643 0.5652945903 0.7961846964 -0.1678808765 0.135454666758 +1413393265855760384.0000000000 1.8492925054 2.9094778785 1.1174344156 0.5653198438 0.7985683102 -0.1594664404 0.13142519764 +1413393265905760512.0000000000 1.8452269725 2.9095641150 1.1212306733 0.5655350088 0.8008277486 -0.1512036320 0.126422041454 +1413393265955760384.0000000000 1.8403980058 2.9097229299 1.1259931393 0.5656507114 0.8032031102 -0.1429651101 0.12027058544 +1413393266005760512.0000000000 1.8345472628 2.9101941442 1.1319606393 0.5668219338 0.8050726794 -0.1337149122 0.11265521982 +1413393266055760384.0000000000 1.8281266568 2.9109026886 1.1381364892 0.5674288570 0.8074204645 -0.1248725207 0.102486776103 +1413393266105760512.0000000000 1.8214664397 2.9119171680 1.1451921172 0.5691898074 0.8089586476 -0.1129764680 0.0940488562588 +1413393266155760384.0000000000 1.8141191191 2.9129252047 1.1529709528 0.5710177718 0.8105092649 -0.0993884121 0.0844711739093 +1413393266205760512.0000000000 1.8060123788 2.9139171372 1.1615125694 0.5722944769 0.8123589749 -0.0850152941 0.0729679890127 +1413393266255760384.0000000000 1.7975060262 2.9146017094 1.1708285535 0.5732548232 0.8141758904 -0.0692368038 0.0608505717465 +1413393266305760512.0000000000 1.7885471279 2.9148044874 1.1811674924 0.5747227027 0.8153460271 -0.0521070449 0.046792381413 +1413393266355760384.0000000000 1.7794310512 2.9147704549 1.1920548076 0.5754084836 0.8165595782 -0.0325308040 0.032821929898 +1413393266405760512.0000000000 1.7702027585 2.9149783293 1.2034785098 0.5761545658 0.8170543215 -0.0126236910 0.0175725506214 +1413393266455760384.0000000000 1.7605866929 2.9146298086 1.2157280567 0.5757952461 0.8175325364 0.0099087378 0.00148436637691 +1413393266505760512.0000000000 1.7509499725 2.9141956937 1.2292727857 0.5759268084 0.8167069590 0.0321729209 -0.0162159670457 +1413393266555760384.0000000000 1.7416714042 2.9132515673 1.2428982079 0.5768380641 0.8143506475 0.0540821461 -0.0341466294964 +1413393266605760512.0000000000 1.7326896474 2.9124341109 1.2553170499 0.5801208828 0.8093831651 0.0749871120 -0.0523028333986 +1413393266655760384.0000000000 1.7245283121 2.9113743419 1.2646286982 0.5812797114 0.8052645522 0.0941360214 -0.0692914683163 +1413393266705760512.0000000000 1.7172679927 2.9097547852 1.2703305128 0.5818168392 0.8012165084 0.1111833267 -0.0847321673882 +1413393266755760384.0000000000 1.7109135361 2.9074853969 1.2726243875 0.5813286317 0.7975821700 0.1269193249 -0.0990514461185 +1413393266805760512.0000000000 1.7054937898 2.9047398774 1.2731690858 0.5805191758 0.7940296283 0.1411192047 -0.112248857371 +1413393266855760384.0000000000 1.7016349122 2.9017237334 1.2749605669 0.5820320181 0.7890970447 0.1535654094 -0.122401997163 +1413393266905760512.0000000000 1.6991561224 2.8987934946 1.2809819432 0.5834459094 0.7846461386 0.1647325119 -0.129555036572 +1413393266955760384.0000000000 1.6980940325 2.8954311674 1.2891476430 0.5789384101 0.7852452061 0.1734672124 -0.134645496696 +1413393267005760512.0000000000 1.6986142926 2.8912263422 1.3023033974 0.5757255067 0.7854977698 0.1800173986 -0.13830087071 +1413393267055760384.0000000000 1.7001243715 2.8868707204 1.3195726512 0.5695082288 0.7883618795 0.1847714907 -0.141440519594 +1413393267105760512.0000000000 1.7033025887 2.8818311690 1.3389522259 0.5680401817 0.7884328901 0.1876619195 -0.143132573685 +1413393267155760384.0000000000 1.7075224790 2.8765188928 1.3568076801 0.5649728340 0.7901697065 0.1884858761 -0.144605000801 +1413393267205760512.0000000000 1.7123553670 2.8714139086 1.3718071540 0.5625006059 0.7918239518 0.1886907536 -0.144926523313 +1413393267255760384.0000000000 1.7177992822 2.8665601111 1.3838398744 0.5611724999 0.7928831529 0.1874450164 -0.145897556971 +1413393267305760512.0000000000 1.7239928549 2.8624039127 1.3925987612 0.5594835566 0.7945328876 0.1860929988 -0.145137990177 +1413393267355760384.0000000000 1.7306493986 2.8588067971 1.3994424330 0.5596632678 0.7950034822 0.1838546735 -0.144720244142 +1413393267405760512.0000000000 1.7377688158 2.8558106037 1.4033304566 0.5601755257 0.7952411526 0.1825612643 -0.143060387157 +1413393267455760384.0000000000 1.7454918529 2.8532474968 1.4051178122 0.5606728783 0.7956500611 0.1811553761 -0.140604528832 +1413393267505760512.0000000000 1.7539416592 2.8511614209 1.4045388234 0.5624876820 0.7952558556 0.1805753460 -0.136265461855 +1413393267555760384.0000000000 1.7626935213 2.8492733598 1.4015095107 0.5632671427 0.7955574771 0.1804471950 -0.131366800797 +1413393267605760512.0000000000 1.7716555228 2.8471356847 1.3965692838 0.5641631569 0.7956688297 0.1804517675 -0.126760425357 +1413393267655760384.0000000000 1.7808792499 2.8445380123 1.3897905686 0.5649934911 0.7957223208 0.1803241667 -0.122847621339 +1413393267705760512.0000000000 1.7903278243 2.8414479851 1.3808432483 0.5660994057 0.7954322037 0.1802716244 -0.119671273408 +1413393267755760384.0000000000 1.7995790518 2.8385441084 1.3692450196 0.5665673046 0.7955048523 0.1811411243 -0.115591576149 +1413393267805760512.0000000000 1.8083076431 2.8350476774 1.3569080381 0.5667634821 0.7955131842 0.1816884502 -0.113698004418 +1413393267855760384.0000000000 1.8164513952 2.8315452923 1.3446148417 0.5682090858 0.7944494659 0.1835300329 -0.110928841577 +1413393267905760512.0000000000 1.8237721553 2.8279004237 1.3331355406 0.5685777343 0.7941408393 0.1847576349 -0.109198460635 +1413393267955760384.0000000000 1.8299531440 2.8239250320 1.3232141882 0.5687843332 0.7938317450 0.1843820888 -0.110990037051 +1413393268005760512.0000000000 1.8353231285 2.8196964723 1.3146391829 0.5675281903 0.7946888382 0.1820515589 -0.115059261216 +1413393268055760384.0000000000 1.8401007640 2.8153452185 1.3071531018 0.5656818173 0.7959795960 0.1789841936 -0.119938412124 +1413393268105760512.0000000000 1.8448785400 2.8111081547 1.3004916599 0.5639956727 0.7970313709 0.1775175526 -0.123034115269 +1413393268155760384.0000000000 1.8495361041 2.8068633110 1.2945767641 0.5614626768 0.7986903015 0.1755527871 -0.126628132195 +1413393268205760512.0000000000 1.8544990560 2.8031623516 1.2890237925 0.5604023420 0.7993761472 0.1752397169 -0.127428536782 +1413393268255760384.0000000000 1.8596170831 2.7998529267 1.2833945491 0.5601538482 0.7993877330 0.1772591017 -0.125642864777 +1413393268305760512.0000000000 1.8648554854 2.7970384797 1.2780140793 0.5604698050 0.7991234768 0.1802545535 -0.121587673941 +1413393268355760384.0000000000 1.8698240643 2.7946230475 1.2733014418 0.5606531643 0.7988795138 0.1845112523 -0.115823786527 +1413393268405760512.0000000000 1.8744652601 2.7922963694 1.2694871496 0.5602655398 0.7989127829 0.1894683006 -0.109282446854 +1413393268455760384.0000000000 1.8780108844 2.7903020504 1.2675012742 0.5604082388 0.7986987328 0.1916511816 -0.106267420495 +1413393268505760512.0000000000 1.8804917717 2.7886403430 1.2666369756 0.5595779192 0.7994234034 0.1924041098 -0.103804783451 +1413393268555760384.0000000000 1.8813710646 2.7869910786 1.2676517675 0.5581636840 0.8007176709 0.1900725082 -0.10572111869 +1413393268605760512.0000000000 1.8811378378 2.7857856958 1.2707402573 0.5582592581 0.8011405652 0.1863490344 -0.108602177312 +1413393268655760384.0000000000 1.8802588191 2.7848092450 1.2749888157 0.5591425332 0.8009164144 0.1832345747 -0.110984753097 +1413393268705760512.0000000000 1.8789030696 2.7841169976 1.2804584883 0.5603103017 0.8004524310 0.1804477526 -0.112990618994 +1413393268755760384.0000000000 1.8772850658 2.7836451940 1.2865484926 0.5600153321 0.8010313463 0.1774886976 -0.115019008578 +1413393268805760512.0000000000 1.8753710271 2.7834202447 1.2930540164 0.5585473363 0.8022923118 0.1756115172 -0.116243341647 +1413393268855760384.0000000000 1.8734361328 2.7838968818 1.3002711755 0.5587915499 0.8024851225 0.1730614628 -0.117555782476 +1413393268905760512.0000000000 1.8714597867 2.7847195463 1.3061616708 0.5576203495 0.8034552482 0.1717228036 -0.118450363767 +1413393268955760384.0000000000 1.8693748431 2.7868704212 1.3108948854 0.5595465946 0.8022971737 0.1709435729 -0.118343349755 +1413393269005760512.0000000000 1.8676590874 2.7892734685 1.3131050700 0.5629326464 0.8000964645 0.1722741905 -0.115213221475 +1413393269055760384.0000000000 1.8659138238 2.7919567772 1.3128982332 0.5665744296 0.7975018175 0.1755149513 -0.110357458461 +1413393269105760512.0000000000 1.8641238007 2.7945296372 1.3117157354 0.5699195203 0.7949141231 0.1805826526 -0.103407847094 +1413393269155760384.0000000000 1.8613921529 2.7963484628 1.3109549089 0.5716397070 0.7931147838 0.1851517152 -0.0995782481468 +1413393269205760512.0000000000 1.8572301428 2.7970965979 1.3114385712 0.5742172330 0.7902889697 0.1886915109 -0.100565538357 +1413393269255760384.0000000000 1.8515375768 2.7963917624 1.3131721996 0.5750336662 0.7882754664 0.1908451501 -0.107406706302 +1413393269305760512.0000000000 1.8449756394 2.7945735227 1.3155902213 0.5760949118 0.7856990880 0.1929837248 -0.116399646103 +1413393269355760384.0000000000 1.8378797413 2.7920903794 1.3185969548 0.5788971013 0.7815649793 0.1951184790 -0.12634519515 +1413393269405760512.0000000000 1.8310002317 2.7884650637 1.3208976784 0.5799577586 0.7785064284 0.1971731916 -0.136746011368 +1413393269455760384.0000000000 1.8248275399 2.7841278335 1.3211385408 0.5802073629 0.7763781561 0.1996619338 -0.143984328956 +1413393269505760512.0000000000 1.8194641355 2.7790288481 1.3183545833 0.5785802886 0.7759102321 0.2012346486 -0.150707589429 +1413393269555760384.0000000000 1.8152557149 2.7732523110 1.3118654937 0.5754877660 0.7767130518 0.2034806188 -0.155326443695 +1413393269605760512.0000000000 1.8121686783 2.7669814370 1.3016813076 0.5719262165 0.7781948576 0.2051288994 -0.158856227661 +1413393269655760384.0000000000 1.8101536259 2.7604420242 1.2887328336 0.5694248265 0.7791208533 0.2061307345 -0.161975872512 +1413393269705760512.0000000000 1.8091747575 2.7536833651 1.2728853091 0.5667515022 0.7803560335 0.2073055375 -0.163895118192 +1413393269755760384.0000000000 1.8093303315 2.7468239538 1.2556077613 0.5633138775 0.7822962129 0.2091678905 -0.164130753673 +1413393269805760512.0000000000 1.8104921084 2.7400830902 1.2378623271 0.5596867642 0.7845406416 0.2114076952 -0.162952428922 +1413393269855760384.0000000000 1.8124599431 2.7338429506 1.2205170430 0.5571150899 0.7861133300 0.2142833189 -0.160409688683 +1413393269905760512.0000000000 1.8149786558 2.7281218649 1.2035665799 0.5558145957 0.7867249594 0.2179790360 -0.156904790553 +1413393269955760384.0000000000 1.8180699667 2.7227993921 1.1869963781 0.5547835517 0.7872185944 0.2218026129 -0.152662032905 +1413393270005760512.0000000000 1.8212423186 2.7180006480 1.1709875631 0.5538568353 0.7876561889 0.2257278638 -0.147943453884 +1413393270055760384.0000000000 1.8238184768 2.7134111713 1.1563084248 0.5535842159 0.7875292861 0.2273417148 -0.147166178936 +1413393270105760512.0000000000 1.8261145420 2.7088501273 1.1419558245 0.5512661979 0.7889575312 0.2280320968 -0.14714943395 +1413393270155760384.0000000000 1.8279771451 2.7046898333 1.1281647662 0.5499405322 0.7897342877 0.2283472273 -0.147454093355 +1413393270205760512.0000000000 1.8293343578 2.7008899282 1.1150074154 0.5489975111 0.7901069949 0.2286344207 -0.148522628329 +1413393270255760384.0000000000 1.8304568946 2.6975647942 1.1020192665 0.5480542351 0.7906156040 0.2287879769 -0.149062348152 +1413393270305760512.0000000000 1.8309946392 2.6950372851 1.0894854427 0.5473836397 0.7907884820 0.2289196502 -0.150401201642 +1413393270355760384.0000000000 1.8311753784 2.6936640541 1.0773831132 0.5480111666 0.7904299712 0.2282634773 -0.150996711395 +1413393270405760512.0000000000 1.8308918221 2.6935661921 1.0661798960 0.5473197426 0.7914784913 0.2256986368 -0.151865145765 +1413393270455760384.0000000000 1.8302828580 2.6951153519 1.0568478165 0.5481231676 0.7919447712 0.2219857911 -0.152009148118 +1413393270505760512.0000000000 1.8301928019 2.6970628726 1.0480102657 0.5484338431 0.7931238224 0.2174483574 -0.151298162366 +1413393270555760384.0000000000 1.8309400198 2.6992356408 1.0386093386 0.5488005810 0.7947256477 0.2133339341 -0.147369263633 +1413393270605760512.0000000000 1.8325607093 2.7010525343 1.0288789440 0.5503952899 0.7956791540 0.2085767576 -0.143022532669 +1413393270655760384.0000000000 1.8348025243 2.7027669126 1.0193850813 0.5506321334 0.7977808125 0.2037268204 -0.137278591041 +1413393270705760512.0000000000 1.8368383741 2.7060392289 1.0113949053 0.5534886816 0.7981142736 0.2003404243 -0.128559714093 +1413393270755760384.0000000000 1.8373573059 2.7106337455 1.0082205562 0.5561141967 0.7981743840 0.1957105911 -0.123903258601 +1413393270805760512.0000000000 1.8373549452 2.7160693132 1.0083569924 0.5575907085 0.7987754050 0.1927619452 -0.117869786586 +1413393270855760384.0000000000 1.8368835289 2.7214575998 1.0131817767 0.5595144595 0.7988738903 0.1900259637 -0.11240200258 +1413393270905760512.0000000000 1.8354020450 2.7269595580 1.0216999128 0.5599062045 0.7996202004 0.1886355189 -0.107374197908 +1413393270955760384.0000000000 1.8333835353 2.7324703018 1.0304760664 0.5632972155 0.7981996330 0.1871606717 -0.102686298498 +1413393271005760512.0000000000 1.8300518226 2.7385681739 1.0399441105 0.5637494004 0.7985722435 0.1869066666 -0.0976467282442 +1413393271055760384.0000000000 1.8255229088 2.7442596191 1.0482719420 0.5644789388 0.7987469294 0.1848930810 -0.0958197216173 +1413393271105760512.0000000000 1.8200053620 2.7500277212 1.0542032033 0.5660574760 0.7982438901 0.1828773522 -0.0945595037676 +1413393271155760384.0000000000 1.8133487798 2.7556497391 1.0578423369 0.5677821981 0.7975999383 0.1799692567 -0.0952301447801 +1413393271205760512.0000000000 1.8060598363 2.7611550767 1.0586319117 0.5694981274 0.7967531919 0.1792521144 -0.0934072459897 +1413393271255760384.0000000000 1.7981300337 2.7661691793 1.0573120896 0.5727823221 0.7947622587 0.1789213648 -0.0908873409682 +1413393271305760512.0000000000 1.7897993381 2.7708145825 1.0537043625 0.5760948997 0.7928990873 0.1787361371 -0.08648177417 +1413393271355760384.0000000000 1.7807092250 2.7748082424 1.0483989263 0.5783114156 0.7921389142 0.1772598902 -0.0815523055223 +1413393271405760512.0000000000 1.7705307302 2.7781532861 1.0435867738 0.5810214638 0.7914248244 0.1731269821 -0.0780247008914 +1413393271455760384.0000000000 1.7593751439 2.7804506828 1.0394906439 0.5825146798 0.7920368406 0.1658596398 -0.076451754259 +1413393271505760512.0000000000 1.7474747070 2.7816389244 1.0368822847 0.5834244107 0.7933136427 0.1568422494 -0.0752989382642 +1413393271555760384.0000000000 1.7346308250 2.7817553482 1.0353468144 0.5853802689 0.7937411371 0.1469026286 -0.0756608599553 +1413393271605760512.0000000000 1.7211621799 2.7807520765 1.0342739450 0.5868456038 0.7941355572 0.1389851011 -0.0751271971133 +1413393271655760384.0000000000 1.7076571261 2.7787891571 1.0335427528 0.5866048144 0.7956879216 0.1319729613 -0.0732028739325 +1413393271705760512.0000000000 1.6943805069 2.7758046610 1.0332986269 0.5847866653 0.7984506206 0.1254276762 -0.0690583848911 +1413393271755760384.0000000000 1.6811523807 2.7723549644 1.0335047826 0.5804990230 0.8030752820 0.1182549503 -0.0640838708209 +1413393271805760512.0000000000 1.6678785624 2.7682329297 1.0350011782 0.5771409602 0.8069438838 0.1104685732 -0.0595531256686 +1413393271855760384.0000000000 1.6543510523 2.7641176905 1.0367905368 0.5740604347 0.8103946750 0.1038130484 -0.0542027575969 +1413393271905760512.0000000000 1.6404594646 2.7602338029 1.0392226531 0.5743044209 0.8112937660 0.0978398622 -0.0490328326714 +1413393271955760384.0000000000 1.6261034077 2.7564510219 1.0420130217 0.5749534968 0.8116879162 0.0929957838 -0.0440793310854 +1413393272005760512.0000000000 1.6110583053 2.7529705224 1.0457194123 0.5768157834 0.8110492478 0.0886074516 -0.0403904585417 +1413393272055760384.0000000000 1.5957318838 2.7492067501 1.0493804592 0.5768416041 0.8115920624 0.0850019751 -0.0366981229934 +1413393272105760512.0000000000 1.5799423943 2.7450482117 1.0536678148 0.5776011394 0.8114728467 0.0821151420 -0.0338503515078 +1413393272155760384.0000000000 1.5638614885 2.7408748766 1.0584561768 0.5786147497 0.8112681142 0.0779113807 -0.0312863411393 +1413393272205760512.0000000000 1.5475099547 2.7367801984 1.0642382479 0.5812525208 0.8099922850 0.0716732688 -0.0303471224195 +1413393272255760384.0000000000 1.5308899079 2.7324468838 1.0702020148 0.5818564788 0.8102255788 0.0631717400 -0.0314146590636 +1413393272305760512.0000000000 1.5146734014 2.7280353428 1.0766018212 0.5830793947 0.8099857650 0.0546250617 -0.0309448326456 +1413393272355760384.0000000000 1.4989578588 2.7233590526 1.0827846635 0.5835764954 0.8102025443 0.0461110881 -0.0297334632606 +1413393272405760512.0000000000 1.4840907815 2.7185263785 1.0884807220 0.5830819248 0.8110682559 0.0390891874 -0.0256083714199 +1413393272455760384.0000000000 1.4700850280 2.7138746483 1.0944054542 0.5836560304 0.8111027248 0.0333116585 -0.0186639052862 +1413393272505760512.0000000000 1.4566582145 2.7090166646 1.1006578597 0.5840748458 0.8111744291 0.0266776075 -0.011871202541 +1413393272555760384.0000000000 1.4437816522 2.7038449774 1.1067296294 0.5841431443 0.8113740097 0.0209179731 -0.00338254677344 +1413393272605760512.0000000000 1.4312610921 2.6986125457 1.1131937796 0.5841786192 0.8114610564 0.0151823049 0.0059826704008 +1413393272655760384.0000000000 1.4187636572 2.6932061687 1.1198468122 0.5835993376 0.8118654119 0.0086039722 0.0145718175576 +1413393272705760512.0000000000 1.4059654947 2.6873820444 1.1264093348 0.5824716760 0.8125098587 0.0019763166 0.0234642360254 +1413393272755760384.0000000000 1.3925673311 2.6814975893 1.1332221430 0.5819411702 0.8126153054 -0.0058677306 0.0310871297284 +1413393272805760512.0000000000 1.3787980144 2.6753306986 1.1400013625 0.5811119653 0.8127640560 -0.0137576645 0.039168861289 +1413393272855760384.0000000000 1.3646782625 2.6691319969 1.1471297070 0.5810766612 0.8121522997 -0.0217669321 0.0477991269069 +1413393272905760512.0000000000 1.3497340980 2.6628666989 1.1546477724 0.5807889250 0.8116365237 -0.0309090036 0.0545436650975 +1413393272955760384.0000000000 1.3340307507 2.6564581925 1.1623758488 0.5798329246 0.8114614148 -0.0403570060 0.0607903270863 +1413393273005760512.0000000000 1.3176936838 2.6499912339 1.1700652361 0.5790162932 0.8110071611 -0.0507970332 0.0665370438761 +1413393273055760384.0000000000 1.3006050019 2.6434763553 1.1776302808 0.5768723607 0.8113531149 -0.0630812637 0.0703218075761 +1413393273105760512.0000000000 1.2833107691 2.6372353289 1.1849080437 0.5737044454 0.8121333077 -0.0746622270 0.0756852148176 +1413393273155760384.0000000000 1.2657646282 2.6311779536 1.1925419035 0.5717837858 0.8118007916 -0.0868956851 0.0805724327928 +1413393273205760512.0000000000 1.2483084468 2.6253891783 1.1997104693 0.5687611644 0.8118976070 -0.0991256838 0.086643594016 +1413393273255760384.0000000000 1.2310506061 2.6200809121 1.2066624283 0.5648173637 0.8123304345 -0.1113628284 0.0932680611978 +1413393273305760512.0000000000 1.2140298340 2.6153757718 1.2138048205 0.5618335588 0.8117715291 -0.1243666450 0.0995136898243 +1413393273355760384.0000000000 1.1973977407 2.6110806690 1.2207445798 0.5587853436 0.8109565400 -0.1361451287 0.107577571262 +1413393273405760512.0000000000 1.1810038392 2.6075223922 1.2280704211 0.5584089419 0.8080570449 -0.1478279333 0.115629442217 +1413393273455760384.0000000000 1.1648597181 2.6040904195 1.2344338710 0.5547017649 0.8072770595 -0.1585051342 0.124442049475 +1413393273505760512.0000000000 1.1491976778 2.6015570520 1.2418159974 0.5546432773 0.8037040292 -0.1690769180 0.133580179191 +1413393273555760384.0000000000 1.1336326598 2.5998434827 1.2498601109 0.5557709703 0.7991710790 -0.1793107857 0.142449489982 +1413393273605760512.0000000000 1.1180021400 2.5985969265 1.2583407072 0.5571448663 0.7944820237 -0.1890858474 0.150447513009 +1413393273655760384.0000000000 1.1023090740 2.5975268621 1.2672359828 0.5585548676 0.7894648449 -0.1994199410 0.158093028432 +1413393273705760512.0000000000 1.0866332033 2.5963895620 1.2763293373 0.5589962130 0.7850246246 -0.2089907084 0.166079668828 +1413393273755760384.0000000000 1.0706396520 2.5952219922 1.2854631260 0.5586611131 0.7812979935 -0.2181512820 0.172861864798 +1413393273805760512.0000000000 1.0547538651 2.5937749129 1.2942498458 0.5571223672 0.7779154641 -0.2283414253 0.179784293397 +1413393273855760384.0000000000 1.0385201745 2.5919091138 1.3028256177 0.5546352513 0.7752177884 -0.2397512957 0.184218443296 +1413393273905760512.0000000000 1.0221286144 2.5898142582 1.3113249597 0.5513707251 0.7731435173 -0.2508523079 0.187916324186 +1413393273955760384.0000000000 1.0063207471 2.5875401795 1.3200084308 0.5476746997 0.7707620352 -0.2621541557 0.19301167612 +1413393274005760512.0000000000 0.9907360122 2.5852681535 1.3290138447 0.5436836089 0.7687483117 -0.2726432987 0.197736689268 +1413393274055760384.0000000000 0.9756530653 2.5829182506 1.3384052274 0.5400439520 0.7665320600 -0.2826400566 0.202226925469 +1413393274105760512.0000000000 0.9615725503 2.5804742676 1.3483503214 0.5370952156 0.7632990066 -0.2930325793 0.207449423542 +1413393274155760384.0000000000 0.9480929824 2.5781431831 1.3587857680 0.5349649751 0.7594786060 -0.3028321411 0.212831897854 +1413393274205760512.0000000000 0.9352004817 2.5757006310 1.3694560021 0.5330120512 0.7556529561 -0.3123901457 0.217483700677 +1413393274255760384.0000000000 0.9231402964 2.5731622913 1.3801138690 0.5300518868 0.7522253535 -0.3219880815 0.222543681434 +1413393274305760512.0000000000 0.9120332916 2.5705398468 1.3912008120 0.5277441388 0.7482705272 -0.3307706543 0.228403407157 +1413393274355760384.0000000000 0.9016473318 2.5677366592 1.4022990528 0.5249934833 0.7448766106 -0.3389008814 0.233852239823 +1413393274405760512.0000000000 0.8924224574 2.5646773375 1.4132909561 0.5218884835 0.7411463954 -0.3472078557 0.240377071071 +1413393274455760384.0000000000 0.8839585474 2.5612831098 1.4230346140 0.5193205245 0.7368932920 -0.3556485730 0.246593920517 +1413393274505760512.0000000000 0.8757571190 2.5572691576 1.4305600030 0.5171475335 0.7321959172 -0.3638512463 0.253100450343 +1413393274555760384.0000000000 0.8682330813 2.5530373025 1.4352005882 0.5140093268 0.7278856767 -0.3731156790 0.258382552814 +1413393274605760512.0000000000 0.8612811454 2.5484246236 1.4370479157 0.5112770840 0.7230470254 -0.3816633873 0.26482409512 +1413393274655760384.0000000000 0.8549866191 2.5436729237 1.4362449808 0.5076217027 0.7187874382 -0.3903931244 0.270662213858 +1413393274705760512.0000000000 0.8498657970 2.5388294694 1.4335238706 0.5043066648 0.7141311715 -0.3985210372 0.277258797222 +1413393274755760384.0000000000 0.8454867375 2.5336023172 1.4290779449 0.5013577222 0.7092981735 -0.4048962575 0.285649358711 +1413393274805760512.0000000000 0.8417444296 2.5280812113 1.4242891214 0.4993513256 0.7037440715 -0.4103948426 0.294904405945 +1413393274855760384.0000000000 0.8382540997 2.5221157189 1.4198902502 0.4971094803 0.6982272966 -0.4157609794 0.304144069134 +1413393274905760512.0000000000 0.8348390469 2.5159088998 1.4163829477 0.4948665204 0.6925306036 -0.4208976649 0.313613848258 +1413393274955760384.0000000000 0.8311104056 2.5097033254 1.4135218154 0.4926749605 0.6872265441 -0.4261270288 0.32156930162 +1413393275005760512.0000000000 0.8271807386 2.5034312165 1.4115649479 0.4909030122 0.6810180542 -0.4321700551 0.329329145434 +1413393275055760384.0000000000 0.8224874777 2.4971530958 1.4099571721 0.4884058987 0.6756132342 -0.4386583119 0.335537361929 +1413393275105760512.0000000000 0.8170477581 2.4906613443 1.4084804415 0.4856308155 0.6702420066 -0.4450451697 0.341867167984 +1413393275155760384.0000000000 0.8108878865 2.4838418354 1.4070702296 0.4824494399 0.6648828803 -0.4524160053 0.347121090668 +1413393275205760512.0000000000 0.8039831783 2.4769525290 1.4055684798 0.4789901791 0.6598154946 -0.4605729540 0.350833971456 +1413393275255760384.0000000000 0.7965602349 2.4696789039 1.4047085114 0.4750080659 0.6545070295 -0.4690589006 0.354924827959 +1413393275305760512.0000000000 0.7885815443 2.4619411584 1.4038920042 0.4696137168 0.6496263189 -0.4781010654 0.35898185751 +1413393275355760384.0000000000 0.7802609276 2.4541657869 1.4035211711 0.4655915113 0.6436880498 -0.4872781991 0.362560609763 +1413393275405760512.0000000000 0.7717779654 2.4459735516 1.4034406957 0.4610758020 0.6374891115 -0.4966772513 0.3665084522 +1413393275455760384.0000000000 0.7630511947 2.4375734912 1.4040772259 0.4573145365 0.6306523989 -0.5056793918 0.37071460612 +1413393275505760512.0000000000 0.7540641809 2.4286789610 1.4054925732 0.4531414930 0.6243162661 -0.5138196335 0.375341672947 +1413393275555760384.0000000000 0.7448506549 2.4192446977 1.4073224665 0.4486409731 0.6178057481 -0.5218485594 0.380409537051 +1413393275605760512.0000000000 0.7354273047 2.4094206236 1.4099236596 0.4453725647 0.6102040296 -0.5302710363 0.384846656351 +1413393275655760384.0000000000 0.7258623146 2.3990382960 1.4129928346 0.4412790390 0.6036711733 -0.5377509915 0.389458335996 +1413393275705760512.0000000000 0.7164207676 2.3878109503 1.4169749991 0.4371320186 0.5963339799 -0.5452355021 0.394993202485 +1413393275755760384.0000000000 0.7064965849 2.3758567986 1.4206014124 0.4297637898 0.5917772860 -0.5533500200 0.398630761642 +1413393275805760512.0000000000 0.6961218961 2.3638120581 1.4243020057 0.4217333527 0.5890256938 -0.5620769113 0.399072997104 +1413393275855760384.0000000000 0.6859276162 2.3515469260 1.4285673265 0.4146353868 0.5864869780 -0.5712755803 0.397183499188 +1413393275905760512.0000000000 0.6762873805 2.3391346062 1.4333633101 0.4084323949 0.5847525440 -0.5801644302 0.393264128749 +1413393275955760384.0000000000 0.6680704699 2.3261659063 1.4385696854 0.4031760469 0.5834195447 -0.5875597151 0.389672030337 +1413393276005760512.0000000000 0.6615971866 2.3125750888 1.4437415922 0.3993462278 0.5820417614 -0.5930214209 0.387395886158 +1413393276055760384.0000000000 0.6570507753 2.2980800257 1.4490791653 0.3959987154 0.5817073188 -0.5936006466 0.390435506914 +1413393276105760512.0000000000 0.6550836381 2.2826386771 1.4557874974 0.3943786678 0.5814746985 -0.5885163745 0.400001397786 +1413393276155760384.0000000000 0.6540954310 2.2669305527 1.4628375387 0.3932842725 0.5814666727 -0.5819659357 0.410535795275 +1413393276205760512.0000000000 0.6538417514 2.2516324130 1.4703434783 0.3927809872 0.5817310886 -0.5749317776 0.420434879299 +1413393276255760384.0000000000 0.6538105219 2.2372245348 1.4776920167 0.3926458366 0.5822085326 -0.5690932921 0.427779495133 +1413393276305760512.0000000000 0.6536811032 2.2238295778 1.4844595228 0.3920405167 0.5832882461 -0.5642975092 0.433182844083 +1413393276355760384.0000000000 0.6534447581 2.2118298040 1.4902985572 0.3924164840 0.5841987919 -0.5618994537 0.434729891467 +1413393276405760512.0000000000 0.6529202772 2.2011365347 1.4939354195 0.3936237017 0.5848128501 -0.5607527679 0.434293270736 +1413393276455760384.0000000000 0.6523246688 2.1916334120 1.4951538442 0.3950661044 0.5853473918 -0.5608587816 0.43212108392 +1413393276505760512.0000000000 0.6522174494 2.1833149131 1.4935544731 0.3967275161 0.5859656520 -0.5624162157 0.427714312197 +1413393276555760384.0000000000 0.6520628432 2.1757589083 1.4890049524 0.3983366834 0.5863011646 -0.5656439671 0.421456680468 +1413393276605760512.0000000000 0.6517647639 2.1686902675 1.4829498532 0.4003042659 0.5862820412 -0.5683475295 0.415945848088 +1413393276655760384.0000000000 0.6521072819 2.1617962199 1.4767835274 0.4011670641 0.5870319855 -0.5706184274 0.410917321382 +1413393276705760512.0000000000 0.6534548846 2.1549275784 1.4712367806 0.4024566251 0.5871303628 -0.5720273402 0.407543033399 +1413393276755760384.0000000000 0.6555016708 2.1478381682 1.4656064304 0.4014081381 0.5887565584 -0.5723966149 0.405708438122 +1413393276805760512.0000000000 0.6584762355 2.1407826680 1.4612850970 0.4025525143 0.5886192527 -0.5727097453 0.404329563951 +1413393276855760384.0000000000 0.6623946877 2.1333968535 1.4576435917 0.4025814706 0.5888516755 -0.5723441231 0.404479997642 +1413393276905760512.0000000000 0.6671285830 2.1258267093 1.4545273144 0.4027945381 0.5892702889 -0.5716384459 0.404656117985 +1413393276955760384.0000000000 0.6727339043 2.1182496432 1.4519575349 0.4031613698 0.5895667486 -0.5705830297 0.405347955684 +1413393277005760512.0000000000 0.6792289931 2.1105317984 1.4495297148 0.4028714083 0.5896818622 -0.5705894866 0.40545969892 +1413393277055760384.0000000000 0.6864377163 2.1029995990 1.4474901133 0.4028084778 0.5897257197 -0.5703835823 0.405748043534 +1413393277105760512.0000000000 0.6943048636 2.0955764591 1.4458896033 0.4027006829 0.5897716916 -0.5699734895 0.406364040184 +1413393277155760384.0000000000 0.7029319314 2.0881784132 1.4451263632 0.4035090790 0.5889187489 -0.5697166421 0.407158541765 +1413393277205760512.0000000000 0.7121093385 2.0808777391 1.4451450298 0.4046815924 0.5877823029 -0.5691267735 0.408459898779 +1413393277255760384.0000000000 0.7218540147 2.0735403741 1.4459512885 0.4060359375 0.5867945854 -0.5676795844 0.410544542599 +1413393277305760512.0000000000 0.7318502857 2.0661350081 1.4471520406 0.4063528416 0.5861901845 -0.5668750876 0.412202705903 +1413393277355760384.0000000000 0.7420929836 2.0586276237 1.4487558621 0.4058158499 0.5858644571 -0.5659114539 0.414512436759 +1413393277405760512.0000000000 0.7523692014 2.0514359693 1.4506652687 0.4054116084 0.5859567111 -0.5654307261 0.415432611347 +1413393277455760384.0000000000 0.7627660978 2.0443488929 1.4529137716 0.4046848794 0.5859814733 -0.5656782767 0.415769104926 +1413393277505760512.0000000000 0.7731668289 2.0375509261 1.4556076309 0.4033930051 0.5865311270 -0.5653916944 0.416638395266 +1413393277555760384.0000000000 0.7836614820 2.0313631918 1.4590002810 0.4040313497 0.5859236229 -0.5657516985 0.416385869371 +1413393277605760512.0000000000 0.7945303089 2.0255150714 1.4631235718 0.4070948112 0.5831431053 -0.5658347348 0.417191786089 +1413393277655760384.0000000000 0.8052209897 2.0197823332 1.4659424259 0.4092412037 0.5806204408 -0.5669404286 0.417109207848 +1413393277705760512.0000000000 0.8162482745 2.0139837817 1.4672608506 0.4122494640 0.5762454155 -0.5689027392 0.417541942696 +1413393277755760384.0000000000 0.8277266068 2.0075420633 1.4662166334 0.4140125236 0.5711153585 -0.5712453717 0.419642232055 +1413393277805760512.0000000000 0.8387426924 2.0006732434 1.4632543020 0.4146580193 0.5659374106 -0.5744249626 0.421674680955 +1413393277855760384.0000000000 0.8493290554 1.9931937797 1.4578396533 0.4137684522 0.5608187557 -0.5781490975 0.424289538314 +1413393277905760512.0000000000 0.8592095352 1.9849620958 1.4499014269 0.4125318627 0.5548902496 -0.5816462749 0.428487904124 +1413393277955760384.0000000000 0.8681456035 1.9760037389 1.4415257732 0.4112109127 0.5480086255 -0.5857909483 0.432944680694 +1413393278005760512.0000000000 0.8761398825 1.9661735454 1.4338251337 0.4095119561 0.5402557102 -0.5909942958 0.437206436104 +1413393278055760384.0000000000 0.8827879903 1.9553660055 1.4266124233 0.4051777208 0.5336529531 -0.5975211805 0.440470179531 +1413393278105760512.0000000000 0.8881936917 1.9435285726 1.4199427125 0.3980528740 0.5281186535 -0.6049100068 0.443540844834 +1413393278155760384.0000000000 0.8926975798 1.9309048090 1.4144442251 0.3910784803 0.5217740152 -0.6123800045 0.446990189412 +1413393278205760512.0000000000 0.8962811754 1.9176342644 1.4100682592 0.3841109322 0.5154166679 -0.6200957339 0.449761860361 +1413393278255760384.0000000000 0.8992355117 1.9034079905 1.4065711324 0.3767110748 0.5083605275 -0.6288337898 0.451914156713 +1413393278305760512.0000000000 0.9016655803 1.8888982314 1.4042753571 0.3719469766 0.5000773304 -0.6388956256 0.450988347805 +1413393278355760384.0000000000 0.9034869213 1.8738033628 1.4028695083 0.3683081224 0.4925538982 -0.6482388500 0.448916671083 +1413393278405760512.0000000000 0.9052592218 1.8577429810 1.4022577772 0.3656914771 0.4854911307 -0.6572172233 0.445683325952 +1413393278455760384.0000000000 0.9066235808 1.8403329090 1.4017173677 0.3629901163 0.4796396445 -0.6653169677 0.442196019174 +1413393278505760512.0000000000 0.9083218978 1.8211710563 1.4019638638 0.3607881268 0.4752642209 -0.6714871738 0.439386872015 +1413393278555760384.0000000000 0.9103718955 1.7999888599 1.4026399611 0.3588188577 0.4716028293 -0.6768697780 0.436677343566 +1413393278605760512.0000000000 0.9125152621 1.7764559436 1.4043166019 0.3577880583 0.4684200971 -0.6802120139 0.435754442538 +1413393278655760384.0000000000 0.9147141005 1.7507967036 1.4055149820 0.3557845290 0.4675169199 -0.6816787338 0.436072703099 +1413393278705760512.0000000000 0.9176263526 1.7222928495 1.4069063018 0.3517385221 0.4687239653 -0.6796053350 0.441264597485 +1413393278755760384.0000000000 0.9209213214 1.6913541167 1.4094168177 0.3454902701 0.4726844768 -0.6732416274 0.45160997531 +1413393278805760512.0000000000 0.9243870489 1.6591312370 1.4123280456 0.3406806746 0.4758508147 -0.6661686697 0.462300750165 +1413393278855760384.0000000000 0.9282320692 1.6261126936 1.4161441646 0.3353589179 0.4796938958 -0.6600845659 0.470867846 +1413393278905760512.0000000000 0.9317840979 1.5934052183 1.4205762800 0.3314986135 0.4829794147 -0.6553590858 0.476806064184 +1413393278955760384.0000000000 0.9354662864 1.5611327034 1.4254853199 0.3287069151 0.4854216311 -0.6521127177 0.480693881185 +1413393279005760512.0000000000 0.9391813058 1.5297895876 1.4315322356 0.3264514900 0.4879208176 -0.6498429023 0.482770030925 +1413393279055760384.0000000000 0.9428259328 1.4994759172 1.4377273490 0.3253769329 0.4901362678 -0.6485071487 0.48304737712 +1413393279105760512.0000000000 0.9467379860 1.4699682783 1.4438313774 0.3238336657 0.4924314947 -0.6478906795 0.482577089565 +1413393279155760384.0000000000 0.9508687140 1.4415014152 1.4483527787 0.3240501839 0.4936875869 -0.6475596538 0.481591673182 +1413393279205760512.0000000000 0.9551854394 1.4139097638 1.4498433406 0.3229385174 0.4961162982 -0.6470395161 0.480540526205 +1413393279255760384.0000000000 0.9599374208 1.3873594186 1.4484316498 0.3218876207 0.4985089569 -0.6474593115 0.47819830557 +1413393279305760512.0000000000 0.9650599636 1.3617563216 1.4443780729 0.3210266255 0.5006837850 -0.6483642425 0.47526988346 +1413393279355760384.0000000000 0.9705214055 1.3371783498 1.4393473748 0.3196608801 0.5033836059 -0.6497134330 0.471480987931 +1413393279405760512.0000000000 0.9763772031 1.3135409337 1.4342534542 0.3176862994 0.5064831314 -0.6512887949 0.467304139046 +1413393279455760384.0000000000 0.9837097153 1.2903815643 1.4298796886 0.3171902820 0.5084469660 -0.6510967787 0.465773542133 +1413393279505760512.0000000000 0.9923044673 1.2680414995 1.4263843710 0.3179341593 0.5093860602 -0.6504647210 0.465122950126 +1413393279555760384.0000000000 1.0021775667 1.2466459714 1.4239048224 0.3195149130 0.5101237824 -0.6487107246 0.465680515773 +1413393279605760512.0000000000 1.0132708375 1.2259989265 1.4224111245 0.3216141950 0.5105174892 -0.6456384997 0.468067442348 +1413393279655760384.0000000000 1.0254493963 1.2062998857 1.4217743963 0.3244148327 0.5101026872 -0.6423708187 0.471073238578 +1413393279705760512.0000000000 1.0383259404 1.1876517711 1.4208792040 0.3266154203 0.5104080278 -0.6398323013 0.472673924157 +1413393279755760384.0000000000 1.0520816549 1.1698733467 1.4202405054 0.3291762605 0.5098161440 -0.6375986781 0.47455075024 +1413393279805760512.0000000000 1.0660080410 1.1530679797 1.4188402196 0.3321547452 0.5088538655 -0.6357359236 0.476005046486 +1413393279855760384.0000000000 1.0801592227 1.1374205964 1.4165740748 0.3358697216 0.5079662397 -0.6338030882 0.476922923342 +1413393279905760512.0000000000 1.0942811110 1.1224976368 1.4138621425 0.3386163538 0.5067804393 -0.6328404152 0.477520219616 +1413393279955760384.0000000000 1.1081498348 1.1086226028 1.4119323685 0.3422727727 0.5052863483 -0.6316874730 0.478023003333 +1413393280005760512.0000000000 1.1214927982 1.0958374565 1.4101222027 0.3447510212 0.5052141209 -0.6313057025 0.476821282469 +1413393280055760384.0000000000 1.1343583882 1.0837981602 1.4087416615 0.3466648097 0.5050694058 -0.6312171925 0.475702912585 +1413393280105760512.0000000000 1.1466944579 1.0729950158 1.4084334744 0.3505089260 0.5042808953 -0.6316928901 0.473083886795 +1413393280155760384.0000000000 1.1584652869 1.0628476830 1.4091317879 0.3547963571 0.5031486719 -0.6323834276 0.470161843873 +1413393280205760512.0000000000 1.1695563828 1.0531023376 1.4108681917 0.3599198583 0.5015060963 -0.6326831326 0.46761243006 +1413393280255760384.0000000000 1.1799007991 1.0433609082 1.4125793416 0.3632765626 0.5010728220 -0.6339223650 0.463787237052 +1413393280305760512.0000000000 1.1896914890 1.0332482703 1.4152180035 0.3663017733 0.5004201742 -0.6337935818 0.462286010807 +1413393280355760384.0000000000 1.1987317211 1.0228523080 1.4187815572 0.3702751571 0.4991837301 -0.6334558231 0.460918248543 +1413393280405760512.0000000000 1.2070641695 1.0119944782 1.4234111688 0.3754163425 0.4967086384 -0.6329269136 0.460159342391 +1413393280455760384.0000000000 1.2144614233 1.0006304601 1.4285270080 0.3811642489 0.4937029335 -0.6339026335 0.457316826759 +1413393280505760512.0000000000 1.2207264787 0.9883167861 1.4338581506 0.3851629049 0.4925616267 -0.6344169163 0.45447525446 +1413393280555760384.0000000000 1.2257170171 0.9745092019 1.4372392729 0.3846501278 0.4939467152 -0.6368193704 0.450024456253 +1413393280605760512.0000000000 1.2296842902 0.9595199672 1.4389762905 0.3851535738 0.4948731313 -0.6384068905 0.446311495071 +1413393280655760384.0000000000 1.2326317280 0.9432444611 1.4382029434 0.3851480579 0.4959901229 -0.6403411052 0.44228728285 +1413393280705760512.0000000000 1.2346654974 0.9255122862 1.4352662965 0.3857655736 0.4959868878 -0.6424629248 0.438660825334 +1413393280755760384.0000000000 1.2358459971 0.9064968906 1.4300169526 0.3874045249 0.4955385753 -0.6446770711 0.43445451839 +1413393280805760512.0000000000 1.2361203650 0.8857479912 1.4222556377 0.3886367670 0.4953678607 -0.6469941468 0.430082224636 +1413393280855760384.0000000000 1.2360571431 0.8628558063 1.4126834253 0.3880756212 0.4959786285 -0.6494655283 0.42614204195 +1413393280905760512.0000000000 1.2358808077 0.8375656711 1.4034277743 0.3873048224 0.4973710467 -0.6496048545 0.42500652863 +1413393280955760384.0000000000 1.2356776732 0.8098581033 1.3950026078 0.3858571160 0.4992736999 -0.6487844733 0.42534546658 +1413393281005760512.0000000000 1.2364863887 0.7791872279 1.3891198456 0.3806492162 0.5030177530 -0.6465257874 0.429049788025 +1413393281055760384.0000000000 1.2380838725 0.7465307348 1.3855023098 0.3742580812 0.5084352412 -0.6419660086 0.435090953722 +1413393281105760512.0000000000 1.2395192434 0.7126798999 1.3837961205 0.3681359600 0.5128254123 -0.6387019165 0.439938488106 +1413393281155760384.0000000000 1.2419508841 0.6777841047 1.3837250508 0.3625921329 0.5163961631 -0.6351615833 0.445456744325 +1413393281205760512.0000000000 1.2445174606 0.6430581847 1.3851367469 0.3591304368 0.5188926788 -0.6321968782 0.449558477284 +1413393281255760384.0000000000 1.2475461037 0.6083919426 1.3870907950 0.3551885733 0.5212589577 -0.6301075333 0.452873793571 +1413393281305760512.0000000000 1.2510108460 0.5743337375 1.3902418960 0.3523270024 0.5226776648 -0.6283842455 0.455858511068 +1413393281355760384.0000000000 1.2551404915 0.5410729939 1.3944303684 0.3504090378 0.5231861378 -0.6274403020 0.458048511478 +1413393281405760512.0000000000 1.2598302215 0.5086953673 1.3986971831 0.3486023576 0.5236976695 -0.6262824340 0.460420959708 +1413393281455760384.0000000000 1.2650292448 0.4773325896 1.4031228806 0.3479703813 0.5226465726 -0.6268782744 0.461281695842 +1413393281505760512.0000000000 1.2706072573 0.4468681427 1.4073441309 0.3466639059 0.5219963998 -0.6275593864 0.462074789888 +1413393281555760384.0000000000 1.2766772102 0.4175490391 1.4118420719 0.3463335505 0.5209549884 -0.6283184635 0.462466085508 +1413393281605760512.0000000000 1.2835285927 0.3890670153 1.4165995250 0.3463062528 0.5191168161 -0.6287277954 0.463994687336 +1413393281655760384.0000000000 1.2909095042 0.3613607447 1.4220633550 0.3462507052 0.5170962612 -0.6282754114 0.466896041078 +1413393281705760512.0000000000 1.2985748472 0.3349540731 1.4281887813 0.3473576279 0.5146676547 -0.6280162766 0.469100671404 +1413393281755760384.0000000000 1.3066537465 0.3093197506 1.4349569970 0.3480519801 0.5120032744 -0.6268979888 0.472981371541 +1413393281805760512.0000000000 1.3149642775 0.2847443331 1.4425506395 0.3498091536 0.5087060417 -0.6246278075 0.478217336923 +1413393281855760384.0000000000 1.3229810708 0.2618714134 1.4508926744 0.3549523948 0.5034327173 -0.6244646306 0.480216848594 +1413393281905760512.0000000000 1.3301337231 0.2397913272 1.4587292080 0.3567675989 0.4999622244 -0.6251226033 0.481639268899 +1413393281955760384.0000000000 1.3361224054 0.2189145583 1.4665877598 0.3583528070 0.4972816943 -0.6277887589 0.479766043383 +1413393282005760512.0000000000 1.3411646850 0.1986589651 1.4740965436 0.3571477975 0.4964271050 -0.6312983825 0.47693598364 +1413393282055760384.0000000000 1.3455552122 0.1790970491 1.4821934249 0.3562820624 0.4956565481 -0.6356456234 0.472591070421 +1413393282105760512.0000000000 1.3493830424 0.1599993610 1.4905560236 0.3561345171 0.4947261271 -0.6400757103 0.467672267744 +1413393282155760384.0000000000 1.3529449059 0.1411385089 1.4995621942 0.3574770355 0.4927357116 -0.6447381441 0.462314192965 +1413393282205760512.0000000000 1.3565268872 0.1220554997 1.5087666306 0.3578985759 0.4920178892 -0.6481139441 0.458012359554 +1413393282255760384.0000000000 1.3601666733 0.1024192277 1.5183520396 0.3582858784 0.4912304828 -0.6511608508 0.454217336216 +1413393282305760512.0000000000 1.3639985924 0.0817592055 1.5283420565 0.3576250668 0.4913063951 -0.6522028484 0.453159775573 +1413393282355760384.0000000000 1.3682750847 0.0601176573 1.5389897669 0.3559898119 0.4926455258 -0.6497367677 0.456523572802 +1413393282405760512.0000000000 1.3726897456 0.0379251185 1.5499755612 0.3539112743 0.4942122690 -0.6463696411 0.461202049152 +1413393282455760384.0000000000 1.3771638089 0.0154572988 1.5606230349 0.3507029498 0.4966793714 -0.6419754536 0.467102301405 +1413393282505760512.0000000000 1.3814242512 -0.0066393703 1.5698957327 0.3480302441 0.4991343994 -0.6388988495 0.470688921294 +1413393282555760384.0000000000 1.3859938900 -0.0283327636 1.5770640521 0.3461247743 0.5009074961 -0.6360728836 0.474025956826 +1413393282605760512.0000000000 1.3908917385 -0.0492805962 1.5812832073 0.3449712245 0.5022657138 -0.6330621517 0.477447713511 +1413393282655760384.0000000000 1.3958628008 -0.0692333906 1.5830814846 0.3446704058 0.5031737105 -0.6303967743 0.480227482925 +1413393282705760512.0000000000 1.4007159660 -0.0879401515 1.5829470600 0.3453251119 0.5037787744 -0.6280946964 0.482135422849 +1413393282755760384.0000000000 1.4052266197 -0.1049881242 1.5826442651 0.3485814290 0.5042146713 -0.6256089031 0.482568184794 +1413393282805760512.0000000000 1.4091698497 -0.1203076467 1.5824933755 0.3548982124 0.5042543410 -0.6231032961 0.481162239524 +1413393282855760384.0000000000 1.4121017246 -0.1339881805 1.5825037533 0.3611431261 0.5064238009 -0.6207114726 0.477313150958 +1413393282905760512.0000000000 1.4140379479 -0.1467506630 1.5822989334 0.3645894821 0.5112770604 -0.6192350167 0.471400330072 +1413393282955760384.0000000000 1.4150763291 -0.1586012665 1.5822814255 0.3668377386 0.5184257215 -0.6170205685 0.464704705083 +1413393283005760512.0000000000 1.4157010692 -0.1697344375 1.5822897778 0.3683325411 0.5266163315 -0.6150300261 0.45688559339 +1413393283055760384.0000000000 1.4161887377 -0.1801948542 1.5829504703 0.3692852149 0.5359979389 -0.6116192339 0.449729421196 +1413393283105760512.0000000000 1.4166017623 -0.1897706878 1.5841328555 0.3711784112 0.5455536872 -0.6068688617 0.44306652553 +1413393283155760384.0000000000 1.4172093836 -0.1988668774 1.5860909590 0.3736772312 0.5549236960 -0.6001417875 0.43846875995 +1413393283205760512.0000000000 1.4181937264 -0.2071303499 1.5883827001 0.3769600047 0.5638860673 -0.5932184385 0.433619121118 +1413393283255760384.0000000000 1.4200636627 -0.2146967391 1.5907669927 0.3799030745 0.5734875928 -0.5851119328 0.429452745875 +1413393283305760512.0000000000 1.4224065712 -0.2212268393 1.5933665248 0.3842393071 0.5819329587 -0.5776355525 0.424324586878 +1413393283355760384.0000000000 1.4253551427 -0.2266099462 1.5960289935 0.3882539608 0.5907208357 -0.5696867732 0.41924305196 +1413393283405760512.0000000000 1.4290168318 -0.2305974811 1.5984661691 0.3937641583 0.5990334936 -0.5612316243 0.413675869443 +1413393283455760384.0000000000 1.4335338868 -0.2336935577 1.6000921058 0.3990593148 0.6069798584 -0.5533033203 0.407654940452 +1413393283505760512.0000000000 1.4384308462 -0.2357628291 1.6001662219 0.4047496605 0.6148532356 -0.5450111832 0.40136768825 +1413393283555760384.0000000000 1.4439904390 -0.2364788515 1.5987208140 0.4117698865 0.6219496257 -0.5368609907 0.39421377496 +1413393283605760512.0000000000 1.4498802702 -0.2366884081 1.5942511040 0.4179163734 0.6284515965 -0.5295144814 0.387309836696 +1413393283655760384.0000000000 1.4563613745 -0.2361052121 1.5861203544 0.4245577849 0.6348391664 -0.5206193238 0.381687620732 +1413393283705760512.0000000000 1.4628007638 -0.2347732966 1.5761376497 0.4323744608 0.6403347013 -0.5115784354 0.375913953486 +1413393283755760384.0000000000 1.4696750462 -0.2328534985 1.5647517568 0.4398582299 0.6453984972 -0.5015220018 0.372103747681 +1413393283805760512.0000000000 1.4770271122 -0.2298449602 1.5529442408 0.4473033060 0.6507002103 -0.4919464320 0.366739276338 +1413393283855760384.0000000000 1.4841493477 -0.2264267034 1.5409394982 0.4535328455 0.6567858834 -0.4815931183 0.361950728462 +1413393283905760512.0000000000 1.4909438525 -0.2224378769 1.5292667072 0.4585787272 0.6634939251 -0.4714356752 0.356692818155 +1413393283955760384.0000000000 1.4973705802 -0.2177553999 1.5179944358 0.4630000754 0.6709450047 -0.4611065664 0.35049174779 +1413393284005760512.0000000000 1.5030379323 -0.2123521053 1.5072044044 0.4657096415 0.6794576126 -0.4520355318 0.342221800055 +1413393284055760384.0000000000 1.5083358718 -0.2060893391 1.4974423286 0.4697145059 0.6867628501 -0.4424119648 0.334659116125 +1413393284105760512.0000000000 1.5132905152 -0.1989172931 1.4884425540 0.4733260763 0.6945995882 -0.4321278321 0.326740530442 +1413393284155760384.0000000000 1.5181396714 -0.1908029291 1.4805482139 0.4781302928 0.7012999433 -0.4216204608 0.319070524606 +1413393284205760512.0000000000 1.5231384826 -0.1819190011 1.4735913718 0.4827515827 0.7076294900 -0.4111133797 0.31176466016 +1413393284255760384.0000000000 1.5280322917 -0.1719753138 1.4678236486 0.4878400540 0.7139625141 -0.3990741194 0.30497451936 +1413393284305760512.0000000000 1.5325638634 -0.1612355424 1.4628238444 0.4930422625 0.7199513151 -0.3875567343 0.29728640895 +1413393284355760384.0000000000 1.5369105994 -0.1495710728 1.4587052871 0.4994335265 0.7248455318 -0.3755091258 0.29009998966 +1413393284405760512.0000000000 1.5406808786 -0.1370226286 1.4549099063 0.5058600321 0.7297875763 -0.3632444710 0.282080087353 +1413393284455760384.0000000000 1.5439993413 -0.1238470621 1.4515395188 0.5120317180 0.7346036574 -0.3503710726 0.274629018417 +1413393284505760512.0000000000 1.5465182108 -0.1102020840 1.4482527711 0.5181227099 0.7393119153 -0.3377688224 0.266231049973 +1413393284555760384.0000000000 1.5482796423 -0.0961343892 1.4449360873 0.5225281860 0.7450506937 -0.3252859807 0.257007372263 +1413393284605760512.0000000000 1.5490713002 -0.0817995822 1.4418965724 0.5270501720 0.7502987451 -0.3131901556 0.247349622398 +1413393284655760384.0000000000 1.5490647201 -0.0671363600 1.4387964166 0.5311282792 0.7557037826 -0.3028111754 0.234776353434 +1413393284705760512.0000000000 1.5483314001 -0.0523615033 1.4356967225 0.5340689522 0.7618278507 -0.2931980059 0.220053651279 +1413393284755760384.0000000000 1.5474706430 -0.0372168298 1.4332695814 0.5376075106 0.7670514233 -0.2836726683 0.20528052946 +1413393284805760512.0000000000 1.5467874356 -0.0220142520 1.4311420244 0.5410938316 0.7721725385 -0.2725950615 0.191465319692 +1413393284855760384.0000000000 1.5463434558 -0.0069139977 1.4289107685 0.5440210692 0.7774417914 -0.2604559654 0.17829197189 +1413393284905760512.0000000000 1.5463754839 0.0079163529 1.4271611395 0.5468919988 0.7822496092 -0.2478294757 0.166057946413 +1413393284955760384.0000000000 1.5470862958 0.0227681910 1.4257755654 0.5498165224 0.7866848857 -0.2341915246 0.154864495743 +1413393285005760512.0000000000 1.5485438797 0.0376746987 1.4247211757 0.5528853193 0.7906910346 -0.2205975850 0.143046205507 +1413393285055760384.0000000000 1.5510374297 0.0524390299 1.4238654886 0.5553797029 0.7945088881 -0.2067387288 0.132544748252 +1413393285105760512.0000000000 1.5544207391 0.0673049648 1.4237502012 0.5582523414 0.7976690977 -0.1933815856 0.121168874905 +1413393285155760384.0000000000 1.5589025520 0.0820614552 1.4240547690 0.5611330135 0.8004555910 -0.1790456900 0.111100084925 +1413393285205760512.0000000000 1.5641996273 0.0966223942 1.4243976527 0.5632221507 0.8032863455 -0.1654906695 0.100621540705 +1413393285255760384.0000000000 1.5704268038 0.1110721677 1.4247946722 0.5658447197 0.8053178808 -0.1520203357 0.0904028848863 +1413393285305760512.0000000000 1.5775488326 0.1253020022 1.4251466821 0.5675800955 0.8076558728 -0.1380431413 0.0805538166063 +1413393285355760384.0000000000 1.5857302186 0.1394586533 1.4256874497 0.5699006004 0.8090862783 -0.1244977758 0.0713652838406 +1413393285405760512.0000000000 1.5947044239 0.1534172828 1.4261758894 0.5713254450 0.8108762563 -0.1104713603 0.0621531294073 +1413393285455760384.0000000000 1.6044784145 0.1674886264 1.4267414424 0.5723638756 0.8125427774 -0.0965269088 0.0534451557236 +1413393285505760512.0000000000 1.6150948961 0.1814444597 1.4273803573 0.5736544330 0.8136899731 -0.0827633902 0.0444909017327 +1413393285555760384.0000000000 1.6265036426 0.1953444062 1.4282286295 0.5750052189 0.8145091535 -0.0676415929 0.0369925947337 +1413393285605760512.0000000000 1.6385120420 0.2092551941 1.4293870991 0.5767066780 0.8147035465 -0.0528683821 0.0295376547326 +1413393285655760384.0000000000 1.6508582229 0.2228968872 1.4309832724 0.5792490418 0.8139801788 -0.0374587812 0.0224422766472 +1413393285705760512.0000000000 1.6636828620 0.2365094777 1.4328605571 0.5813996157 0.8131575184 -0.0217388054 0.0166361505862 +1413393285755760384.0000000000 1.6768089136 0.2498507644 1.4349928753 0.5835869710 0.8119148973 -0.0044707598 0.0141583550766 +1413393285805760512.0000000000 1.6895684389 0.2625304933 1.4377425544 0.5850477594 0.8108525074 0.0113057506 0.01046472727 +1413393285855760384.0000000000 1.7017851772 0.2745905304 1.4409761879 0.5854394869 0.8103535867 0.0238870931 0.00413260917864 +1413393285905760512.0000000000 1.7136318398 0.2862477228 1.4445867887 0.5842817389 0.8109268788 0.0314777913 -0.00464709854334 +1413393285955760384.0000000000 1.7251092474 0.2975412810 1.4483370918 0.5831970177 0.8113491599 0.0379205129 -0.0124825449663 +1413393286005760512.0000000000 1.7365708217 0.3086673253 1.4521447050 0.5821371743 0.8117844130 0.0417793301 -0.0194130051152 +1413393286055760384.0000000000 1.7480223803 0.3197871061 1.4557773759 0.5802860475 0.8128277928 0.0438587749 -0.0256025442629 +1413393286105760512.0000000000 1.7595010707 0.3311029910 1.4597041672 0.5791139729 0.8134337052 0.0447747927 -0.0307868742839 +1413393286155760384.0000000000 1.7712282754 0.3427407534 1.4640776442 0.5792293671 0.8131878921 0.0451952307 -0.0342955327799 +1413393286205760512.0000000000 1.7833260406 0.3544506903 1.4684351542 0.5790939670 0.8132049459 0.0450325507 -0.0363312902246 +1413393286255760384.0000000000 1.7959506043 0.3663865504 1.4720767819 0.5798520181 0.8126488374 0.0449413676 -0.0367937170983 +1413393286305760512.0000000000 1.8091151581 0.3780983433 1.4735117309 0.5799701650 0.8126188504 0.0441289170 -0.0365766365544 +1413393286355760384.0000000000 1.8227708103 0.3896096002 1.4725828214 0.5807013561 0.8122061205 0.0439285217 -0.0343138153921 +1413393286405760512.0000000000 1.8368764761 0.4009127757 1.4694957812 0.5814691509 0.8117894186 0.0435646116 -0.0315228643861 +1413393286455760384.0000000000 1.8512635805 0.4116332131 1.4628604057 0.5823392591 0.8113318565 0.0427007492 -0.0282533526792 +1413393286505760512.0000000000 1.8655837483 0.4213801399 1.4533225616 0.5826971528 0.8112374064 0.0408465583 -0.0262575169402 +1413393286555760384.0000000000 1.8797533457 0.4310665774 1.4431419469 0.5829728363 0.8112091682 0.0383828027 -0.0246803180889 +1413393286605760512.0000000000 1.8937338625 0.4403617938 1.4336467411 0.5819699899 0.8120766315 0.0354818267 -0.0241560630114 +1413393286655760384.0000000000 1.9079893716 0.4495187994 1.4257274222 0.5812173714 0.8127465613 0.0337962965 -0.0220727149994 +1413393286705760512.0000000000 1.9223762408 0.4586262023 1.4198048201 0.5804579662 0.8133956777 0.0329856984 -0.019182402689 +1413393286755760384.0000000000 1.9367787102 0.4675584113 1.4155704651 0.5796461248 0.8140413178 0.0337017355 -0.0145360227746 +1413393286805760512.0000000000 1.9511270390 0.4763113127 1.4130638713 0.5788973175 0.8145636220 0.0360433852 -0.00805455914976 +1413393286855760384.0000000000 1.9647503397 0.4847712526 1.4119110600 0.5780078828 0.8150707946 0.0395471976 -0.00158313981626 +1413393286905760512.0000000000 1.9769430213 0.4928473003 1.4116218385 0.5777718979 0.8149630196 0.0447336889 0.00371588364662 +1413393286955760384.0000000000 1.9873421058 0.5008609580 1.4122106055 0.5776013325 0.8147217417 0.0506087850 0.00662835725364 +1413393287005760512.0000000000 1.9958174248 0.5092283903 1.4133857048 0.5772813035 0.8145301150 0.0568113538 0.00771093360162 +1413393287055760384.0000000000 2.0019751217 0.5176015939 1.4152377635 0.5781528676 0.8134773738 0.0629020357 0.0060957322401 +1413393287105760512.0000000000 2.0058690736 0.5256763076 1.4173123475 0.5777427507 0.8132782252 0.0691704242 0.00270092371524 +1413393287155760384.0000000000 2.0072902413 0.5332795758 1.4207058445 0.5771362454 0.8131639829 0.0752789185 -0.00334299423851 +1413393287205760512.0000000000 2.0063003586 0.5403892700 1.4246983683 0.5760701195 0.8133901423 0.0797916932 -0.013152167576 +1413393287255760384.0000000000 2.0032317709 0.5469069498 1.4289672017 0.5746208018 0.8136178196 0.0847931624 -0.0254381105965 +1413393287305760512.0000000000 1.9987806946 0.5534168155 1.4340455830 0.5740220014 0.8129222443 0.0905957945 -0.0380600679634 +1413393287355760384.0000000000 1.9932058886 0.5600283310 1.4399731279 0.5741466619 0.8113078806 0.0975416601 -0.0511933399534 +1413393287405760512.0000000000 1.9870362785 0.5663878011 1.4459750331 0.5742741841 0.8092807696 0.1059121655 -0.06368995622 +1413393287455760384.0000000000 1.9804218749 0.5726643260 1.4524786681 0.5731844111 0.8077123830 0.1154731406 -0.0756722600714 +1413393287505760512.0000000000 1.9737362926 0.5788447561 1.4590642178 0.5717782128 0.8059602287 0.1268091939 -0.0861232452285 +1413393287555760384.0000000000 1.9670288824 0.5847856667 1.4655954324 0.5694951723 0.8044841821 0.1389529338 -0.0957733346087 +1413393287605760512.0000000000 1.9603949533 0.5904676133 1.4717851297 0.5667869355 0.8028758033 0.1513332361 -0.106024836398 +1413393287655760384.0000000000 1.9538467603 0.5963618725 1.4777192660 0.5636271850 0.8013399153 0.1632561367 -0.116302065077 +1413393287705760512.0000000000 1.9474329757 0.6024290462 1.4843930413 0.5617178259 0.7985346712 0.1749745185 -0.127276788663 +1413393287755760384.0000000000 1.9412802139 0.6087872082 1.4909323467 0.5598209277 0.7954196006 0.1866630963 -0.138076342514 +1413393287805760512.0000000000 1.9355084834 0.6154448199 1.4966244444 0.5577053570 0.7921985255 0.1987312813 -0.147959821234 +1413393287855760384.0000000000 1.9300472673 0.6222182867 1.5019058877 0.5565365893 0.7879245474 0.2099255045 -0.159289720155 +1413393287905760512.0000000000 1.9253182011 0.6292349760 1.5062050921 0.5545877597 0.7839918630 0.2219626095 -0.168883911389 +1413393287955760384.0000000000 1.9211053999 0.6368127696 1.5103053531 0.5532865099 0.7793970200 0.2339514385 -0.177991706306 +1413393288005760512.0000000000 1.9173878241 0.6450447587 1.5142554377 0.5520247657 0.7747574119 0.2447124093 -0.187444518315 +1413393288055760384.0000000000 1.9144098689 0.6539385666 1.5174129267 0.5495317482 0.7713145346 0.2552828140 -0.194729123139 +1413393288105760512.0000000000 1.9125407106 0.6633610725 1.5194898326 0.5475066566 0.7683306013 0.2645455066 -0.199800458131 +1413393288155760384.0000000000 1.9114802429 0.6733673777 1.5207810601 0.5442541252 0.7669488141 0.2723398501 -0.203489483518 +1413393288205760512.0000000000 1.9109907088 0.6843005046 1.5214232674 0.5410866102 0.7665048932 0.2786568160 -0.205050988731 +1413393288255760384.0000000000 1.9108267384 0.6958029071 1.5213291891 0.5363647101 0.7678945874 0.2837708927 -0.205243467488 +1413393288305760512.0000000000 1.9107324330 0.7080606814 1.5207242155 0.5315414081 0.7696881532 0.2886777562 -0.204227890721 +1413393288355760384.0000000000 1.9103624985 0.7215336987 1.5199413644 0.5273412199 0.7718437612 0.2910070611 -0.203674584521 +1413393288405760512.0000000000 1.9093936716 0.7363441019 1.5194106277 0.5261574063 0.7722692006 0.2922413493 -0.20335599156 +1413393288455760384.0000000000 1.9076077990 0.7524585668 1.5194495029 0.5290131778 0.7701829547 0.2920563997 -0.204123328903 +1413393288505760512.0000000000 1.9055091476 0.7696444277 1.5193811523 0.5325843419 0.7680962541 0.2904039300 -0.205055164922 +1413393288555760384.0000000000 1.9031895913 0.7877664616 1.5192430118 0.5377337006 0.7651663200 0.2882150100 -0.205657671859 +1413393288605760512.0000000000 1.9007128804 0.8058071897 1.5186777191 0.5425688358 0.7616986810 0.2872818256 -0.207131191225 +1413393288655760384.0000000000 1.8985134962 0.8235638498 1.5183141151 0.5471555038 0.7579941827 0.2868061057 -0.209303443409 +1413393288705760512.0000000000 1.8967106218 0.8405186989 1.5175293275 0.5505658465 0.7542679201 0.2878660337 -0.212344767079 +1413393288755760384.0000000000 1.8955953193 0.8567012294 1.5156710058 0.5511859249 0.7520175460 0.2910198703 -0.214408772506 +1413393288805760512.0000000000 1.8950016530 0.8725942613 1.5129796933 0.5513456737 0.7505102333 0.2938842732 -0.215370313256 +1413393288855760384.0000000000 1.8947546524 0.8882449264 1.5092878890 0.5499420476 0.7503098843 0.2972407884 -0.215050541633 +1413393288905760512.0000000000 1.8946168757 0.9036427011 1.5060306811 0.5482580525 0.7502026001 0.2996848372 -0.216328835377 +1413393288955760384.0000000000 1.8949655366 0.9188718266 1.5008215892 0.5460665275 0.7509285727 0.3020122566 -0.216116225816 +1413393289005760512.0000000000 1.8952418963 0.9342394527 1.4939883461 0.5453240223 0.7505311056 0.3039442397 -0.216662570241 +1413393289055760384.0000000000 1.8957828078 0.9492863110 1.4843452997 0.5444623751 0.7503524969 0.3060495968 -0.216484403006 +1413393289105760512.0000000000 1.8965348210 0.9637427196 1.4733143635 0.5444971364 0.7497386024 0.3063916832 -0.218034476696 +1413393289155760384.0000000000 1.8970119223 0.9780347735 1.4617787314 0.5448735972 0.7485205198 0.3069675934 -0.220455644326 +1413393289205760512.0000000000 1.8975156686 0.9921623315 1.4506081401 0.5441604916 0.7480061442 0.3075561171 -0.223126427151 +1413393289255760384.0000000000 1.8985893618 1.0060293426 1.4404647318 0.5446509199 0.7466976724 0.3090179917 -0.224289639417 +1413393289305760512.0000000000 1.9000005033 1.0196680829 1.4317088569 0.5451235360 0.7457052720 0.3102269793 -0.2247736619 +1413393289355760384.0000000000 1.9017783644 1.0329468599 1.4244873826 0.5444829659 0.7454648140 0.3118477971 -0.224880996044 +1413393289405760512.0000000000 1.9039068754 1.0460691420 1.4183117230 0.5442050555 0.7451900794 0.3142082802 -0.223172040459 +1413393289455760384.0000000000 1.9061418454 1.0588662141 1.4140071670 0.5432260426 0.7456534762 0.3153480521 -0.22240046352 +1413393289505760512.0000000000 1.9084632420 1.0713098078 1.4119614659 0.5415075870 0.7468214563 0.3159294719 -0.22184637566 +1413393289555760384.0000000000 1.9106372061 1.0835735733 1.4116277946 0.5408655137 0.7471733370 0.3170979214 -0.22055704224 +1413393289605760512.0000000000 1.9127775268 1.0956514707 1.4120034038 0.5404158982 0.7476765343 0.3175702919 -0.219270533167 +1413393289655760384.0000000000 1.9145707518 1.1074583040 1.4124887118 0.5397023668 0.7482197574 0.3179310417 -0.218651326701 +1413393289705760512.0000000000 1.9161565601 1.1188383410 1.4130235087 0.5390249480 0.7487956800 0.3178819222 -0.218422111338 +1413393289755760384.0000000000 1.9172742957 1.1303413588 1.4140215667 0.5395596482 0.7488389108 0.3171773223 -0.217977563024 +1413393289805760512.0000000000 1.9180148014 1.1415657644 1.4155638586 0.5404276018 0.7485591679 0.3162806550 -0.218091097169 +1413393289855760384.0000000000 1.9183503504 1.1527865078 1.4177968507 0.5418987522 0.7479917743 0.3148523353 -0.218453781901 +1413393289905760512.0000000000 1.9183852103 1.1639695718 1.4203641746 0.5438255462 0.7472575285 0.3136988883 -0.217837023712 +1413393289955760384.0000000000 1.9181266258 1.1748270177 1.4235804042 0.5455030644 0.7466294244 0.3123536998 -0.217729363025 +1413393290005760512.0000000000 1.9179040040 1.1851841304 1.4264967186 0.5462466721 0.7467272562 0.3111216854 -0.217293062281 +1413393290055760384.0000000000 1.9177900123 1.1948481530 1.4279940165 0.5462211336 0.7474183653 0.3095879306 -0.21717176086 +1413393290105760512.0000000000 1.9176731528 1.2043015075 1.4272870498 0.5465507809 0.7479167409 0.3078394425 -0.217112114531 +1413393290155760384.0000000000 1.9175461291 1.2131324680 1.4237376184 0.5466927300 0.7484538268 0.3062318686 -0.217177279743 +1413393290205760512.0000000000 1.9176923016 1.2213932397 1.4173960975 0.5460579337 0.7497164990 0.3042790671 -0.217163886115 +1413393290255760384.0000000000 1.9179691213 1.2293125244 1.4089121838 0.5457280696 0.7506310517 0.3029099526 -0.216747454364 +1413393290305760512.0000000000 1.9183470541 1.2369354522 1.3977204829 0.5446108587 0.7521083534 0.3023933977 -0.215151737861 +1413393290355760384.0000000000 1.9185366091 1.2444920263 1.3853170209 0.5432484614 0.7535708612 0.3025230003 -0.213288303964 +1413393290405760512.0000000000 1.9185676532 1.2517499874 1.3727131562 0.5412396226 0.7548078748 0.3038580673 -0.212120291399 +1413393290455760384.0000000000 1.9183135683 1.2586380917 1.3600323995 0.5388936023 0.7554939427 0.3063495054 -0.212067367605 +1413393290505760512.0000000000 1.9177637823 1.2652763777 1.3475610211 0.5364629550 0.7557391688 0.3096530757 -0.212557708433 +1413393290555760384.0000000000 1.9167013168 1.2722562239 1.3356899660 0.5347767022 0.7556071246 0.3125440774 -0.213044483037 +1413393290605760512.0000000000 1.9150600001 1.2795837565 1.3244206296 0.5337135220 0.7550260160 0.3150412556 -0.214090165512 +1413393290655760384.0000000000 1.9127947016 1.2872645769 1.3132840633 0.5319146864 0.7551859181 0.3168069388 -0.215393497992 +1413393290705760512.0000000000 1.9099026521 1.2953316898 1.3018277776 0.5304539747 0.7551242981 0.3190613546 -0.215883596342 +1413393290755760384.0000000000 1.9062566116 1.3039895036 1.2905275176 0.5306526615 0.7541064317 0.3204330785 -0.216919073933 +1413393290805760512.0000000000 1.9025711840 1.3124746212 1.2789498521 0.5310763542 0.7529947329 0.3220727442 -0.217315406205 +1413393290855760384.0000000000 1.8985917761 1.3210167188 1.2669094853 0.5315948734 0.7521629084 0.3228330871 -0.217799558471 +1413393290905760512.0000000000 1.8938849675 1.3295485145 1.2549221103 0.5315024289 0.7518418929 0.3220987948 -0.220207407998 +1413393290955760384.0000000000 1.8881357857 1.3384178932 1.2436424013 0.5312947565 0.7515746222 0.3193618725 -0.225542597792 +1413393291005760512.0000000000 1.8821103107 1.3480966756 1.2320231099 0.5314841360 0.7511870857 0.3165643314 -0.230281565892 +1413393291055760384.0000000000 1.8760431169 1.3584569839 1.2201364394 0.5323000128 0.7505646812 0.3127871425 -0.235528255706 +1413393291105760512.0000000000 1.8705564556 1.3693334767 1.2073205021 0.5330511630 0.7498916632 0.3098759743 -0.239782884311 +1413393291155760384.0000000000 1.8655785813 1.3810622798 1.1950493185 0.5355841562 0.7482037820 0.3069806640 -0.243112287141 +1413393291205760512.0000000000 1.8617310374 1.3932121536 1.1825738405 0.5374555553 0.7470252722 0.3048461694 -0.245282656917 +1413393291255760384.0000000000 1.8590128650 1.4059067344 1.1702842488 0.5392431678 0.7459885762 0.3032940136 -0.246435775469 +1413393291305760512.0000000000 1.8578599499 1.4190926232 1.1572976507 0.5403890053 0.7457611197 0.3037956794 -0.243984139696 +1413393291355760384.0000000000 1.8576513032 1.4326150418 1.1440863001 0.5402909304 0.7463493306 0.3056974294 -0.239994726841 +1413393291405760512.0000000000 1.8582501422 1.4461181154 1.1311775975 0.5403035283 0.7463144282 0.3089554530 -0.235867334887 +1413393291455760384.0000000000 1.8598712654 1.4589933433 1.1185471532 0.5392874023 0.7464542088 0.3132293008 -0.232083211391 +1413393291505760512.0000000000 1.8619556311 1.4715315754 1.1070731804 0.5384668609 0.7459420455 0.3175644289 -0.229731882832 +1413393291555760384.0000000000 1.8642206533 1.4842487530 1.0969912026 0.5379555312 0.7453869424 0.3211648534 -0.227717565041 +1413393291605760512.0000000000 1.8662707774 1.4969540991 1.0882771437 0.5379152705 0.7443569033 0.3242514642 -0.226805974712 +1413393291655760384.0000000000 1.8680745097 1.5098255140 1.0807181616 0.5378332831 0.7434370682 0.3272439803 -0.225716775195 +1413393291705760512.0000000000 1.8696538503 1.5226002165 1.0743333885 0.5370604677 0.7431551409 0.3296010358 -0.225054766125 +1413393291755760384.0000000000 1.8709740466 1.5351683443 1.0694305771 0.5367405417 0.7425817869 0.3317589731 -0.224539226903 +1413393291805760512.0000000000 1.8718338668 1.5472404032 1.0663939995 0.5365275875 0.7415964125 0.3342574839 -0.22459929494 +1413393291855760384.0000000000 1.8720917600 1.5586329134 1.0662713550 0.5354372332 0.7404296820 0.3378530362 -0.225668299102 +1413393291905760512.0000000000 1.8715028605 1.5697997709 1.0703039510 0.5348641767 0.7388178837 0.3412987822 -0.227120207121 +1413393291955760384.0000000000 1.8705798625 1.5805191140 1.0780872622 0.5349573407 0.7371851272 0.3440991303 -0.227979210319 +1413393292005760512.0000000000 1.8692857184 1.5905352759 1.0887088539 0.5365310371 0.7344773911 0.3462764517 -0.229717276771 +1413393292055760384.0000000000 1.8679461590 1.5998883861 1.1005220669 0.5389961368 0.7313417144 0.3481837508 -0.231063924033 +1413393292105760512.0000000000 1.8661418786 1.6086189006 1.1124496056 0.5410550790 0.7284986240 0.3490996364 -0.233834557321 +1413393292155760384.0000000000 1.8640355820 1.6168767141 1.1242187393 0.5437863871 0.7254283121 0.3500258065 -0.235652421983 +1413393292205760512.0000000000 1.8620783279 1.6237033776 1.1360006628 0.5458117995 0.7223909186 0.3516829647 -0.237823322352 +1413393292255760384.0000000000 1.8602445381 1.6293014322 1.1471687520 0.5479088640 0.7192156876 0.3535524815 -0.239844354125 +1413393292305760512.0000000000 1.8588194343 1.6333171216 1.1580371668 0.5487365181 0.7172175770 0.3547307866 -0.242184330576 +1413393292355760384.0000000000 1.8579418029 1.6356935526 1.1678158629 0.5487075088 0.7158637333 0.3557903460 -0.244688403711 +1413393292405760512.0000000000 1.8571263847 1.6368802371 1.1780768209 0.5480952276 0.7151112533 0.3558518886 -0.248147033508 +1413393292455760384.0000000000 1.8565890025 1.6370754699 1.1886344060 0.5485227369 0.7136649514 0.3565304151 -0.250382122728 +1413393292505760512.0000000000 1.8565893800 1.6358826272 1.1981081938 0.5467062222 0.7137597463 0.3584811565 -0.25129781455 +1413393292555760384.0000000000 1.8570464431 1.6338011963 1.2074291716 0.5456150994 0.7135040140 0.3602458104 -0.251871279524 +1413393292605760512.0000000000 1.8582203080 1.6302427689 1.2163358352 0.5434521318 0.7138989788 0.3629697934 -0.251517310647 +1413393292655760384.0000000000 1.8600488604 1.6253175619 1.2251927956 0.5419388248 0.7138045603 0.3665084889 -0.249913759944 +1413393292705760512.0000000000 1.8614674081 1.6196236341 1.2341503557 0.5405314157 0.7136474205 0.3695875996 -0.248873771516 +1413393292755760384.0000000000 1.8624939912 1.6127999291 1.2428842518 0.5394946910 0.7127352194 0.3727830383 -0.24897146803 +1413393292805760512.0000000000 1.8639231742 1.6046786574 1.2524635642 0.5393692834 0.7115056541 0.3747279947 -0.2498387685 +1413393292855760384.0000000000 1.8652025741 1.5951345065 1.2629611483 0.5398014917 0.7096816921 0.3761636623 -0.251926863411 +1413393292905760512.0000000000 1.8662840985 1.5842083908 1.2742889332 0.5399689544 0.7079006762 0.3776075767 -0.254406522969 +1413393292955760384.0000000000 1.8672685783 1.5718421418 1.2861262380 0.5389797268 0.7071207754 0.3779724580 -0.258104405609 +1413393293005760512.0000000000 1.8683364153 1.5582161851 1.2977230515 0.5370246622 0.7069798520 0.3791848335 -0.260773585898 +1413393293055760384.0000000000 1.8697407708 1.5434661991 1.3092829116 0.5352313928 0.7068374038 0.3801166969 -0.263475876457 +1413393293105760512.0000000000 1.8714171356 1.5277921061 1.3205619077 0.5331181541 0.7069771735 0.3814870076 -0.265397763769 +1413393293155760384.0000000000 1.8731263504 1.5111683897 1.3322124435 0.5305338687 0.7075955235 0.3816248782 -0.268709585908 +1413393293205760512.0000000000 1.8752015203 1.4939424851 1.3438417190 0.5287696665 0.7077713804 0.3825133082 -0.270454953531 +1413393293255760384.0000000000 1.8773464237 1.4759492719 1.3553841087 0.5263297108 0.7085673326 0.3820385121 -0.273780835623 +1413393293305760512.0000000000 1.8799143921 1.4574624597 1.3647539178 0.5238323118 0.7093798456 0.3826175690 -0.275651482231 +1413393293355760384.0000000000 1.8827777162 1.4386522652 1.3718713794 0.5221322764 0.7098819880 0.3811155766 -0.279636132094 +1413393293405760512.0000000000 1.8861789400 1.4196000013 1.3754097727 0.5200341928 0.7107362991 0.3800124623 -0.282858409639 +1413393293455760384.0000000000 1.8900018636 1.4008439562 1.3768718835 0.5181213162 0.7117022559 0.3785766267 -0.285849503005 +1413393293505760512.0000000000 1.8943004211 1.3824498830 1.3753192464 0.5167658439 0.7125189070 0.3785876371 -0.286253857022 +1413393293555760384.0000000000 1.8989590826 1.3644791794 1.3723461462 0.5168140504 0.7123741995 0.3800019358 -0.284648495573 +1413393293605760512.0000000000 1.9042479354 1.3466165515 1.3681279263 0.5176912587 0.7116214676 0.3824482500 -0.281645137598 +1413393293655760384.0000000000 1.9101040044 1.3288703565 1.3637738452 0.5184452239 0.7111398212 0.3855806915 -0.277168242881 +1413393293705760512.0000000000 1.9162189407 1.3110757474 1.3598806384 0.5191059649 0.7103543632 0.3895828111 -0.272306645463 +1413393293755760384.0000000000 1.9221580438 1.2928716281 1.3570800933 0.5197145143 0.7095531123 0.3928303717 -0.268543299354 +1413393293805760512.0000000000 1.9280199135 1.2741413202 1.3553008018 0.5203981986 0.7088806103 0.3949590922 -0.265859569424 +1413393293855760384.0000000000 1.9336331885 1.2544638543 1.3545234614 0.5201799480 0.7085320682 0.3967620127 -0.264527948096 +1413393293905760512.0000000000 1.9387466561 1.2339906455 1.3546081772 0.5201406585 0.7080834384 0.3982247546 -0.263606874984 +1413393293955760384.0000000000 1.9433155877 1.2128536064 1.3555425864 0.5201900053 0.7076907256 0.3999917899 -0.261883109955 +1413393294005760512.0000000000 1.9470115235 1.1908122038 1.3575806397 0.5202039828 0.7072062440 0.4007331140 -0.262030754264 +1413393294055760384.0000000000 1.9500367046 1.1680114052 1.3601342824 0.5201934932 0.7069081173 0.4013004640 -0.261987749512 +1413393294105760512.0000000000 1.9521930409 1.1445110230 1.3640760522 0.5224227079 0.7050513828 0.4001289808 -0.264336642549 +1413393294155760384.0000000000 1.9537991345 1.1202514591 1.3690250355 0.5249998241 0.7030674641 0.3977062153 -0.268143789839 +1413393294205760512.0000000000 1.9551735508 1.0952063028 1.3744210315 0.5271009946 0.7015880827 0.3947903097 -0.272175155224 +1413393294255760384.0000000000 1.9569819021 1.0695606152 1.3791514689 0.5277884031 0.7014731214 0.3937409815 -0.272658946178 +1413393294305760512.0000000000 1.9592712565 1.0431471328 1.3832461164 0.5275060459 0.7020781486 0.3939809693 -0.271298066031 +1413393294355760384.0000000000 1.9617780633 1.0160099250 1.3867277340 0.5262912604 0.7036189989 0.3941021178 -0.269483458579 +1413393294405760512.0000000000 1.9643770836 0.9881171838 1.3899862789 0.5253988597 0.7048980904 0.3947985669 -0.266849792801 +1413393294455760384.0000000000 1.9668666173 0.9596866573 1.3929091162 0.5250017577 0.7060444721 0.3954752105 -0.263578670926 +1413393294505760512.0000000000 1.9688162204 0.9304497450 1.3956795734 0.5235129928 0.7079341184 0.3958815761 -0.260847097102 +1413393294555760384.0000000000 1.9701279889 0.9005246210 1.3986217708 0.5220610809 0.7098451132 0.3952113627 -0.259576813008 +1413393294605760512.0000000000 1.9708341642 0.8700451219 1.4015373210 0.5204097562 0.7119432878 0.3934527167 -0.25981801398 +1413393294655760384.0000000000 1.9711504522 0.8389996830 1.4044444947 0.5188191646 0.7138097144 0.3909424895 -0.261660726875 +1413393294705760512.0000000000 1.9712534450 0.8075330079 1.4072351289 0.5164658241 0.7160649070 0.3884784292 -0.263815487878 +1413393294755760384.0000000000 1.9710051099 0.7760378367 1.4100496834 0.5150853603 0.7177628240 0.3854105219 -0.266387555515 +1413393294805760512.0000000000 1.9705025364 0.7445802382 1.4127090169 0.5133347212 0.7196490565 0.3820306913 -0.269527828586 +1413393294855760384.0000000000 1.9699826059 0.7133994201 1.4149527782 0.5114385719 0.7212802488 0.3806013743 -0.270791402745 +1413393294905760512.0000000000 1.9692986863 0.6829634070 1.4173394119 0.5107852717 0.7223122660 0.3800759718 -0.270010466772 +1413393294955760384.0000000000 1.9684065831 0.6532746817 1.4199910779 0.5114226437 0.7222403268 0.3809680674 -0.26772956798 +1413393295005760512.0000000000 1.9673368151 0.6238279611 1.4227096698 0.5123567709 0.7214639323 0.3833802383 -0.264574992305 +1413393295055760384.0000000000 1.9661160757 0.5949589842 1.4259100209 0.5141994710 0.7205952990 0.3852770543 -0.260581869041 +1413393295105760512.0000000000 1.9643923263 0.5661081802 1.4294440948 0.5156056688 0.7197000665 0.3873331662 -0.257207361761 +1413393295155760384.0000000000 1.9618628599 0.5368136817 1.4335684754 0.5156733415 0.7195169183 0.3877544687 -0.256949180168 +1413393295205760512.0000000000 1.9586997052 0.5076102133 1.4380387188 0.5156931879 0.7198439228 0.3862469275 -0.258260670163 +1413393295255760384.0000000000 1.9550690418 0.4782135466 1.4423990580 0.5141757615 0.7210933477 0.3845702013 -0.260294891261 +1413393295305760512.0000000000 1.9509547591 0.4489905793 1.4469202556 0.5125398310 0.7223030657 0.3825545726 -0.263122028416 +1413393295355760384.0000000000 1.9463968510 0.4201586347 1.4517361201 0.5112027969 0.7235304489 0.3805981114 -0.265180066377 +1413393295405760512.0000000000 1.9414301458 0.3916749664 1.4568713046 0.5080374058 0.7255920774 0.3781979282 -0.269036166134 +1413393295455760384.0000000000 1.9360792856 0.3641798144 1.4624242121 0.5066763557 0.7266124805 0.3757994677 -0.272191355125 +1413393295505760512.0000000000 1.9306371824 0.3375890866 1.4675987924 0.5045393544 0.7281648382 0.3731039749 -0.275698081624 +1413393295555760384.0000000000 1.9250852706 0.3119494503 1.4715521270 0.5027566862 0.7290355193 0.3710753425 -0.279367171017 +1413393295605760512.0000000000 1.9198894849 0.2876709807 1.4730170624 0.5016485396 0.7299129236 0.3693448358 -0.281354329854 +1413393295655760384.0000000000 1.9151879957 0.2644696394 1.4723697861 0.5007115222 0.7303808866 0.3683444030 -0.283115052188 +1413393295705760512.0000000000 1.9118119679 0.2420021715 1.4693558182 0.5000500801 0.7306010052 0.3682987767 -0.283774734051 +1413393295755760384.0000000000 1.9086571278 0.2211762494 1.4638511030 0.5003637125 0.7303742081 0.3689480338 -0.282961162767 +1413393295805760512.0000000000 1.9055637779 0.2017507000 1.4568341066 0.5017725314 0.7292197761 0.3711237995 -0.28058861389 +1413393295855760384.0000000000 1.9028966631 0.1837644780 1.4494121396 0.5046246543 0.7270555292 0.3756269124 -0.275042975433 +1413393295905760512.0000000000 1.9002582335 0.1670454346 1.4425904069 0.5080472868 0.7246415441 0.3803717517 -0.268514277879 +1413393295955760384.0000000000 1.8972855813 0.1509884094 1.4368623169 0.5112817235 0.7220151632 0.3857247615 -0.261727934487 +1413393296005760512.0000000000 1.8936855886 0.1350362685 1.4324733031 0.5139385690 0.7198375156 0.3892924533 -0.257201252431 +1413393296055760384.0000000000 1.8893536966 0.1189412995 1.4291713103 0.5158129131 0.7183316533 0.3923433626 -0.252988854311 +1413393296105760512.0000000000 1.8839730137 0.1022129346 1.4270878999 0.5165801961 0.7173788982 0.3947080068 -0.250435634177 +1413393296155760384.0000000000 1.8773752688 0.0849797521 1.4262136393 0.5166989459 0.7173360622 0.3951394999 -0.249631626258 +1413393296205760512.0000000000 1.8697513741 0.0671926737 1.4259821891 0.5163709101 0.7176390179 0.3960757048 -0.247950316085 +1413393296255760384.0000000000 1.8608253165 0.0486367232 1.4264837456 0.5152504917 0.7183080312 0.3967299272 -0.247297124664 +1413393296305760512.0000000000 1.8504987471 0.0296541841 1.4278489855 0.5150400036 0.7186923813 0.3968590541 -0.246410119378 +1413393296355760384.0000000000 1.8387969391 0.0099610444 1.4300442700 0.5135870698 0.7200538934 0.3953728313 -0.247852852594 +1413393296405760512.0000000000 1.8257882706 -0.0101047079 1.4329205067 0.5113928986 0.7221026025 0.3925312911 -0.250926922129 +1413393296455760384.0000000000 1.8119807512 -0.0301972670 1.4346500263 0.5088854464 0.7248381482 0.3888902259 -0.25379057032 +1413393296505760512.0000000000 1.7976726837 -0.0501902077 1.4337427070 0.5070481548 0.7277952503 0.3842322984 -0.256089404819 +1413393296555760384.0000000000 1.7832422008 -0.0697650356 1.4300827859 0.5064844643 0.7306384574 0.3789181698 -0.25702519831 +1413393296605760512.0000000000 1.7683797625 -0.0887634526 1.4236097428 0.5065575474 0.7334071853 0.3730032305 -0.257646932437 +1413393296655760384.0000000000 1.7531700715 -0.1068038188 1.4141118958 0.5070343192 0.7363482721 0.3672264257 -0.256616783542 +1413393296705760512.0000000000 1.7375631350 -0.1241551658 1.4035181798 0.5078156072 0.7390057382 0.3610959648 -0.256131864749 +1413393296755760384.0000000000 1.7216414347 -0.1407998197 1.3925388175 0.5080023424 0.7417356271 0.3559183277 -0.255115706295 +1413393296805760512.0000000000 1.7053595045 -0.1564150926 1.3824508124 0.5088129903 0.7436707239 0.3513378777 -0.254214261938 +1413393296855760384.0000000000 1.6890230958 -0.1709253454 1.3730451775 0.5104669289 0.7448502287 0.3478513342 -0.252232235492 +1413393296905760512.0000000000 1.6726923322 -0.1845174277 1.3642013310 0.5119039481 0.7457587477 0.3455086279 -0.249844003693 +1413393296955760384.0000000000 1.6562162565 -0.1969825685 1.3561668329 0.5138839831 0.7462103174 0.3433194207 -0.247437243497 +1413393297005760512.0000000000 1.6396436458 -0.2083196155 1.3488141914 0.5153459464 0.7469916135 0.3414336934 -0.244632618159 +1413393297055760384.0000000000 1.6229157837 -0.2186365147 1.3420920417 0.5171583967 0.7478694934 0.3389244945 -0.241595945002 +1413393297105760512.0000000000 1.6060575380 -0.2281435960 1.3356160338 0.5185250915 0.7491593097 0.3356530778 -0.239225979875 +1413393297155760384.0000000000 1.5892573434 -0.2372523232 1.3293570339 0.5193165178 0.7505250504 0.3327195977 -0.237318714895 +1413393297205760512.0000000000 1.5722802869 -0.2457745636 1.3235748044 0.5195789940 0.7518310020 0.3292629917 -0.237431454739 +1413393297255760384.0000000000 1.5552315348 -0.2534569477 1.3181030449 0.5199047883 0.7528925111 0.3257245613 -0.238233893465 +1413393297305760512.0000000000 1.5384104727 -0.2602579388 1.3126633349 0.5207119246 0.7534088221 0.3231314097 -0.238370154387 +1413393297355760384.0000000000 1.5218072564 -0.2660674019 1.3073109947 0.5214538004 0.7538156988 0.3217812457 -0.237286021882 +1413393297405760512.0000000000 1.5050589386 -0.2708695873 1.3024066084 0.5227328356 0.7536586587 0.3205776944 -0.236598712208 +1413393297455760384.0000000000 1.4885455668 -0.2747693053 1.2975204715 0.5236234788 0.7537894034 0.3203585614 -0.234500276938 +1413393297505760512.0000000000 1.4719937213 -0.2778843041 1.2928071066 0.5248996643 0.7531990472 0.3212777131 -0.232276061729 +1413393297555760384.0000000000 1.4552261637 -0.2804877086 1.2881480956 0.5257447185 0.7527291070 0.3211597190 -0.232051324954 +1413393297605760512.0000000000 1.4383503220 -0.2823394772 1.2835682243 0.5262928295 0.7524139252 0.3209174805 -0.23216613344 +1413393297655760384.0000000000 1.4215452466 -0.2839178969 1.2793294365 0.5260471669 0.7523965311 0.3197321094 -0.234403959793 +1413393297705760512.0000000000 1.4047844234 -0.2849107450 1.2753912844 0.5253914710 0.7525870923 0.3182307608 -0.237288123613 +1413393297755760384.0000000000 1.3881940061 -0.2851221817 1.2716723469 0.5256346811 0.7521339071 0.3164888775 -0.240494403916 +1413393297805760512.0000000000 1.3719990456 -0.2844869045 1.2678008070 0.5254878288 0.7518555056 0.3150505924 -0.243554849564 +1413393297855760384.0000000000 1.3564797546 -0.2830263491 1.2638654831 0.5262069169 0.7510502754 0.3134615538 -0.246519002593 +1413393297905760512.0000000000 1.3417500592 -0.2807500362 1.2596238552 0.5259628646 0.7507315423 0.3134763931 -0.247987434082 +1413393297955760384.0000000000 1.3277048234 -0.2774918103 1.2555735507 0.5255397962 0.7505044929 0.3138336176 -0.24911721978 +1413393298005760512.0000000000 1.3145730768 -0.2733241837 1.2513884324 0.5252881454 0.7503301744 0.3140944676 -0.249843269088 +1413393298055760384.0000000000 1.3022808132 -0.2684955787 1.2473423467 0.5247256970 0.7501979011 0.3149491358 -0.250345948372 +1413393298105760512.0000000000 1.2909886120 -0.2625566621 1.2431223904 0.5237623962 0.7506722616 0.3164321830 -0.249067825253 +1413393298155760384.0000000000 1.2803333091 -0.2557603738 1.2385150494 0.5220130820 0.7513924062 0.3190035179 -0.24728232782 +1413393298205760512.0000000000 1.2702068818 -0.2478652204 1.2334906946 0.5206841114 0.7519177828 0.3225466545 -0.243867504507 +1413393298255760384.0000000000 1.2601948186 -0.2388400424 1.2285056444 0.5207495002 0.7516538381 0.3262480778 -0.239580169057 +1413393298305760512.0000000000 1.2499989845 -0.2291774409 1.2234221800 0.5206351368 0.7511598313 0.3310630352 -0.234723728802 +1413393298355760384.0000000000 1.2395511674 -0.2187834644 1.2182574336 0.5209956517 0.7503594061 0.3359965274 -0.229413657576 +1413393298405760512.0000000000 1.2284369384 -0.2078084417 1.2131795335 0.5229001779 0.7485248743 0.3408279339 -0.223879959013 +1413393298455760384.0000000000 1.2161333539 -0.1968217118 1.2086784898 0.5261049317 0.7455317085 0.3450073545 -0.219922708598 +1413393298505760512.0000000000 1.2026165290 -0.1860303527 1.2047136190 0.5292446404 0.7426427592 0.3479588149 -0.217500588393 +1413393298555760384.0000000000 1.1876851699 -0.1757261617 1.2012542124 0.5320206521 0.7402643235 0.3492484623 -0.21676777576 +1413393298605760512.0000000000 1.1715752746 -0.1663228171 1.1984468603 0.5329247843 0.7391307369 0.3490170284 -0.218778522535 +1413393298655760384.0000000000 1.1541180200 -0.1579787290 1.1961539175 0.5319625957 0.7393241004 0.3474929962 -0.222854860691 +1413393298705760512.0000000000 1.1356618559 -0.1502320243 1.1945965690 0.5302961163 0.7402843665 0.3443948157 -0.228379720458 +1413393298755760384.0000000000 1.1166925075 -0.1428236014 1.1931018593 0.5282414226 0.7414524369 0.3413690761 -0.233829932322 +1413393298805760512.0000000000 1.0974221214 -0.1352640146 1.1918709735 0.5268155880 0.7423865889 0.3385689627 -0.238114565799 +1413393298855760384.0000000000 1.0780323423 -0.1277319058 1.1910872133 0.5255574167 0.7432170891 0.3361153241 -0.241752454429 +1413393298905760512.0000000000 1.0588556073 -0.1198383995 1.1906108676 0.5248414454 0.7439210703 0.3339405552 -0.244144637235 +1413393298955760384.0000000000 1.0400230441 -0.1115940233 1.1899307241 0.5236925778 0.7451905985 0.3319823061 -0.24540742497 +1413393299005760512.0000000000 1.0213278972 -0.1029790090 1.1897706905 0.5232597583 0.7459703697 0.3300422880 -0.246575588738 +1413393299055760384.0000000000 1.0030684388 -0.0937598933 1.1897511163 0.5232768869 0.7466626482 0.3292474257 -0.245504220237 +1413393299105760512.0000000000 0.9849512116 -0.0838333415 1.1902662530 0.5248603348 0.7462716650 0.3288816051 -0.243797294373 +1413393299155760384.0000000000 0.9671401593 -0.0732444675 1.1906827424 0.5283642737 0.7446318487 0.3297577287 -0.24003009102 +1413393299205760512.0000000000 0.9493843723 -0.0623897112 1.1914720658 0.5338352512 0.7416856357 0.3307501793 -0.235640958193 +1413393299255760384.0000000000 0.9314412949 -0.0519609503 1.1930682737 0.5400661181 0.7379585296 0.3307549066 -0.233124405671 +1413393299305760512.0000000000 0.9134216657 -0.0422863788 1.1951925510 0.5469325733 0.7336755087 0.3298093343 -0.231971574055 +1413393299355760384.0000000000 0.8956944520 -0.0338369406 1.1976378463 0.5526751307 0.7301959755 0.3270358634 -0.23326290173 +1413393299405760512.0000000000 0.8784153750 -0.0269144212 1.1996353551 0.5566157056 0.7278298627 0.3243580040 -0.235020281075 +1413393299455760384.0000000000 0.8620252610 -0.0215683318 1.2015606923 0.5578754429 0.7273234904 0.3216741516 -0.237278887928 +1413393299505760512.0000000000 0.8464428565 -0.0175275026 1.2033950646 0.5576334467 0.7279066796 0.3192121815 -0.239374994828 +1413393299555760384.0000000000 0.8318334232 -0.0150097149 1.2051016636 0.5555131463 0.7297792409 0.3172746741 -0.241172521262 +1413393299605760512.0000000000 0.8182765966 -0.0137963398 1.2069558750 0.5525683367 0.7320836845 0.3158159685 -0.24286207263 +1413393299655760384.0000000000 0.8057764488 -0.0134499019 1.2089785250 0.5488782790 0.7348966776 0.3143043183 -0.244688176242 +1413393299705760512.0000000000 0.7944435675 -0.0135912893 1.2115040381 0.5457314298 0.7372807334 0.3142079208 -0.244678787679 +1413393299755760384.0000000000 0.7841015693 -0.0142202307 1.2148641965 0.5444285720 0.7381536115 0.3142280213 -0.244923511428 +1413393299805760512.0000000000 0.7747250335 -0.0153295335 1.2183947854 0.5446233935 0.7378157628 0.3155031205 -0.243866849611 +1413393299855760384.0000000000 0.7663009580 -0.0166574953 1.2221031948 0.5446081071 0.7376533498 0.3173763381 -0.241954138605 +1413393299905760512.0000000000 0.7585474133 -0.0183456092 1.2257547881 0.5436870904 0.7379933779 0.3208711521 -0.238352314248 +1413393299955760384.0000000000 0.7514348859 -0.0202808388 1.2295255442 0.5434106742 0.7380185378 0.3252637562 -0.232888312272 +1413393300005760512.0000000000 0.7444300110 -0.0228768431 1.2337901320 0.5440844148 0.7371817365 0.3293741629 -0.228140083423 +1413393300055760384.0000000000 0.7372166175 -0.0261877977 1.2379269026 0.5440365915 0.7367465110 0.3334261893 -0.223731405902 +1413393300105760512.0000000000 0.7295142757 -0.0301764799 1.2422881058 0.5438024698 0.7367226506 0.3355237945 -0.221229277376 +1413393300155760384.0000000000 0.7209575643 -0.0354010060 1.2471281176 0.5426438633 0.7372161938 0.3357422889 -0.222096908365 +1413393300205760512.0000000000 0.7115593209 -0.0418290746 1.2522675431 0.5398646906 0.7385563159 0.3347131637 -0.225937562462 +1413393300255760384.0000000000 0.7014750548 -0.0493806170 1.2576327576 0.5363081545 0.7396672338 0.3334093562 -0.232602983254 +1413393300305760512.0000000000 0.6910922482 -0.0578261231 1.2632757754 0.5316978161 0.7401778615 0.3332598804 -0.241603016938 +1413393300355760384.0000000000 0.6808394690 -0.0666493132 1.2689789651 0.5269547065 0.7400379273 0.3343031989 -0.250806647981 +1413393300405760512.0000000000 0.6705115655 -0.0751881658 1.2751017038 0.5217514383 0.7393041588 0.3369910878 -0.260080380182 +1413393300455760384.0000000000 0.6602072220 -0.0832438817 1.2819209466 0.5163658746 0.7377209750 0.3410081521 -0.269902735784 +1413393300505760512.0000000000 0.6505145890 -0.0904502264 1.2886702665 0.5124230311 0.7347743762 0.3468800361 -0.27785516695 +1413393300555760384.0000000000 0.6416293919 -0.0969322868 1.2949714780 0.5084265152 0.7309609150 0.3541438672 -0.28597332158 +1413393300605760512.0000000000 0.6336570063 -0.1025083882 1.3009666628 0.5049965572 0.7261834328 0.3632217281 -0.292755999631 +1413393300655760384.0000000000 0.6266089271 -0.1068875257 1.3064743892 0.5024978201 0.7204055273 0.3738952429 -0.2978492309 +1413393300705760512.0000000000 0.6201671994 -0.1102358881 1.3121628752 0.5000041731 0.7140611944 0.3862653358 -0.301515385923 +1413393300755760384.0000000000 0.6141104980 -0.1127241400 1.3181945056 0.4977885143 0.7072305360 0.3988195284 -0.304917279988 +1413393300805760512.0000000000 0.6088545898 -0.1143479642 1.3234768323 0.4969760498 0.7003204091 0.4103699988 -0.306859242276 +1413393300855760384.0000000000 0.6040490285 -0.1154743625 1.3269474925 0.4974197652 0.6932209660 0.4201765735 -0.308982065166 +1413393300905760512.0000000000 0.5991033674 -0.1160261231 1.3278747404 0.4988003245 0.6863625267 0.4281156551 -0.311161861691 +1413393300955760384.0000000000 0.5942363507 -0.1165140785 1.3255728372 0.5003173347 0.6803189539 0.4338351191 -0.314063329515 +1413393301005760512.0000000000 0.5895082576 -0.1171496005 1.3201360497 0.5022079789 0.6746174747 0.4376754907 -0.317991467854 +1413393301055760384.0000000000 0.5846085682 -0.1181342194 1.3127252985 0.5037865411 0.6695017048 0.4404093428 -0.322499921139 +1413393301105760512.0000000000 0.5798858107 -0.1198697008 1.3035279873 0.5042790704 0.6649712419 0.4434616844 -0.326890809237 +1413393301155760384.0000000000 0.5754100884 -0.1223312647 1.2919321916 0.5041812959 0.6605545214 0.4467848048 -0.331439712898 +1413393301205760512.0000000000 0.5714864199 -0.1256859989 1.2786702025 0.5027595150 0.6565099925 0.4507662138 -0.336210232255 +1413393301255760384.0000000000 0.5686647164 -0.1300743667 1.2647467979 0.5001726711 0.6526895415 0.4556458820 -0.340896599713 +1413393301305760512.0000000000 0.5670641489 -0.1354397029 1.2515194477 0.4978162804 0.6480990992 0.4610378040 -0.34581881367 +1413393301355760384.0000000000 0.5666668377 -0.1419538693 1.2387540331 0.4945622871 0.6432506671 0.4677734426 -0.350463592783 +1413393301405760512.0000000000 0.5675466831 -0.1494323890 1.2271470364 0.4904071902 0.6384872717 0.4743275958 -0.356157442106 +1413393301455760384.0000000000 0.5697505470 -0.1576558717 1.2159617413 0.4857413808 0.6336486523 0.4815404698 -0.361474027207 +1413393301505760512.0000000000 0.5731230468 -0.1666418785 1.2054542247 0.4799964232 0.6289035309 0.4900812259 -0.365929193359 +1413393301555760384.0000000000 0.5774360192 -0.1761930340 1.1954808288 0.4730519898 0.6247459240 0.4999939520 -0.36867383068 +1413393301605760512.0000000000 0.5824123537 -0.1862885064 1.1863270193 0.4659553939 0.6203233504 0.5106042710 -0.370631609933 +1413393301655760384.0000000000 0.5878364371 -0.1968729384 1.1781987047 0.4592616569 0.6153603136 0.5213428010 -0.372306458153 +1413393301705760512.0000000000 0.5932600260 -0.2075083653 1.1710819093 0.4544706240 0.6101950092 0.5302806181 -0.374060113753 +1413393301755760384.0000000000 0.5985867896 -0.2185521259 1.1644516069 0.4499059827 0.6056795239 0.5383006320 -0.375458853549 +1413393301805760512.0000000000 0.6035305743 -0.2300543476 1.1583955064 0.4470309044 0.6009971776 0.5450801377 -0.376634314113 +1413393301855760384.0000000000 0.6079073966 -0.2421137664 1.1531073996 0.4449039598 0.5972355670 0.5492458021 -0.37907676381 +1413393301905760512.0000000000 0.6118641350 -0.2547540515 1.1481442259 0.4432923477 0.5939342668 0.5530676303 -0.380591877954 +1413393301955760384.0000000000 0.6154453316 -0.2681923835 1.1436550616 0.4422129989 0.5909935151 0.5563998233 -0.38156724874 +1413393302005760512.0000000000 0.6183610055 -0.2822791496 1.1399593479 0.4422043752 0.5883956106 0.5581368878 -0.383052359854 +1413393302055760384.0000000000 0.6209377720 -0.2973026163 1.1370354755 0.4423042940 0.5862275445 0.5593740691 -0.384453935445 +1413393302105760512.0000000000 0.6229735185 -0.3132716731 1.1347765799 0.4414535769 0.5853303987 0.5599391713 -0.385973040827 +1413393302155760384.0000000000 0.6245514150 -0.3300538124 1.1332811716 0.4408296388 0.5851950941 0.5594407793 -0.387610559489 +1413393302205760512.0000000000 0.6256887024 -0.3476531543 1.1325302530 0.4404414808 0.5855502675 0.5588188502 -0.388411738859 +1413393302255760384.0000000000 0.6267083594 -0.3660987086 1.1323686449 0.4393121241 0.5865977675 0.5577266676 -0.389677919509 +1413393302305760512.0000000000 0.6273804677 -0.3851389506 1.1330272173 0.4395100045 0.5874342363 0.5555539703 -0.391294978159 +1413393302355760384.0000000000 0.6280199649 -0.4048643839 1.1339350843 0.4379404610 0.5898058767 0.5530753164 -0.392994751609 +1413393302405760512.0000000000 0.6284621951 -0.4247717392 1.1353918285 0.4376238851 0.5915715208 0.5510552971 -0.393530850702 +1413393302455760384.0000000000 0.6288282232 -0.4448625659 1.1378048829 0.4370086338 0.5940718206 0.5481999363 -0.394434982961 +1413393302505760512.0000000000 0.6291014200 -0.4650324835 1.1409293517 0.4361332382 0.5968223119 0.5457149814 -0.394697460883 +1413393302555760384.0000000000 0.6292557118 -0.4851957771 1.1449099840 0.4348984115 0.6000251302 0.5423256474 -0.39587385225 +1413393302605760512.0000000000 0.6293113863 -0.5051101565 1.1495467443 0.4330361707 0.6035458358 0.5392895770 -0.396710034114 +1413393302655760384.0000000000 0.6293130283 -0.5243721672 1.1547545095 0.4321418733 0.6064202384 0.5371311807 -0.39622971937 +1413393302705760512.0000000000 0.6293035029 -0.5430732592 1.1606702597 0.4319214160 0.6084157543 0.5357242786 -0.395314631245 +1413393302755760384.0000000000 0.6290691054 -0.5611523231 1.1672835480 0.4313040328 0.6103881181 0.5342458304 -0.39494881856 +1413393302805760512.0000000000 0.6285585989 -0.5783473066 1.1747409932 0.4313852539 0.6116503540 0.5326763684 -0.395027206311 +1413393302855760384.0000000000 0.6278508260 -0.5947604435 1.1827443251 0.4307111883 0.6130206452 0.5316639860 -0.395002489602 +1413393302905760512.0000000000 0.6267558658 -0.6103916577 1.1910333680 0.4306582572 0.6135111112 0.5312526674 -0.394852105603 +1413393302955760384.0000000000 0.6254049534 -0.6250544444 1.1994813641 0.4303053924 0.6143328598 0.5309958631 -0.394304197411 +1413393303005760512.0000000000 0.6237200252 -0.6386610192 1.2080834256 0.4316687789 0.6136216704 0.5317084010 -0.392958887428 +1413393303055760384.0000000000 0.6218237049 -0.6515455438 1.2169702716 0.4329388699 0.6124774655 0.5322831160 -0.392568431654 +1413393303105760512.0000000000 0.6196760184 -0.6635016913 1.2258172074 0.4344227508 0.6115929308 0.5324696779 -0.3920548466 +1413393303155760384.0000000000 0.6174593642 -0.6750219678 1.2344876861 0.4349704711 0.6109494758 0.5331565914 -0.391516891513 +1413393303205760512.0000000000 0.6151355302 -0.6859419145 1.2435525217 0.4355767798 0.6102273348 0.5330856333 -0.392065270484 +1413393303255760384.0000000000 0.6128111134 -0.6961155210 1.2524995746 0.4357593010 0.6100342828 0.5335643187 -0.391511332111 +1413393303305760512.0000000000 0.6101852947 -0.7055216722 1.2613498445 0.4376804975 0.6087561274 0.5353266412 -0.388943629078 +1413393303355760384.0000000000 0.6073633953 -0.7143596366 1.2703274071 0.4405786796 0.6068397926 0.5379381475 -0.385043429587 +1413393303405760512.0000000000 0.6042649206 -0.7231280927 1.2796983443 0.4433912138 0.6051058274 0.5402474920 -0.381292298142 +1413393303455760384.0000000000 0.6009168424 -0.7320969293 1.2897961611 0.4450409377 0.6042243483 0.5417135811 -0.378679147568 +1413393303505760512.0000000000 0.5972139976 -0.7415219693 1.3008979717 0.4472655872 0.6027999745 0.5424940723 -0.377207988785 +1413393303555760384.0000000000 0.5931269850 -0.7513502563 1.3127959725 0.4490049455 0.6026125149 0.5420362426 -0.376097630313 +1413393303605760512.0000000000 0.5884312793 -0.7618166602 1.3256495432 0.4510671229 0.6017978140 0.5412483516 -0.376069227105 +1413393303655760384.0000000000 0.5834640790 -0.7730007187 1.3391933943 0.4525116572 0.6014191342 0.5397046406 -0.377156633232 +1413393303705760512.0000000000 0.5786512741 -0.7846286663 1.3531275577 0.4529420251 0.6022287588 0.5380233823 -0.377749763854 +1413393303755760384.0000000000 0.5738824839 -0.7968870187 1.3675161715 0.4522122528 0.6033719343 0.5370185661 -0.378229357661 +1413393303805760512.0000000000 0.5691898038 -0.8095216725 1.3825666838 0.4523566912 0.6037253766 0.5357932458 -0.379229074963 +1413393303855760384.0000000000 0.5646551255 -0.8224332869 1.3979705843 0.4510287767 0.6052962453 0.5339735129 -0.380869774962 +1413393303905760512.0000000000 0.5602304536 -0.8356030836 1.4137610465 0.4494169605 0.6066758804 0.5324892019 -0.382653918783 +1413393303955760384.0000000000 0.5558123275 -0.8486469016 1.4288950482 0.4472327161 0.6083045745 0.5304174946 -0.385494129285 +1413393304005760512.0000000000 0.5514674467 -0.8613506627 1.4416717787 0.4446050788 0.6105711171 0.5287173716 -0.387281778287 +1413393304055760384.0000000000 0.5470436114 -0.8735171669 1.4517096232 0.4428778219 0.6118126208 0.5273535596 -0.38915649163 +1413393304105760512.0000000000 0.5429495383 -0.8849386095 1.4579180242 0.4404560459 0.6134804761 0.5274835772 -0.389103139216 +1413393304155760384.0000000000 0.5391272588 -0.8953553159 1.4605135552 0.4381769104 0.6153954097 0.5289110323 -0.386707389054 +1413393304205760512.0000000000 0.5350511134 -0.9050373238 1.4604222240 0.4360352481 0.6165240804 0.5311267965 -0.384285891956 +1413393304255760384.0000000000 0.5305598109 -0.9137177393 1.4582402032 0.4355563858 0.6165773567 0.5344330445 -0.380137236962 +1413393304305760512.0000000000 0.5253724994 -0.9216934919 1.4540209070 0.4358635412 0.6160574667 0.5373347750 -0.376520266033 +1413393304355760384.0000000000 0.5199559617 -0.9292995136 1.4487479871 0.4363466081 0.6149442267 0.5406202723 -0.373061599286 +1413393304405760512.0000000000 0.5136657652 -0.9364619009 1.4435970690 0.4369157149 0.6137973891 0.5429653902 -0.370871956746 +1413393304455760384.0000000000 0.5062788136 -0.9434060241 1.4387536781 0.4384282531 0.6119064151 0.5449620350 -0.369279821256 +1413393304505760512.0000000000 0.4979267783 -0.9504085481 1.4344057916 0.4393659971 0.6102535395 0.5461079438 -0.369207599943 +1413393304555760384.0000000000 0.4887319766 -0.9573287132 1.4306030357 0.4414374107 0.6075410288 0.5468729032 -0.370076935965 +1413393304605760512.0000000000 0.4789371116 -0.9641721941 1.4267495883 0.4442953733 0.6047196304 0.5477977745 -0.369909972878 +1413393304655760384.0000000000 0.4687453556 -0.9714466878 1.4233200783 0.4458158824 0.6025539832 0.5482783951 -0.370901196828 +1413393304705760512.0000000000 0.4578538348 -0.9791585867 1.4205818259 0.4482198875 0.5998066637 0.5482773410 -0.372455173231 +1413393304755760384.0000000000 0.4466543347 -0.9875847559 1.4182667248 0.4471637074 0.5994485823 0.5485042153 -0.373964091501 +1413393304805760512.0000000000 0.4349430824 -0.9964866284 1.4168704130 0.4465859772 0.5983369111 0.5486670298 -0.376189309003 +1413393304855760384.0000000000 0.4229153808 -1.0059542324 1.4160346312 0.4441914008 0.5986385067 0.5483984902 -0.378926158694 +1413393304905760512.0000000000 0.4106353742 -1.0153820402 1.4153375421 0.4433725751 0.5980287917 0.5498577111 -0.378733179761 +1413393304955760384.0000000000 0.3978117115 -1.0251830695 1.4153890121 0.4423546971 0.5977117454 0.5501975394 -0.379928491981 +1413393305005760512.0000000000 0.3848625013 -1.0348448667 1.4154411122 0.4422797421 0.5970600776 0.5518081378 -0.378702617463 +1413393305055760384.0000000000 0.3716555379 -1.0449102718 1.4157495214 0.4406168486 0.5976686684 0.5524186043 -0.378791025747 +1413393305105760512.0000000000 0.3579451467 -1.0550613522 1.4169504971 0.4399783934 0.5979930400 0.5524208806 -0.379017820264 +1413393305155760384.0000000000 0.3437741823 -1.0652134684 1.4186119291 0.4384999285 0.5993499552 0.5521360114 -0.379002993195 +1413393305205760512.0000000000 0.3287713806 -1.0752439126 1.4210076410 0.4396801891 0.5988817825 0.5524900469 -0.377858028855 +1413393305255760384.0000000000 0.3135315993 -1.0852341743 1.4238914606 0.4424411781 0.5975904944 0.5541370877 -0.37425057498 +1413393305305760512.0000000000 0.2977512116 -1.0956190315 1.4280990148 0.4446378996 0.5975546271 0.5533767926 -0.37282667745 +1413393305355760384.0000000000 0.2814249883 -1.1064911413 1.4327199204 0.4470034690 0.5980863616 0.5519533024 -0.371252144365 +1413393305405760512.0000000000 0.2646961046 -1.1180541411 1.4374471411 0.4478610245 0.6000055691 0.5500891074 -0.369886190155 +1413393305455760384.0000000000 0.2478943723 -1.1304688737 1.4425080675 0.4468525196 0.6032319048 0.5473670220 -0.369896523395 +1413393305505760512.0000000000 0.2306686782 -1.1434613829 1.4477970389 0.4470791478 0.6053183928 0.5449541077 -0.369776823915 +1413393305555760384.0000000000 0.2129862335 -1.1569075213 1.4532846720 0.4473004992 0.6074233032 0.5424941249 -0.369674611623 +1413393305605760512.0000000000 0.1951565439 -1.1709792775 1.4589064244 0.4468847312 0.6095061605 0.5405658861 -0.369573808904 +1413393305655760384.0000000000 0.1766630178 -1.1849648292 1.4648172678 0.4482408977 0.6111823496 0.5387403147 -0.367824831092 +1413393305705760512.0000000000 0.1576166136 -1.1990076800 1.4710671843 0.4504709252 0.6130662671 0.5363340830 -0.365474279647 +1413393305755760384.0000000000 0.1380622050 -1.2130136517 1.4775023669 0.4552497409 0.6135512349 0.5344613316 -0.361460427339 +1413393305805760512.0000000000 0.1181646712 -1.2274473679 1.4845079618 0.4604481833 0.6142864125 0.5319799019 -0.35726328925 +1413393305855760384.0000000000 0.0980468069 -1.2424407701 1.4917583570 0.4666905446 0.6137370185 0.5307325267 -0.351922992534 +1413393305905760512.0000000000 0.0777418069 -1.2586527516 1.4988027156 0.4717586036 0.6137143480 0.5303971127 -0.345655061812 +1413393305955760384.0000000000 0.0569380370 -1.2767496015 1.5068534756 0.4754154042 0.6143255930 0.5279546328 -0.343290205222 +1413393306005760512.0000000000 0.0359109585 -1.2967765899 1.5153355935 0.4758016252 0.6167411062 0.5246828092 -0.34344020022 +1413393306055760384.0000000000 0.0145606652 -1.3185335329 1.5243008537 0.4754564787 0.6189810180 0.5209170972 -0.345613966698 +1413393306105760512.0000000000 -0.0068318166 -1.3415050068 1.5329379839 0.4743687274 0.6214546251 0.5180819994 -0.346928668803 +1413393306155760384.0000000000 -0.0282911717 -1.3656953588 1.5413848148 0.4731920492 0.6231631569 0.5160989867 -0.34842330633 +1413393306205760512.0000000000 -0.0497886595 -1.3908409396 1.5498849777 0.4717700454 0.6247727543 0.5143145536 -0.350103655622 +1413393306255760384.0000000000 -0.0712707498 -1.4165225965 1.5582442892 0.4703268503 0.6262953367 0.5133148371 -0.350791509521 +1413393306305760512.0000000000 -0.0927061004 -1.4427400886 1.5663311890 0.4678995873 0.6286333200 0.5125032806 -0.351042038077 +1413393306355760384.0000000000 -0.1143571686 -1.4690591783 1.5742755590 0.4653527978 0.6322168330 0.5105777436 -0.35079768717 +1413393306405760512.0000000000 -0.1363807653 -1.4950822630 1.5812223700 0.4632421066 0.6368896403 0.5075977355 -0.349460835575 +1413393306455760384.0000000000 -0.1589797147 -1.5206947318 1.5863378619 0.4620199231 0.6426631081 0.5029135110 -0.347274704941 +1413393306505760512.0000000000 -0.1820979413 -1.5457321804 1.5893606319 0.4623587384 0.6486849220 0.4964127716 -0.344973374566 +1413393306555760384.0000000000 -0.2057155763 -1.5698239988 1.5894813995 0.4647732930 0.6544864056 0.4892008868 -0.341051056807 +1413393306605760512.0000000000 -0.2296368352 -1.5930919895 1.5875976592 0.4692134774 0.6597387544 0.4802997070 -0.337484340491 +1413393306655760384.0000000000 -0.2540405088 -1.6156727757 1.5836746955 0.4738756616 0.6650408037 0.4710062095 -0.33364013134 +1413393306705760512.0000000000 -0.2785779900 -1.6381708945 1.5791700725 0.4754677371 0.6721552295 0.4589035741 -0.333983963932 +1413393306755760384.0000000000 -0.3029966745 -1.6599808668 1.5749499140 0.4765224376 0.6786936832 0.4483879436 -0.333540856369 +1413393306805760512.0000000000 -0.3271396046 -1.6809654431 1.5714692398 0.4777250250 0.6839366161 0.4382857217 -0.334537190477 +1413393306855760384.0000000000 -0.3507581731 -1.7007185326 1.5684261575 0.4779367860 0.6891874481 0.4303654292 -0.333740448901 +1413393306905760512.0000000000 -0.3736919957 -1.7187217146 1.5658135915 0.4794596071 0.6936170737 0.4228701000 -0.331955898976 +1413393306955760384.0000000000 -0.3960451115 -1.7349861986 1.5641104682 0.4804604974 0.6984865601 0.4154252871 -0.329690865269 +1413393307005760512.0000000000 -0.4177239862 -1.7491418457 1.5631202546 0.4825792796 0.7029974601 0.4088344743 -0.325217131561 +1413393307055760384.0000000000 -0.4385588797 -1.7613179139 1.5622710426 0.4857474740 0.7070253113 0.4028468463 -0.31918492928 +1413393307105760512.0000000000 -0.4586702050 -1.7714420736 1.5612503527 0.4901766192 0.7104346596 0.3973149219 -0.311689475727 +1413393307155760384.0000000000 -0.4782722359 -1.7797870783 1.5601150893 0.4951006709 0.7135659764 0.3925272628 -0.302690057614 +1413393307205760512.0000000000 -0.4974927443 -1.7865539966 1.5593986487 0.4995743131 0.7172135206 0.3870404100 -0.293649438237 +1413393307255760384.0000000000 -0.5163549455 -1.7921190237 1.5593645659 0.5044190270 0.7205361338 0.3807894560 -0.285286724697 +1413393307305760512.0000000000 -0.5349584308 -1.7966499983 1.5598019029 0.5098193551 0.7234411905 0.3742953391 -0.276803302324 +1413393307355760384.0000000000 -0.5531941143 -1.8003941480 1.5602818279 0.5126005140 0.7284531272 0.3668120620 -0.268413236846 +1413393307405760512.0000000000 -0.5712688419 -1.8031893508 1.5614754542 0.5164843653 0.7329104063 0.3586126882 -0.259775242738 +1413393307455760384.0000000000 -0.5892416467 -1.8049446853 1.5636256212 0.5204910069 0.7376471983 0.3495250020 -0.250595282477 +1413393307505760512.0000000000 -0.6070739511 -1.8060777504 1.5663633710 0.5234201355 0.7430738703 0.3398322364 -0.241633267591 +1413393307555760384.0000000000 -0.6247639226 -1.8067761165 1.5695113379 0.5246913524 0.7495198284 0.3301355926 -0.232227263915 +1413393307605760512.0000000000 -0.6428191841 -1.8069207646 1.5732979582 0.5259653171 0.7557655185 0.3194476499 -0.223902133293 +1413393307655760384.0000000000 -0.6612914112 -1.8065398036 1.5776165980 0.5255769514 0.7630139786 0.3080615920 -0.216047661825 +1413393307705760512.0000000000 -0.6800250840 -1.8054540688 1.5821742612 0.5254674595 0.7696310978 0.2971792015 -0.207933750423 +1413393307755760384.0000000000 -0.6992633594 -1.8031274242 1.5871083784 0.5277975039 0.7743817519 0.2868171813 -0.198742551541 +1413393307805760512.0000000000 -0.7189981331 -1.7996754046 1.5925333867 0.5343344163 0.7757080392 0.2777260475 -0.188764435108 +1413393307855760384.0000000000 -0.7392706211 -1.7956404551 1.5980892797 0.5402943408 0.7770638166 0.2681139157 -0.179913252787 +1413393307905760512.0000000000 -0.7599741846 -1.7910896589 1.6039003435 0.5467142848 0.7777993756 0.2587234862 -0.170861873347 +1413393307955760384.0000000000 -0.7810890204 -1.7864109657 1.6098627280 0.5517313133 0.7792193939 0.2494904266 -0.16175358166 +1413393308005760512.0000000000 -0.8026903585 -1.7817217089 1.6162832753 0.5562957534 0.7807858596 0.2393340159 -0.153713060695 +1413393308055760384.0000000000 -0.8247171054 -1.7773180893 1.6224719185 0.5597511504 0.7828542948 0.2296942158 -0.145115023131 +1413393308105760512.0000000000 -0.8473900887 -1.7730235128 1.6288355246 0.5629367306 0.7848813523 0.2198648166 -0.136831877107 +1413393308155760384.0000000000 -0.8705339613 -1.7689279820 1.6351042576 0.5646765953 0.7877845659 0.2097003343 -0.128691842522 +1413393308205760512.0000000000 -0.8943691551 -1.7650837423 1.6416134015 0.5665891038 0.7902585934 0.1998364572 -0.120555105524 +1413393308255760384.0000000000 -0.9188551858 -1.7614578762 1.6483119244 0.5687797085 0.7924253305 0.1894476286 -0.11252259703 +1413393308305760512.0000000000 -0.9440292647 -1.7580050112 1.6552770593 0.5714248815 0.7942610870 0.1773986358 -0.105606129527 +1413393308355760384.0000000000 -0.9696165266 -1.7550045998 1.6621848522 0.5732186033 0.7963300915 0.1654525162 -0.0995202647623 +1413393308405760512.0000000000 -0.9956011316 -1.7523325942 1.6691676858 0.5746798710 0.7984760471 0.1526602120 -0.094201420669 +1413393308455760384.0000000000 -1.0217840742 -1.7500268803 1.6750954541 0.5743312137 0.8016632316 0.1398691054 -0.0889738923317 +1413393308505760512.0000000000 -1.0480567847 -1.7477292294 1.6795612854 0.5727619707 0.8054434211 0.1267535997 -0.0844875453714 +1413393308555760384.0000000000 -1.0740828863 -1.7456576361 1.6815910848 0.5714828541 0.8087866500 0.1138345385 -0.0794556487461 +1413393308605760512.0000000000 -1.0995510502 -1.7438860669 1.6812187231 0.5707832273 0.8115308621 0.1005636893 -0.0742368624491 +1413393308655760384.0000000000 -1.1246879732 -1.7415721834 1.6782508160 0.5690413945 0.8147812299 0.0865057003 -0.0695715643738 +1413393308705760512.0000000000 -1.1494572624 -1.7380387101 1.6733064737 0.5678673817 0.8173667786 0.0721478435 -0.0650605460967 +1413393308755760384.0000000000 -1.1734208021 -1.7338867720 1.6670356415 0.5682577494 0.8186316119 0.0580455263 -0.0596333050384 +1413393308805760512.0000000000 -1.1963189806 -1.7294883029 1.6587593378 0.5707161651 0.8181833317 0.0445873271 -0.053582319318 +1413393308855760384.0000000000 -1.2177718632 -1.7251140961 1.6476248959 0.5743038218 0.8167407573 0.0331345565 -0.0448526117074 +1413393308905760512.0000000000 -1.2381472937 -1.7202407171 1.6347291862 0.5773689612 0.8153796796 0.0218687239 -0.0363705879873 +1413393308955760384.0000000000 -1.2574332607 -1.7147661654 1.6213775135 0.5801972386 0.8139360103 0.0113475077 -0.0273965238829 +1413393309005760512.0000000000 -1.2755393595 -1.7092117282 1.6081131098 0.5826760032 0.8125109266 0.0014624805 -0.0176785369422 +1413393309055760384.0000000000 -1.2927040260 -1.7043068612 1.5948978080 0.5832168855 0.8122076981 -0.0089289972 -0.00984848266145 +1413393309105760512.0000000000 -1.3088371383 -1.6996692879 1.5825661347 0.5855064750 0.8104488987 -0.0187487787 -0.00179823318596 +1413393309155760384.0000000000 -1.3239712815 -1.6954843466 1.5705305768 0.5856355828 0.8100542849 -0.0284629438 0.0057341502289 +1413393309205760512.0000000000 -1.3384283485 -1.6916644261 1.5596532244 0.5868478166 0.8087654139 -0.0369145987 0.0120605908304 +1413393309255760384.0000000000 -1.3521643091 -1.6887361995 1.5491620595 0.5866464723 0.8084823305 -0.0430521788 0.0186747909716 +1413393309305760512.0000000000 -1.3654162543 -1.6864374869 1.5397359408 0.5868142974 0.8079773550 -0.0468687231 0.0249979380322 +1413393309355760384.0000000000 -1.3781648785 -1.6843570352 1.5304841488 0.5868154310 0.8076561642 -0.0481175073 0.0319980593549 +1413393309405760512.0000000000 -1.3910149393 -1.6830780220 1.5216378992 0.5860094144 0.8079892398 -0.0485113549 0.0373229566349 +1413393309455760384.0000000000 -1.4039105521 -1.6823616480 1.5137615093 0.5851195699 0.8084500360 -0.0478857646 0.0418399544204 +1413393309505760512.0000000000 -1.4171028213 -1.6820751898 1.5074012033 0.5825745618 0.8102003559 -0.0467799632 0.0446530892762 +1413393309555760384.0000000000 -1.4307340076 -1.6819986205 1.5020178083 0.5795354223 0.8123987527 -0.0456813009 0.0453892025425 +1413393309605760512.0000000000 -1.4446116559 -1.6823700912 1.4967852673 0.5740470865 0.8163252588 -0.0442114332 0.046134189631 +1413393309655760384.0000000000 -1.4589158964 -1.6824788158 1.4925556587 0.5699377825 0.8193251995 -0.0422062180 0.0457796536502 +1413393309705760512.0000000000 -1.4735442382 -1.6817062152 1.4891229958 0.5663966987 0.8219198034 -0.0412593298 0.0440486581112 +1413393309755760384.0000000000 -1.4881934861 -1.6798425864 1.4867622527 0.5646944641 0.8232204743 -0.0420793870 0.0407128732084 +1413393309805760512.0000000000 -1.5030537785 -1.6770930349 1.4850105599 0.5643730781 0.8236172864 -0.0439361674 0.0347448900921 +1413393309855760384.0000000000 -1.5173344265 -1.6734802589 1.4835123337 0.5636627300 0.8241946430 -0.0460483762 0.0294459558741 +1413393309905760512.0000000000 -1.5306743292 -1.6689167417 1.4823085050 0.5636699199 0.8242403485 -0.0475029541 0.0254467797695 +1413393309955760384.0000000000 -1.5431504161 -1.6636013576 1.4809671080 0.5628112563 0.8248600739 -0.0490680890 0.0210159706596 +1413393310005760512.0000000000 -1.5544508942 -1.6573745754 1.4800408639 0.5627772233 0.8248712787 -0.0509618300 0.0164943159985 +1413393310055760384.0000000000 -1.5643092559 -1.6500536860 1.4793654848 0.5633952150 0.8244532468 -0.0515635773 0.0142784114223 +1413393310105760512.0000000000 -1.5727715931 -1.6417247304 1.4792805015 0.5654182996 0.8231071706 -0.0512898279 0.0128874252721 +1413393310155760384.0000000000 -1.5794770355 -1.6324921951 1.4794099057 0.5683392728 0.8211774189 -0.0494787648 0.0144903279631 +1413393310205760512.0000000000 -1.5845005810 -1.6228365813 1.4792701775 0.5709893371 0.8194889128 -0.0450439983 0.01949710016 +1413393310255760384.0000000000 -1.5887792315 -1.6129230299 1.4790746358 0.5733617288 0.8179354870 -0.0400510786 0.0251749501549 +1413393310305760512.0000000000 -1.5923643276 -1.6028380473 1.4783483142 0.5747044687 0.8169955455 -0.0356056490 0.0310691186893 +1413393310355760384.0000000000 -1.5958138110 -1.5925046670 1.4776100370 0.5752599534 0.8165798803 -0.0314759194 0.0358127295162 +1413393310405760512.0000000000 -1.5992334533 -1.5817543293 1.4769709371 0.5762430917 0.8158019750 -0.0286455569 0.0398806829709 +1413393310455760384.0000000000 -1.6030409809 -1.5710356406 1.4763393245 0.5767271670 0.8154022226 -0.0278218654 0.0416044953933 +1413393310505760512.0000000000 -1.6077844661 -1.5602969540 1.4761457974 0.5771238326 0.8151808193 -0.0294123542 0.0392839292213 +1413393310555760384.0000000000 -1.6127363075 -1.5494544637 1.4757747993 0.5776779606 0.8148208374 -0.0310979611 0.0372571275221 +1413393310605760512.0000000000 -1.6179878846 -1.5386495159 1.4751403632 0.5773587381 0.8151048918 -0.0340267416 0.0332127030586 +1413393310655760384.0000000000 -1.6231467353 -1.5278663446 1.4748593403 0.5774536439 0.8150533838 -0.0379234289 0.0282326788161 +1413393310705760512.0000000000 -1.6278365131 -1.5172341137 1.4746649777 0.5774671934 0.8150096713 -0.0417246189 0.0234506368462 +1413393310755760384.0000000000 -1.6318229506 -1.5066980898 1.4739538686 0.5764082064 0.8156962640 -0.0451348805 0.018868676335 +1413393310805760512.0000000000 -1.6347677769 -1.4958941154 1.4734229282 0.5758730244 0.8159734343 -0.0482156592 0.0152598977015 +1413393310855760384.0000000000 -1.6362807614 -1.4848939739 1.4728537208 0.5749287970 0.8165207377 -0.0507008700 0.0134233034704 +1413393310905760512.0000000000 -1.6361690110 -1.4736809106 1.4715968316 0.5740272755 0.8171395412 -0.0501509677 0.0161411769053 +1413393310955760384.0000000000 -1.6344412385 -1.4621562125 1.4691929603 0.5721020993 0.8185008967 -0.0472293116 0.0229098712826 +1413393311005760512.0000000000 -1.6318003587 -1.4503363730 1.4665603010 0.5704224059 0.8195967704 -0.0450075545 0.0292187069943 +1413393311055760384.0000000000 -1.6286786551 -1.4380729405 1.4635801535 0.5684265748 0.8208495548 -0.0435779030 0.0346150803977 +1413393311105760512.0000000000 -1.6254332554 -1.4250011639 1.4595362643 0.5664398220 0.8220764364 -0.0433529718 0.0381677955187 +1413393311155760384.0000000000 -1.6219968380 -1.4112828337 1.4534916678 0.5665989659 0.8218038037 -0.0432349262 0.0416516656222 +1413393311205760512.0000000000 -1.6189095858 -1.3972562989 1.4450869999 0.5663942476 0.8218339229 -0.0458116069 0.0410835249192 +1413393311255760384.0000000000 -1.6158949708 -1.3823914006 1.4343181633 0.5664763764 0.8217125764 -0.0484208354 0.0393494535092 +1413393311305760512.0000000000 -1.6125649853 -1.3672411026 1.4218648351 0.5660090627 0.8219808144 -0.0493038726 0.039375244474 +1413393311355760384.0000000000 -1.6087774991 -1.3513382457 1.4093274236 0.5653361448 0.8223777370 -0.0488265870 0.0413021240067 +1413393311405760512.0000000000 -1.6046553778 -1.3346825446 1.3970312278 0.5649303789 0.8225855457 -0.0481132921 0.0434948057109 +1413393311455760384.0000000000 -1.6003618812 -1.3170873498 1.3850239265 0.5642592974 0.8229851297 -0.0470590513 0.0457424022132 +1413393311505760512.0000000000 -1.5960513595 -1.2985854973 1.3740215660 0.5633847393 0.8235282257 -0.0467653961 0.0470307862332 +1413393311555760384.0000000000 -1.5917179660 -1.2792101435 1.3638882606 0.5626812359 0.8239359647 -0.0454067516 0.0495739825757 +1413393311605760512.0000000000 -1.5875628688 -1.2586918888 1.3550041103 0.5625895760 0.8239483177 -0.0442845421 0.0513908364458 +1413393311655760384.0000000000 -1.5838329770 -1.2372234604 1.3476123948 0.5640748549 0.8229291577 -0.0434413338 0.0521537143247 +1413393311705760512.0000000000 -1.5805905049 -1.2146093118 1.3420971574 0.5670906795 0.8208717868 -0.0426411714 0.0525300044476 +1413393311755760384.0000000000 -1.5778022656 -1.1910999150 1.3377249706 0.5701212454 0.8188052128 -0.0413750888 0.0529895375458 +1413393311805760512.0000000000 -1.5756933636 -1.1672374968 1.3341176427 0.5734688061 0.8165623632 -0.0395335129 0.0528822912966 +1413393311855760384.0000000000 -1.5743488428 -1.1432788228 1.3314013096 0.5762851361 0.8147325934 -0.0382660436 0.0513999323037 +1413393311905760512.0000000000 -1.5736397342 -1.1193714004 1.3288393850 0.5782361944 0.8135430562 -0.0355938183 0.0502362345906 +1413393311955760384.0000000000 -1.5738182914 -1.0956018723 1.3266830904 0.5799217196 0.8126222454 -0.0335191512 0.0470356457795 +1413393312005760512.0000000000 -1.5744144104 -1.0719190260 1.3252752794 0.5836774749 0.8101615833 -0.0303464466 0.0451431875832 +1413393312055760384.0000000000 -1.5754306845 -1.0487698258 1.3237539728 0.5874769186 0.8075875126 -0.0259495338 0.044720256938 +1413393312105760512.0000000000 -1.5771911494 -1.0263003615 1.3223346975 0.5914071368 0.8048513556 -0.0216214760 0.0445466680124 +1413393312155760384.0000000000 -1.5798713687 -1.0047161032 1.3208757059 0.5933116737 0.8035950339 -0.0186206278 0.043238311735 +1413393312205760512.0000000000 -1.5833489567 -0.9841532730 1.3193490221 0.5931888656 0.8038329440 -0.0166488201 0.0412599646583 +1413393312255760384.0000000000 -1.5875025904 -0.9643949551 1.3178184052 0.5918246120 0.8049662115 -0.0162492225 0.0388457177723 +1413393312305760512.0000000000 -1.5925166573 -0.9450819253 1.3173908563 0.5920013680 0.8050414942 -0.0191849928 0.032779702337 +1413393312355760384.0000000000 -1.5979617150 -0.9265364181 1.3173940030 0.5906386221 0.8061944314 -0.0229367603 0.025893278988 +1413393312405760512.0000000000 -1.6034635176 -0.9086480055 1.3170142935 0.5873308708 0.8086794997 -0.0269921252 0.0187440698508 +1413393312455760384.0000000000 -1.6087679776 -0.8910465375 1.3168693251 0.5854355331 0.8100490235 -0.0307070076 0.0119539005629 +1413393312505760512.0000000000 -1.6132196109 -0.8739480088 1.3163538754 0.5824145466 0.8121530680 -0.0339928809 0.00672116276651 +1413393312555760384.0000000000 -1.6163426585 -0.8568138374 1.3164251536 0.5818538663 0.8125080775 -0.0353910717 0.0049167384765 +1413393312605760512.0000000000 -1.6181644792 -0.8396031812 1.3167315147 0.5829379778 0.8117910589 -0.0334252065 0.00783239078747 +1413393312655760384.0000000000 -1.6189097956 -0.8227419336 1.3166319492 0.5835452661 0.8114261042 -0.0298114614 0.0131862290281 +1413393312705760512.0000000000 -1.6190376651 -0.8063268765 1.3161735218 0.5827990199 0.8119889978 -0.0254924028 0.0192173677812 +1413393312755760384.0000000000 -1.6190447363 -0.7900259762 1.3164065519 0.5828484983 0.8119458234 -0.0233230306 0.0220826639992 +1413393312805760512.0000000000 -1.6190630396 -0.7737143208 1.3167770889 0.5829972614 0.8118381034 -0.0217115864 0.0237000876133 +1413393312855760384.0000000000 -1.6192339693 -0.7575865408 1.3175911630 0.5835766175 0.8114589367 -0.0205717998 0.0234419821602 +1413393312905760512.0000000000 -1.6194442270 -0.7416072815 1.3189420989 0.5863407972 0.8095244757 -0.0196697821 0.0220837593985 +1413393312955760384.0000000000 -1.6198384197 -0.7263331291 1.3206307864 0.5882580017 0.8082175459 -0.0194154679 0.0189726508649 +1413393313005760512.0000000000 -1.6203235617 -0.7114947415 1.3238065002 0.5939194237 0.8041533850 -0.0187040257 0.0157229449185 +1413393313055760384.0000000000 -1.6206314960 -0.6981275819 1.3255201088 0.5919937045 0.8056567704 -0.0162223499 0.0140519565932 +1413393313105760512.0000000000 -1.6204675184 -0.6863174630 1.3277719652 0.5893565478 0.8076489128 -0.0114359263 0.0152089739424 +1413393313155760384.0000000000 -1.6204804912 -0.6753768781 1.3291427863 0.5851874020 0.8107056151 -0.0063706003 0.0164780372732 +1413393313205760512.0000000000 -1.6206334663 -0.6643311748 1.3328528034 0.5824768859 0.8126711455 -0.0011195724 0.0168829264763 +1413393313255760384.0000000000 -1.6208850494 -0.6530077619 1.3375625671 0.5793528450 0.8148885740 0.0035125292 0.0171626065206 +1413393313305760512.0000000000 -1.6218538114 -0.6422902302 1.3424639984 0.5782451691 0.8157390385 0.0051427775 0.0132626312446 +1413393313355760384.0000000000 -1.6229476953 -0.6319553295 1.3470593888 0.5773836064 0.8163899264 0.0064719617 0.00968363842262 +1413393313405760512.0000000000 -1.6237982246 -0.6220044861 1.3512153616 0.5773441195 0.8164385412 0.0072179723 0.00705528342121 +1413393313455760384.0000000000 -1.6244964572 -0.6116956750 1.3561476096 0.5787132355 0.8155003347 0.0062433510 0.00334897670059 +1413393313505760512.0000000000 -1.6249409212 -0.6004474257 1.3601489597 0.5818707535 0.8132690434 0.0044295401 -0.000518083127149 +1413393313555760384.0000000000 -1.6245901767 -0.5884837869 1.3634945084 0.5864314431 0.8099883594 0.0012548656 -0.00393008196689 +1413393313605760512.0000000000 -1.6232613458 -0.5778738513 1.3644133549 0.5908155224 0.8067640533 -0.0033694307 -0.0075781052557 +1413393313655760384.0000000000 -1.6205491029 -0.5673371488 1.3646400233 0.5961529182 0.8027498673 -0.0092005825 -0.0104736818107 +1413393313705760512.0000000000 -1.6160324019 -0.5574268104 1.3633439644 0.6011769717 0.7989524969 -0.0133748447 -0.00907028052465 +1413393313755760384.0000000000 -1.6096987432 -0.5487840981 1.3614677504 0.6053096965 0.7958289734 -0.0156185508 -0.00353231479372 +1413393313805760512.0000000000 -1.6020962290 -0.5427668633 1.3598358950 0.6088013687 0.7931260274 -0.0175546524 0.00195762784312 +1413393313855760384.0000000000 -1.5933357452 -0.5384648371 1.3583427353 0.6086353573 0.7931713037 -0.0191065165 0.00878782768192 +1413393313905760512.0000000000 -1.5836666215 -0.5368020055 1.3558272343 0.6029412493 0.7973572100 -0.0209735467 0.0156025595757 +1413393313955760384.0000000000 -1.5733118283 -0.5363912158 1.3535981460 0.5951471610 0.8029651283 -0.0246905813 0.0209101566312 +1413393314005760512.0000000000 -1.5624523708 -0.5369636835 1.3517933861 0.5879804624 0.8079504826 -0.0289455601 0.0256348992187 +1413393314055760384.0000000000 -1.5512710575 -0.5379879188 1.3506184260 0.5811047805 0.8126015713 -0.0339178453 0.0290774846812 +1413393314105760512.0000000000 -1.5403088335 -0.5388449851 1.3506042959 0.5773656299 0.8150353496 -0.0378910903 0.0305053043774 +1413393314155760384.0000000000 -1.5293172315 -0.5395128003 1.3509419998 0.5757194040 0.8160520711 -0.0394554351 0.0323952729953 +1413393314205760512.0000000000 -1.5183391461 -0.5397302778 1.3517707726 0.5753074455 0.8163056217 -0.0390225287 0.03381889123 +1413393314255760384.0000000000 -1.5075545916 -0.5393361726 1.3528243699 0.5753213651 0.8163889000 -0.0357430242 0.0351699750098 +1413393314305760512.0000000000 -1.4971954776 -0.5385596827 1.3545549574 0.5758719204 0.8162252960 -0.0319873292 0.0335351807313 +1413393314355760384.0000000000 -1.4873682271 -0.5378868103 1.3558081233 0.5758653112 0.8165197145 -0.0258007151 0.0317651115897 +1413393314405760512.0000000000 -1.4781491521 -0.5372742872 1.3564212697 0.5746784040 0.8176658341 -0.0173886099 0.0294100661679 +1413393314455760384.0000000000 -1.4696095821 -0.5364842366 1.3569771079 0.5736892330 0.8186417562 -0.0083793448 0.0252215275318 +1413393314505760512.0000000000 -1.4618776924 -0.5355114167 1.3570318627 0.5724624113 0.8196928044 0.0018655817 0.0196726642518 +1413393314555760384.0000000000 -1.4553184491 -0.5338379357 1.3571677422 0.5727900955 0.8194846479 0.0137801435 0.0129044956887 +1413393314605760512.0000000000 -1.4495670810 -0.5317082429 1.3569153082 0.5717920258 0.8199610681 0.0261189414 0.00596045026433 +1413393314655760384.0000000000 -1.4447861615 -0.5293581043 1.3565792726 0.5704762807 0.8203723102 0.0392836624 -0.0016969643851 +1413393314705760512.0000000000 -1.4407155382 -0.5262329679 1.3562782326 0.5691705513 0.8205334525 0.0518640259 -0.00893642579366 +1413393314755760384.0000000000 -1.4374440063 -0.5223336042 1.3555790808 0.5670540035 0.8211674094 0.0622014882 -0.0162732220212 +1413393314805760512.0000000000 -1.4351594629 -0.5173253282 1.3543924233 0.5653342223 0.8213946991 0.0719656407 -0.022998087315 +1413393314855760384.0000000000 -1.4339444085 -0.5116309299 1.3527130510 0.5637664437 0.8214231406 0.0805161474 -0.0307988822402 +1413393314905760512.0000000000 -1.4337597193 -0.5049461067 1.3504349260 0.5617350794 0.8216283391 0.0890091893 -0.0381829437846 +1413393314955760384.0000000000 -1.4346612176 -0.4971951321 1.3483490830 0.5605504230 0.8210318876 0.0978237633 -0.0460475195442 +1413393315005760512.0000000000 -1.4363289528 -0.4881897149 1.3458866563 0.5590578076 0.8206063376 0.1054619431 -0.0541976467671 +1413393315055760384.0000000000 -1.4385940172 -0.4775870821 1.3430879843 0.5581959608 0.8199528844 0.1110750046 -0.0612933928807 +1413393315105760512.0000000000 -1.4412762361 -0.4656047497 1.3396724206 0.5577033413 0.8191451434 0.1158595069 -0.0674150711821 +1413393315155760384.0000000000 -1.4442261385 -0.4522618160 1.3353364266 0.5567920422 0.8187511474 0.1213076013 -0.0700974053488 +1413393315205760512.0000000000 -1.4475848333 -0.4373456235 1.3310635931 0.5586539456 0.8166966684 0.1259110796 -0.0711246854146 +1413393315255760384.0000000000 -1.4513821760 -0.4212351335 1.3256078581 0.5598711508 0.8152616665 0.1305594159 -0.0696200298392 +1413393315305760512.0000000000 -1.4558607450 -0.4040651456 1.3197174565 0.5624484568 0.8130932949 0.1343454121 -0.0669502616317 +1413393315355760384.0000000000 -1.4612984378 -0.3859277237 1.3138979220 0.5666342418 0.8099499948 0.1375369690 -0.0631682205839 +1413393315405760512.0000000000 -1.4677418797 -0.3673060496 1.3079636694 0.5711465458 0.8066427253 0.1404353838 -0.0582841299008 +1413393315455760384.0000000000 -1.4756729168 -0.3485497061 1.3024642674 0.5762276172 0.8029965986 0.1424780438 -0.0534621628176 +1413393315505760512.0000000000 -1.4856423373 -0.3301267539 1.2975257490 0.5798790451 0.8006182282 0.1414852527 -0.05227493657 +1413393315555760384.0000000000 -1.4973839074 -0.3121232912 1.2931421086 0.5832780890 0.7983833782 0.1406838112 -0.0507810755541 +1413393315605760512.0000000000 -1.5111630157 -0.2949601281 1.2903466850 0.5854961921 0.7971508280 0.1379568645 -0.0520832978637 +1413393315655760384.0000000000 -1.5269056548 -0.2785578871 1.2909595583 0.5889170948 0.7950058462 0.1343411236 -0.0556311276942 +1413393315705760512.0000000000 -1.5436762979 -0.2633047672 1.2935875466 0.5897746972 0.7946953309 0.1316738850 -0.057333460381 +1413393315755760384.0000000000 -1.5618055672 -0.2488571902 1.3002651610 0.5900909058 0.7948319725 0.1273936121 -0.0616905669147 +1413393315805760512.0000000000 -1.5806025991 -0.2359012728 1.3100668670 0.5882940410 0.7963749352 0.1240365078 -0.0656660389304 +1413393315855760384.0000000000 -1.5999607291 -0.2240313699 1.3235235781 0.5882253930 0.7966299077 0.1192310703 -0.07180270991 +1413393315905760512.0000000000 -1.6192125819 -0.2124174024 1.3382811232 0.5858879578 0.7984474153 0.1167484658 -0.0747450440358 +1413393315955760384.0000000000 -1.6384886135 -0.2012377716 1.3539451751 0.5853812944 0.7987706647 0.1152647912 -0.0775125371084 +1413393316005760512.0000000000 -1.6573133045 -0.1901733399 1.3693119325 0.5851041027 0.7989860648 0.1150107037 -0.0777624284284 +1413393316055760384.0000000000 -1.6759717670 -0.1793732501 1.3847957026 0.5853879870 0.7987579077 0.1147197578 -0.0783969824844 +1413393316105760512.0000000000 -1.6943015782 -0.1689847680 1.4003528182 0.5851085143 0.7988604858 0.1164952331 -0.0768037197746 +1413393316155760384.0000000000 -1.7124503258 -0.1587324933 1.4172203810 0.5864882657 0.7978054848 0.1183498341 -0.0743723025325 +1413393316205760512.0000000000 -1.7306260419 -0.1489892783 1.4350809843 0.5879036679 0.7966852340 0.1202045273 -0.0721996316773 +1413393316255760384.0000000000 -1.7491183469 -0.1400774335 1.4536193922 0.5885837708 0.7959876362 0.1222616871 -0.0708865824568 +1413393316305760512.0000000000 -1.7678312023 -0.1318506023 1.4723770266 0.5891527324 0.7954446948 0.1232033573 -0.0706238501382 +1413393316355760384.0000000000 -1.7870445317 -0.1245371524 1.4912096446 0.5883602225 0.7958181948 0.1236949734 -0.0721470922222 +1413393316405760512.0000000000 -1.8064735896 -0.1178474361 1.5103244296 0.5879873622 0.7958889049 0.1244054237 -0.073177890128 +1413393316455760384.0000000000 -1.8261627565 -0.1119091402 1.5292825933 0.5863971197 0.7968883254 0.1244517351 -0.0749611931833 +1413393316505760512.0000000000 -1.8460028334 -0.1064272946 1.5483178765 0.5850337250 0.7976947576 0.1243571562 -0.0771615959298 +1413393316555760384.0000000000 -1.8658804790 -0.1012903450 1.5668783359 0.5837064614 0.7984745345 0.1249649644 -0.0781597232342 +1413393316605760512.0000000000 -1.8858648679 -0.0963963075 1.5847683727 0.5823447178 0.7992567292 0.1257369158 -0.0790793172037 +1413393316655760384.0000000000 -1.9060412409 -0.0917981272 1.6014692498 0.5803904905 0.8004115966 0.1268387797 -0.0800004906719 +1413393316705760512.0000000000 -1.9263848057 -0.0872010250 1.6164872183 0.5784458154 0.8015571606 0.1281500127 -0.0805241037536 +1413393316755760384.0000000000 -1.9468669740 -0.0826511037 1.6292835455 0.5765032722 0.8026471625 0.1299407133 -0.0807274465753 +1413393316805760512.0000000000 -1.9677075685 -0.0779507409 1.6395566372 0.5755039777 0.8030292250 0.1314213247 -0.0816558076629 +1413393316855760384.0000000000 -1.9885905901 -0.0731521728 1.6462871987 0.5741581803 0.8036244031 0.1333437135 -0.0821562955551 +1413393316905760512.0000000000 -2.0096231953 -0.0682166540 1.6495736683 0.5738400970 0.8034783823 0.1353551720 -0.0825167237731 +1413393316955760384.0000000000 -2.0309451360 -0.0630383694 1.6499289562 0.5728482144 0.8038201597 0.1367590536 -0.083755807873 +1413393317005760512.0000000000 -2.0525367013 -0.0574022657 1.6487211692 0.5737941824 0.8028153321 0.1382066324 -0.0845381899401 +1413393317055760384.0000000000 -2.0744024463 -0.0515159455 1.6458304946 0.5761141109 0.8009250505 0.1394105029 -0.0847130829794 +1413393317105760512.0000000000 -2.0965903554 -0.0459014736 1.6411612561 0.5794677683 0.7982583383 0.1401770428 -0.0857387166656 +1413393317155760384.0000000000 -2.1190881252 -0.0404578134 1.6359707258 0.5830059829 0.7954779194 0.1408297951 -0.086520936402 +1413393317205760512.0000000000 -2.1415484199 -0.0353030463 1.6309643615 0.5866988155 0.7927042465 0.1412938713 -0.0862584454206 +1413393317255760384.0000000000 -2.1643314628 -0.0308167073 1.6264389115 0.5891335442 0.7908936725 0.1410153888 -0.0867382619722 +1413393317305760512.0000000000 -2.1873322298 -0.0270302001 1.6224340807 0.5914606659 0.7891877119 0.1407547842 -0.0868626889489 +1413393317355760384.0000000000 -2.2104761109 -0.0239461157 1.6191621596 0.5931224080 0.7880572307 0.1398180785 -0.0873070172176 +1413393317405760512.0000000000 -2.2335362667 -0.0219514617 1.6160636970 0.5942410221 0.7874133670 0.1392143186 -0.0864706339648 +1413393317455760384.0000000000 -2.2566535938 -0.0210189042 1.6132914249 0.5945591907 0.7872832570 0.1389402533 -0.0859072060013 +1413393317505760512.0000000000 -2.2798676225 -0.0210564999 1.6098947457 0.5951414865 0.7869768597 0.1385362304 -0.0853331484472 +1413393317555760384.0000000000 -2.3030624187 -0.0223955497 1.6045496121 0.5960360015 0.7864985508 0.1374420770 -0.085268927656 +1413393317605760512.0000000000 -2.3264278215 -0.0251589493 1.5966411372 0.5951286968 0.7872783748 0.1369853782 -0.0851445880443 +1413393317655760384.0000000000 -2.3498265725 -0.0287364453 1.5863032072 0.5949873138 0.7876040213 0.1356365715 -0.0852802588361 +1413393317705760512.0000000000 -2.3731992971 -0.0332511276 1.5739788044 0.5946431657 0.7881135931 0.1336154665 -0.0861590215037 +1413393317755760384.0000000000 -2.3963751971 -0.0387373661 1.5613275719 0.5941493884 0.7886485384 0.1326243335 -0.0862019334021 +1413393317805760512.0000000000 -2.4193272361 -0.0451709451 1.5495097378 0.5934585500 0.7894332503 0.1310906011 -0.0861240210686 +1413393317855760384.0000000000 -2.4418628927 -0.0524719739 1.5383025369 0.5925357762 0.7903527256 0.1306637701 -0.0846811802101 +1413393317905760512.0000000000 -2.4640515134 -0.0606479351 1.5274936526 0.5918949169 0.7911152755 0.1307752564 -0.0818221275861 +1413393317955760384.0000000000 -2.4862046705 -0.0696907420 1.5167451360 0.5899482098 0.7929346972 0.1297875283 -0.0798177497589 +1413393318005760512.0000000000 -2.5083545607 -0.0793857906 1.5060683750 0.5889706568 0.7940795136 0.1290111049 -0.0768597833371 +1413393318055760384.0000000000 -2.5308882778 -0.0898500399 1.4951478245 0.5861922938 0.7965861779 0.1266782311 -0.0760373699237 +1413393318105760512.0000000000 -2.5536061649 -0.1008086130 1.4843067433 0.5844505829 0.7983297570 0.1241055375 -0.0753984799572 +1413393318155760384.0000000000 -2.5765513136 -0.1122172092 1.4729967996 0.5818112038 0.8006803987 0.1209195675 -0.0760597161706 +1413393318205760512.0000000000 -2.5996496175 -0.1237370658 1.4614941027 0.5795950858 0.8027286629 0.1168562826 -0.07772283785 +1413393318255760384.0000000000 -2.6228635983 -0.1353216932 1.4499482827 0.5783739976 0.8039460219 0.1123823343 -0.0807745241732 +1413393318305760512.0000000000 -2.6457889025 -0.1467449326 1.4381579083 0.5783276260 0.8042845916 0.1081561186 -0.0834608089435 +1413393318355760384.0000000000 -2.6682176625 -0.1581243098 1.4257763256 0.5781570440 0.8046498620 0.1043274640 -0.0859582004485 +1413393318405760512.0000000000 -2.6899744815 -0.1694333121 1.4127325803 0.5778016569 0.8050665912 0.1020442683 -0.0871779575664 +1413393318455760384.0000000000 -2.7109388859 -0.1802772429 1.3993628358 0.5780281295 0.8050168947 0.0999442880 -0.0885574399558 +1413393318505760512.0000000000 -2.7308849913 -0.1907301607 1.3850628888 0.5781423790 0.8051087044 0.0982052404 -0.0889218449177 +1413393318555760384.0000000000 -2.7498595314 -0.2013933168 1.3701872351 0.5787592969 0.8047724539 0.0974979039 -0.0887306735784 +1413393318605760512.0000000000 -2.7678178415 -0.2118986339 1.3553277060 0.5783782015 0.8051080634 0.0967544922 -0.0889844401141 +1413393318655760384.0000000000 -2.7848059767 -0.2221667001 1.3411217075 0.5788120532 0.8048840512 0.0959847838 -0.0890235505584 +1413393318705760512.0000000000 -2.8009199562 -0.2322995156 1.3278567114 0.5784797150 0.8051118004 0.0954208176 -0.0897277869843 +1413393318755760384.0000000000 -2.8160164792 -0.2421629375 1.3161009840 0.5788477499 0.8047979656 0.0951052773 -0.0905013986718 +1413393318805760512.0000000000 -2.8298901759 -0.2518848601 1.3055152377 0.5798292846 0.8040767854 0.0959771222 -0.0897046034559 +1413393318855760384.0000000000 -2.8427000898 -0.2613536697 1.2965451124 0.5822778836 0.8023035294 0.0968159256 -0.0888154800514 +1413393318905760512.0000000000 -2.8546654352 -0.2708088028 1.2893934017 0.5870704445 0.7987566472 0.0974821042 -0.0885062206171 +1413393318955760384.0000000000 -2.8656458732 -0.2807213345 1.2831977933 0.5917105416 0.7952481668 0.0983613511 -0.0882271660691 +1413393319005760512.0000000000 -2.8754133812 -0.2914812267 1.2777224813 0.5951852940 0.7926208920 0.0990448561 -0.0877308600287 +1413393319055760384.0000000000 -2.8842574498 -0.3033611226 1.2727631867 0.5955114029 0.7922575838 0.1002790358 -0.0873968247152 +1413393319105760512.0000000000 -2.8923319681 -0.3162757467 1.2688082688 0.5927360857 0.7942081826 0.1004497478 -0.0883580418716 +1413393319155760384.0000000000 -2.8994176235 -0.3300401845 1.2658120775 0.5881322143 0.7975317826 0.1007924536 -0.0887943443445 +1413393319205760512.0000000000 -2.9057142863 -0.3444863142 1.2648622216 0.5845924635 0.7999529426 0.1012316297 -0.0898838052296 +1413393319255760384.0000000000 -2.9111131555 -0.3592482998 1.2646904412 0.5797874209 0.8033233586 0.1020460099 -0.0900263289731 +1413393319305760512.0000000000 -2.9155832123 -0.3740782318 1.2643527214 0.5753366823 0.8063980319 0.1024652536 -0.0906133979264 +1413393319355760384.0000000000 -2.9193126842 -0.3888316178 1.2627694876 0.5713840059 0.8091374767 0.1028630582 -0.0907527012099 +1413393319405760512.0000000000 -2.9224485456 -0.4031078464 1.2591171577 0.5682578023 0.8112872336 0.1038123803 -0.0901059615811 +1413393319455760384.0000000000 -2.9252734210 -0.4163021313 1.2536743574 0.5655642297 0.8131149686 0.1042844732 -0.0900327641617 +1413393319505760512.0000000000 -2.9276555428 -0.4287677904 1.2467833901 0.5610221340 0.8161353545 0.1048014627 -0.0905201731367 +1413393319555760384.0000000000 -2.9298023115 -0.4399404211 1.2384234397 0.5555792453 0.8197232041 0.1037324771 -0.0928716541267 +1413393319605760512.0000000000 -2.9315298752 -0.4496714566 1.2288182171 0.5510182230 0.8226246059 0.1027342452 -0.0954638707284 +1413393319655760384.0000000000 -2.9323805426 -0.4583915869 1.2182234250 0.5462175556 0.8256645825 0.1016186423 -0.0979695398133 +1413393319705760512.0000000000 -2.9321047108 -0.4655667611 1.2074742359 0.5433445144 0.8274316349 0.1013224810 -0.0993347022938 +1413393319755760384.0000000000 -2.9311200574 -0.4698314580 1.1959471443 0.5455658075 0.8259441311 0.1042450621 -0.0964738774176 +1413393319805760512.0000000000 -2.9294876252 -0.4717536814 1.1827066771 0.5483918831 0.8240833437 0.1095581877 -0.0902772877037 +1413393319855760384.0000000000 -2.9279565817 -0.4712777839 1.1684761250 0.5530398805 0.8208627317 0.1142534086 -0.0853078240598 +1413393319905760512.0000000000 -2.9265404902 -0.4695457977 1.1534597970 0.5577647644 0.8175059518 0.1186212894 -0.0806937178993 +1413393319955760384.0000000000 -2.9254167874 -0.4673135520 1.1368455492 0.5621811405 0.8143120659 0.1220887249 -0.077088052011 +1413393320005760512.0000000000 -2.9248317157 -0.4643448217 1.1194322562 0.5662386492 0.8113385893 0.1247862182 -0.0743766463727 +1413393320055760384.0000000000 -2.9248265727 -0.4612990481 1.1015690044 0.5694985515 0.8089461337 0.1262601679 -0.0730473994205 +1413393320105760512.0000000000 -2.9253172077 -0.4583161382 1.0835340798 0.5735237378 0.8060400121 0.1268712481 -0.0726202966671 +1413393320155760384.0000000000 -2.9265225540 -0.4548506318 1.0658115665 0.5787642415 0.8023281090 0.1266879391 -0.0724687822105 +1413393320205760512.0000000000 -2.9284131098 -0.4515968634 1.0484107263 0.5837582242 0.7988215319 0.1253572949 -0.0734577734299 +1413393320255760384.0000000000 -2.9308269286 -0.4490339581 1.0324336749 0.5867980930 0.7967486816 0.1243785832 -0.0734132444165 +1413393320305760512.0000000000 -2.9337633083 -0.4473720680 1.0187435100 0.5854141601 0.7980095324 0.1228004820 -0.0734240360324 +1413393320355760384.0000000000 -2.9373126068 -0.4464510820 1.0090899244 0.5834934567 0.7996340554 0.1213117151 -0.0735134763751 +1413393320405760512.0000000000 -2.9414495999 -0.4465035460 1.0034283050 0.5788524162 0.8031681072 0.1197556436 -0.0742257214851 +1413393320455760384.0000000000 -2.9459927138 -0.4468800954 1.0014113689 0.5739547779 0.8068766029 0.1188096046 -0.0735550029843 +1413393320505760512.0000000000 -2.9510391027 -0.4469193252 1.0022810892 0.5704592837 0.8095325853 0.1186750292 -0.0717595740658 +1413393320555760384.0000000000 -2.9565729855 -0.4468314847 1.0036197527 0.5689867908 0.8106970091 0.1187440017 -0.0701730248472 +1413393320605760512.0000000000 -2.9625826600 -0.4464217240 1.0021292439 0.5683456748 0.8113467922 0.1180948372 -0.068943355405 +1413393320655760384.0000000000 -2.9689757537 -0.4456320512 0.9947660118 0.5671488865 0.8123353394 0.1187245619 -0.0660145077848 +1413393320705760512.0000000000 -2.9761855059 -0.4444909372 0.9813183903 0.5667816967 0.8126977323 0.1186089452 -0.0649062576888 +1413393320755760384.0000000000 -2.9841030661 -0.4432380951 0.9610407520 0.5682009467 0.8117961696 0.1181076910 -0.0646934041854 +1413393320805760512.0000000000 -2.9925608244 -0.4420202482 0.9340892439 0.5703245630 0.8103753956 0.1169400473 -0.0659290252334 +1413393320855760384.0000000000 -2.9952413351 -0.4430346464 0.9261549605 0.5854086724 0.8000152068 0.1130937441 -0.0669489372375 +1413393320905760512.0000000000 -2.9900833100 -0.4459609339 0.9436582747 0.5897353911 0.7969162564 0.1150412871 -0.0624672006264 +1413393320955760384.0000000000 -2.9847547519 -0.4499899052 0.9513694592 0.5749904556 0.8075239044 0.1195534725 -0.0547547904124 +1413393321005760512.0000000000 -2.9802627922 -0.4539433853 0.9526212259 0.5647377300 0.8143194798 0.1254143255 -0.0471839814358 +1413393321055760384.0000000000 -2.9775167230 -0.4572419985 0.9473476781 0.5630128029 0.8151887522 0.1278091939 -0.0463539853612 +1413393321105760512.0000000000 -2.9761231580 -0.4595786990 0.9330802608 0.5687946278 0.8113039212 0.1251061689 -0.0510594289274 +1413393321155760384.0000000000 -2.9742106819 -0.4613911817 0.9266386578 0.5901035982 0.7964966901 0.1099039593 -0.0727453490719 +1413393321205760512.0000000000 -2.9714087436 -0.4631595802 0.9384642730 0.6008250630 0.7886575761 0.1126579225 -0.0658533510303 +1413393321255760384.0000000000 -2.9720419152 -0.4641751172 0.9410204274 0.5960385963 0.7924161384 0.1161222151 -0.0577086343401 +1413393321305760512.0000000000 -2.9724203179 -0.4638321318 0.9309808460 0.5832989510 0.8026692120 0.1126706924 -0.0528184141476 +1413393321355760384.0000000000 -2.9715430487 -0.4626623309 0.9288923119 0.5838870579 0.8022979008 0.1056630954 -0.0650330087238 +1413393321405760512.0000000000 -2.9694206274 -0.4634202291 0.9337895454 0.5888988892 0.7986780834 0.1065556221 -0.0629072080731 +1413393321455760384.0000000000 -2.9711543921 -0.4644426423 0.9335037895 0.5919447732 0.7965027345 0.1053561315 -0.0639129489065 +1413393321505760512.0000000000 -2.9713543761 -0.4639758143 0.9313748725 0.5911867908 0.7969596557 0.1083625133 -0.06009202415 +1413393321555760384.0000000000 -2.9707488073 -0.4635080173 0.9323754683 0.5884076990 0.7990787177 0.1061871207 -0.0630387038044 +1413393321605760512.0000000000 -2.9708707503 -0.4635680226 0.9315992683 0.5890776692 0.7985583704 0.1067947813 -0.0623450343308 +1413393321655760384.0000000000 -2.9712777656 -0.4641928029 0.9319170019 0.5905810139 0.7974631337 0.1068392377 -0.0620644317546 +1413393321705760512.0000000000 -2.9707208019 -0.4639898334 0.9320624347 0.5910484742 0.7971157053 0.1066957306 -0.0623239489462 +1413393321755760384.0000000000 -2.9708708517 -0.4639568395 0.9315485788 0.5895548638 0.7982198641 0.1065933735 -0.0625137095616 +1413393321805760512.0000000000 -2.9709248219 -0.4640198434 0.9317088918 0.5903980048 0.7976059004 0.1066874263 -0.0622319583756 +1413393321855760384.0000000000 -2.9707694231 -0.4641894975 0.9317111766 0.5906142222 0.7974490633 0.1064465002 -0.0626017142992 +1413393321905760512.0000000000 -2.9707135690 -0.4641217871 0.9317932345 0.5907793120 0.7973303463 0.1064925639 -0.0624776537306 +1413393321955760384.0000000000 -2.9710488937 -0.4641914066 0.9316062530 0.5901557584 0.7977867509 0.1064677528 -0.0625867277978 +1413393322005760512.0000000000 -2.9707429938 -0.4641372474 0.9317764682 0.5909067572 0.7972348767 0.1065008652 -0.0624765658557 +1413393322055760384.0000000000 -2.9709203930 -0.4642166657 0.9317456384 0.5908324101 0.7972813621 0.1063791511 -0.0627930655624 +1413393322105760512.0000000000 -2.9709121141 -0.4641252254 0.9316926485 0.5907271951 0.7973615699 0.1065167284 -0.0625307472753 +1413393322155760384.0000000000 -2.9708751111 -0.4641453272 0.9317085294 0.5906803100 0.7973909773 0.1064606416 -0.0626939592358 +1413393322205760512.0000000000 -2.9709237076 -0.4641897782 0.9317905564 0.5909284326 0.7971975059 0.1065146544 -0.0627244175379 +1413393322255760384.0000000000 -2.9709631319 -0.4641280559 0.9317502793 0.5908650880 0.7972642419 0.1063972545 -0.0626721678629 +1413393322305760512.0000000000 -2.9709049681 -0.4640995773 0.9317072454 0.5907861092 0.7973219340 0.1064185589 -0.0626466048786 +1413393322355760384.0000000000 -2.9709603754 -0.4642173767 0.9317002069 0.5909382754 0.7971992594 0.1064566010 -0.0627079554243 +1413393322405760512.0000000000 -2.9708979306 -0.4642441799 0.9316147700 0.5908701901 0.7972582487 0.1064183655 -0.0626644629391 +1413393322455760384.0000000000 -2.9708747336 -0.4642449460 0.9315398030 0.5908890685 0.7972549816 0.1063772332 -0.0625978219236 +1413393322505760512.0000000000 -2.9708861320 -0.4643313659 0.9315282733 0.5909326881 0.7972114682 0.1064108688 -0.0626830125899 +1413393322555760384.0000000000 -2.9708119069 -0.4643344298 0.9314937063 0.5909823449 0.7971623221 0.1065017495 -0.0626855455971 +1413393322605760512.0000000000 -2.9708060348 -0.4643322914 0.9314504898 0.5909459676 0.7972020461 0.1064347435 -0.0626371012811 +1413393322655760384.0000000000 -2.9707447579 -0.4643138841 0.9314634243 0.5909319584 0.7972192298 0.1063926603 -0.0626220569442 +1413393322705760512.0000000000 -2.9707135414 -0.4643391395 0.9315317667 0.5909080391 0.7972291084 0.1064176907 -0.062679447719 +1413393322755760384.0000000000 -2.9707380468 -0.4643364347 0.9315618540 0.5909073240 0.7972227874 0.1064331013 -0.0627403906436 +1413393322805760512.0000000000 -2.9707339326 -0.4643153315 0.9315406756 0.5909739478 0.7971763959 0.1064418687 -0.0626874432451 +1413393322855760384.0000000000 -2.9707318661 -0.4642623863 0.9315151272 0.5909679022 0.7971800583 0.1064447054 -0.0626930446853 +1413393322905760512.0000000000 -2.9707769198 -0.4642346755 0.9315022783 0.5909449615 0.7971965401 0.1064323970 -0.0627206002679 +1413393322955760384.0000000000 -2.9707604282 -0.4642094687 0.9315318159 0.5909958360 0.7971625146 0.1063960397 -0.0627353952431 +1413393323005760512.0000000000 -2.9707611612 -0.4642161774 0.9315469138 0.5910014994 0.7971524524 0.1064177720 -0.0627730289875 +1413393323055760384.0000000000 -2.9707313327 -0.4642425476 0.9315355683 0.5910248368 0.7971275458 0.1064412236 -0.0628298008719 +1413393323105760512.0000000000 -2.9706668618 -0.4643030909 0.9315335754 0.5910136180 0.7971284669 0.1064802325 -0.0628575421541 +1413393323155760384.0000000000 -2.9706400621 -0.4643520599 0.9316013317 0.5910510305 0.7970976685 0.1064788076 -0.0628987268585 +1413393323205760512.0000000000 -2.9706265091 -0.4643730777 0.9316424742 0.5910707855 0.7970802483 0.1064953310 -0.0629058725028 +1413393323255760384.0000000000 -2.9706219127 -0.4643869543 0.9316914180 0.5910514491 0.7970946126 0.1065006061 -0.0628966133061 +1413393323305760512.0000000000 -2.9706557568 -0.4644120751 0.9317771794 0.5910570235 0.7970931399 0.1064715311 -0.0629121154791 +1413393323355760384.0000000000 -2.9706567765 -0.4644153132 0.9318426760 0.5910509887 0.7970956485 0.1064999841 -0.0628888638486 +1413393323405760512.0000000000 -2.9707035513 -0.4643361805 0.9319041021 0.5910038485 0.7971370988 0.1064556700 -0.062881532808 +1413393323455760384.0000000000 -2.9707427269 -0.4643246750 0.9317924940 0.5910151588 0.7971222675 0.1064629479 -0.0629508808077 +1413393323505760512.0000000000 -2.9707899022 -0.4643677380 0.9315864884 0.5910582495 0.7970860975 0.1064542715 -0.0630189419346 +1413393323555760384.0000000000 -2.9708414608 -0.4643948258 0.9314300587 0.5910204641 0.7971097036 0.1064931286 -0.0630090866653 +1413393323605760512.0000000000 -2.9708754153 -0.4643748174 0.9312876345 0.5910070697 0.7971226451 0.1064601821 -0.0630266753925 +1413393323655760384.0000000000 -2.9708864274 -0.4643667443 0.9311920265 0.5909944901 0.7971340550 0.1064526070 -0.0630131214291 +1413393323705760512.0000000000 -2.9708781710 -0.4643701849 0.9311185574 0.5910122189 0.7971174534 0.1064792140 -0.0630119002839 +1413393323755760384.0000000000 -2.9708300611 -0.4643689489 0.9310657747 0.5909788592 0.7971451568 0.1064571106 -0.0630116700181 +1413393323805760512.0000000000 -2.9708217068 -0.4643838941 0.9310476473 0.5909678705 0.7971521496 0.1064523466 -0.0630343095945 +1413393323855760384.0000000000 -2.9708253803 -0.4643854435 0.9310427602 0.5909862041 0.7971339281 0.1065065370 -0.0630013083356 +1413393323905760512.0000000000 -2.9708316784 -0.4643761279 0.9310449071 0.5909640899 0.7971526518 0.1064594823 -0.0630513498292 +1413393323955760384.0000000000 -2.9708187837 -0.4643851439 0.9310860007 0.5909804759 0.7971386149 0.1065116171 -0.0629871514913 +1413393324005760512.0000000000 -2.9708022696 -0.4643819564 0.9311411237 0.5909741441 0.7971456499 0.1064636073 -0.0630386713193 +1413393324055760384.0000000000 -2.9707757255 -0.4643803041 0.9311773449 0.5909713059 0.7971469647 0.1065067679 -0.0629757150176 +1413393324105760512.0000000000 -2.9707500474 -0.4643977593 0.9311839106 0.5909464625 0.7971637817 0.1064944829 -0.063016733612 +1413393324155760384.0000000000 -2.9707542291 -0.4644328318 0.9311802949 0.5909552165 0.7971575172 0.1065270228 -0.0629588619591 +1413393324205760512.0000000000 -2.9707583959 -0.4644604682 0.9312306213 0.5909749626 0.7971452834 0.1064961320 -0.0629806682168 +1413393324255760384.0000000000 -2.9707775239 -0.4644825679 0.9312591118 0.5909428882 0.7971656627 0.1065257216 -0.0629736431772 +1413393324305760512.0000000000 -2.9707740490 -0.4644756048 0.9312617192 0.5909235711 0.7971792332 0.1065204493 -0.0629920401822 +1413393324355760384.0000000000 -2.9707854689 -0.4644429564 0.9312483940 0.5909155311 0.7971850571 0.1065269263 -0.0629828064834 +1413393324405760512.0000000000 -2.9708334684 -0.4644442764 0.9312139223 0.5909176391 0.7971768046 0.1065593220 -0.0630126722189 +1413393324455760384.0000000000 -2.9708754010 -0.4644491840 0.9311843886 0.5909223824 0.7971751519 0.1065316186 -0.0630359378434 +1413393324505760512.0000000000 -2.9708822434 -0.4644756013 0.9311198106 0.5908861865 0.7971939687 0.1066015194 -0.0630191003066 +1413393324555760384.0000000000 -2.9708753570 -0.4645007892 0.9310679677 0.5908536747 0.7972150749 0.1066184159 -0.0630283503374 +1413393324605760512.0000000000 -2.9708418975 -0.4644965461 0.9310345059 0.5908602596 0.7972065425 0.1066585984 -0.0630065521153 +1413393324655760384.0000000000 -2.9708586777 -0.4644782819 0.9310539133 0.5908483280 0.7972124842 0.1066806835 -0.063005874603 +1413393324705760512.0000000000 -2.9708752459 -0.4644821407 0.9310684307 0.5908352616 0.7972179593 0.1067091618 -0.0630109022 +1413393324755760384.0000000000 -2.9708551405 -0.4644915927 0.9310839718 0.5908383709 0.7972121070 0.1067331049 -0.0630152383532 +1413393324805760512.0000000000 -2.9708264855 -0.4645017228 0.9311131598 0.5908398517 0.7972086496 0.1067365208 -0.0630393034499 +1413393324855760384.0000000000 -2.9707659318 -0.4644767571 0.9311508624 0.5908107523 0.7972279775 0.1067590459 -0.0630294608855 +1413393324905760512.0000000000 -2.9707075092 -0.4644681525 0.9311836765 0.5908178771 0.7972236740 0.1067383984 -0.0630520734221 +1413393324955760384.0000000000 -2.9706776068 -0.4644986208 0.9312193638 0.5907812083 0.7972489500 0.1067517622 -0.0630534454809 +1413393325005760512.0000000000 -2.9706511120 -0.4645091274 0.9312142024 0.5907805227 0.7972468936 0.1067537799 -0.0630824470932 +1413393325055760384.0000000000 -2.9706241658 -0.4645118248 0.9311938115 0.5907917693 0.7972386533 0.1067422149 -0.0631008279749 +1413393325105760512.0000000000 -2.9706576477 -0.4645311052 0.9311481018 0.5907786066 0.7972329199 0.1068179181 -0.0631683613574 +1413393325155760384.0000000000 -2.9707091698 -0.4645516687 0.9310934234 0.5907048074 0.7972911051 0.1067952635 -0.0631624564838 +1413393325205760512.0000000000 -2.9707682528 -0.4646001238 0.9310575138 0.5906780355 0.7973054359 0.1068091089 -0.0632085002303 +1413393325255760384.0000000000 -2.9708339983 -0.4646416966 0.9310151836 0.5907066364 0.7972815174 0.1068227019 -0.0632199499178 +1413393325305760512.0000000000 -2.9709321784 -0.4646794980 0.9310052958 0.5906992630 0.7972770285 0.1068621479 -0.0632787631922 +1413393325355760384.0000000000 -2.9710356287 -0.4647183245 0.9310146351 0.5906733247 0.7972977766 0.1068386176 -0.0632991997062 +1413393325405760512.0000000000 -2.9711603003 -0.4647505950 0.9310668263 0.5906812667 0.7972907101 0.1068235451 -0.0633395205082 +1413393325455760384.0000000000 -2.9712838138 -0.4647519531 0.9311527960 0.5906977919 0.7973099620 0.1066759084 -0.0631917219542 diff --git a/data/euroc_groundtruth/V2_02_medium.txt b/data/euroc_groundtruth/V2_02_medium.txt new file mode 100755 index 00000000..1a537a73 --- /dev/null +++ b/data/euroc_groundtruth/V2_02_medium.txt @@ -0,0 +1,2310 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1413393887255760384.0000000000 -1.0015689347 0.4141769115 1.3066970514 0.4134526643 0.5539092534 0.5832203034 -0.426726506144 +1413393887305760512.0000000000 -1.0027620519 0.4140434295 1.3065348813 0.4134223843 0.5539398609 0.5832670628 -0.426652195718 +1413393887355760384.0000000000 -1.0036602084 0.4139507385 1.3064876562 0.4134479154 0.5540319114 0.5831752378 -0.42663345443 +1413393887405760512.0000000000 -1.0042670068 0.4139217677 1.3063770302 0.4134436852 0.5541313235 0.5831565583 -0.426533965843 +1413393887455760384.0000000000 -1.0046488641 0.4138853406 1.3064192335 0.4133100632 0.5541927127 0.5831801917 -0.426551395251 +1413393887505760512.0000000000 -1.0048077485 0.4138484092 1.3064169974 0.4132240486 0.5541575597 0.5832649471 -0.426564515897 +1413393887555760384.0000000000 -1.0048687556 0.4138832521 1.3065311577 0.4131578907 0.5541708025 0.5832452355 -0.426638341424 +1413393887605760512.0000000000 -1.0048283979 0.4140305739 1.3066988386 0.4133851147 0.5541721281 0.5831950694 -0.426485064676 +1413393887655760384.0000000000 -1.0046467253 0.4140420566 1.3070645117 0.4133934840 0.5542450580 0.5828560534 -0.426845480252 +1413393887705760512.0000000000 -1.0044945897 0.4139995671 1.3068919150 0.4132057358 0.5543854918 0.5829076769 -0.42677439763 +1413393887755760384.0000000000 -1.0044440076 0.4140094801 1.3069943763 0.4132768958 0.5543515986 0.5828154230 -0.426875503374 +1413393887805760512.0000000000 -1.0042420762 0.4139805240 1.3067851678 0.4132096625 0.5543802023 0.5830126726 -0.426634023123 +1413393887855760384.0000000000 -1.0041235173 0.4139112598 1.3068017733 0.4131375062 0.5544545995 0.5829280708 -0.426722816722 +1413393887905760512.0000000000 -1.0039619892 0.4139265665 1.3065399419 0.4129984274 0.5545791085 0.5830808689 -0.426486824738 +1413393887955760384.0000000000 -1.0038449911 0.4138327474 1.3065811472 0.4129184977 0.5546279859 0.5829809114 -0.426637279761 +1413393888005760512.0000000000 -1.0037483812 0.4138314616 1.3063460576 0.4129582436 0.5546043031 0.5830724228 -0.426504520355 +1413393888055760384.0000000000 -1.0037815965 0.4137857839 1.3063605555 0.4128046054 0.5547716955 0.5830842657 -0.426419350832 +1413393888105760512.0000000000 -1.0037707171 0.4137491940 1.3062369105 0.4127226935 0.5547742756 0.5831448960 -0.426412372791 +1413393888155760384.0000000000 -1.0037652803 0.4137692930 1.3063151557 0.4128571343 0.5547641744 0.5829950478 -0.426500259865 +1413393888205760512.0000000000 -1.0037872369 0.4137185192 1.3061853794 0.4126933747 0.5548269671 0.5831102407 -0.426419584777 +1413393888255760384.0000000000 -1.0037993975 0.4136953173 1.3062700691 0.4126898252 0.5549183202 0.5830525105 -0.426383086046 +1413393888305760512.0000000000 -1.0037677772 0.4136519845 1.3062613802 0.4126953662 0.5549096247 0.5830796996 -0.42635185824 +1413393888355760384.0000000000 -1.0037583751 0.4136133894 1.3064282619 0.4126247319 0.5549605116 0.5830110005 -0.426447927041 +1413393888405760512.0000000000 -1.0037393082 0.4137123863 1.3065923362 0.4128851676 0.5548962836 0.5828873473 -0.426448464771 +1413393888455760384.0000000000 -1.0037349021 0.4137138645 1.3066596116 0.4126396667 0.5550228893 0.5830100103 -0.426353639251 +1413393888505760512.0000000000 -1.0036625530 0.4138278599 1.3067487905 0.4125873879 0.5550400865 0.5830337851 -0.42634933463 +1413393888555760384.0000000000 -1.0034912114 0.4138996760 1.3069164486 0.4127200841 0.5548990855 0.5828926203 -0.42659738663 +1413393888605760512.0000000000 -1.0034034794 0.4140050280 1.3069153862 0.4126771881 0.5549121213 0.5828975075 -0.426615250282 +1413393888655760384.0000000000 -1.0035507214 0.4139806751 1.3071863277 0.4126219799 0.5549586060 0.5828023949 -0.426738111546 +1413393888705760512.0000000000 -1.0036068411 0.4140295662 1.3072233083 0.4126683051 0.5548978897 0.5828460991 -0.426712580964 +1413393888755760384.0000000000 -1.0037007870 0.4140089642 1.3074204986 0.4127127405 0.5548782759 0.5826742380 -0.42692976602 +1413393888805760512.0000000000 -1.0037276022 0.4139918914 1.3073720623 0.4127454976 0.5547988322 0.5826806355 -0.426992607637 +1413393888855760384.0000000000 -1.0037414006 0.4139462377 1.3072795454 0.4125514441 0.5549658337 0.5826919512 -0.426947677569 +1413393888905760512.0000000000 -1.0037191583 0.4141080626 1.3071521811 0.4126874787 0.5548919366 0.5826769456 -0.426932735515 +1413393888955760384.0000000000 -1.0036212516 0.4140177539 1.3073493522 0.4127004833 0.5548733323 0.5825918640 -0.427060436233 +1413393889005760512.0000000000 -1.0035699720 0.4138960939 1.3077822374 0.4129722094 0.5546397121 0.5822865187 -0.427517431416 +1413393889055760384.0000000000 -1.0034789532 0.4138708704 1.3077337401 0.4131110112 0.5545017669 0.5824278928 -0.427369667485 +1413393889105760512.0000000000 -1.0035506365 0.4136699004 1.3079488624 0.4127938910 0.5547108212 0.5823144111 -0.42755939365 +1413393889155760384.0000000000 -1.0036481401 0.4136440280 1.3084684324 0.4129423822 0.5547408763 0.5819975612 -0.427808354162 +1413393889205760512.0000000000 -1.0035937412 0.4138235194 1.3087838196 0.4128172241 0.5546720314 0.5820596927 -0.427933863027 +1413393889255760384.0000000000 -1.0037358386 0.4138864839 1.3094702870 0.4131433935 0.5543906461 0.5818917406 -0.428212038723 +1413393889305760512.0000000000 -1.0037740181 0.4140024090 1.3094881255 0.4125670485 0.5544984452 0.5824079363 -0.427926279321 +1413393889355760384.0000000000 -1.0037625757 0.4143053200 1.3092636718 0.4116525339 0.5553536808 0.5829383503 -0.426974660106 +1413393889405760512.0000000000 -1.0034717564 0.4146225509 1.3093363637 0.4106381299 0.5561874250 0.5833279752 -0.426333610972 +1413393889455760384.0000000000 -1.0028233740 0.4150270286 1.3093176181 0.4102355951 0.5568558702 0.5836601527 -0.42539290361 +1413393889505760512.0000000000 -1.0019988383 0.4153375562 1.3091772244 0.4085503066 0.5583643110 0.5843136953 -0.424138478106 +1413393889555760384.0000000000 -1.0008560730 0.4160801191 1.3090515189 0.4054826051 0.5610672247 0.5868988383 -0.419925207583 +1413393889605760512.0000000000 -0.9998563216 0.4171713576 1.3099825148 0.4027055861 0.5636930671 0.5894545791 -0.415477600093 +1413393889655760384.0000000000 -0.9986161515 0.4190115648 1.3122965886 0.4007624433 0.5661639527 0.5924582079 -0.409684164505 +1413393889705760512.0000000000 -0.9979749399 0.4211939707 1.3171381173 0.4016068261 0.5663673901 0.5955658178 -0.404031302337 +1413393889755760384.0000000000 -0.9977117647 0.4234769859 1.3250910732 0.4016388124 0.5669316505 0.5993223189 -0.397602221021 +1413393889805760512.0000000000 -0.9987136208 0.4255244307 1.3377333103 0.4027304937 0.5668051748 0.6016513919 -0.393135658331 +1413393889855760384.0000000000 -1.0009432447 0.4271657782 1.3542762033 0.4050392236 0.5654641601 0.6049723748 -0.38755894607 +1413393889905760512.0000000000 -1.0046833825 0.4280030634 1.3754402363 0.4092812217 0.5623530529 0.6078626654 -0.383080808033 +1413393889955760384.0000000000 -1.0104781987 0.4275245676 1.4008962637 0.4159938343 0.5578582020 0.6087626451 -0.380987399015 +1413393890005760512.0000000000 -1.0177548870 0.4250496073 1.4296801558 0.4228650312 0.5527084736 0.6090305249 -0.380500102956 +1413393890055760384.0000000000 -1.0261330334 0.4202013271 1.4612158895 0.4265665048 0.5505797078 0.6065418187 -0.383418863034 +1413393890105760512.0000000000 -1.0351103533 0.4129912904 1.4940688847 0.4266108852 0.5510700383 0.6027883956 -0.38855001695 +1413393890155760384.0000000000 -1.0443979859 0.4040595862 1.5254815943 0.4262669039 0.5518279341 0.5986037124 -0.394279156528 +1413393890205760512.0000000000 -1.0538482785 0.3938602042 1.5525261114 0.4249641566 0.5532638123 0.5950439406 -0.399032991566 +1413393890255760384.0000000000 -1.0636441578 0.3826886991 1.5746393018 0.4238529459 0.5543404966 0.5919483627 -0.403301909171 +1413393890305760512.0000000000 -1.0735950562 0.3708621897 1.5916572038 0.4221833705 0.5559382947 0.5893547505 -0.406638404783 +1413393890355760384.0000000000 -1.0835374506 0.3585698211 1.6033480253 0.4205927496 0.5573788451 0.5876401968 -0.408790363277 +1413393890405760512.0000000000 -1.0934684606 0.3458286240 1.6096311930 0.4189960473 0.5587140674 0.5860679434 -0.410859183938 +1413393890455760384.0000000000 -1.1035351801 0.3328223206 1.6117159823 0.4189237256 0.5590194678 0.5833260303 -0.41440425811 +1413393890505760512.0000000000 -1.1137896604 0.3194662608 1.6116257710 0.4214425765 0.5572424147 0.5786071504 -0.420809709296 +1413393890555760384.0000000000 -1.1237971964 0.3061850792 1.6124012038 0.4257293371 0.5538016622 0.5727335319 -0.428992484601 +1413393890605760512.0000000000 -1.1325836080 0.2933454584 1.6134021826 0.4308078227 0.5502640852 0.5683802190 -0.434232636941 +1413393890655760384.0000000000 -1.1393812728 0.2808462953 1.6137468780 0.4325275661 0.5490649090 0.5680729740 -0.434443007311 +1413393890705760512.0000000000 -1.1442158502 0.2684792862 1.6139555128 0.4310574983 0.5502934834 0.5705112879 -0.431141955286 +1413393890755760384.0000000000 -1.1473299598 0.2561635612 1.6148721555 0.4287969278 0.5519707293 0.5740314504 -0.42655527493 +1413393890805760512.0000000000 -1.1492255195 0.2437813751 1.6168883906 0.4257516845 0.5542712906 0.5773106054 -0.422174495219 +1413393890855760384.0000000000 -1.1503586842 0.2315483037 1.6199941058 0.4236894632 0.5560561779 0.5801524347 -0.417985547964 +1413393890905760512.0000000000 -1.1509619738 0.2190584431 1.6243578997 0.4217288830 0.5575330993 0.5819701320 -0.415466434232 +1413393890955760384.0000000000 -1.1513934352 0.2063544646 1.6296774429 0.4209461318 0.5580900467 0.5837318534 -0.413033869248 +1413393891005760512.0000000000 -1.1518354591 0.1933222582 1.6360258369 0.4201847551 0.5587386796 0.5848601009 -0.411332617218 +1413393891055760384.0000000000 -1.1523292935 0.1798784353 1.6432459317 0.4199364699 0.5585765492 0.5861959696 -0.409902287259 +1413393891105760512.0000000000 -1.1530699261 0.1660750141 1.6518774480 0.4201011369 0.5584602285 0.5858741545 -0.410351901569 +1413393891155760384.0000000000 -1.1537056632 0.1519106207 1.6611898102 0.4190232220 0.5589656416 0.5859192483 -0.410701333505 +1413393891205760512.0000000000 -1.1544733199 0.1376033261 1.6707249928 0.4191217284 0.5586615444 0.5855484566 -0.41154253802 +1413393891255760384.0000000000 -1.1548958621 0.1230843207 1.6773294719 0.4196613254 0.5581203462 0.5844571376 -0.413274612568 +1413393891305760512.0000000000 -1.1558591587 0.1083807052 1.6806178299 0.4240898309 0.5545365850 0.5810088730 -0.418408509347 +1413393891355760384.0000000000 -1.1572438617 0.0934628965 1.6818264754 0.4355209507 0.5455186840 0.5715253428 -0.431381095389 +1413393891405760512.0000000000 -1.1573360854 0.0785049163 1.6810312975 0.4500182974 0.5334425685 0.5575139217 -0.449556209205 +1413393891455760384.0000000000 -1.1537136376 0.0632877556 1.6781489585 0.4634762726 0.5207354224 0.5429417657 -0.468229221266 +1413393891505760512.0000000000 -1.1451141820 0.0484709363 1.6738861984 0.4740905822 0.5107888348 0.5313832928 -0.481627119555 +1413393891555760384.0000000000 -1.1304503283 0.0340326467 1.6691211863 0.4794317984 0.5045967329 0.5244034361 -0.490436870572 +1413393891605760512.0000000000 -1.1087303912 0.0205572031 1.6640609547 0.4838770460 0.5008431598 0.5231545181 -0.491251955647 +1413393891655760384.0000000000 -1.0798337348 0.0073467323 1.6604153861 0.4837642952 0.5007025347 0.5226420033 -0.492051231854 +1413393891705760512.0000000000 -1.0437707624 -0.0052635224 1.6576638709 0.4840225211 0.5005756678 0.5231907349 -0.491342706066 +1413393891755760384.0000000000 -1.0018197591 -0.0175088143 1.6571472245 0.4832666292 0.5010583274 0.5242014885 -0.490516785763 +1413393891805760512.0000000000 -0.9534842568 -0.0291300252 1.6586472608 0.4825171236 0.5022608215 0.5257358639 -0.488378023716 +1413393891855760384.0000000000 -0.8979433981 -0.0403674279 1.6614388194 0.4799982145 0.5050917554 0.5290463944 -0.484348991298 +1413393891905760512.0000000000 -0.8359549320 -0.0512312899 1.6651667445 0.4741069862 0.5111151352 0.5355006279 -0.476679097204 +1413393891955760384.0000000000 -0.7680953784 -0.0617686191 1.6692540402 0.4644624316 0.5203532139 0.5448853994 -0.465410661496 +1413393892005760512.0000000000 -0.6955688333 -0.0721162188 1.6740569439 0.4518639242 0.5315650065 0.5563867330 -0.451321882038 +1413393892055760384.0000000000 -0.6197550929 -0.0824669140 1.6803318986 0.4400785931 0.5415060558 0.5670692982 -0.437646472045 +1413393892105760512.0000000000 -0.5423520666 -0.0929058419 1.6883672718 0.4305791452 0.5494027409 0.5752806508 -0.426392308574 +1413393892155760384.0000000000 -0.4645175623 -0.1034406016 1.6979334682 0.4239970650 0.5550524789 0.5814488902 -0.417205492132 +1413393892205760512.0000000000 -0.3867558681 -0.1144054161 1.7080390529 0.4194391605 0.5588571146 0.5855688297 -0.410924155724 +1413393892255760384.0000000000 -0.3095932063 -0.1255536814 1.7170437148 0.4177182386 0.5609122870 0.5882269615 -0.406051623831 +1413393892305760512.0000000000 -0.2338112072 -0.1371618908 1.7244609365 0.4163721628 0.5628848504 0.5888149289 -0.403846315749 +1413393892355760384.0000000000 -0.1594388466 -0.1490391141 1.7293075309 0.4147741920 0.5648539575 0.5901969295 -0.400711817597 +1413393892405760512.0000000000 -0.0862167207 -0.1611614067 1.7314249636 0.4130242324 0.5669392020 0.5912487558 -0.398014865888 +1413393892455760384.0000000000 -0.0143886162 -0.1735463241 1.7305205082 0.4119597956 0.5686265134 0.5919991025 -0.395588267935 +1413393892505760512.0000000000 0.0558371886 -0.1863383185 1.7271183795 0.4121430079 0.5693068739 0.5925873371 -0.39353280981 +1413393892555760384.0000000000 0.1245688787 -0.1997809922 1.7209748821 0.4106343257 0.5713312778 0.5928612561 -0.391759559669 +1413393892605760512.0000000000 0.1923397679 -0.2135885611 1.7125989075 0.4085427139 0.5733753960 0.5944136111 -0.388594859956 +1413393892655760384.0000000000 0.2583301210 -0.2277642765 1.7023916224 0.4048035872 0.5764181226 0.5972819339 -0.383575931386 +1413393892705760512.0000000000 0.3221486573 -0.2422960603 1.6917950652 0.3995531225 0.5806345703 0.6015594226 -0.375961512783 +1413393892755760384.0000000000 0.3835300632 -0.2573762612 1.6813375010 0.3918103004 0.5858270627 0.6068746721 -0.367415940724 +1413393892805760512.0000000000 0.4416617179 -0.2730140918 1.6712286556 0.3840332079 0.5904822143 0.6132038950 -0.357533541057 +1413393892855760384.0000000000 0.4951791830 -0.2893188206 1.6627751295 0.3772310506 0.5949061281 0.6179497221 -0.349172699589 +1413393892905760512.0000000000 0.5437140123 -0.3065223476 1.6556880191 0.3698587257 0.5990853858 0.6226017751 -0.341567348028 +1413393892955760384.0000000000 0.5865284766 -0.3247375434 1.6500288347 0.3634109707 0.6020806708 0.6270432738 -0.335034423582 +1413393893005760512.0000000000 0.6231183999 -0.3436934889 1.6458620326 0.3589751884 0.6041213584 0.6307082506 -0.329213154546 +1413393893055760384.0000000000 0.6530060022 -0.3638571408 1.6434428306 0.3561522123 0.6048763017 0.6329148235 -0.326648262853 +1413393893105760512.0000000000 0.6758146102 -0.3848728178 1.6424058627 0.3547801908 0.6050529925 0.6338661208 -0.325968761424 +1413393893155760384.0000000000 0.6915362802 -0.4067824488 1.6434709283 0.3560562881 0.6038390777 0.6328352040 -0.328818935914 +1413393893205760512.0000000000 0.7006522699 -0.4293065099 1.6461787402 0.3598676085 0.6006640663 0.6316977899 -0.332649794883 +1413393893255760384.0000000000 0.7034779586 -0.4527027389 1.6503768017 0.3632829259 0.5985775745 0.6294645168 -0.336904771609 +1413393893305760512.0000000000 0.7004052534 -0.4771380358 1.6561215698 0.3648827856 0.5982853755 0.6257745361 -0.342522104594 +1413393893355760384.0000000000 0.6922990642 -0.5022075112 1.6629043938 0.3636057815 0.5999959010 0.6220182836 -0.347690968034 +1413393893405760512.0000000000 0.6786736594 -0.5273461451 1.6708027770 0.3630888234 0.6015717462 0.6174253966 -0.353643634346 +1413393893455760384.0000000000 0.6604881293 -0.5524219449 1.6789417349 0.3616481070 0.6033210516 0.6136437370 -0.358686101634 +1413393893505760512.0000000000 0.6380716559 -0.5773041734 1.6872784649 0.3590795981 0.6049645514 0.6111821046 -0.362679154049 +1413393893555760384.0000000000 0.6113633234 -0.6013856885 1.6958537760 0.3575886418 0.6058880373 0.6088728006 -0.366475049946 +1413393893605760512.0000000000 0.5803123592 -0.6246311525 1.7046755875 0.3562885042 0.6066169738 0.6064016092 -0.370609548227 +1413393893655760384.0000000000 0.5454248848 -0.6467593867 1.7131852402 0.3530924020 0.6083094661 0.6049179948 -0.373308945238 +1413393893705760512.0000000000 0.5061034103 -0.6674212564 1.7221234074 0.3507060609 0.6100385188 0.6026488143 -0.376394302612 +1413393893755760384.0000000000 0.4624908519 -0.6864679355 1.7317968815 0.3504108226 0.6103382074 0.5998169383 -0.380682503548 +1413393893805760512.0000000000 0.4150678444 -0.7035296616 1.7418397614 0.3519579369 0.6093691756 0.5978667192 -0.38386222083 +1413393893855760384.0000000000 0.3637050786 -0.7188334861 1.7529752900 0.3573719813 0.6066770660 0.5938633518 -0.389300043574 +1413393893905760512.0000000000 0.3093177883 -0.7322986903 1.7640601898 0.3642554862 0.6019764268 0.5909679708 -0.394587353874 +1413393893955760384.0000000000 0.2522617141 -0.7439436499 1.7754465663 0.3723012964 0.5966947220 0.5869626115 -0.401026241169 +1413393894005760512.0000000000 0.1935179475 -0.7540784030 1.7866665278 0.3781522063 0.5931260324 0.5837810008 -0.405465364324 +1413393894055760384.0000000000 0.1336460406 -0.7629883301 1.7977803401 0.3820608471 0.5898395972 0.5824327117 -0.408522820744 +1413393894105760512.0000000000 0.0725086838 -0.7705246933 1.8094142229 0.3846852315 0.5879909179 0.5808586217 -0.410958896558 +1413393894155760384.0000000000 0.0107174331 -0.7768386104 1.8211360333 0.3848557575 0.5874907140 0.5800456965 -0.412659298813 +1413393894205760512.0000000000 -0.0518085610 -0.7817527380 1.8330815887 0.3842698575 0.5874464753 0.5794774892 -0.414064191725 +1413393894255760384.0000000000 -0.1151372824 -0.7848413910 1.8448357491 0.3842962256 0.5875926628 0.5787241004 -0.414885151918 +1413393894305760512.0000000000 -0.1789831013 -0.7865434075 1.8557309498 0.3832805496 0.5884139188 0.5775644565 -0.416274403573 +1413393894355760384.0000000000 -0.2432044565 -0.7866879465 1.8637047964 0.3834981902 0.5882821402 0.5770996935 -0.416904311992 +1413393894405760512.0000000000 -0.3079928299 -0.7855516187 1.8666271608 0.3843671933 0.5875802519 0.5776866518 -0.416280483151 +1413393894455760384.0000000000 -0.3733822856 -0.7832537866 1.8645552131 0.3860145646 0.5862309306 0.5784931646 -0.415537856769 +1413393894505760512.0000000000 -0.4393005105 -0.7798160617 1.8584292187 0.3881519300 0.5845782279 0.5789614390 -0.415222864002 +1413393894555760384.0000000000 -0.5059573181 -0.7752062024 1.8496986516 0.3915818944 0.5825474905 0.5791403316 -0.414606461075 +1413393894605760512.0000000000 -0.5728842418 -0.7695618119 1.8384140472 0.3940041817 0.5809103942 0.5800241074 -0.413371326475 +1413393894655760384.0000000000 -0.6404355422 -0.7629268628 1.8266063023 0.3969945932 0.5788726647 0.5800626826 -0.413314668512 +1413393894705760512.0000000000 -0.7079929279 -0.7554170787 1.8149164791 0.3990435586 0.5775266551 0.5801360259 -0.41312152258 +1413393894755760384.0000000000 -0.7754257086 -0.7471995168 1.8040092600 0.4005492799 0.5758123988 0.5805487012 -0.413477401214 +1413393894805760512.0000000000 -0.8427451907 -0.7382535195 1.7938173889 0.4000023937 0.5756392117 0.5806822684 -0.41406000313 +1413393894855760384.0000000000 -0.9100758498 -0.7286242813 1.7847354078 0.4010416804 0.5745005604 0.5802643750 -0.415220341201 +1413393894905760512.0000000000 -0.9771529292 -0.7187085570 1.7766602479 0.4030028513 0.5723002103 0.5798796231 -0.41689422384 +1413393894955760384.0000000000 -1.0440720269 -0.7082608225 1.7697719645 0.4064143594 0.5693749280 0.5785187018 -0.419470703962 +1413393895005760512.0000000000 -1.1105970449 -0.6973354709 1.7637546427 0.4100980571 0.5662475880 0.5766960703 -0.422616723748 +1413393895055760384.0000000000 -1.1763756513 -0.6861443340 1.7586098080 0.4132407731 0.5631222106 0.5747818076 -0.426323014867 +1413393895105760512.0000000000 -1.2411569220 -0.6745462169 1.7535188108 0.4148917502 0.5614571372 0.5749549121 -0.426682045169 +1413393895155760384.0000000000 -1.3048594637 -0.6626590655 1.7489243160 0.4147584953 0.5610352369 0.5763108497 -0.425535730725 +1413393895205760512.0000000000 -1.3673639643 -0.6505196900 1.7449775057 0.4127747079 0.5618624461 0.5781388279 -0.423890466774 +1413393895255760384.0000000000 -1.4291583271 -0.6381500413 1.7415920856 0.4121014685 0.5622143745 0.5793345012 -0.422443975622 +1413393895305760512.0000000000 -1.4902936491 -0.6258845312 1.7375171834 0.4124369790 0.5615439810 0.5792209880 -0.423163257968 +1413393895355760384.0000000000 -1.5502098591 -0.6136121186 1.7322669888 0.4141337808 0.5601816218 0.5786593695 -0.424079115646 +1413393895405760512.0000000000 -1.6092144136 -0.6011761500 1.7251309569 0.4158947953 0.5590061251 0.5771392128 -0.425974178162 +1413393895455760384.0000000000 -1.6665215296 -0.5883234032 1.7147803569 0.4173626651 0.5584351426 0.5767627722 -0.425797254416 +1413393895505760512.0000000000 -1.7226775727 -0.5750584763 1.7031098481 0.4192879749 0.5589781228 0.5747676967 -0.42589100396 +1413393895555760384.0000000000 -1.7777970731 -0.5613187167 1.6906532165 0.4202625593 0.5618705481 0.5726601864 -0.423958935901 +1413393895605760512.0000000000 -1.8319006765 -0.5473791190 1.6790187169 0.4211795002 0.5657927347 0.5691219443 -0.422595104577 +1413393895655760384.0000000000 -1.8847148654 -0.5328498697 1.6683522276 0.4244247569 0.5691493034 0.5661385895 -0.418831462099 +1413393895705760512.0000000000 -1.9365347111 -0.5177912755 1.6594693204 0.4312936492 0.5710169140 0.5609726964 -0.416215215923 +1413393895755760384.0000000000 -1.9870213488 -0.5025819702 1.6512864739 0.4363044157 0.5753562344 0.5550382479 -0.41296029319 +1413393895805760512.0000000000 -2.0365504036 -0.4869398469 1.6442465839 0.4427307811 0.5799991499 0.5474579815 -0.409731863572 +1413393895855760384.0000000000 -2.0853926030 -0.4706162892 1.6385126483 0.4492394175 0.5862595575 0.5393405996 -0.404469275286 +1413393895905760512.0000000000 -2.1311937491 -0.4539577373 1.6328246680 0.4566156063 0.5935465569 0.5306642211 -0.396988862894 +1413393895955760384.0000000000 -2.1746170688 -0.4372842919 1.6286564105 0.4624240939 0.6029958062 0.5202709680 -0.389715453769 +1413393896005760512.0000000000 -2.2160233662 -0.4203123104 1.6243738910 0.4696760600 0.6123605331 0.5112183133 -0.378252312955 +1413393896055760384.0000000000 -2.2558429515 -0.4036492183 1.6199612579 0.4772100617 0.6225151795 0.4998592552 -0.367268475787 +1413393896105760512.0000000000 -2.2945679274 -0.3870248868 1.6163954504 0.4863354318 0.6322294932 0.4875149716 -0.355095576175 +1413393896155760384.0000000000 -2.3319077571 -0.3713354325 1.6140009848 0.4946458442 0.6418513389 0.4735669762 -0.345089360306 +1413393896205760512.0000000000 -2.3683107947 -0.3558906339 1.6123291746 0.5045855211 0.6502308006 0.4593049676 -0.334114208927 +1413393896255760384.0000000000 -2.4026054665 -0.3410571287 1.6116151669 0.5171505450 0.6565654315 0.4429621637 -0.324440548413 +1413393896305760512.0000000000 -2.4347660340 -0.3276610499 1.6112795014 0.5284859687 0.6628758173 0.4272513768 -0.314252275514 +1413393896355760384.0000000000 -2.4649116117 -0.3154679867 1.6117733060 0.5391802799 0.6694668557 0.4105225527 -0.304253165277 +1413393896405760512.0000000000 -2.4925281691 -0.3050557757 1.6142331334 0.5478026911 0.6775050178 0.3913287247 -0.29624481698 +1413393896455760384.0000000000 -2.5173811846 -0.2969645677 1.6184718121 0.5525314385 0.6877411772 0.3693157100 -0.292107838045 +1413393896505760512.0000000000 -2.5389124939 -0.2907931042 1.6230690946 0.5543417969 0.6995304285 0.3490705990 -0.28550318508 +1413393896555760384.0000000000 -2.5565898469 -0.2860077361 1.6286546993 0.5531510448 0.7133464882 0.3280934286 -0.278415896823 +1413393896605760512.0000000000 -2.5716751562 -0.2815171877 1.6339712745 0.5512895975 0.7267419984 0.3087852008 -0.269402203518 +1413393896655760384.0000000000 -2.5845059232 -0.2768243586 1.6399983625 0.5491626999 0.7392735059 0.2903192175 -0.26001877691 +1413393896705760512.0000000000 -2.5947591598 -0.2718022333 1.6467996556 0.5467238542 0.7512453447 0.2709067088 -0.251660514343 +1413393896755760384.0000000000 -2.6023765350 -0.2660547365 1.6541379462 0.5434246739 0.7629061172 0.2511786529 -0.244076144839 +1413393896805760512.0000000000 -2.6071912973 -0.2591633345 1.6620560150 0.5406629300 0.7732002903 0.2317445385 -0.236937494064 +1413393896855760384.0000000000 -2.6088336373 -0.2508197107 1.6695760077 0.5359358077 0.7842025686 0.2128933160 -0.229075483964 +1413393896905760512.0000000000 -2.6069635569 -0.2406764827 1.6768131094 0.5294363022 0.7958409587 0.1951378216 -0.219671575109 +1413393896955760384.0000000000 -2.6019818581 -0.2280525100 1.6833443482 0.5222218883 0.8072397901 0.1810296240 -0.207066404737 +1413393897005760512.0000000000 -2.5940569576 -0.2131043344 1.6878487696 0.5127574459 0.8191263093 0.1733789743 -0.189872647977 +1413393897055760384.0000000000 -2.5840366182 -0.1951044048 1.6896774132 0.5031791256 0.8301126336 0.1726758459 -0.167053390551 +1413393897105760512.0000000000 -2.5732085619 -0.1726734222 1.6900496981 0.4984781939 0.8367803863 0.1762944611 -0.142261513606 +1413393897155760384.0000000000 -2.5626893443 -0.1464078284 1.6891813312 0.4984641890 0.8391906553 0.1823431234 -0.1185051969 +1413393897205760512.0000000000 -2.5535338607 -0.1163452869 1.6876220579 0.5043994711 0.8368562348 0.1899500209 -0.0957695426753 +1413393897255760384.0000000000 -2.5469010827 -0.0831453057 1.6864511589 0.5167613868 0.8293407334 0.1986158850 -0.0755205091997 +1413393897305760512.0000000000 -2.5436695872 -0.0479711709 1.6863949660 0.5333663769 0.8179980393 0.2071909033 -0.0589189727284 +1413393897355760384.0000000000 -2.5447672185 -0.0120195036 1.6874788785 0.5485097974 0.8072352687 0.2124918420 -0.04853287768 +1413393897405760512.0000000000 -2.5509459510 0.0239888514 1.6895104625 0.5596487760 0.7997706486 0.2119321451 -0.0473806185571 +1413393897455760384.0000000000 -2.5618727571 0.0595095697 1.6922202453 0.5673691549 0.7952737239 0.2068277370 -0.0534250252457 +1413393897505760512.0000000000 -2.5765170652 0.0937182059 1.6951585857 0.5725105780 0.7924352425 0.2010751820 -0.0620225424416 +1413393897555760384.0000000000 -2.5939056837 0.1268464121 1.6979340901 0.5756520322 0.7906678639 0.1965312896 -0.0696025790565 +1413393897605760512.0000000000 -2.6134734659 0.1585897448 1.7003429024 0.5749121331 0.7915855547 0.1924225886 -0.076432298207 +1413393897655760384.0000000000 -2.6348242742 0.1891502324 1.7028029997 0.5735011280 0.7925768684 0.1905391607 -0.0813215353386 +1413393897705760512.0000000000 -2.6577803581 0.2190295351 1.7054914840 0.5712897200 0.7939504617 0.1900092142 -0.0846594275659 +1413393897755760384.0000000000 -2.6821533257 0.2486944921 1.7089230651 0.5699559833 0.7947166956 0.1903297632 -0.085732910892 +1413393897805760512.0000000000 -2.7079782269 0.2778087110 1.7129085154 0.5692686423 0.7947074756 0.1923589539 -0.0858561232757 +1413393897855760384.0000000000 -2.7349411025 0.3070769910 1.7174291192 0.5696448067 0.7944363742 0.1932455633 -0.0838557922625 +1413393897905760512.0000000000 -2.7630911128 0.3363979301 1.7224608659 0.5697994474 0.7948055587 0.1928064790 -0.080239486792 +1413393897955760384.0000000000 -2.7925340379 0.3657419250 1.7281658682 0.5710426812 0.7947906382 0.1919209863 -0.073378693776 +1413393898005760512.0000000000 -2.8234590393 0.3948589596 1.7343984075 0.5733805964 0.7944876520 0.1893722109 -0.0645153339893 +1413393898055760384.0000000000 -2.8559992345 0.4236439703 1.7409195145 0.5773085418 0.7934877187 0.1851263257 -0.053106792747 +1413393898105760512.0000000000 -2.8911260875 0.4519365902 1.7496679084 0.5858714107 0.7893347832 0.1784907688 -0.0429690062053 +1413393898155760384.0000000000 -2.9285306924 0.4782568999 1.7595607950 0.5983944445 0.7827326473 0.1670455759 -0.0367350958478 +1413393898205760512.0000000000 -2.9682012977 0.5022541470 1.7707362351 0.6124280228 0.7751469477 0.1514559182 -0.0337673091039 +1413393898255760384.0000000000 -3.0101619292 0.5232968865 1.7835814112 0.6282260251 0.7654481519 0.1353251146 -0.0332911634957 +1413393898305760512.0000000000 -3.0536718912 0.5400290320 1.7972636563 0.6426450917 0.7559480752 0.1194407045 -0.0358289240726 +1413393898355760384.0000000000 -3.0983431990 0.5521250187 1.8114684499 0.6562121352 0.7464301170 0.1019359826 -0.0428575483782 +1413393898405760512.0000000000 -3.1430234627 0.5587096173 1.8260651732 0.6700250028 0.7355886114 0.0857548946 -0.0512053564226 +1413393898455760384.0000000000 -3.1868643261 0.5589756815 1.8407355149 0.6829191628 0.7244272340 0.0701992762 -0.062439261539 +1413393898505760512.0000000000 -3.2286286545 0.5527137524 1.8530646698 0.6893977457 0.7184796327 0.0564516618 -0.0730135294414 +1413393898555760384.0000000000 -3.2681466840 0.5396240348 1.8605156083 0.6811276639 0.7257381469 0.0450394265 -0.0856778709483 +1413393898605760512.0000000000 -3.3043271431 0.5207715987 1.8627948060 0.6620517456 0.7428570639 0.0395513908 -0.0910305238149 +1413393898655760384.0000000000 -3.3368326838 0.4968267302 1.8625948812 0.6384157202 0.7629321971 0.0345011477 -0.095757515246 +1413393898705760512.0000000000 -3.3655303344 0.4688111266 1.8592444067 0.6115217426 0.7846987718 0.0325692315 -0.0960637343247 +1413393898755760384.0000000000 -3.3904419838 0.4386485062 1.8534509369 0.5814658023 0.8073856810 0.0313571754 -0.0950926406421 +1413393898805760512.0000000000 -3.4114964114 0.4084002744 1.8461497358 0.5490631938 0.8301598308 0.0316549830 -0.091445210634 +1413393898855760384.0000000000 -3.4289014491 0.3804766044 1.8397661800 0.5175425776 0.8507181372 0.0322712258 -0.0859470726423 +1413393898905760512.0000000000 -3.4431563747 0.3571628706 1.8362136880 0.4911094022 0.8668234688 0.0322179012 -0.0799414532289 +1413393898955760384.0000000000 -3.4543026567 0.3399811923 1.8348169183 0.4686199802 0.8798438069 0.0342361586 -0.0714008051075 +1413393899005760512.0000000000 -3.4628469561 0.3301176887 1.8356872742 0.4505967185 0.8898544879 0.0386391341 -0.0602379029224 +1413393899055760384.0000000000 -3.4694860610 0.3303552125 1.8393827434 0.4436844832 0.8938569164 0.0462965482 -0.0449502173753 +1413393899105760512.0000000000 -3.4753282967 0.3410051132 1.8473985334 0.4502672414 0.8906301483 0.0568694946 -0.0283409739121 +1413393899155760384.0000000000 -3.4821885622 0.3622323336 1.8608574837 0.4744368291 0.8776962881 0.0657852893 -0.0152058134415 +1413393899205760512.0000000000 -3.4909664732 0.3912366016 1.8790204213 0.5111968489 0.8564635628 0.0714325284 -0.0067335874752 +1413393899255760384.0000000000 -3.5020002590 0.4238366165 1.9001290103 0.5528179220 0.8299862647 0.0741544610 -0.00403255733234 +1413393899305760512.0000000000 -3.5151075043 0.4571137502 1.9236284901 0.5963381796 0.7993861063 0.0729207968 -0.0067220480981 +1413393899355760384.0000000000 -3.5295702856 0.4877073100 1.9474121728 0.6343123623 0.7697752656 0.0703317801 -0.0121370588106 +1413393899405760512.0000000000 -3.5447474783 0.5135651743 1.9709353263 0.6648193424 0.7437413024 0.0668523943 -0.0198714492383 +1413393899455760384.0000000000 -3.5597390144 0.5326711319 1.9940416988 0.6886895604 0.7217752352 0.0628939137 -0.0281345836269 +1413393899505760512.0000000000 -3.5745485859 0.5434316787 2.0181733314 0.7101943424 0.7004979104 0.0565252986 -0.0416120674714 +1413393899555760384.0000000000 -3.5880264297 0.5450220042 2.0412411264 0.7265912799 0.6829458560 0.0510551074 -0.0551674340861 +1413393899605760512.0000000000 -3.5991841806 0.5366971109 2.0622545734 0.7359408402 0.6720159077 0.0451981860 -0.0688681609252 +1413393899655760384.0000000000 -3.6073778937 0.5179734812 2.0796190748 0.7349939606 0.6717292389 0.0404400201 -0.0832364833656 +1413393899705760512.0000000000 -3.6119461625 0.4891493164 2.0931556291 0.7235782075 0.6825380406 0.0383115391 -0.0954391259158 +1413393899755760384.0000000000 -3.6124062464 0.4514041107 2.1027686163 0.6993983267 0.7059201059 0.0369380144 -0.105614240475 +1413393899805760512.0000000000 -3.6083199147 0.4061262818 2.1105623305 0.6704064725 0.7323872179 0.0363417819 -0.113328723495 +1413393899855760384.0000000000 -3.5996251636 0.3549108203 2.1162201640 0.6351862714 0.7620061305 0.0350781479 -0.12105610762 +1413393899905760512.0000000000 -3.5863453478 0.3003901209 2.1194395827 0.5951026018 0.7930234439 0.0343547645 -0.125644183786 +1413393899955760384.0000000000 -3.5683772134 0.2449211051 2.1203420364 0.5514640537 0.8237816163 0.0338463664 -0.126986887798 +1413393900005760512.0000000000 -3.5456233539 0.1915515205 2.1210228248 0.5134277898 0.8483261332 0.0325310519 -0.125205459542 +1413393900055760384.0000000000 -3.5184690102 0.1427664459 2.1214095392 0.4839629043 0.8662132704 0.0312262439 -0.120330374614 +1413393900105760512.0000000000 -3.4873665472 0.1005311150 2.1211633663 0.4625180628 0.8788951833 0.0308794621 -0.11254668885 +1413393900155760384.0000000000 -3.4525933645 0.0660060247 2.1197312701 0.4487267683 0.8874178567 0.0343883962 -0.0997560685531 +1413393900205760512.0000000000 -3.4151496249 0.0396780411 2.1170139034 0.4392627066 0.8934331824 0.0392857811 -0.0853349320877 +1413393900255760384.0000000000 -3.3755108522 0.0221755679 2.1132968453 0.4364961450 0.8958831795 0.0481431644 -0.0674290725987 +1413393900305760512.0000000000 -3.3350746322 0.0138794322 2.1087020001 0.4406289568 0.8944671015 0.0592855428 -0.0475389444671 +1413393900355760384.0000000000 -3.2953072983 0.0143679281 2.1037783102 0.4519410924 0.8887934065 0.0702457635 -0.0293438619894 +1413393900405760512.0000000000 -3.2576571588 0.0233880451 2.0993222214 0.4729905256 0.8773966974 0.0789059710 -0.0151276545058 +1413393900455760384.0000000000 -3.2224455599 0.0382264303 2.0940396574 0.4979281553 0.8630145925 0.0851699672 -0.00440930151183 +1413393900505760512.0000000000 -3.1903140014 0.0570011372 2.0884389076 0.5266008717 0.8454828489 0.0885932909 0.0012259682726 +1413393900555760384.0000000000 -3.1612500313 0.0787431808 2.0815660070 0.5575169769 0.8252478277 0.0901373875 0.00401182628704 +1413393900605760512.0000000000 -3.1348400248 0.1009625212 2.0731816337 0.5918729718 0.8010843401 0.0891282795 0.0025327998543 +1413393900655760384.0000000000 -3.1106239724 0.1214833644 2.0626881502 0.6235658308 0.7769401903 0.0867655561 -0.00115481264364 +1413393900705760512.0000000000 -3.0880268555 0.1386634494 2.0498614797 0.6520244832 0.7536715884 0.0823895683 -0.00742760197806 +1413393900755760384.0000000000 -3.0666881567 0.1501549421 2.0340687856 0.6730086992 0.7353935901 0.0776629840 -0.0149672751776 +1413393900805760512.0000000000 -3.0461663742 0.1550165804 2.0174338481 0.6864212914 0.7232503887 0.0717310991 -0.0242762284836 +1413393900855760384.0000000000 -3.0259073651 0.1521878202 2.0000974538 0.6907548877 0.7193052156 0.0649455844 -0.0352102681183 +1413393900905760512.0000000000 -3.0051417738 0.1417364839 1.9819070387 0.6853649348 0.7243883822 0.0591714021 -0.0451123388339 +1413393900955760384.0000000000 -2.9836735466 0.1237451261 1.9631500080 0.6702868044 0.7380715471 0.0535759296 -0.0556382148785 +1413393901005760512.0000000000 -2.9606729664 0.0996986460 1.9452334045 0.6503500684 0.7553024427 0.0480609019 -0.0652162426723 +1413393901055760384.0000000000 -2.9357994921 0.0709912557 1.9284408383 0.6271412888 0.7741848644 0.0436367212 -0.0736711352857 +1413393901105760512.0000000000 -2.9079950867 0.0391228568 1.9111113442 0.6010599053 0.7946374068 0.0449828845 -0.0724908408149 +1413393901155760384.0000000000 -2.8777840727 0.0060390220 1.8939050079 0.5717780686 0.8162258687 0.0486154930 -0.0669455401876 +1413393901205760512.0000000000 -2.8456422062 -0.0262787248 1.8779029646 0.5456452415 0.8342813523 0.0561612911 -0.055604002101 +1413393901255760384.0000000000 -2.8126100514 -0.0559405451 1.8641387461 0.5241072187 0.8481357676 0.0636380349 -0.0439037994345 +1413393901305760512.0000000000 -2.7796914991 -0.0815769257 1.8524656511 0.5065195027 0.8587542852 0.0698470203 -0.0331732549078 +1413393901355760384.0000000000 -2.7478257215 -0.1020720298 1.8433056066 0.4942861796 0.8657540210 0.0743612317 -0.02493100321 +1413393901405760512.0000000000 -2.7173077037 -0.1170883395 1.8354301877 0.4840214639 0.8714088899 0.0775632883 -0.0188070580834 +1413393901455760384.0000000000 -2.6886601290 -0.1260321902 1.8287647884 0.4752651014 0.8761520671 0.0793076615 -0.013817871175 +1413393901505760512.0000000000 -2.6621230433 -0.1284119032 1.8231836499 0.4695806063 0.8790056274 0.0823321972 -0.00803557604283 +1413393901555760384.0000000000 -2.6379152897 -0.1239741609 1.8185639585 0.4658596033 0.8806796334 0.0858640766 -0.0023608723486 +1413393901605760512.0000000000 -2.6165259077 -0.1120891033 1.8155288448 0.4669119192 0.8796892695 0.0901422393 0.00379809086784 +1413393901655760384.0000000000 -2.5984779004 -0.0925547115 1.8147980899 0.4771124764 0.8734788255 0.0962963780 0.0111997240822 +1413393901705760512.0000000000 -2.5845186714 -0.0660516619 1.8167377452 0.4962909748 0.8619566991 0.1022018696 0.0167539582448 +1413393901755760384.0000000000 -2.5746494578 -0.0346625576 1.8203905787 0.5178613725 0.8486568489 0.1058412298 0.0199696210085 +1413393901805760512.0000000000 -2.5693091128 -0.0001670340 1.8254863914 0.5406837896 0.8343553624 0.1057872655 0.0179227038345 +1413393901855760384.0000000000 -2.5675007283 0.0354672914 1.8303367814 0.5576291333 0.8236398398 0.1024156888 0.0133488084149 +1413393901905760512.0000000000 -2.5687683983 0.0710899231 1.8341154964 0.5666638685 0.8181391780 0.0974131847 0.00714262602232 +1413393901955760384.0000000000 -2.5722677497 0.1065802594 1.8368935791 0.5701305739 0.8162508792 0.0931547722 0.00279629173196 +1413393902005760512.0000000000 -2.5780660559 0.1420770293 1.8396270987 0.5710722868 0.8159504043 0.0900075945 -0.000117861458965 +1413393902055760384.0000000000 -2.5860108445 0.1775870553 1.8427375160 0.5704450968 0.8166457660 0.0876169906 -0.00231245022642 +1413393902105760512.0000000000 -2.5956573752 0.2132505612 1.8461610031 0.5694860368 0.8174355249 0.0864778552 -0.00252924514367 +1413393902155760384.0000000000 -2.6072447876 0.2491128223 1.8500850658 0.5705074944 0.8167252546 0.0864672969 -0.00211279604685 +1413393902205760512.0000000000 -2.6206222518 0.2847134024 1.8538025636 0.5700179082 0.8170344971 0.0867909101 -0.00124610284308 +1413393902255760384.0000000000 -2.6359150671 0.3204667921 1.8580304718 0.5705889275 0.8166410464 0.0867499081 -0.000361442656894 +1413393902305760512.0000000000 -2.6532775792 0.3561785548 1.8620160107 0.5704668084 0.8167207451 0.0868033149 0.000171793095613 +1413393902355760384.0000000000 -2.6724018195 0.3920985063 1.8649224347 0.5706931809 0.8165198151 0.0871987015 0.00103500265621 +1413393902405760512.0000000000 -2.6933107740 0.4287636235 1.8660366425 0.5726767486 0.8151438703 0.0870624706 0.00139231624426 +1413393902455760384.0000000000 -2.7159212509 0.4650235873 1.8652948399 0.5753883823 0.8131962260 0.0873899552 0.00176163360562 +1413393902505760512.0000000000 -2.7403316626 0.5004463845 1.8635238923 0.5790832889 0.8105938931 0.0871629162 0.00164652575319 +1413393902555760384.0000000000 -2.7667407304 0.5351669758 1.8617419202 0.5800297964 0.8099510083 0.0868479453 0.00149458787279 +1413393902605760512.0000000000 -2.7952678448 0.5692072225 1.8620590621 0.5798577324 0.8101129383 0.0864932455 0.000977718039736 +1413393902655760384.0000000000 -2.8257002892 0.6028213261 1.8647906885 0.5786198350 0.8110430923 0.0860631307 0.00115175496678 +1413393902705760512.0000000000 -2.8582907766 0.6365876049 1.8715549861 0.5778405985 0.8116366073 0.0857009155 0.00127026461673 +1413393902755760384.0000000000 -2.8927752314 0.6689932890 1.8812889873 0.5762891669 0.8128336838 0.0848067606 0.000109721361903 +1413393902805760512.0000000000 -2.9295255339 0.7012396637 1.8944167850 0.5725325619 0.8159238844 0.0802954779 -0.00522652324804 +1413393902855760384.0000000000 -2.9680601602 0.7334100016 1.9099502939 0.5677689243 0.8197363612 0.0741025994 -0.013399681206 +1413393902905760512.0000000000 -3.0078125758 0.7658841232 1.9263177339 0.5591687850 0.8260768337 0.0659746748 -0.0239724199807 +1413393902955760384.0000000000 -3.0475250207 0.7993862444 1.9427597055 0.5502669008 0.8322749299 0.0586088037 -0.0330119234113 +1413393903005760512.0000000000 -3.0867560075 0.8344578410 1.9593754367 0.5429000485 0.8371739612 0.0517040051 -0.0415450592598 +1413393903055760384.0000000000 -3.1249168506 0.8717461379 1.9764092687 0.5385883057 0.8399424989 0.0458744482 -0.0481120621066 +1413393903105760512.0000000000 -3.1613996907 0.9115723663 1.9935760881 0.5390163176 0.8397040616 0.0446505898 -0.0486294473478 +1413393903155760384.0000000000 -3.1964876478 0.9537014683 2.0111789091 0.5448501239 0.8359862239 0.0454166007 -0.0469330184625 +1413393903205760512.0000000000 -3.2301459775 0.9975536444 2.0281081990 0.5510142549 0.8320406681 0.0474989460 -0.0428423569111 +1413393903255760384.0000000000 -3.2626564302 1.0431289125 2.0444000190 0.5573593921 0.8279795633 0.0485293857 -0.0380164369483 +1413393903305760512.0000000000 -3.2939654980 1.0898529611 2.0598400597 0.5630546412 0.8244067469 0.0478745765 -0.0321093692184 +1413393903355760384.0000000000 -3.3241865116 1.1373571648 2.0732707392 0.5662401296 0.8226560940 0.0447434906 -0.0246391293556 +1413393903405760512.0000000000 -3.3534440073 1.1859240780 2.0840980158 0.5694584862 0.8210083373 0.0369798442 -0.0171707249548 +1413393903455760384.0000000000 -3.3819255722 1.2346014239 2.0904242339 0.5716702752 0.8200227501 0.0254266068 -0.0104533962945 +1413393903505760512.0000000000 -3.4097239301 1.2833908833 2.0917236158 0.5736650774 0.8190070865 0.0106606340 -0.00470340928609 +1413393903555760384.0000000000 -3.4368315363 1.3315516051 2.0875895833 0.5764088699 0.8171425857 -0.0054536012 0.00103324818493 +1413393903605760512.0000000000 -3.4632980350 1.3795240657 2.0822700751 0.5826415483 0.8124011745 -0.0225728068 0.00486068786705 +1413393903655760384.0000000000 -3.4885606616 1.4264050921 2.0769680876 0.5896628604 0.8066387613 -0.0394516305 0.0086711409045 +1413393903705760512.0000000000 -3.5124478063 1.4719384750 2.0715596396 0.5943019699 0.8022216621 -0.0556799206 0.0120548727188 +1413393903755760384.0000000000 -3.5344134528 1.5162302174 2.0669434238 0.5981111869 0.7981320971 -0.0706741031 0.0159164939054 +1413393903805760512.0000000000 -3.5546613148 1.5585583741 2.0629699982 0.5982386480 0.7966723416 -0.0842028835 0.0182640253156 +1413393903855760384.0000000000 -3.5729498125 1.5987981650 2.0598588476 0.5963223120 0.7966019570 -0.0975034725 0.0178352222295 +1413393903905760512.0000000000 -3.5888668682 1.6371632155 2.0579005738 0.5937681714 0.7969907556 -0.1094606152 0.0162316930965 +1413393903955760384.0000000000 -3.6019033724 1.6736717561 2.0575167942 0.5919071082 0.7969156443 -0.1198277039 0.0145860399534 +1413393904005760512.0000000000 -3.6116887680 1.7083608449 2.0584377068 0.5908367408 0.7965352214 -0.1274144825 0.0144615509955 +1413393904055760384.0000000000 -3.6181363823 1.7412242468 2.0585592810 0.5885455070 0.7974557239 -0.1320347231 0.0156648198055 +1413393904105760512.0000000000 -3.6211843023 1.7723439661 2.0566273460 0.5881882042 0.7973449747 -0.1337307281 0.0197919214287 +1413393904155760384.0000000000 -3.6212366948 1.8015288427 2.0519251854 0.5855286915 0.7993429696 -0.1324790882 0.0256175629345 +1413393904205760512.0000000000 -3.6186137572 1.8289446327 2.0452333886 0.5825727694 0.8016339481 -0.1303306394 0.031716022271 +1413393904255760384.0000000000 -3.6133363570 1.8547807308 2.0387128419 0.5794121402 0.8040999542 -0.1276917813 0.037411821897 +1413393904305760512.0000000000 -3.6052334418 1.8795206249 2.0362228324 0.5786353299 0.8048231512 -0.1249787704 0.0426750188846 +1413393904355760384.0000000000 -3.5946832650 1.9032339868 2.0381637693 0.5789783326 0.8046548497 -0.1234514186 0.0455456954001 +1413393904405760512.0000000000 -3.5814916658 1.9254616407 2.0444152039 0.5786944769 0.8046957655 -0.1235762053 0.0480244603477 +1413393904455760384.0000000000 -3.5654781963 1.9478870540 2.0547679636 0.5784862924 0.8043788556 -0.1253901301 0.0510448966901 +1413393904505760512.0000000000 -3.5467164228 1.9707164328 2.0701557947 0.5782920042 0.8038291846 -0.1280382885 0.0551651746721 +1413393904555760384.0000000000 -3.5252236916 1.9927534140 2.0879194346 0.5776851501 0.8032756558 -0.1304488305 0.0633339619079 +1413393904605760512.0000000000 -3.5016881758 2.0132185376 2.1036796914 0.5705794574 0.8070333486 -0.1310308483 0.0772474847958 +1413393904655760384.0000000000 -3.4767073435 2.0330197497 2.1168229631 0.5584417127 0.8136625253 -0.1310774608 0.094418471885 +1413393904705760512.0000000000 -3.4512955429 2.0525029500 2.1275921364 0.5449847680 0.8203311690 -0.1346442267 0.109175583967 +1413393904755760384.0000000000 -3.4256991882 2.0725283877 2.1357804991 0.5315578988 0.8261663736 -0.1399016836 0.123785469213 +1413393904805760512.0000000000 -3.4003604621 2.0943576382 2.1428418000 0.5208576418 0.8297565404 -0.1470200633 0.136368990639 +1413393904855760384.0000000000 -3.3753231481 2.1185541138 2.1486709241 0.5132769245 0.8308959559 -0.1549704714 0.148804778968 +1413393904905760512.0000000000 -3.3509454178 2.1456974649 2.1535038049 0.5105797159 0.8287188516 -0.1640314012 0.160084721789 +1413393904955760384.0000000000 -3.3267206014 2.1761529288 2.1576727042 0.5143724013 0.8220554122 -0.1729363967 0.172449803754 +1413393905005760512.0000000000 -3.3030436699 2.2098798762 2.1606020395 0.5221899113 0.8123542677 -0.1831590628 0.183986406997 +1413393905055760384.0000000000 -3.2804733028 2.2457088835 2.1613454512 0.5296042070 0.8024737427 -0.1933830509 0.195341423865 +1413393905105760512.0000000000 -3.2594035575 2.2822436214 2.1589887826 0.5349077563 0.7935806435 -0.2044462945 0.205682199405 +1413393905155760384.0000000000 -3.2399867540 2.3190901397 2.1529528105 0.5388294504 0.7851707225 -0.2169195248 0.214745616092 +1413393905205760512.0000000000 -3.2223679189 2.3564050964 2.1434592047 0.5414506014 0.7775781528 -0.2311195038 0.220878331892 +1413393905255760384.0000000000 -3.2062880474 2.3940166015 2.1316866055 0.5429670205 0.7703770422 -0.2458437459 0.226421906976 +1413393905305760512.0000000000 -3.1917794305 2.4316060086 2.1188735562 0.5436038484 0.7634057930 -0.2615116642 0.23090712557 +1413393905355760384.0000000000 -3.1787223186 2.4689693475 2.1064400694 0.5428899836 0.7572005212 -0.2767972624 0.23516188446 +1413393905405760512.0000000000 -3.1668087069 2.5058801437 2.0943233262 0.5408319392 0.7517870001 -0.2908508993 0.240255851942 +1413393905455760384.0000000000 -3.1557542442 2.5423725612 2.0833719991 0.5387582269 0.7458964164 -0.3049189775 0.245769253719 +1413393905505760512.0000000000 -3.1455965091 2.5780266018 2.0733657300 0.5353555251 0.7406722619 -0.3188231219 0.251298386707 +1413393905555760384.0000000000 -3.1364064309 2.6127640420 2.0642757823 0.5320035954 0.7350505160 -0.3349002498 0.253997511935 +1413393905605760512.0000000000 -3.1276804657 2.6463630514 2.0556030456 0.5277859319 0.7294607201 -0.3525780610 0.254985840153 +1413393905655760384.0000000000 -3.1188308682 2.6786481834 2.0478384034 0.5243830182 0.7229204293 -0.3695479355 0.256598570627 +1413393905705760512.0000000000 -3.1096483500 2.7092560921 2.0411717847 0.5220851866 0.7152495175 -0.3859528232 0.258622512438 +1413393905755760384.0000000000 -3.0997315371 2.7378356355 2.0358744758 0.5208358191 0.7062891086 -0.4021145421 0.261131460405 +1413393905805760512.0000000000 -3.0893098522 2.7642696240 2.0314374617 0.5187299631 0.6980534668 -0.4183391212 0.26197893549 +1413393905855760384.0000000000 -3.0781031185 2.7880957221 2.0274532973 0.5139241300 0.6917386698 -0.4356918008 0.259908168648 +1413393905905760512.0000000000 -3.0652057969 2.8091625722 2.0238341385 0.5063836262 0.6874031448 -0.4523189869 0.257798513771 +1413393905955760384.0000000000 -3.0502038809 2.8271488572 2.0208074302 0.4967053048 0.6847264055 -0.4674994860 0.256666749837 +1413393906005760512.0000000000 -3.0320772909 2.8421176197 2.0193056652 0.4877978152 0.6814757607 -0.4801970416 0.258949570765 +1413393906055760384.0000000000 -3.0100237931 2.8538846899 2.0188821622 0.4763299045 0.6809713707 -0.4871890043 0.268392787799 +1413393906105760512.0000000000 -2.9848989412 2.8627081533 2.0190943728 0.4654024327 0.6806005753 -0.4894416854 0.28395469547 +1413393906155760384.0000000000 -2.9572224533 2.8697871618 2.0192888542 0.4577292335 0.6783919462 -0.4892378938 0.301520479055 +1413393906205760512.0000000000 -2.9277207810 2.8757846441 2.0178033201 0.4522189990 0.6748352785 -0.4865486958 0.321505350565 +1413393906255760384.0000000000 -2.8970841426 2.8814606817 2.0148081556 0.4499486584 0.6692441084 -0.4831994688 0.340847182112 +1413393906305760512.0000000000 -2.8652115617 2.8875014139 2.0098691565 0.4484837952 0.6633161660 -0.4804703878 0.357801838691 +1413393906355760384.0000000000 -2.8330954604 2.8940249330 2.0020435254 0.4466190511 0.6578885260 -0.4795143955 0.371187358509 +1413393906405760512.0000000000 -2.8017800119 2.9012561759 1.9915836716 0.4448543514 0.6529690950 -0.4809506568 0.380029515562 +1413393906455760384.0000000000 -2.7722683247 2.9089354782 1.9783784078 0.4442533583 0.6474310529 -0.4827443791 0.387852871462 +1413393906505760512.0000000000 -2.7440093388 2.9172158346 1.9618160202 0.4432887020 0.6418723624 -0.4868449389 0.393035624942 +1413393906555760384.0000000000 -2.7164239561 2.9265259442 1.9427055979 0.4438812443 0.6356484679 -0.4920927447 0.395935849352 +1413393906605760512.0000000000 -2.6900486391 2.9362824450 1.9208239883 0.4454615557 0.6285733115 -0.4995905029 0.396066817383 +1413393906655760384.0000000000 -2.6649503970 2.9460642951 1.8971961094 0.4482862801 0.6202002408 -0.5084769888 0.394768570492 +1413393906705760512.0000000000 -2.6411654191 2.9560556095 1.8732915258 0.4528102009 0.6117003383 -0.5189860046 0.389151827946 +1413393906755760384.0000000000 -2.6186470850 2.9652176465 1.8502288264 0.4582171269 0.6034627699 -0.5283883449 0.38298238454 +1413393906805760512.0000000000 -2.5969808461 2.9727598397 1.8282214476 0.4642624598 0.5952392358 -0.5351965790 0.379097932405 +1413393906855760384.0000000000 -2.5764637909 2.9777216043 1.8067018243 0.4671788145 0.5897480425 -0.5388931113 0.378860681911 +1413393906905760512.0000000000 -2.5572368770 2.9801999511 1.7854992245 0.4695758226 0.5856147547 -0.5399635212 0.38077985984 +1413393906955760384.0000000000 -2.5391465236 2.9801717978 1.7646688051 0.4709602733 0.5826265714 -0.5398454855 0.383809263975 +1413393907005760512.0000000000 -2.5224429905 2.9777714931 1.7440745838 0.4706792046 0.5816876648 -0.5389268162 0.386857123097 +1413393907055760384.0000000000 -2.5075960884 2.9726217302 1.7226813732 0.4642873144 0.5858211323 -0.5350854875 0.39361708762 +1413393907105760512.0000000000 -2.4946013194 2.9655909446 1.7012223140 0.4568456024 0.5907847179 -0.5311610292 0.40016680743 +1413393907155760384.0000000000 -2.4834079890 2.9571546579 1.6802673383 0.4491933567 0.5959692863 -0.5281329605 0.405119135724 +1413393907205760512.0000000000 -2.4735459268 2.9476711025 1.6597788568 0.4407335169 0.6014219849 -0.5239503060 0.411730057064 +1413393907255760384.0000000000 -2.4650400836 2.9377771238 1.6398980360 0.4300620730 0.6083962899 -0.5176638345 0.420624205435 +1413393907305760512.0000000000 -2.4582105197 2.9282075234 1.6199036701 0.4172186978 0.6165066601 -0.5099882815 0.430998896828 +1413393907355760384.0000000000 -2.4527556213 2.9203414744 1.6012996338 0.4057980346 0.6231931943 -0.5020039409 0.441531698751 +1413393907405760512.0000000000 -2.4492458036 2.9154909405 1.5843059675 0.3976737600 0.6274044584 -0.4995354350 0.445739358156 +1413393907455760384.0000000000 -2.4471749658 2.9153042650 1.5710496393 0.3976211884 0.6274077301 -0.5031997949 0.441641140788 +1413393907505760512.0000000000 -2.4473114151 2.9187133997 1.5618830987 0.4013627477 0.6252231253 -0.5085256772 0.435207564255 +1413393907555760384.0000000000 -2.4476825037 2.9256657029 1.5585739827 0.4105817171 0.6192762013 -0.5172469917 0.424706003728 +1413393907605760512.0000000000 -2.4486090329 2.9340535943 1.5591889056 0.4184507014 0.6143449314 -0.5224235279 0.417795372466 +1413393907655760384.0000000000 -2.4502692295 2.9428401908 1.5592980649 0.4231995893 0.6111631055 -0.5276113507 0.411105860677 +1413393907705760512.0000000000 -2.4528774442 2.9515789460 1.5573479426 0.4251566735 0.6098369440 -0.5322499304 0.405031747344 +1413393907755760384.0000000000 -2.4553382825 2.9601191003 1.5521956229 0.4262452179 0.6091678963 -0.5351644531 0.401034283416 +1413393907805760512.0000000000 -2.4578989952 2.9681455964 1.5427186595 0.4286252304 0.6074584712 -0.5361813766 0.399730095209 +1413393907855760384.0000000000 -2.4609050780 2.9755439443 1.5276800584 0.4310599178 0.6053773785 -0.5366771394 0.399603834908 +1413393907905760512.0000000000 -2.4640694186 2.9823706054 1.5072340790 0.4346619051 0.6027914882 -0.5361668642 0.400295570386 +1413393907955760384.0000000000 -2.4676135308 2.9880485044 1.4812774040 0.4353129590 0.6020002025 -0.5337729464 0.40396141589 +1413393908005760512.0000000000 -2.4719947447 2.9928309494 1.4524962267 0.4347085892 0.6017058528 -0.5315117297 0.408011997876 +1413393908055760384.0000000000 -2.4770000511 2.9972524509 1.4248476134 0.4328571170 0.6025481254 -0.5288177093 0.412216330551 +1413393908105760512.0000000000 -2.4839340786 3.0014866393 1.3988358953 0.4293243203 0.6044623394 -0.5283649702 0.413686314153 +1413393908155760384.0000000000 -2.4923788082 3.0058228114 1.3749134210 0.4244402246 0.6073738761 -0.5299794825 0.412394493756 +1413393908205760512.0000000000 -2.5017436670 3.0103428101 1.3550174295 0.4202275706 0.6098092388 -0.5305724928 0.412352168772 +1413393908255760384.0000000000 -2.5116173520 3.0154035175 1.3394774479 0.4188098518 0.6103958760 -0.5311473602 0.412186443823 +1413393908305760512.0000000000 -2.5225816816 3.0209961268 1.3271679348 0.4208050926 0.6087542676 -0.5293459153 0.414890609247 +1413393908355760384.0000000000 -2.5337439272 3.0270875309 1.3174512205 0.4266708608 0.6041855890 -0.5266770072 0.418954747719 +1413393908405760512.0000000000 -2.5463599998 3.0334641435 1.3071898512 0.4287963101 0.6022824476 -0.5260205230 0.420347459933 +1413393908455760384.0000000000 -2.5602045095 3.0402471306 1.2969569711 0.4291560070 0.6015841046 -0.5273953523 0.419256280944 +1413393908505760512.0000000000 -2.5750558054 3.0470799572 1.2865986521 0.4275867569 0.6021142174 -0.5297678441 0.417101985025 +1413393908555760384.0000000000 -2.5909946755 3.0538581240 1.2761187198 0.4245808603 0.6036050339 -0.5320384966 0.415122986886 +1413393908605760512.0000000000 -2.6079756686 3.0610022528 1.2662947122 0.4234720933 0.6037824637 -0.5358455535 0.411081093578 +1413393908655760384.0000000000 -2.6257334043 3.0681855871 1.2565567720 0.4228356258 0.6034337361 -0.5412072423 0.405182033945 +1413393908705760512.0000000000 -2.6439746867 3.0756501613 1.2488362579 0.4305251797 0.5972068507 -0.5511376178 0.392733208834 +1413393908755760384.0000000000 -2.6621535544 3.0819508908 1.2427334778 0.4408420870 0.5888580862 -0.5600092490 0.381174565874 +1413393908805760512.0000000000 -2.6803378072 3.0856796883 1.2389312975 0.4515427135 0.5798412925 -0.5653945072 0.374462687893 +1413393908855760384.0000000000 -2.6978425844 3.0855356407 1.2396960287 0.4601643359 0.5724626083 -0.5651638034 0.375666369762 +1413393908905760512.0000000000 -2.7164496343 3.0809869228 1.2435088417 0.4609077788 0.5711764835 -0.5596425351 0.38486579095 +1413393908955760384.0000000000 -2.7348759470 3.0728448167 1.2486382935 0.4525255366 0.5769457934 -0.5526548427 0.396139893144 +1413393909005760512.0000000000 -2.7546726028 3.0624356738 1.2562607239 0.4419821718 0.5839802232 -0.5478228203 0.404362481297 +1413393909055760384.0000000000 -2.7755080713 3.0506231910 1.2663149556 0.4307076275 0.5910051881 -0.5434309800 0.41217299434 +1413393909105760512.0000000000 -2.7978292885 3.0384651443 1.2779190432 0.4212763323 0.5964314791 -0.5409565805 0.41732687504 +1413393909155760384.0000000000 -2.8209977544 3.0266584085 1.2907726403 0.4142347944 0.5999389641 -0.5394306184 0.421304382086 +1413393909205760512.0000000000 -2.8446925850 3.0155740840 1.3035843155 0.4096111208 0.6015256064 -0.5388644823 0.424276730857 +1413393909255760384.0000000000 -2.8692237011 3.0055048150 1.3146893766 0.4079818921 0.6011428708 -0.5382876308 0.427111754905 +1413393909305760512.0000000000 -2.8947724061 2.9961873160 1.3233989037 0.4061071909 0.6008219912 -0.5375622984 0.430251856176 +1413393909355760384.0000000000 -2.9204903386 2.9878176244 1.3293829169 0.4042371508 0.6005165693 -0.5374360444 0.432590654308 +1413393909405760512.0000000000 -2.9468581648 2.9804689400 1.3326247021 0.4025490580 0.6000552613 -0.5381807350 0.433877212835 +1413393909455760384.0000000000 -2.9740145419 2.9743097586 1.3329424840 0.4013093279 0.5995939146 -0.5395050821 0.434018694651 +1413393909505760512.0000000000 -3.0019177417 2.9693291779 1.3309059444 0.4007523542 0.5988849750 -0.5408877632 0.433791153637 +1413393909555760384.0000000000 -3.0307450946 2.9653026630 1.3254203501 0.3984622270 0.5994666992 -0.5432207561 0.432179060518 +1413393909605760512.0000000000 -3.0603360254 2.9621372846 1.3164245578 0.3938705686 0.6013696380 -0.5469771244 0.428994824013 +1413393909655760384.0000000000 -3.0899919057 2.9598785675 1.3042205615 0.3868232794 0.6046468341 -0.5521705677 0.424119818742 +1413393909705760512.0000000000 -3.1190632489 2.9585003931 1.2900611615 0.3788869654 0.6079888726 -0.5579626471 0.418893641257 +1413393909755760384.0000000000 -3.1469392932 2.9582992562 1.2741131153 0.3701957743 0.6114869331 -0.5640154454 0.413431247771 +1413393909805760512.0000000000 -3.1732454653 2.9594836258 1.2566467912 0.3636557484 0.6133003396 -0.5694669079 0.409053335067 +1413393909855760384.0000000000 -3.1972077758 2.9616929648 1.2373222741 0.3572153063 0.6150195335 -0.5741379332 0.405603047449 +1413393909905760512.0000000000 -3.2187707528 2.9650214400 1.2160147643 0.3510029341 0.6163072185 -0.5789412977 0.402230439615 +1413393909955760384.0000000000 -3.2376249947 2.9696294060 1.1930123404 0.3460496661 0.6169409735 -0.5827457495 0.400051065761 +1413393910005760512.0000000000 -3.2538522343 2.9755552683 1.1688782909 0.3413366174 0.6174594484 -0.5862925779 0.398113245514 +1413393910055760384.0000000000 -3.2666033125 2.9831243962 1.1455261609 0.3369322855 0.6180689155 -0.5897775505 0.395764944882 +1413393910105760512.0000000000 -3.2753411680 2.9925942349 1.1254460424 0.3343920771 0.6172450436 -0.5938456568 0.393113000039 +1413393910155760384.0000000000 -3.2797310792 3.0035793232 1.1091699622 0.3319162170 0.6162985807 -0.5984497493 0.389699347952 +1413393910205760512.0000000000 -3.2789304451 3.0158143151 1.0972216573 0.3302486039 0.6153884123 -0.6014197359 0.38797843107 +1413393910255760384.0000000000 -3.2733160969 3.0290896432 1.0895035735 0.3276707992 0.6153126621 -0.6041031194 0.386110860244 +1413393910305760512.0000000000 -3.2623893223 3.0433667302 1.0857113397 0.3258055959 0.6146140964 -0.6071496974 0.384017540074 +1413393910355760384.0000000000 -3.2461041321 3.0587932716 1.0853952941 0.3230696197 0.6142912688 -0.6128734019 0.377701537101 +1413393910405760512.0000000000 -3.2240177001 3.0750918016 1.0893145086 0.3222056820 0.6127266817 -0.6202710666 0.368799831768 +1413393910455760384.0000000000 -3.1969107746 3.0916199167 1.0963465286 0.3245511555 0.6096365941 -0.6271133631 0.360192449157 +1413393910505760512.0000000000 -3.1642327114 3.1075123705 1.1038916442 0.3261898520 0.6080566854 -0.6319869474 0.352788528827 +1413393910555760384.0000000000 -3.1258304207 3.1222181073 1.1098988092 0.3284483740 0.6070390927 -0.6347050043 0.347526636406 +1413393910605760512.0000000000 -3.0823854658 3.1354510090 1.1140682834 0.3325322913 0.6062632511 -0.6338554822 0.346546350893 +1413393910655760384.0000000000 -3.0338227604 3.1472822099 1.1160365737 0.3382330851 0.6054176686 -0.6304608496 0.348693194399 +1413393910705760512.0000000000 -2.9807886579 3.1578943240 1.1156110798 0.3465474495 0.6029577096 -0.6274215860 0.350269923128 +1413393910755760384.0000000000 -2.9237067169 3.1671189991 1.1126969236 0.3552373552 0.6008377044 -0.6226607313 0.353686426275 +1413393910805760512.0000000000 -2.8629296098 3.1748027738 1.1064522162 0.3618312638 0.6006585739 -0.6167324020 0.357671019941 +1413393910855760384.0000000000 -2.7990188299 3.1813337064 1.0975663047 0.3677741597 0.6015620464 -0.6099440011 0.36170925794 +1413393910905760512.0000000000 -2.7322702337 3.1866619962 1.0867874696 0.3742822973 0.6023997916 -0.6020783777 0.366781788194 +1413393910955760384.0000000000 -2.6630978662 3.1908967946 1.0742546078 0.3826808059 0.6023842140 -0.5918265979 0.374739826483 +1413393911005760512.0000000000 -2.5919987033 3.1945252683 1.0599586094 0.3913402135 0.6022765853 -0.5820780401 0.381183561219 +1413393911055760384.0000000000 -2.5201118003 3.1977133906 1.0434333682 0.3992370059 0.6029092978 -0.5728082317 0.386006374803 +1413393911105760512.0000000000 -2.4478223620 3.2004884911 1.0262362001 0.4067439591 0.6034533119 -0.5651065085 0.388661917473 +1413393911155760384.0000000000 -2.3755149532 3.2027252510 1.0087354362 0.4120403406 0.6050425394 -0.5590283864 0.38940152334 +1413393911205760512.0000000000 -2.3030303259 3.2043676795 0.9913577201 0.4160243569 0.6067704308 -0.5529409556 0.391164515868 +1413393911255760384.0000000000 -2.2307700390 3.2053220709 0.9738231232 0.4184336219 0.6085200203 -0.5484941763 0.392136235941 +1413393911305760512.0000000000 -2.1589722245 3.2057094863 0.9564179505 0.4212035015 0.6092387175 -0.5446381638 0.393427332634 +1413393911355760384.0000000000 -2.0868508949 3.2058161457 0.9411744256 0.4261258515 0.6074209466 -0.5383327111 0.399567822215 +1413393911405760512.0000000000 -2.0154181297 3.2056416428 0.9266178218 0.4304579888 0.6048320982 -0.5320551081 0.407187198683 +1413393911455760384.0000000000 -1.9456160401 3.2054856513 0.9137761525 0.4350556060 0.6016214856 -0.5258024680 0.415102363733 +1413393911505760512.0000000000 -1.8786576380 3.2053482486 0.9019584727 0.4372630828 0.5994733708 -0.5213819647 0.42141846296 +1413393911555760384.0000000000 -1.8138617748 3.2055232464 0.8917377646 0.4367949300 0.5984525345 -0.5189178880 0.426367187531 +1413393911605760512.0000000000 -1.7530702647 3.2062705196 0.8861775346 0.4376174633 0.5963754959 -0.5171827753 0.430522009469 +1413393911655760384.0000000000 -1.6950016870 3.2080290500 0.8853797948 0.4399280128 0.5932271722 -0.5148767086 0.435254914519 +1413393911705760512.0000000000 -1.6399552959 3.2103430006 0.8873899444 0.4391588147 0.5916401879 -0.5141957028 0.438980868423 +1413393911755760384.0000000000 -1.5906571123 3.2133849863 0.8916190119 0.4340348823 0.5931452501 -0.5186609673 0.436787401678 +1413393911805760512.0000000000 -1.5449770281 3.2173996256 0.8991648198 0.4263688256 0.5970456710 -0.5240244802 0.43260193648 +1413393911855760384.0000000000 -1.5026875596 3.2223912920 0.9103543480 0.4176848079 0.6014393466 -0.5310110291 0.426423968091 +1413393911905760512.0000000000 -1.4626951024 3.2289728695 0.9254007279 0.4127684226 0.6031751391 -0.5422942432 0.414389834109 +1413393911955760384.0000000000 -1.4239186149 3.2365564719 0.9438136426 0.4087869686 0.6041252103 -0.5565347992 0.397737302569 +1413393912005760512.0000000000 -1.3840068150 3.2442704515 0.9656622565 0.4019658887 0.6063430391 -0.5714181622 0.379806302098 +1413393912055760384.0000000000 -1.3426454168 3.2512978882 0.9915422940 0.3935862957 0.6091307690 -0.5850328685 0.363023521104 +1413393912105760512.0000000000 -1.2983669519 3.2570776498 1.0208654150 0.3863987205 0.6111161291 -0.5949812714 0.351041866849 +1413393912155760384.0000000000 -1.2509840282 3.2612864294 1.0512355225 0.3792499982 0.6126830526 -0.6034166356 0.341580561324 +1413393912205760512.0000000000 -1.1999343832 3.2637412083 1.0819767634 0.3730964772 0.6139933813 -0.6095029163 0.335137794682 +1413393912255760384.0000000000 -1.1445079967 3.2643631145 1.1129568187 0.3683011757 0.6148718681 -0.6132785399 0.331928098039 +1413393912305760512.0000000000 -1.0843702116 3.2632954167 1.1442882288 0.3653979836 0.6145545564 -0.6161455352 0.33041139548 +1413393912355760384.0000000000 -1.0190300704 3.2605301228 1.1764739414 0.3654743604 0.6129238549 -0.6166176550 0.33246880678 +1413393912405760512.0000000000 -0.9484890422 3.2559714692 1.2101696247 0.3701087498 0.6089998487 -0.6144617902 0.33848989055 +1413393912455760384.0000000000 -0.8732280156 3.2497123283 1.2448103818 0.3778920327 0.6032918394 -0.6098138376 0.348372862955 +1413393912505760512.0000000000 -0.7946894704 3.2419138165 1.2793502606 0.3872828072 0.5973257094 -0.6030165719 0.359979219051 +1413393912555760384.0000000000 -0.7143708143 3.2328324481 1.3116961398 0.3959687833 0.5918036654 -0.5974408123 0.368838203076 +1413393912605760512.0000000000 -0.6327969699 3.2223157058 1.3407961113 0.4022753058 0.5881168986 -0.5923290383 0.37608430207 +1413393912655760384.0000000000 -0.5515622588 3.2106844140 1.3663073024 0.4073981696 0.5858827490 -0.5863333166 0.383381503972 +1413393912705760512.0000000000 -0.4701217434 3.1979746704 1.3884063911 0.4115885209 0.5840406650 -0.5804163361 0.390651081959 +1413393912755760384.0000000000 -0.3885578545 3.1843841316 1.4074610330 0.4153953619 0.5825368977 -0.5742983342 0.397842782327 +1413393912805760512.0000000000 -0.3068738440 3.1696217513 1.4232732579 0.4172019327 0.5810601067 -0.5694256278 0.405050804397 +1413393912855760384.0000000000 -0.2257396992 3.1537270803 1.4364393293 0.4172722126 0.5789921372 -0.5665247560 0.411948669828 +1413393912905760512.0000000000 -0.1456392163 3.1369436846 1.4462679111 0.4156283251 0.5762012556 -0.5661427518 0.418004297941 +1413393912955760384.0000000000 -0.0669957670 3.1195304947 1.4529993904 0.4129145476 0.5723848912 -0.5687553897 0.422367635436 +1413393913005760512.0000000000 0.0106260955 3.1015997636 1.4579467369 0.4116319038 0.5654097214 -0.5749688267 0.424596126918 +1413393913055760384.0000000000 0.0870856606 3.0830787187 1.4612000483 0.4109447305 0.5568162035 -0.5829679231 0.425709460335 +1413393913105760512.0000000000 0.1620607240 3.0635400325 1.4627246083 0.4112460737 0.5458586735 -0.5913416628 0.42805375051 +1413393913155760384.0000000000 0.2359791266 3.0428247443 1.4630932807 0.4131966380 0.5318687881 -0.5997187606 0.432112877365 +1413393913205760512.0000000000 0.3076706891 3.0206140285 1.4612110761 0.4137997410 0.5177494668 -0.6084018424 0.436523151962 +1413393913255760384.0000000000 0.3768570639 2.9966942418 1.4575065390 0.4134564611 0.5029353901 -0.6187071838 0.439671660349 +1413393913305760512.0000000000 0.4432282341 2.9706970477 1.4511390564 0.4098726867 0.4891256807 -0.6294866188 0.443291152476 +1413393913355760384.0000000000 0.5064384800 2.9424923888 1.4420516209 0.4031562869 0.4766943031 -0.6411616814 0.446250207789 +1413393913405760512.0000000000 0.5670485457 2.9119025087 1.4321129707 0.3977680299 0.4622078044 -0.6529226426 0.449262242753 +1413393913455760384.0000000000 0.6254101364 2.8782133519 1.4235950490 0.3928017679 0.4460292874 -0.6642422349 0.453372803839 +1413393913505760512.0000000000 0.6808852793 2.8411493637 1.4164273554 0.3872208426 0.4294332482 -0.6734807004 0.460511509701 +1413393913555760384.0000000000 0.7327922501 2.8006781054 1.4107826931 0.3803957524 0.4124914633 -0.6807579571 0.470869905743 +1413393913605760512.0000000000 0.7817953029 2.7567054040 1.4070032114 0.3721433782 0.3963334484 -0.6867593808 0.482483840794 +1413393913655760384.0000000000 0.8268239121 2.7098767520 1.4044899797 0.3633052964 0.3799242713 -0.6912600219 0.495808825827 +1413393913705760512.0000000000 0.8673040930 2.6604397252 1.4043288954 0.3528356504 0.3647539108 -0.6955202341 0.508638567541 +1413393913755760384.0000000000 0.9032471219 2.6087090397 1.4076923758 0.3430581549 0.3487104960 -0.6996644146 0.520751187606 +1413393913805760512.0000000000 0.9339255305 2.5558761401 1.4120551209 0.3328204444 0.3332250819 -0.7045093277 0.530903196198 +1413393913855760384.0000000000 0.9595934972 2.5020264847 1.4169456542 0.3220290480 0.3183276186 -0.7094974681 0.539979779399 +1413393913905760512.0000000000 0.9799378390 2.4477315297 1.4233903513 0.3122034315 0.3031062047 -0.7154425656 0.546623802462 +1413393913955760384.0000000000 0.9948216832 2.3931403397 1.4296154431 0.2994269041 0.2902809537 -0.7208086953 0.553638258934 +1413393914005760512.0000000000 1.0044493996 2.3378814276 1.4372971454 0.2841579722 0.2782604554 -0.7233217690 0.564474077667 +1413393914055760384.0000000000 1.0092040446 2.2830829988 1.4459851862 0.2685150832 0.2663457970 -0.7247939353 0.575876130643 +1413393914105760512.0000000000 1.0089757478 2.2291719341 1.4545728469 0.2487463997 0.2566124376 -0.7272284404 0.586015427291 +1413393914155760384.0000000000 1.0045027525 2.1764873040 1.4630078795 0.2261417731 0.2486095586 -0.7317723699 0.592926963834 +1413393914205760512.0000000000 0.9963332412 2.1257552525 1.4704415205 0.2013001456 0.2420893283 -0.7411452644 0.592937353833 +1413393914255760384.0000000000 0.9853365399 2.0775903331 1.4792493203 0.1797134088 0.2334427886 -0.7502760697 0.591855872979 +1413393914305760512.0000000000 0.9726034161 2.0315201548 1.4889603509 0.1605819674 0.2230443190 -0.7591882069 0.58999824575 +1413393914355760384.0000000000 0.9588614531 1.9873033712 1.5002688817 0.1439630647 0.2113683948 -0.7668551327 0.588669043747 +1413393914405760512.0000000000 0.9446778718 1.9445917915 1.5126412837 0.1292282610 0.1985157142 -0.7739150468 0.587321945959 +1413393914455760384.0000000000 0.9304502760 1.9036033705 1.5259481661 0.1190252425 0.1829357060 -0.7812878925 0.584770679927 +1413393914505760512.0000000000 0.9159949773 1.8638524131 1.5396202983 0.1097621578 0.1679510123 -0.7878641776 0.582249743511 +1413393914555760384.0000000000 0.9015147592 1.8247942031 1.5545816790 0.1035773438 0.1512381592 -0.7919862584 0.582371461889 +1413393914605760512.0000000000 0.8865689668 1.7863150605 1.5699958439 0.0978007054 0.1350484652 -0.7951239182 0.583073656411 +1413393914655760384.0000000000 0.8711302398 1.7483668397 1.5854997903 0.0918815237 0.1198858588 -0.7976991544 0.583833217243 +1413393914705760512.0000000000 0.8548210553 1.7106681574 1.6009410846 0.0866037738 0.1034094154 -0.8009338591 0.583362008186 +1413393914755760384.0000000000 0.8375949090 1.6733798581 1.6166910824 0.0831925324 0.0860116897 -0.8041779853 0.582218824659 +1413393914805760512.0000000000 0.8188692742 1.6363730774 1.6318897568 0.0782676886 0.0702303678 -0.8079606464 0.579777076356 +1413393914855760384.0000000000 0.7983980786 1.5990565112 1.6467696300 0.0719826219 0.0552878108 -0.8118372304 0.57678598413 +1413393914905760512.0000000000 0.7763210994 1.5615815441 1.6609207210 0.0621139730 0.0457351097 -0.8149926543 0.57431448481 +1413393914955760384.0000000000 0.7527075653 1.5238769940 1.6744560292 0.0493697732 0.0412501027 -0.8184463180 0.570969945813 +1413393915005760512.0000000000 0.7280519237 1.4857095605 1.6876937486 0.0368410927 0.0385408109 -0.8227528041 0.565893243522 +1413393915055760384.0000000000 0.7030864953 1.4467574532 1.7014084990 0.0263238515 0.0369768538 -0.8257841617 0.562156815727 +1413393915105760512.0000000000 0.6781261740 1.4067776343 1.7152845958 0.0183407391 0.0360207197 -0.8284431305 0.558612660641 +1413393915155760384.0000000000 0.6534938463 1.3654491874 1.7291138713 0.0116169197 0.0353605001 -0.8307438472 0.555409166759 +1413393915205760512.0000000000 0.6295849867 1.3227444928 1.7426359774 0.0073581013 0.0348520105 -0.8322751851 0.55321714728 +1413393915255760384.0000000000 0.6062219727 1.2784857212 1.7545630471 0.0036849009 0.0349596194 -0.8327597766 0.552517330995 +1413393915305760512.0000000000 0.5838408792 1.2327438013 1.7643702516 0.0022728094 0.0359042693 -0.8323086766 0.553143728766 +1413393915355760384.0000000000 0.5624341235 1.1857971812 1.7714687074 0.0009076304 0.0408699099 -0.8297665123 0.556611499758 +1413393915405760512.0000000000 0.5420676872 1.1378807129 1.7762709237 0.0010792725 -0.0495002694 0.8255181262 -0.56219959247 +1413393915455760384.0000000000 0.5229572778 1.0893303872 1.7804514441 0.0047163551 -0.0617352018 0.8196241562 -0.569546102931 +1413393915505760512.0000000000 0.5056098798 1.0398330955 1.7850165245 0.0072406550 -0.0732583071 0.8137343949 -0.576556265988 +1413393915555760384.0000000000 0.4904757435 0.9899468113 1.7901439505 0.0070087059 -0.0820407215 0.8096248202 -0.581143569737 +1413393915605760512.0000000000 0.4778172365 0.9406525817 1.7960110113 0.0025718172 -0.0875653927 0.8061460833 -0.585195847697 +1413393915655760384.0000000000 0.4672428273 0.8920761222 1.8022268788 0.0033766854 0.0906001300 -0.8044947151 0.586999546696 +1413393915705760512.0000000000 0.4584406678 0.8442427349 1.8083092843 0.0069467176 0.0944655937 -0.8030041691 0.588398078791 +1413393915755760384.0000000000 0.4512274743 0.7973138798 1.8145611620 0.0093364212 0.0987864469 -0.8013666541 0.589886052433 +1413393915805760512.0000000000 0.4456735347 0.7513428015 1.8205107735 0.0096084808 0.1035262190 -0.8001224778 0.590757157852 +1413393915855760384.0000000000 0.4419670523 0.7066477316 1.8261866774 0.0096106924 0.1080152694 -0.7998419789 0.590333079614 +1413393915905760512.0000000000 0.4402324346 0.6630139301 1.8318439199 0.0099678117 0.1117114952 -0.8000111912 0.589409262269 +1413393915955760384.0000000000 0.4406026660 0.6202759423 1.8380699041 0.0101641908 0.1146961325 -0.7991729867 0.589969510808 +1413393916005760512.0000000000 0.4431446039 0.5786292997 1.8445333741 0.0091074931 0.1182364500 -0.7972128071 0.591936597607 +1413393916055760384.0000000000 0.4480377600 0.5382913918 1.8512474911 0.0084176999 0.1211258053 -0.7956167395 0.593507948882 +1413393916105760512.0000000000 0.4552618235 0.4991987106 1.8583075652 0.0063738617 0.1240987298 -0.7935686227 0.595657384898 +1413393916155760384.0000000000 0.4650761997 0.4616102163 1.8657778696 0.0048172367 0.1259208858 -0.7914558894 0.598095560845 +1413393916205760512.0000000000 0.4772675569 0.4257746704 1.8737001379 0.0033253530 0.1254425795 -0.7896159580 0.600632783094 +1413393916255760384.0000000000 0.4922929251 0.3918269637 1.8822569815 0.0073938314 0.1181613042 -0.7892375140 0.602567327292 +1413393916305760512.0000000000 0.5091254129 0.3592372111 1.8899059914 0.0104937104 0.1084854481 -0.7901283977 0.603173196245 +1413393916355760384.0000000000 0.5275417797 0.3271941718 1.8983156245 0.0122616124 0.0967394124 -0.7925194778 0.602000013463 +1413393916405760512.0000000000 0.5469781430 0.2958622338 1.9073577393 0.0118563221 0.0836754242 -0.7960031470 0.599363696697 +1413393916455760384.0000000000 0.5669032663 0.2649397254 1.9171545290 0.0080667015 0.0702516047 -0.7989887959 0.597173797495 +1413393916505760512.0000000000 0.5870119657 0.2361336563 1.9278237790 0.0033392060 0.0551593497 -0.8018531919 0.594960296616 +1413393916555760384.0000000000 0.6069717659 0.2085376899 1.9383657285 0.0047356405 -0.0397566360 0.8042508341 -0.592939777313 +1413393916605760512.0000000000 0.6268293635 0.1815104642 1.9486282534 0.0155320964 -0.0234598472 0.8079718742 -0.588548927475 +1413393916655760384.0000000000 0.6470952513 0.1551793587 1.9596447127 0.0265281587 -0.0058423398 0.8117402093 -0.583386626897 +1413393916705760512.0000000000 0.6675565858 0.1283964060 1.9718800490 0.0382790722 0.0134075277 0.8156005391 -0.577192092273 +1413393916755760384.0000000000 0.6882538447 0.1027765224 1.9836052870 0.0506633039 0.0327490324 0.8179717302 -0.572086513583 +1413393916805760512.0000000000 0.7090928843 0.0780721949 1.9943843886 0.0627949892 0.0525951402 0.8176533942 -0.569853900193 +1413393916855760384.0000000000 0.7293728219 0.0517884054 2.0053860160 0.0766282438 0.0721720226 0.8151688347 -0.569577986195 +1413393916905760512.0000000000 0.7500222824 0.0253048042 2.0170089727 0.0877227332 0.0932229388 0.8116269746 -0.569978824048 +1413393916955760384.0000000000 0.7706786074 -0.0014037399 2.0294318031 0.0969715129 0.1155430767 0.8073153355 -0.570515794782 +1413393917005760512.0000000000 0.7910382966 -0.0284423010 2.0432590907 0.1036523411 0.1403335580 0.8003282706 -0.573617768106 +1413393917055760384.0000000000 0.8106668857 -0.0551875083 2.0573655587 0.1100800374 0.1648285896 0.7931129044 -0.575921732826 +1413393917105760512.0000000000 0.8291542637 -0.0809320466 2.0714467835 0.1176354228 0.1880217117 0.7857880277 -0.577362034431 +1413393917155760384.0000000000 0.8459195160 -0.1057632940 2.0855343632 0.1272559014 0.2098826724 0.7783961190 -0.577801593311 +1413393917205760512.0000000000 0.8611102514 -0.1291650740 2.0999120639 0.1371507044 0.2309949627 0.7714780307 -0.576760487212 +1413393917255760384.0000000000 0.8750339933 -0.1504020359 2.1136751592 0.1450909474 0.2522179501 0.7659551176 -0.573277838807 +1413393917305760512.0000000000 0.8870794187 -0.1694304752 2.1268491103 0.1550664934 0.2719195263 0.7625840027 -0.566109346935 +1413393917355760384.0000000000 0.8971944487 -0.1864827367 2.1391800382 0.1653129355 0.2915036749 0.7593056739 -0.557810124003 +1413393917405760512.0000000000 0.9052629572 -0.2019818737 2.1501145922 0.1744335388 0.3123803953 0.7542399298 -0.550557496965 +1413393917455760384.0000000000 0.9108825280 -0.2159511156 2.1584335509 0.1854398808 0.3327832515 0.7489609542 -0.542148362708 +1413393917505760512.0000000000 0.9141333950 -0.2285782840 2.1641270033 0.1973716916 0.3526350365 0.7429251037 -0.533624621468 +1413393917555760384.0000000000 0.9152976656 -0.2394606465 2.1674366002 0.2079927214 0.3739525454 0.7360454489 -0.52453371553 +1413393917605760512.0000000000 0.9136812679 -0.2488740661 2.1678898554 0.2225722327 0.3929058174 0.7293119475 -0.513994847482 +1413393917655760384.0000000000 0.9091859727 -0.2572539379 2.1659800606 0.2385496696 0.4107560261 0.7223739901 -0.502542894292 +1413393917705760512.0000000000 0.9021735077 -0.2644740102 2.1621585048 0.2568777123 0.4270394507 0.7137187995 -0.492195716911 +1413393917755760384.0000000000 0.8929477270 -0.2706379396 2.1568126760 0.2761726819 0.4422397149 0.7024949004 -0.484410568972 +1413393917805760512.0000000000 0.8815865338 -0.2760482887 2.1516340985 0.2968375048 0.4556351107 0.6890714439 -0.479024724633 +1413393917855760384.0000000000 0.8687447585 -0.2810311071 2.1476005572 0.3147299265 0.4704640973 0.6736036618 -0.475254366951 +1413393917905760512.0000000000 0.8551294363 -0.2851422799 2.1442842363 0.3286764505 0.4870848634 0.6576355284 -0.471418750629 +1413393917955760384.0000000000 0.8410013451 -0.2882566644 2.1412008979 0.3398844328 0.5044492895 0.6428898419 -0.46551276866 +1413393918005760512.0000000000 0.8260562766 -0.2902498521 2.1391186635 0.3496415630 0.5219050118 0.6274980333 -0.460013211036 +1413393918055760384.0000000000 0.8108012206 -0.2906482432 2.1377840137 0.3583251693 0.5391462329 0.6124791567 -0.453644899882 +1413393918105760512.0000000000 0.7954822967 -0.2892884042 2.1369310775 0.3664069932 0.5559195575 0.5976782819 -0.446631875613 +1413393918155760384.0000000000 0.7798121589 -0.2861466448 2.1361280306 0.3735293882 0.5724829629 0.5838053265 -0.438075785844 +1413393918205760512.0000000000 0.7637665056 -0.2811467682 2.1361889591 0.3779528208 0.5901447397 0.5690007848 -0.430254527462 +1413393918255760384.0000000000 0.7468436432 -0.2737438150 2.1359084100 0.3851760739 0.6052314110 0.5556240956 -0.420257296777 +1413393918305760512.0000000000 0.7292363330 -0.2637917043 2.1365221596 0.3911437777 0.6206909127 0.5408604406 -0.411362759386 +1413393918355760384.0000000000 0.7106771959 -0.2511335620 2.1377064523 0.3980797052 0.6350367256 0.5260502156 -0.401910532386 +1413393918405760512.0000000000 0.6916302595 -0.2356760867 2.1392521519 0.4053270950 0.6487540218 0.5113493124 -0.391599343651 +1413393918455760384.0000000000 0.6721129666 -0.2172147557 2.1410520212 0.4129623796 0.6622009820 0.4964093416 -0.380170616963 +1413393918505760512.0000000000 0.6517907373 -0.1956897308 2.1436457590 0.4204899988 0.6756460212 0.4803112545 -0.368770543613 +1413393918555760384.0000000000 0.6306957332 -0.1710447049 2.1470268685 0.4275829416 0.6891514890 0.4632666819 -0.357249261234 +1413393918605760512.0000000000 0.6090450365 -0.1429645667 2.1512916313 0.4375754925 0.7009243799 0.4445164693 -0.345886990953 +1413393918655760384.0000000000 0.5870543612 -0.1115844679 2.1555976444 0.4503672375 0.7106783786 0.4249534532 -0.333946337305 +1413393918705760512.0000000000 0.5649280794 -0.0772821877 2.1608075766 0.4620715222 0.7207393715 0.4025301093 -0.32402805102 +1413393918755760384.0000000000 0.5436455820 -0.0403607203 2.1658769111 0.4712423441 0.7323609869 0.3784631504 -0.313597961943 +1413393918805760512.0000000000 0.5233598955 -0.0005053153 2.1712887627 0.4814183229 0.7428702547 0.3517455898 -0.30439320474 +1413393918855760384.0000000000 0.5039764948 0.0426995525 2.1773988515 0.4916276261 0.7527568867 0.3220840995 -0.296515058032 +1413393918905760512.0000000000 0.4871653055 0.0889324769 2.1832921512 0.5073097446 0.7586649824 0.2934252293 -0.284545079669 +1413393918955760384.0000000000 0.4731289473 0.1376998266 2.1885868148 0.5238263813 0.7630970859 0.2662468385 -0.269075046732 +1413393919005760512.0000000000 0.4626822040 0.1882004802 2.1937405464 0.5402577872 0.7664277546 0.2409489361 -0.250307072568 +1413393919055760384.0000000000 0.4557486954 0.2397796485 2.1993497785 0.5550748705 0.7697100619 0.2152228268 -0.230472218534 +1413393919105760512.0000000000 0.4522116461 0.2917949260 2.2048078259 0.5680146080 0.7726253205 0.1908329153 -0.209743456711 +1413393919155760384.0000000000 0.4521593604 0.3432920345 2.2102570729 0.5778407380 0.7761869751 0.1653239676 -0.190530435764 +1413393919205760512.0000000000 0.4553980572 0.3940503604 2.2164358090 0.5885335587 0.7773865524 0.1392529190 -0.172936471021 +1413393919255760384.0000000000 0.4621944185 0.4434858198 2.2226740234 0.5986924181 0.7774100991 0.1134103446 -0.156009679743 +1413393919305760512.0000000000 0.4724337385 0.4912241741 2.2291042958 0.6106946123 0.7743745278 0.0867895019 -0.140938864701 +1413393919355760384.0000000000 0.4859962472 0.5360396113 2.2336879034 0.6212617378 0.7707110986 0.0610824463 -0.127699609996 +1413393919405760512.0000000000 0.5028771499 0.5768189665 2.2360007124 0.6300402263 0.7667736713 0.0358075975 -0.1175808923 +1413393919455760384.0000000000 0.5228984318 0.6141474643 2.2348634343 0.6330729097 0.7661661519 0.0124932012 -0.109781776859 +1413393919505760512.0000000000 0.5466246428 0.6482913741 2.2308213433 0.6327420063 0.7676730583 -0.0077336152 -0.101271023558 +1413393919555760384.0000000000 0.5744259420 0.6787899276 2.2246062430 0.6307846633 0.7698306019 -0.0268309658 -0.0935502650685 +1413393919605760512.0000000000 0.6061463644 0.7054975159 2.2151300275 0.6282278334 0.7721853739 -0.0435019002 -0.0846588590899 +1413393919655760384.0000000000 0.6417862583 0.7290227846 2.2032878662 0.6277580595 0.7727771499 -0.0569078326 -0.0741403666481 +1413393919705760512.0000000000 0.6809633053 0.7496259035 2.1895472875 0.6289017365 0.7720440480 -0.0664058495 -0.0634102265934 +1413393919755760384.0000000000 0.7238954344 0.7671594127 2.1742285041 0.6331171330 0.7694008648 -0.0696329483 -0.0483348496276 +1413393919805760512.0000000000 0.7697838935 0.7812281416 2.1570492363 0.6388790419 0.7656165482 -0.0684885840 -0.0312119339425 +1413393919855760384.0000000000 0.8179562263 0.7912995157 2.1375965350 0.6441938436 0.7620559772 -0.0640951121 -0.0132964699442 +1413393919905760512.0000000000 0.8674904103 0.7966717618 2.1156128712 0.6471011748 0.7601694942 -0.0582653427 0.00274947252204 +1413393919955760384.0000000000 0.9175289840 0.7970900451 2.0906455735 0.6466484407 0.7608246595 -0.0522817258 0.0160702439831 +1413393920005760512.0000000000 0.9673478998 0.7935966508 2.0630979183 0.6429293315 0.7640481451 -0.0473130932 0.0251749446045 +1413393920055760384.0000000000 1.0165980588 0.7863548430 2.0340188783 0.6388263672 0.7675119777 -0.0435402755 0.0305037859738 +1413393920105760512.0000000000 1.0650983273 0.7754723077 2.0032335956 0.6353621377 0.7704216956 -0.0405835739 0.0334415680862 +1413393920155760384.0000000000 1.1128631997 0.7615837037 1.9706280492 0.6314880135 0.7736656408 -0.0373858776 0.035590184256 +1413393920205760512.0000000000 1.1598483543 0.7447359148 1.9365823025 0.6284139756 0.7762527710 -0.0350865195 0.0360062063814 +1413393920255760384.0000000000 1.2060243105 0.7250668955 1.9018578685 0.6262463724 0.7780750034 -0.0328601730 0.0365373671398 +1413393920305760512.0000000000 1.2509794955 0.7023453249 1.8675852817 0.6238211904 0.7801377625 -0.0309128090 0.0357294311238 +1413393920355760384.0000000000 1.2952175049 0.6767779091 1.8338373907 0.6210066950 0.7824547343 -0.0283903221 0.0361837424857 +1413393920405760512.0000000000 1.3383455070 0.6484865681 1.8007354499 0.6144951255 0.7876571406 -0.0264789375 0.0359281982845 +1413393920455760384.0000000000 1.3805052342 0.6180811066 1.7685182152 0.6058444058 0.7944215935 -0.0249731787 0.0349746780546 +1413393920505760512.0000000000 1.4219396018 0.5861287270 1.7372734957 0.5977647127 0.8005890699 -0.0225416989 0.0350194404262 +1413393920555760384.0000000000 1.4624071883 0.5534727014 1.7076047790 0.5915335463 0.8052716265 -0.0208371037 0.0345179115393 +1413393920605760512.0000000000 1.5018295402 0.5205059367 1.6790622840 0.5870134577 0.8086311407 -0.0180633468 0.034707263825 +1413393920655760384.0000000000 1.5401829059 0.4876018563 1.6513912218 0.5836962454 0.8110745364 -0.0156706380 0.0348025951259 +1413393920705760512.0000000000 1.5775261884 0.4550272343 1.6245529754 0.5817482101 0.8124909867 -0.0133008862 0.0353624525222 +1413393920755760384.0000000000 1.6135800057 0.4225459732 1.5983928883 0.5813800274 0.8127750824 -0.0107707258 0.0357480168392 +1413393920805760512.0000000000 1.6483296500 0.3903294063 1.5723344490 0.5800485484 0.8137695838 -0.0096541941 0.0350648338736 +1413393920855760384.0000000000 1.6820943749 0.3584172886 1.5465062697 0.5792748192 0.8142728400 -0.0071776193 0.0367274767911 +1413393920905760512.0000000000 1.7145688276 0.3264259560 1.5202742415 0.5748470603 0.8173372522 -0.0046740778 0.0385853129428 +1413393920955760384.0000000000 1.7456471308 0.2948666084 1.4944017029 0.5693902328 0.8210872275 -0.0020998716 0.0400764033631 +1413393921005760512.0000000000 1.7755627360 0.2640001734 1.4683017637 0.5607613909 0.8269342166 -0.0010130265 0.0415383879189 +1413393921055760384.0000000000 1.8038316911 0.2342600904 1.4422143344 0.5510579190 0.8333508990 0.0010313016 0.0431321864882 +1413393921105760512.0000000000 1.8305178251 0.2064503686 1.4171334615 0.5421463623 0.8391211626 0.0026209548 0.0441149286324 +1413393921155760384.0000000000 1.8555353044 0.1815908095 1.3935829520 0.5360625557 0.8429672418 0.0034335199 0.0450707950021 +1413393921205760512.0000000000 1.8789300383 0.1595364684 1.3711614886 0.5312016135 0.8458931906 0.0054703912 0.0475355731755 +1413393921255760384.0000000000 1.9002257629 0.1408006360 1.3501196035 0.5280876433 0.8477697820 0.0067189674 0.048628111127 +1413393921305760512.0000000000 1.9196131813 0.1257498995 1.3303724635 0.5264382050 0.8487531161 0.0068288508 0.0493389413168 +1413393921355760384.0000000000 1.9367638774 0.1141393196 1.3119180104 0.5250181565 0.8497242537 0.0060558198 0.0478325727792 +1413393921405760512.0000000000 1.9521357340 0.1063948691 1.2952930466 0.5268528239 0.8486929926 0.0048152842 0.0460773196317 +1413393921455760384.0000000000 1.9657787677 0.1024607580 1.2805987097 0.5331659243 0.8448577439 0.0028337272 0.0440619991245 +1413393921505760512.0000000000 1.9776966916 0.1015692445 1.2670336263 0.5421931908 0.8391798647 0.0020920016 0.0424184153143 +1413393921555760384.0000000000 1.9882896086 0.1032808970 1.2543146976 0.5528654174 0.8322835893 0.0006406485 0.0405394482776 +1413393921605760512.0000000000 1.9978012281 0.1066637568 1.2411203845 0.5617534158 0.8262869484 0.0000461056 0.0410240985998 +1413393921655760384.0000000000 2.0059296729 0.1110528649 1.2269300668 0.5675630993 0.8223567827 -0.0011024187 0.0400029370215 +1413393921705760512.0000000000 2.0131299075 0.1154737131 1.2094605876 0.5717050836 0.8194656729 -0.0018852910 0.0403206402002 +1413393921755760384.0000000000 2.0191892504 0.1197691038 1.1887526154 0.5749674753 0.8171742674 -0.0030906567 0.0403616993868 +1413393921805760512.0000000000 2.0242703531 0.1240977185 1.1652846094 0.5784658860 0.8146763273 -0.0034829468 0.0408358851196 +1413393921855760384.0000000000 2.0283466718 0.1286214740 1.1398766189 0.5828011080 0.8115437765 -0.0038266586 0.0415322058418 +1413393921905760512.0000000000 2.0312131378 0.1332906344 1.1133014403 0.5900141244 0.8063040443 -0.0050432720 0.041613538505 +1413393921955760384.0000000000 2.0330372251 0.1375530843 1.0863377596 0.5976874990 0.8005795610 -0.0054035135 0.0425772476637 +1413393922005760512.0000000000 2.0338851626 0.1405816825 1.0593521168 0.6024765478 0.7969754068 -0.0063541485 0.0425656573946 +1413393922055760384.0000000000 2.0337765234 0.1418378119 1.0312727001 0.6005110349 0.7984088017 -0.0071327041 0.0433475137521 +1413393922105760512.0000000000 2.0325701010 0.1418820148 1.0031780538 0.5962592235 0.8015412036 -0.0079173014 0.0440902891595 +1413393922155760384.0000000000 2.0302367297 0.1405928447 0.9744702225 0.5880826698 0.8074980006 -0.0084409193 0.0451054701596 +1413393922205760512.0000000000 2.0268742722 0.1382367846 0.9447659890 0.5738555220 0.8176320953 -0.0097222109 0.0455310362924 +1413393922255760384.0000000000 2.0226494238 0.1359930405 0.9152911201 0.5605970614 0.8266987080 -0.0106405112 0.0467649493974 +1413393922305760512.0000000000 2.0172365314 0.1346930586 0.8860009888 0.5467146653 0.8359429946 -0.0126107656 0.0462963625539 +1413393922355760384.0000000000 2.0109382431 0.1353756601 0.8575552802 0.5341627533 0.8440111761 -0.0142495093 0.0459591023754 +1413393922405760512.0000000000 2.0038562705 0.1390712076 0.8306175698 0.5242587160 0.8501840827 -0.0161048719 0.045612029849 +1413393922455760384.0000000000 1.9957156778 0.1467163158 0.8057985955 0.5184364690 0.8538768293 -0.0211770375 0.0408597734028 +1413393922505760512.0000000000 1.9871561908 0.1585537945 0.7828610787 0.5184148418 0.8540144339 -0.0276016687 0.0338163632759 +1413393922555760384.0000000000 1.9787048921 0.1749711038 0.7620112261 0.5239074124 0.8506627396 -0.0348956170 0.0260042803908 +1413393922605760512.0000000000 1.9707698296 0.1950464542 0.7428885064 0.5324317573 0.8452384708 -0.0421275798 0.0177092741047 +1413393922655760384.0000000000 1.9642234641 0.2178621273 0.7241584204 0.5393367013 0.8406584193 -0.0479115519 0.0106690157052 +1413393922705760512.0000000000 1.9596372231 0.2431691502 0.7060030975 0.5461005613 0.8361020687 -0.0516457430 0.00634230686545 +1413393922755760384.0000000000 1.9568955193 0.2701122586 0.6878546803 0.5494304217 0.8338343874 -0.0532526977 0.00325211832586 +1413393922805760512.0000000000 1.9565835667 0.2988124384 0.6698815853 0.5504155695 0.8332121061 -0.0528247739 0.00313534241717 +1413393922855760384.0000000000 1.9587276316 0.3287094525 0.6519497309 0.5474353459 0.8353449824 -0.0496369803 0.00703367892955 +1413393922905760512.0000000000 1.9628985557 0.3604379078 0.6358700912 0.5426103754 0.8386526998 -0.0457969360 0.0117588348942 +1413393922955760384.0000000000 1.9690173141 0.3944427457 0.6225846371 0.5373540831 0.8421808734 -0.0400656557 0.0194089967583 +1413393923005760512.0000000000 1.9765386658 0.4304713531 0.6125159243 0.5315823596 0.8458405536 -0.0328601191 0.0299025991228 +1413393923055760384.0000000000 1.9844557312 0.4694133301 0.6062690916 0.5270410271 0.8485152449 -0.0265371183 0.0393117832309 +1413393923105760512.0000000000 1.9920722334 0.5120881842 0.6036491968 0.5239668273 0.8502012215 -0.0229492024 0.0457163085087 +1413393923155760384.0000000000 1.9990371639 0.5584702813 0.6040532313 0.5207030734 0.8519854351 -0.0202574058 0.0507815446107 +1413393923205760512.0000000000 2.0050197323 0.6090142052 0.6078902917 0.5196023076 0.8525062011 -0.0188919425 0.0537560561314 +1413393923255760384.0000000000 2.0100555082 0.6632483883 0.6134214751 0.5210896586 0.8515061472 -0.0189150413 0.0551821544379 +1413393923305760512.0000000000 2.0136077869 0.7211498953 0.6200686605 0.5249731238 0.8492812293 -0.0226741214 0.0510930232988 +1413393923355760384.0000000000 2.0158828098 0.7825658618 0.6277765145 0.5312464864 0.8457306573 -0.0293545104 0.0406833954651 +1413393923405760512.0000000000 2.0175455059 0.8464176339 0.6360965988 0.5368119509 0.8425210960 -0.0366863667 0.0254016282429 +1413393923455760384.0000000000 2.0193743837 0.9117105504 0.6446520619 0.5433318781 0.8385167522 -0.0400386775 0.00877672494582 +1413393923505760512.0000000000 2.0225396120 0.9785262881 0.6532928703 0.5505025356 0.8338810268 -0.0391483154 -0.00753664048826 +1413393923555760384.0000000000 2.0276400504 1.0457839727 0.6618795390 0.5578342846 0.8289907231 -0.0329111338 -0.0226307139536 +1413393923605760512.0000000000 2.0347169791 1.1130040594 0.6700031622 0.5626226028 0.8256064775 -0.0212782658 -0.0371077693455 +1413393923655760384.0000000000 2.0446713801 1.1803423276 0.6773095052 0.5659916278 0.8231510398 -0.0023455699 -0.0455010022631 +1413393923705760512.0000000000 2.0570126677 1.2475439749 0.6845293075 0.5681263687 0.8210632356 0.0211699266 -0.0513753493496 +1413393923755760384.0000000000 2.0713521650 1.3143744247 0.6907386345 0.5660004093 0.8211381702 0.0481310443 -0.0553086308308 +1413393923805760512.0000000000 2.0869609481 1.3812747557 0.6962593260 0.5621865722 0.8213874205 0.0742237905 -0.0613171466628 +1413393923855760384.0000000000 2.1035843318 1.4482877591 0.7020763313 0.5586019051 0.8205738635 0.0992554340 -0.069071014074 +1413393923905760512.0000000000 2.1208423002 1.5153763447 0.7086016410 0.5549074321 0.8190444448 0.1233321150 -0.0776732170953 +1413393923955760384.0000000000 2.1382911437 1.5823907740 0.7154672555 0.5507544234 0.8171617257 0.1451799836 -0.0885384187075 +1413393924005760512.0000000000 2.1557767609 1.6497909233 0.7220955998 0.5451986597 0.8157081426 0.1659428593 -0.0992049141663 +1413393924055760384.0000000000 2.1732218300 1.7179440123 0.7287079398 0.5400870036 0.8136558016 0.1854363899 -0.109011974019 +1413393924105760512.0000000000 2.1902608399 1.7871414387 0.7349489846 0.5353623587 0.8108255009 0.2064162793 -0.115505288051 +1413393924155760384.0000000000 2.2063646134 1.8577934647 0.7411533974 0.5332793602 0.8058112603 0.2289795494 -0.117684759588 +1413393924205760512.0000000000 2.2210325702 1.9292772063 0.7476599047 0.5341766641 0.7981643874 0.2528702562 -0.11681410763 +1413393924255760384.0000000000 2.2334878785 2.0008974102 0.7544722139 0.5377174202 0.7878805998 0.2777437888 -0.113853081536 +1413393924305760512.0000000000 2.2431200878 2.0720333506 0.7615710524 0.5406433775 0.7780573859 0.3001164944 -0.110731804072 +1413393924355760384.0000000000 2.2491847220 2.1420532889 0.7690261945 0.5432923939 0.7685505713 0.3207026107 -0.106363666423 +1413393924405760512.0000000000 2.2511824464 2.2104585883 0.7772866464 0.5466164610 0.7589807540 0.3390377842 -0.101054641185 +1413393924455760384.0000000000 2.2482384110 2.2768325205 0.7862407565 0.5496688388 0.7502667416 0.3551828263 -0.0938570397413 +1413393924505760512.0000000000 2.2392096382 2.3400015647 0.7969065750 0.5531216593 0.7421873457 0.3679463325 -0.0884865540376 +1413393924555760384.0000000000 2.2247533683 2.3985858507 0.8092369559 0.5569167183 0.7346719096 0.3781049680 -0.0844842429845 +1413393924605760512.0000000000 2.2037595014 2.4530344304 0.8229580988 0.5640494252 0.7255833750 0.3856306381 -0.0816457153612 +1413393924655760384.0000000000 2.1767003262 2.5015139963 0.8386952931 0.5722161138 0.7164034829 0.3912240922 -0.0792368500837 +1413393924705760512.0000000000 2.1424947555 2.5437551092 0.8569791268 0.5816341093 0.7067593060 0.3952500818 -0.077268486586 +1413393924755760384.0000000000 2.1013174054 2.5780986294 0.8794841871 0.5902846067 0.6989723777 0.3963742491 -0.0767408162623 +1413393924805760512.0000000000 2.0534661334 2.6045215134 0.9055587319 0.5956296669 0.6951774169 0.3952345599 -0.0757845740726 +1413393924855760384.0000000000 1.9985403924 2.6218544132 0.9362116831 0.5957122095 0.6982611246 0.3883577868 -0.0820767613595 +1413393924905760512.0000000000 1.9370452476 2.6308271813 0.9716152746 0.5905799684 0.7070991366 0.3775485995 -0.0931835121562 +1413393924955760384.0000000000 1.8691238509 2.6322560591 1.0119636987 0.5792475110 0.7211784237 0.3636734005 -0.110071159076 +1413393925005760512.0000000000 1.7974069776 2.6268434353 1.0566069158 0.5679184075 0.7334077498 0.3509302370 -0.128178484195 +1413393925055760384.0000000000 1.7227119498 2.6169070037 1.1045988725 0.5566980403 0.7437047978 0.3405356048 -0.145003336339 +1413393925105760512.0000000000 1.6454195319 2.6040783121 1.1548785576 0.5456874632 0.7520009002 0.3326783870 -0.161384415152 +1413393925155760384.0000000000 1.5657733218 2.5898269761 1.2071948214 0.5331216072 0.7595765578 0.3270254189 -0.178547417049 +1413393925205760512.0000000000 1.4847903296 2.5745914637 1.2600219491 0.5180093123 0.7669450849 0.3231832081 -0.197520133341 +1413393925255760384.0000000000 1.4032944695 2.5596923656 1.3123528581 0.5026848889 0.7724751540 0.3230850656 -0.214955993968 +1413393925305760512.0000000000 1.3215583421 2.5467060914 1.3647477970 0.4897387371 0.7751879010 0.3257505090 -0.230491417168 +1413393925355760384.0000000000 1.2402010181 2.5370025717 1.4163151061 0.4813061779 0.7746616265 0.3324073160 -0.240310432252 +1413393925405760512.0000000000 1.1592130108 2.5311600425 1.4676485500 0.4791239447 0.7707322078 0.3412268571 -0.244900676564 +1413393925455760384.0000000000 1.0783041341 2.5286014178 1.5193110251 0.4799177147 0.7655561492 0.3483202423 -0.24955115361 +1413393925505760512.0000000000 0.9976479707 2.5290838173 1.5706662046 0.4830251395 0.7595346988 0.3552199536 -0.252215265944 +1413393925555760384.0000000000 0.9171448787 2.5318398483 1.6211679934 0.4848699506 0.7547752777 0.3607854040 -0.255047649472 +1413393925605760512.0000000000 0.8366319288 2.5368615103 1.6699946673 0.4857304391 0.7512996798 0.3640107530 -0.25905772192 +1413393925655760384.0000000000 0.7557468114 2.5441049658 1.7151416439 0.4869224089 0.7480056027 0.3673006903 -0.261695221339 +1413393925705760512.0000000000 0.6749489628 2.5529589237 1.7532854983 0.4878166708 0.7453048763 0.3709150448 -0.262635805987 +1413393925755760384.0000000000 0.5941069128 2.5631581151 1.7839937140 0.4900035579 0.7423209850 0.3736738068 -0.263104455774 +1413393925805760512.0000000000 0.5133664245 2.5743622645 1.8066137028 0.4925175607 0.7393519521 0.3754287944 -0.264269490611 +1413393925855760384.0000000000 0.4330193681 2.5865032999 1.8223193000 0.4956804054 0.7363860081 0.3763142028 -0.26537558968 +1413393925905760512.0000000000 0.3530635323 2.5995794782 1.8320478753 0.5005973496 0.7323943497 0.3769546484 -0.266281811514 +1413393925955760384.0000000000 0.2733631977 2.6132229733 1.8369914150 0.5065838373 0.7277142355 0.3757357171 -0.269494857486 +1413393926005760512.0000000000 0.1941606447 2.6274247916 1.8374468594 0.5136834162 0.7225793714 0.3736812624 -0.272709944999 +1413393926055760384.0000000000 0.1157565650 2.6416596628 1.8359258743 0.5215648798 0.7168025375 0.3693964469 -0.278765965234 +1413393926105760512.0000000000 0.0391910625 2.6556474409 1.8340010065 0.5284341315 0.7116045295 0.3648569023 -0.285054035412 +1413393926155760384.0000000000 -0.0348648290 2.6692083502 1.8320056314 0.5324363150 0.7085269826 0.3613174082 -0.289742671845 +1413393926205760512.0000000000 -0.1062744428 2.6824940195 1.8303437805 0.5335830660 0.7077452887 0.3584285406 -0.29311209338 +1413393926255760384.0000000000 -0.1747940788 2.6954623019 1.8290621365 0.5328795343 0.7085525097 0.3566800196 -0.294571054995 +1413393926305760512.0000000000 -0.2404354452 2.7081439809 1.8284197473 0.5295755151 0.7114135673 0.3558927192 -0.294585950858 +1413393926355760384.0000000000 -0.3035790410 2.7207232869 1.8284061422 0.5246305521 0.7153688003 0.3564026600 -0.293236095036 +1413393926405760512.0000000000 -0.3641801016 2.7332895912 1.8291206699 0.5195706081 0.7185447568 0.3593901609 -0.290823877861 +1413393926455760384.0000000000 -0.4228728503 2.7461595653 1.8311534580 0.5179184739 0.7183483602 0.3623033339 -0.290641328732 +1413393926505760512.0000000000 -0.4794921572 2.7589496023 1.8327613242 0.5190322478 0.7153696015 0.3648064668 -0.292861914267 +1413393926555760384.0000000000 -0.5343035509 2.7718533457 1.8307726597 0.5220512771 0.7102096115 0.3687247117 -0.295138710916 +1413393926605760512.0000000000 -0.5875526317 2.7847744248 1.8245345382 0.5252797136 0.7040622025 0.3735159087 -0.298099821313 +1413393926655760384.0000000000 -0.6391912445 2.7973772018 1.8147652588 0.5265358559 0.6984493436 0.3796437203 -0.301328977225 +1413393926705760512.0000000000 -0.6885317553 2.8095572285 1.8046554717 0.5268526611 0.6927019911 0.3879018651 -0.303516668568 +1413393926755760384.0000000000 -0.7357874605 2.8209075663 1.7971445795 0.5243035597 0.6882377322 0.3960812852 -0.307496693953 +1413393926805760512.0000000000 -0.7804603370 2.8313041483 1.7926437735 0.5205202320 0.6842359119 0.4047586779 -0.311528999669 +1413393926855760384.0000000000 -0.8232447293 2.8411268055 1.7924944663 0.5150670596 0.6804584815 0.4145322114 -0.315982950307 +1413393926905760512.0000000000 -0.8634171259 2.8501541102 1.7959144048 0.5068991874 0.6783336315 0.4254295453 -0.319259142505 +1413393926955760384.0000000000 -0.9016800811 2.8585570949 1.8033891931 0.4973558159 0.6769316989 0.4357750567 -0.323265784401 +1413393927005760512.0000000000 -0.9377872819 2.8668028444 1.8145618595 0.4867296894 0.6767965597 0.4464308204 -0.325177103821 +1413393927055760384.0000000000 -0.9733261946 2.8755175293 1.8296497029 0.4745802779 0.6787285406 0.4546168955 -0.327756931656 +1413393927105760512.0000000000 -1.0088624109 2.8853279119 1.8482535790 0.4640438192 0.6801739737 0.4604640687 -0.331661786782 +1413393927155760384.0000000000 -1.0446480117 2.8962555392 1.8685578199 0.4538586779 0.6819988350 0.4635395844 -0.337669873199 +1413393927205760512.0000000000 -1.0805247116 2.9091353223 1.8894850692 0.4456300874 0.6833864420 0.4651174017 -0.343602384657 +1413393927255760384.0000000000 -1.1163559012 2.9238988271 1.9102299907 0.4359490678 0.6861972679 0.4666836171 -0.348264441589 +1413393927305760512.0000000000 -1.1523803797 2.9410054687 1.9304628011 0.4267651370 0.6885875744 0.4709249054 -0.349211116248 +1413393927355760384.0000000000 -1.1891133621 2.9609083528 1.9503325313 0.4205085617 0.6884587927 0.4785981739 -0.346613369882 +1413393927405760512.0000000000 -1.2269304955 2.9838674732 1.9703270602 0.4189342477 0.6849969184 0.4878331090 -0.342479452785 +1413393927455760384.0000000000 -1.2664427733 3.0094673309 1.9908814068 0.4242423644 0.6765906955 0.4985512831 -0.337179573911 +1413393927505760512.0000000000 -1.3078857818 3.0368442940 2.0122904620 0.4331752572 0.6659099887 0.5085574148 -0.332103055231 +1413393927555760384.0000000000 -1.3510620597 3.0648528582 2.0342314682 0.4418431115 0.6552602925 0.5181498271 -0.327000566642 +1413393927605760512.0000000000 -1.3958778476 3.0922978155 2.0567846948 0.4501888117 0.6434173757 0.5283707018 -0.322751476967 +1413393927655760384.0000000000 -1.4422866609 3.1185095810 2.0800644508 0.4586515790 0.6305348768 0.5380441381 -0.320270204071 +1413393927705760512.0000000000 -1.4902213063 3.1426212673 2.1042829662 0.4678950842 0.6163214068 0.5466385857 -0.320013078293 +1413393927755760384.0000000000 -1.5394200957 3.1641864147 2.1294142381 0.4783101968 0.6015847379 0.5544210955 -0.319268550993 +1413393927805760512.0000000000 -1.5896122799 3.1823180834 2.1558092601 0.4885347418 0.5878625975 0.5602006821 -0.319259405944 +1413393927855760384.0000000000 -1.6405202174 3.1959972371 2.1835701721 0.4960352859 0.5773315980 0.5636991507 -0.320749884761 +1413393927905760512.0000000000 -1.6914664091 3.2046364058 2.2124816782 0.4997465566 0.5708694881 0.5648373418 -0.324530713485 +1413393927955760384.0000000000 -1.7420511033 3.2085841048 2.2416690080 0.5025339266 0.5661562571 0.5657135625 -0.326947871017 +1413393928005760512.0000000000 -1.7920883057 3.2079528104 2.2697041071 0.5049561915 0.5626966633 0.5656735060 -0.329249441068 +1413393928055760384.0000000000 -1.8412596253 3.2030314309 2.2952782450 0.5072198147 0.5597808790 0.5662994871 -0.329663947146 +1413393928105760512.0000000000 -1.8894592289 3.1935718092 2.3189216955 0.5097306512 0.5573145950 0.5660167839 -0.330454392914 +1413393928155760384.0000000000 -1.9365242840 3.1793009364 2.3407315099 0.5113403943 0.5558061899 0.5654999506 -0.331391439743 +1413393928205760512.0000000000 -1.9825326302 3.1604418930 2.3606547461 0.5117674063 0.5558295554 0.5651456168 -0.33129753842 +1413393928255760384.0000000000 -2.0277448982 3.1366822845 2.3786783276 0.5080575347 0.5596036785 0.5637560159 -0.333017145008 +1413393928305760512.0000000000 -2.0719444380 3.1080899117 2.3951478532 0.4991373069 0.5678043184 0.5599240001 -0.339035866655 +1413393928355760384.0000000000 -2.1153881126 3.0753385684 2.4111755882 0.4891563892 0.5766864612 0.5525053081 -0.350566166219 +1413393928405760512.0000000000 -2.1581608772 3.0398509931 2.4253254891 0.4809610904 0.5840723385 0.5438698220 -0.362962187574 +1413393928455760384.0000000000 -2.1992541911 3.0024779689 2.4362634846 0.4733095114 0.5908705023 0.5357810719 -0.373883402857 +1413393928505760512.0000000000 -2.2390020125 2.9642008681 2.4445533985 0.4678930821 0.5957892754 0.5279305483 -0.383927778596 +1413393928555760384.0000000000 -2.2777933363 2.9259341763 2.4507831246 0.4659000486 0.5982186240 0.5204169767 -0.392731196694 +1413393928605760512.0000000000 -2.3150539012 2.8878204556 2.4557808832 0.4681052474 0.5972418493 0.5127596726 -0.401568386395 +1413393928655760384.0000000000 -2.3498368981 2.8499876064 2.4599903275 0.4700160233 0.5966322114 0.5064516863 -0.408193130394 +1413393928705760512.0000000000 -2.3817376015 2.8128227365 2.4639986426 0.4726082953 0.5958337001 0.5035745699 -0.409922253165 +1413393928755760384.0000000000 -2.4104341624 2.7760979670 2.4680097505 0.4741739332 0.5961259161 0.5023283421 -0.409217802618 +1413393928805760512.0000000000 -2.4361296480 2.7401081015 2.4721422556 0.4795286992 0.5942324043 0.5038571631 -0.403816834076 +1413393928855760384.0000000000 -2.4586605127 2.7041431125 2.4765183752 0.4839473030 0.5930003441 0.5058874069 -0.397773216004 +1413393928905760512.0000000000 -2.4787115043 2.6682956034 2.4813199232 0.4907249538 0.5907475350 0.5079153181 -0.390164579752 +1413393928955760384.0000000000 -2.4959205156 2.6323362412 2.4864138695 0.4977379547 0.5899105670 0.5089717040 -0.38106463477 +1413393929005760512.0000000000 -2.5104490583 2.5953829555 2.4921469058 0.5042032466 0.5910817793 0.5083770629 -0.371421833199 +1413393929055760384.0000000000 -2.5225975417 2.5569615391 2.4986844531 0.5086062644 0.5954038342 0.5051537483 -0.362813495689 +1413393929105760512.0000000000 -2.5324707136 2.5169651319 2.5061639033 0.5139644340 0.6000796221 0.5006583557 -0.353675301021 +1413393929155760384.0000000000 -2.5401279966 2.4749386741 2.5147149078 0.5190937041 0.6055296682 0.4945792807 -0.345350376277 +1413393929205760512.0000000000 -2.5457867615 2.4310951102 2.5235219788 0.5223444097 0.6134629701 0.4880505708 -0.335598185819 +1413393929255760384.0000000000 -2.5494234729 2.3853976854 2.5331739390 0.5243174007 0.6235682997 0.4791595765 -0.326588332875 +1413393929305760512.0000000000 -2.5514433200 2.3374789090 2.5432662500 0.5243787995 0.6354047530 0.4687905878 -0.318626833954 +1413393929355760384.0000000000 -2.5523531732 2.2877655918 2.5543148731 0.5238170129 0.6485133759 0.4563432330 -0.311122149567 +1413393929405760512.0000000000 -2.5525538429 2.2366640365 2.5660821013 0.5233778536 0.6616364065 0.4423805107 -0.304322808351 +1413393929455760384.0000000000 -2.5519933162 2.1846524767 2.5782028765 0.5242661062 0.6735974889 0.4283544225 -0.29651974903 +1413393929505760512.0000000000 -2.5503815877 2.1321377764 2.5906135134 0.5256916553 0.6853354357 0.4148577045 -0.286106115158 +1413393929555760384.0000000000 -2.5480560077 2.0789454143 2.6034552676 0.5272272699 0.6966076884 0.4010998066 -0.275477911082 +1413393929605760512.0000000000 -2.5451965927 2.0254564118 2.6168640260 0.5302970059 0.7065335537 0.3873061779 -0.263797929603 +1413393929655760384.0000000000 -2.5419952849 1.9716437674 2.6304601102 0.5335626142 0.7159935792 0.3735076590 -0.251308893714 +1413393929705760512.0000000000 -2.5387971661 1.9175857916 2.6447193888 0.5375082340 0.7241908621 0.3592228398 -0.239982176655 +1413393929755760384.0000000000 -2.5356538968 1.8631409037 2.6593829417 0.5404109951 0.7327789537 0.3440232936 -0.229431765362 +1413393929805760512.0000000000 -2.5326404558 1.8085178435 2.6746034233 0.5421460058 0.7416508032 0.3268452203 -0.221819738848 +1413393929855760384.0000000000 -2.5296137275 1.7538552205 2.6901744875 0.5422534925 0.7511270393 0.3074509233 -0.217355125304 +1413393929905760512.0000000000 -2.5265032831 1.6995000050 2.7066563238 0.5419441453 0.7600804560 0.2860646418 -0.216197281327 +1413393929955760384.0000000000 -2.5227046217 1.6459842306 2.7232418199 0.5411664372 0.7684218497 0.2653060859 -0.215126541938 +1413393930005760512.0000000000 -2.5178025709 1.5937924288 2.7392024716 0.5408620611 0.7757188675 0.2457168976 -0.212959328763 +1413393930055760384.0000000000 -2.5116129724 1.5433142411 2.7531247533 0.5406093934 0.7822998178 0.2275296156 -0.209711117683 +1413393930105760512.0000000000 -2.5038008792 1.4943594106 2.7648315571 0.5406248892 0.7878240442 0.2114721645 -0.205760851979 +1413393930155760384.0000000000 -2.4943561005 1.4472660800 2.7743010560 0.5419340916 0.7914234611 0.1988232055 -0.201061380241 +1413393930205760512.0000000000 -2.4832822669 1.4018193427 2.7811110664 0.5433700833 0.7940196927 0.1887245255 -0.196633500824 +1413393930255760384.0000000000 -2.4704248814 1.3579184318 2.7852062183 0.5452017743 0.7955487348 0.1828517643 -0.190846713732 +1413393930305760512.0000000000 -2.4557492851 1.3157279134 2.7862173312 0.5477429825 0.7961224493 0.1802211112 -0.183540245976 +1413393930355760384.0000000000 -2.4390901168 1.2752253898 2.7837272308 0.5520588768 0.7952072087 0.1841400279 -0.170202649481 +1413393930405760512.0000000000 -2.4212900643 1.2355389336 2.7786898102 0.5555343324 0.7940362774 0.1895796407 -0.157947952173 +1413393930455760384.0000000000 -2.4029731354 1.1967972861 2.7700405609 0.5585377727 0.7926956456 0.1957804588 -0.146079368541 +1413393930505760512.0000000000 -2.3848005383 1.1585793090 2.7565143450 0.5606879652 0.7915025344 0.2009715455 -0.136978763108 +1413393930555760384.0000000000 -2.3672325979 1.1203416550 2.7380331329 0.5622407790 0.7903845845 0.2032139681 -0.133722093342 +1413393930605760512.0000000000 -2.3504925906 1.0822972106 2.7147137233 0.5635902244 0.7893119141 0.2021494928 -0.135971849015 +1413393930655760384.0000000000 -2.3340207309 1.0445100031 2.6859936456 0.5649765876 0.7880196253 0.1999269002 -0.140910468516 +1413393930705760512.0000000000 -2.3174629572 1.0068826682 2.6526897895 0.5666523724 0.7863709310 0.1973955122 -0.146836165763 +1413393930755760384.0000000000 -2.3008192539 0.9698526365 2.6174024199 0.5688999783 0.7841628479 0.1948084226 -0.153268134967 +1413393930805760512.0000000000 -2.2836663989 0.9335035313 2.5815695328 0.5709813231 0.7818912376 0.1940873187 -0.157976371202 +1413393930855760384.0000000000 -2.2655828819 0.8974365211 2.5469633188 0.5721005842 0.7802939817 0.1935543867 -0.162415895261 +1413393930905760512.0000000000 -2.2459908112 0.8617917676 2.5148111403 0.5721234177 0.7796507951 0.1949703875 -0.16372532069 +1413393930955760384.0000000000 -2.2248879602 0.8262128970 2.4857813147 0.5709048812 0.7797347826 0.1985169342 -0.163316601358 +1413393931005760512.0000000000 -2.2028724638 0.7910590408 2.4614278389 0.5694025495 0.7800707776 0.2001650869 -0.164937128971 +1413393931055760384.0000000000 -2.1794909314 0.7566199677 2.4412015977 0.5677155511 0.7808484964 0.2029026399 -0.163722928756 +1413393931105760512.0000000000 -2.1555101043 0.7225041285 2.4259846052 0.5666872937 0.7808484010 0.2040384028 -0.165860230583 +1413393931155760384.0000000000 -2.1302317356 0.6886847246 2.4140908110 0.5635857894 0.7826325515 0.2055428368 -0.166161035078 +1413393931205760512.0000000000 -2.1042245401 0.6556841661 2.4055602678 0.5605956653 0.7844186150 0.2066832134 -0.166439135109 +1413393931255760384.0000000000 -2.0779955692 0.6235305721 2.3986764806 0.5568768497 0.7864000810 0.2075464915 -0.16848602521 +1413393931305760512.0000000000 -2.0510900901 0.5924077856 2.3906682922 0.5534028515 0.7884617501 0.2073366185 -0.170542895294 +1413393931355760384.0000000000 -2.0237134271 0.5623455564 2.3803748706 0.5503027017 0.7902293927 0.2064235612 -0.173475522289 +1413393931405760512.0000000000 -1.9959683105 0.5336505426 2.3673915437 0.5462926480 0.7923990351 0.2050598304 -0.177816135194 +1413393931455760384.0000000000 -1.9674622501 0.5067842992 2.3522130033 0.5437047972 0.7937759686 0.2030518340 -0.181864669056 +1413393931505760512.0000000000 -1.9379602355 0.4814581689 2.3354642980 0.5412698320 0.7949541637 0.2012005069 -0.185992480155 +1413393931555760384.0000000000 -1.9066137324 0.4568324678 2.3154648476 0.5398184477 0.7954757991 0.2003080140 -0.188920607845 +1413393931605760512.0000000000 -1.8740464849 0.4339302227 2.2922917231 0.5376079123 0.7965502217 0.2001064950 -0.190900150833 +1413393931655760384.0000000000 -1.8401534415 0.4131124427 2.2673863979 0.5375643487 0.7961719483 0.2003106663 -0.192380967807 +1413393931705760512.0000000000 -1.8053237924 0.3949075955 2.2406553391 0.5372743376 0.7960921032 0.2007600965 -0.193051891995 +1413393931755760384.0000000000 -1.7694782996 0.3787585109 2.2119348373 0.5372481529 0.7956732023 0.2019727301 -0.193586140277 +1413393931805760512.0000000000 -1.7325518530 0.3651303223 2.1816498077 0.5374353787 0.7953136774 0.2031938028 -0.19326574152 +1413393931855760384.0000000000 -1.6942541869 0.3535166267 2.1506330290 0.5375440717 0.7950112305 0.2046040697 -0.192719197175 +1413393931905760512.0000000000 -1.6545864504 0.3440862595 2.1201626087 0.5373883845 0.7948899498 0.2058896829 -0.192283983904 +1413393931955760384.0000000000 -1.6136796780 0.3369821748 2.0912098390 0.5379836932 0.7942732962 0.2073667484 -0.191578987404 +1413393932005760512.0000000000 -1.5715963049 0.3321419602 2.0636643982 0.5385228877 0.7938006085 0.2091986859 -0.190025269789 +1413393932055760384.0000000000 -1.5283401794 0.3293124837 2.0373978608 0.5386990380 0.7935551681 0.2122587430 -0.187135692987 +1413393932105760512.0000000000 -1.4842279213 0.3287043636 2.0124883526 0.5388723370 0.7933877623 0.2156945311 -0.183380294394 +1413393932155760384.0000000000 -1.4393507639 0.3299059483 1.9884927124 0.5394386001 0.7930153398 0.2203602229 -0.177690854526 +1413393932205760512.0000000000 -1.3940586807 0.3328885292 1.9654029106 0.5406605509 0.7922177281 0.2253425322 -0.171166536475 +1413393932255760384.0000000000 -1.3489443237 0.3375636818 1.9433414698 0.5426862027 0.7907895704 0.2311416053 -0.163453660351 +1413393932305760512.0000000000 -1.3044137173 0.3433046804 1.9223720984 0.5439439179 0.7898018064 0.2361617483 -0.156734646735 +1413393932355760384.0000000000 -1.2606834095 0.3500192938 1.9024915063 0.5453014228 0.7888859471 0.2400549319 -0.150595320004 +1413393932405760512.0000000000 -1.2183586597 0.3573215401 1.8835969552 0.5458292492 0.7885031318 0.2427788309 -0.14625895213 +1413393932455760384.0000000000 -1.1774682803 0.3653199326 1.8652396148 0.5462144415 0.7883346643 0.2448938228 -0.14214519524 +1413393932505760512.0000000000 -1.1382956451 0.3740709878 1.8474358314 0.5468265347 0.7881606575 0.2460483964 -0.138721683776 +1413393932555760384.0000000000 -1.1011133160 0.3833832723 1.8305313191 0.5484341753 0.7872479516 0.2468931621 -0.136030822425 +1413393932605760512.0000000000 -1.0659906271 0.3931305308 1.8149228264 0.5513853043 0.7855129236 0.2465497604 -0.134747573742 +1413393932655760384.0000000000 -1.0328222184 0.4031606992 1.8003714942 0.5549535341 0.7834492058 0.2454877693 -0.134051005656 +1413393932705760512.0000000000 -1.0015059065 0.4128941626 1.7866583450 0.5574812833 0.7820432567 0.2442439386 -0.134044253268 +1413393932755760384.0000000000 -0.9718124976 0.4224735852 1.7738976625 0.5599282607 0.7808149164 0.2425668437 -0.134051242036 +1413393932805760512.0000000000 -0.9436403844 0.4318748925 1.7620371506 0.5626289647 0.7793692015 0.2411032677 -0.13379652493 +1413393932855760384.0000000000 -0.9167825556 0.4409811726 1.7504533179 0.5643978930 0.7784589464 0.2411381730 -0.131563933736 +1413393932905760512.0000000000 -0.8916137293 0.4495919364 1.7400120675 0.5668592983 0.7770837710 0.2409335252 -0.129469630527 +1413393932955760384.0000000000 -0.8682872663 0.4578950087 1.7315495113 0.5729643876 0.7730834337 0.2394812731 -0.129238287068 +1413393933005760512.0000000000 -0.8466803812 0.4650445910 1.7243637112 0.5817890396 0.7666451916 0.2378324734 -0.131195952879 +1413393933055760384.0000000000 -0.8261662815 0.4703598750 1.7176974774 0.5897111391 0.7604498089 0.2369998921 -0.133371330157 +1413393933105760512.0000000000 -0.8066163370 0.4733540663 1.7120605166 0.5977835728 0.7539550077 0.2356855743 -0.136597791215 +1413393933155760384.0000000000 -0.7873991817 0.4737415132 1.7068086469 0.6023759430 0.7502538232 0.2338438696 -0.139926654756 +1413393933205760512.0000000000 -0.7683482728 0.4712915868 1.7028500518 0.6046837062 0.7484339091 0.2310786090 -0.144246232473 +1413393933255760384.0000000000 -0.7493887254 0.4656991338 1.7001351669 0.6037704113 0.7490684241 0.2270610560 -0.15100020962 +1413393933305760512.0000000000 -0.7301755403 0.4575509992 1.6990658938 0.6018905813 0.7505274638 0.2207826291 -0.160285011666 +1413393933355760384.0000000000 -0.7100441729 0.4469374857 1.6987103849 0.5991630658 0.7524363095 0.2151703300 -0.168952507584 +1413393933405760512.0000000000 -0.6884787635 0.4342786292 1.6995328891 0.5942249389 0.7559384721 0.2088211109 -0.178458656332 +1413393933455760384.0000000000 -0.6650019590 0.4200841418 1.7004266691 0.5862755610 0.7617162383 0.2028198086 -0.186904960122 +1413393933505760512.0000000000 -0.6394694369 0.4047815771 1.7012069111 0.5759245052 0.7688984130 0.1976007136 -0.19509011451 +1413393933555760384.0000000000 -0.6117246865 0.3896894599 1.7009472723 0.5657035278 0.7759249587 0.1933373977 -0.201347033072 +1413393933605760512.0000000000 -0.5817456446 0.3756346337 1.6985394856 0.5570095242 0.7820153138 0.1903399129 -0.204849106713 +1413393933655760384.0000000000 -0.5491752939 0.3630337615 1.6941261361 0.5519079198 0.7858778224 0.1900098615 -0.204181166834 +1413393933705760512.0000000000 -0.5143162895 0.3521703452 1.6877749843 0.5499009007 0.7878335223 0.1937697388 -0.198445531481 +1413393933755760384.0000000000 -0.4772716651 0.3427747850 1.6794281087 0.5506117480 0.7881794311 0.2002015641 -0.188465437411 +1413393933805760512.0000000000 -0.4385458594 0.3343310393 1.6689132559 0.5521283947 0.7877940435 0.2073075990 -0.177646672357 +1413393933855760384.0000000000 -0.3992608860 0.3265110404 1.6566379538 0.5526650259 0.7876978160 0.2131136463 -0.169340171071 +1413393933905760512.0000000000 -0.3599401766 0.3194374138 1.6430707701 0.5536364676 0.7871952533 0.2170208411 -0.163438824985 +1413393933955760384.0000000000 -0.3210572513 0.3136020743 1.6298551714 0.5569033500 0.7850414264 0.2199918096 -0.158657559912 +1413393934005760512.0000000000 -0.2826590703 0.3085452930 1.6195153395 0.5666450876 0.7779133238 0.2230265767 -0.154994682151 +1413393934055760384.0000000000 -0.2444736348 0.3029395000 1.6126828811 0.5764766705 0.7706982496 0.2251319079 -0.15170524229 +1413393934105760512.0000000000 -0.2068016417 0.2962192861 1.6100398474 0.5854392552 0.7637088665 0.2267701638 -0.150282861745 +1413393934155760384.0000000000 -0.1691469891 0.2876142404 1.6101762665 0.5899984183 0.7599751142 0.2287644122 -0.148346000538 +1413393934205760512.0000000000 -0.1317729844 0.2765781257 1.6126979445 0.5927014701 0.7576608179 0.2301694855 -0.147231315609 +1413393934255760384.0000000000 -0.0950418110 0.2630007212 1.6159239327 0.5908090108 0.7586977153 0.2300757971 -0.149624921583 +1413393934305760512.0000000000 -0.0588265113 0.2478347436 1.6189272697 0.5874818956 0.7608850532 0.2292503080 -0.152850431787 +1413393934355760384.0000000000 -0.0228900981 0.2314742984 1.6191953953 0.5805363054 0.7658204318 0.2273369226 -0.157526467394 +1413393934405760512.0000000000 0.0128407146 0.2144558062 1.6164041433 0.5725887351 0.7713990801 0.2245778821 -0.163249424412 +1413393934455760384.0000000000 0.0488349753 0.1971368023 1.6100770433 0.5656870384 0.7761757948 0.2219681511 -0.168164949095 +1413393934505760512.0000000000 0.0850237409 0.1800341100 1.6001962528 0.5595343847 0.7803509974 0.2193516380 -0.172795984132 +1413393934555760384.0000000000 0.1216408673 0.1630964795 1.5874431991 0.5541507654 0.7838586840 0.2164247686 -0.177884266494 +1413393934605760512.0000000000 0.1586095689 0.1473376010 1.5723989166 0.5500155372 0.7865583685 0.2134697321 -0.182317073341 +1413393934655760384.0000000000 0.1963712976 0.1323605124 1.5559017421 0.5467637158 0.7885572115 0.2093054579 -0.18819720662 +1413393934705760512.0000000000 0.2352040385 0.1184493098 1.5373442999 0.5438115086 0.7902518298 0.2054210335 -0.193838302675 +1413393934755760384.0000000000 0.2747576885 0.1055157230 1.5162598698 0.5383398945 0.7927743866 0.2015141509 -0.20270909444 +1413393934805760512.0000000000 0.3154834961 0.0937416776 1.4932068022 0.5307346963 0.7958067044 0.1985842772 -0.213486899327 +1413393934855760384.0000000000 0.3580062439 0.0837306405 1.4680131067 0.5222388295 0.7984918494 0.1998511251 -0.223017710658 +1413393934905760512.0000000000 0.4026333744 0.0758518285 1.4400303533 0.5126170819 0.8011519779 0.2062187408 -0.229897948233 +1413393934955760384.0000000000 0.4492835527 0.0710919371 1.4098016219 0.5040653268 0.8025527264 0.2192555669 -0.231849658123 +1413393935005760512.0000000000 0.4978891634 0.0695687289 1.3769018301 0.5000987854 0.8003825998 0.2402996173 -0.227035223543 +1413393935055760384.0000000000 0.5472741315 0.0712282861 1.3418418168 0.4980483641 0.7956216689 0.2667285674 -0.21860891653 +1413393935105760512.0000000000 0.5961720486 0.0758579501 1.3070030760 0.4961595434 0.7890985926 0.2934379408 -0.212234053888 +1413393935155760384.0000000000 0.6435652581 0.0829007547 1.2746965934 0.4934935742 0.7816115118 0.3185967766 -0.209865744736 +1413393935205760512.0000000000 0.6883546391 0.0919105415 1.2466639828 0.4898297995 0.7734848579 0.3421607269 -0.211456801694 +1413393935255760384.0000000000 0.7298276982 0.1029754790 1.2238263447 0.4853584091 0.7651236697 0.3632465679 -0.216944499223 +1413393935305760512.0000000000 0.7675396298 0.1158520741 1.2051096178 0.4802870076 0.7566420048 0.3825629514 -0.224639388881 +1413393935355760384.0000000000 0.8014898174 0.1300620490 1.1908157869 0.4747183318 0.7483290284 0.3991041936 -0.235291337125 +1413393935405760512.0000000000 0.8319742203 0.1458172445 1.1805955396 0.4714883144 0.7376598877 0.4168738500 -0.244484872025 +1413393935455760384.0000000000 0.8594535468 0.1623297846 1.1742709523 0.4693133867 0.7258552845 0.4343269663 -0.253454408978 +1413393935505760512.0000000000 0.8832773032 0.1794792906 1.1719987479 0.4687308685 0.7123880871 0.4517058785 -0.262214388548 +1413393935555760384.0000000000 0.9037671427 0.1964288401 1.1729295088 0.4660408746 0.6997895500 0.4692671645 -0.26997929053 +1413393935605760512.0000000000 0.9209705872 0.2135555379 1.1760033938 0.4653324074 0.6863214434 0.4869205358 -0.274475898443 +1413393935655760384.0000000000 0.9344631476 0.2305361685 1.1801386325 0.4640931985 0.6746078474 0.5030089254 -0.276593160098 +1413393935705760512.0000000000 0.9445071264 0.2469239072 1.1846577483 0.4656506714 0.6618410027 0.5184983848 -0.276216155084 +1413393935755760384.0000000000 0.9511160532 0.2616792614 1.1892920646 0.4680594462 0.6496078039 0.5323888467 -0.274758388136 +1413393935805760512.0000000000 0.9540116894 0.2739730518 1.1941907137 0.4723007428 0.6360813529 0.5460237653 -0.272379456943 +1413393935855760384.0000000000 0.9532022074 0.2826448419 1.1997479020 0.4765672967 0.6221246049 0.5588604587 -0.27114493419 +1413393935905760512.0000000000 0.9488135816 0.2864528244 1.2060161291 0.4774025819 0.6108154019 0.5690388004 -0.274200954095 +1413393935955760384.0000000000 0.9411027172 0.2840100213 1.2137257787 0.4704372476 0.6058354294 0.5736123256 -0.287438912472 +1413393936005760512.0000000000 0.9305408345 0.2761612339 1.2227004150 0.4593458748 0.6030213473 0.5756750833 -0.306536817414 +1413393936055760384.0000000000 0.9177076716 0.2643965431 1.2322783578 0.4468938709 0.5995825891 0.5783026501 -0.326117512533 +1413393936105760512.0000000000 0.9030769977 0.2493772558 1.2426329637 0.4332660615 0.5949809395 0.5810167178 -0.347415853478 +1413393936155760384.0000000000 0.8868054896 0.2321790174 1.2534546593 0.4187211402 0.5893238808 0.5842672073 -0.368784219632 +1413393936205760512.0000000000 0.8691203576 0.2138739203 1.2649169251 0.4016354804 0.5836245951 0.5884339086 -0.389636764273 +1413393936255760384.0000000000 0.8504090124 0.1955627798 1.2763577077 0.3850695831 0.5759952623 0.5944659795 -0.408118944907 +1413393936305760512.0000000000 0.8300499648 0.1778007798 1.2881912962 0.3681363564 0.5674070374 0.6019969105 -0.424410882035 +1413393936355760384.0000000000 0.8087956889 0.1611501602 1.2994372993 0.3519572351 0.5568555934 0.6111549122 -0.438779700969 +1413393936405760512.0000000000 0.7864513647 0.1463124734 1.3105488041 0.3378158944 0.5445877205 0.6210554886 -0.451214711854 +1413393936455760384.0000000000 0.7627872558 0.1334662053 1.3218465948 0.3260277306 0.5303057666 0.6320107139 -0.461567081102 +1413393936505760512.0000000000 0.7374835590 0.1227349327 1.3336747989 0.3198383447 0.5116010298 0.6433468190 -0.471245891169 +1413393936555760384.0000000000 0.7107210090 0.1140438435 1.3457471454 0.3161233884 0.4914316882 0.6537858528 -0.480754571253 +1413393936605760512.0000000000 0.6829895665 0.1069065604 1.3583212431 0.3136435678 0.4710058780 0.6621057771 -0.491321804083 +1413393936655760384.0000000000 0.6547298894 0.1010255754 1.3716537132 0.3117578542 0.4507325760 0.6682010281 -0.503144682269 +1413393936705760512.0000000000 0.6264550750 0.0964493780 1.3854382410 0.3098464202 0.4317394340 0.6729019227 -0.514586493695 +1413393936755760384.0000000000 0.5989051545 0.0931189693 1.3992715369 0.3064058899 0.4145009152 0.6775495526 -0.524624652236 +1413393936805760512.0000000000 0.5725199060 0.0911541170 1.4131287730 0.3022893327 0.3981988237 0.6826400454 -0.532974131239 +1413393936855760384.0000000000 0.5477129599 0.0905253264 1.4272838765 0.2974122389 0.3820632573 0.6881359256 -0.540409636811 +1413393936905760512.0000000000 0.5244068201 0.0912931300 1.4420208405 0.2932848230 0.3651769023 0.6935295643 -0.547399841109 +1413393936955760384.0000000000 0.5033079546 0.0933233101 1.4569625049 0.2874833899 0.3483217412 0.6998795701 -0.553347858475 +1413393937005760512.0000000000 0.4845502974 0.0965613960 1.4727044745 0.2834651831 0.3294474621 0.7059197918 -0.55927552 +1413393937055760384.0000000000 0.4687215839 0.1011395667 1.4889169528 0.2781095465 0.3107522035 0.7123848492 -0.564443066034 +1413393937105760512.0000000000 0.4559534482 0.1067409090 1.5058580880 0.2712679109 0.2926417227 0.7186562859 -0.5694801888 +1413393937155760384.0000000000 0.4463338626 0.1136053989 1.5235733934 0.2630700719 0.2757631810 0.7243511655 -0.574512135866 +1413393937205760512.0000000000 0.4401029612 0.1217114682 1.5421433265 0.2541847728 0.2590808472 0.7293149903 -0.579971431029 +1413393937255760384.0000000000 0.4370004660 0.1310225001 1.5613545045 0.2448142311 0.2436499966 0.7344156917 -0.584238190413 +1413393937305760512.0000000000 0.4371332039 0.1415274876 1.5816273337 0.2344898399 0.2296029283 0.7389210523 -0.588466387153 +1413393937355760384.0000000000 0.4400422888 0.1535126095 1.6022964369 0.2247390313 0.2168770468 0.7439161724 -0.590800679467 +1413393937405760512.0000000000 0.4453081086 0.1667658881 1.6235236464 0.2161000837 0.2066104485 0.7480600656 -0.592468576883 +1413393937455760384.0000000000 0.4527566064 0.1816658522 1.6433126782 0.2078934538 0.1988828938 0.7540078091 -0.590506672436 +1413393937505760512.0000000000 0.4621104317 0.1978747272 1.6590994257 0.1983805083 0.1952268730 0.7627611072 -0.583718369888 +1413393937555760384.0000000000 0.4729736764 0.2145305416 1.6706129314 0.1873179966 0.1949474348 0.7701864043 -0.577685354139 +1413393937605760512.0000000000 0.4845425662 0.2312738526 1.6765113453 0.1780360033 0.1954462598 0.7762602549 -0.572297088706 +1413393937655760384.0000000000 0.4966359971 0.2477627355 1.6776573841 0.1680179052 0.1976517600 0.7814420114 -0.567496385936 +1413393937705760512.0000000000 0.5088277645 0.2645308665 1.6752994167 0.1601417805 0.2001292050 0.7863567146 -0.562090765653 +1413393937755760384.0000000000 0.5207496601 0.2811243689 1.6713401914 0.1540978433 0.2024348406 0.7918453255 -0.555207141919 +1413393937805760512.0000000000 0.5320952556 0.2968853724 1.6680819762 0.1485978422 0.2049536137 0.7969206695 -0.548479848436 +1413393937855760384.0000000000 0.5422291897 0.3113185212 1.6662213803 0.1442352825 0.2078084371 0.8004779678 -0.543366229993 +1413393937905760512.0000000000 0.5505994042 0.3239749449 1.6666522213 0.1444262518 0.2075952494 0.8015786438 -0.54177204432 +1413393937955760384.0000000000 0.5576597119 0.3356294199 1.6681629082 0.1487116026 0.2045897110 0.7999024384 -0.544227892054 +1413393938005760512.0000000000 0.5636665683 0.3456968267 1.6705143213 0.1548389407 0.2010977471 0.7979433927 -0.546690900421 +1413393938055760384.0000000000 0.5691944751 0.3545961556 1.6734790627 0.1633785181 0.1956065938 0.7956579155 -0.549521611711 +1413393938105760512.0000000000 0.5749473415 0.3622387919 1.6772114092 0.1739882566 0.1875038949 0.7928212418 -0.553177055376 +1413393938155760384.0000000000 0.5816427220 0.3687387368 1.6820751322 0.1862596672 0.1765065936 0.7891941609 -0.55796535306 +1413393938205760512.0000000000 0.5904785461 0.3741740510 1.6878484966 0.1981318409 0.1629512320 0.7855526814 -0.563114246246 +1413393938255760384.0000000000 0.6026031009 0.3786275319 1.6944647024 0.2061436701 0.1503583937 0.7823973823 -0.568112204531 +1413393938305760512.0000000000 0.6189662206 0.3822418409 1.7022265397 0.2076462190 0.1409614219 0.7800919051 -0.573122626317 +1413393938355760384.0000000000 0.6400663363 0.3851794783 1.7114136751 0.2015701340 0.1349023370 0.7782896727 -0.579168391651 +1413393938405760512.0000000000 0.6655746448 0.3877735311 1.7216514299 0.1890594389 0.1318474625 0.7776018010 -0.584985652994 +1413393938455760384.0000000000 0.6950861988 0.3906188448 1.7330265343 0.1702191528 0.1313350832 0.7771979346 -0.591388118202 +1413393938505760512.0000000000 0.7272271320 0.3942948314 1.7444061107 0.1514202817 0.1292101368 0.7781215911 -0.595737717718 +1413393938555760384.0000000000 0.7610778132 0.3989720735 1.7555712514 0.1340822226 0.1254846819 0.7796558875 -0.598675412324 +1413393938605760512.0000000000 0.7958942223 0.4044478383 1.7651396369 0.1185052444 0.1195015673 0.7814460441 -0.600847703303 +1413393938655760384.0000000000 0.8312635764 0.4114106879 1.7717027806 0.1033404157 0.1131192873 0.7839215623 -0.601657518391 +1413393938705760512.0000000000 0.8666558207 0.4196626783 1.7746141900 0.0894308845 0.1065713056 0.7871141041 -0.600912689908 +1413393938755760384.0000000000 0.9017874075 0.4292314504 1.7748451199 0.0771146316 0.0987782770 0.7886182081 -0.601977995771 +1413393938805760512.0000000000 0.9363079037 0.4406084215 1.7725295551 0.0676684635 0.0891254123 0.7883279879 -0.604993077195 +1413393938855760384.0000000000 0.9701353419 0.4534469554 1.7691255382 0.0619839275 0.0772253638 0.7870476075 -0.608892682966 +1413393938905760512.0000000000 1.0035758762 0.4678485884 1.7655682816 0.0566033093 0.0650465163 0.7866079650 -0.611402425175 +1413393938955760384.0000000000 1.0365921630 0.4840943933 1.7624162290 0.0514927556 0.0528418044 0.7871096256 -0.612384419393 +1413393939005760512.0000000000 1.0694239832 0.5020694301 1.7599461517 0.0455076163 0.0412502522 0.7883104900 -0.612204250975 +1413393939055760384.0000000000 1.1018598978 0.5214651096 1.7590765546 0.0405925499 0.0299695412 0.7880334281 -0.613561233799 +1413393939105760512.0000000000 1.1344091829 0.5417901475 1.7618303010 0.0346669815 0.0191655308 0.7803683471 -0.624064200009 +1413393939155760384.0000000000 1.1669012399 0.5642427998 1.7657120902 0.0288399398 0.0083499312 0.7716686833 -0.635315653677 +1413393939205760512.0000000000 1.1994589019 0.5898166773 1.7679561604 0.0224717169 -0.0011490489 0.7700292433 -0.637611689131 +1413393939255760384.0000000000 1.2316036554 0.6188225078 1.7680430850 0.0177026416 -0.0092663745 0.7754454269 -0.631098360585 +1413393939305760512.0000000000 1.2632561181 0.6505912433 1.7667716297 0.0133141202 -0.0152014671 0.7858007631 -0.618149504846 +1413393939355760384.0000000000 1.2943317977 0.6849782179 1.7634132615 0.0103431253 -0.0200045510 0.8013381581 -0.597787582745 +1413393939405760512.0000000000 1.3254305649 0.7202320325 1.7584597466 0.0046181801 -0.0208761842 0.8197790533 -0.572280666361 +1413393939455760384.0000000000 1.3563147719 0.7547411624 1.7515926525 0.0026671064 0.0189743571 -0.8384969275 0.544569337149 +1413393939505760512.0000000000 1.3868252759 0.7866274003 1.7431559716 0.0108557008 0.0144153177 -0.8554106276 0.517635982684 +1413393939555760384.0000000000 1.4165173890 0.8142152331 1.7332355997 0.0187451920 0.0090599050 -0.8691618946 0.494089199231 +1413393939605760512.0000000000 1.4446696698 0.8364453186 1.7216548321 0.0246895227 0.0035891682 -0.8803640984 0.473641847454 +1413393939655760384.0000000000 1.4711291491 0.8521253754 1.7087286636 0.0286353208 -0.0010625043 -0.8894835623 0.456067847922 +1413393939705760512.0000000000 1.4950480234 0.8596924725 1.6948241893 0.0255890196 -0.0005705217 -0.8952027562 0.444923478591 +1413393939755760384.0000000000 1.5167860624 0.8580318805 1.6809341989 0.0193113593 0.0023616498 -0.8961633649 0.443297549534 +1413393939805760512.0000000000 1.5369179504 0.8465509027 1.6681860401 0.0114303505 0.0065414100 -0.8899908608 0.455788135757 +1413393939855760384.0000000000 1.5561214946 0.8253996228 1.6578744305 0.0052369324 0.0088341696 -0.8751201369 0.48379673202 +1413393939905760512.0000000000 1.5746156009 0.7973873141 1.6508133228 0.0020003953 0.0078286964 -0.8526422659 0.522432652477 +1413393939955760384.0000000000 1.5925972980 0.7659867897 1.6464610684 0.0004543585 -0.0067105171 0.8246619055 -0.565585982969 +1413393940005760512.0000000000 1.6102199537 0.7348825266 1.6432871347 0.0008873135 -0.0045042225 0.7961079076 -0.605137277031 +1413393940055760384.0000000000 1.6276458665 0.7060350382 1.6417457609 0.0030864907 -0.0000531566 -0.7678924454 0.64057135672 +1413393940105760512.0000000000 1.6442216498 0.6818338447 1.6403638803 0.0074372083 -0.0042084086 -0.7432142374 0.66899893462 +1413393940155760384.0000000000 1.6595697335 0.6644187134 1.6386679558 0.0143907484 -0.0092303504 -0.7240166371 0.689570602744 +1413393940205760512.0000000000 1.6729638345 0.6558216982 1.6371012287 0.0189716723 -0.0122144992 -0.7086747723 0.705174410153 +1413393940255760384.0000000000 1.6845134962 0.6551270992 1.6341691626 0.0226638669 -0.0145249751 -0.7024196769 0.711253802605 +1413393940305760512.0000000000 1.6938276270 0.6625998052 1.6298293586 0.0242438017 -0.0153712304 -0.7089149930 0.704709511794 +1413393940355760384.0000000000 1.7006570854 0.6790923213 1.6236258456 0.0212516732 -0.0133658966 -0.7268638045 0.686322612798 +1413393940405760512.0000000000 1.7049474857 0.7029462506 1.6178630019 0.0161081802 -0.0106572114 -0.7505270788 0.660557381609 +1413393940455760384.0000000000 1.7072533644 0.7324661362 1.6120983280 0.0128519918 -0.0096803108 -0.7774751801 0.628707771698 +1413393940505760512.0000000000 1.7078793165 0.7653032491 1.6058815754 0.0113074980 -0.0100737970 -0.8070633738 0.590270590252 +1413393940555760384.0000000000 1.7074515847 0.7987950234 1.6014791755 0.0139331987 -0.0135563667 -0.8332162994 0.552605364963 +1413393940605760512.0000000000 1.7056820547 0.8297390053 1.5996429028 0.0188876112 -0.0198586875 -0.8533797720 0.520568780757 +1413393940655760384.0000000000 1.7019023650 0.8556404445 1.6004870643 0.0239880394 -0.0266834079 -0.8673421503 0.496417328457 +1413393940705760512.0000000000 1.6957689229 0.8746511868 1.6038093830 0.0309210250 -0.0350547561 -0.8765579959 0.479021016438 +1413393940755760384.0000000000 1.6866952287 0.8860840547 1.6095359605 0.0400359658 -0.0460594941 -0.8818687301 0.467528809042 +1413393940805760512.0000000000 1.6734055211 0.8886679435 1.6177857250 0.0455470358 -0.0540129784 -0.8814353861 0.46699007029 +1413393940855760384.0000000000 1.6548318745 0.8826627074 1.6284743504 0.0423237748 -0.0550684791 -0.8737892702 0.481319511229 +1413393940905760512.0000000000 1.6316806421 0.8700551523 1.6403621593 0.0324509846 -0.0500003715 -0.8623963678 0.502712046068 +1413393940955760384.0000000000 1.6055002644 0.8522839534 1.6537021628 0.0225736427 -0.0438332241 -0.8469282555 0.529416290921 +1413393941005760512.0000000000 1.5767281547 0.8311393484 1.6683177202 0.0130920743 -0.0375213543 -0.8273801986 0.560234551329 +1413393941055760384.0000000000 1.5464045587 0.8087194262 1.6845768342 0.0077327394 -0.0338287279 -0.8043369229 0.593159284164 +1413393941105760512.0000000000 1.5146765695 0.7873041685 1.7012262304 0.0027109810 -0.0294490740 -0.7810387379 0.623781927102 +1413393941155760384.0000000000 1.4819504140 0.7689946928 1.7177153396 0.0003559082 -0.0259014180 -0.7604495725 0.648880141082 +1413393941205760512.0000000000 1.4484267592 0.7553751308 1.7331067981 0.0009972902 0.0228035626 0.7440369809 -0.667748436113 +1413393941255760384.0000000000 1.4140723307 0.7473771182 1.7464620873 0.0020432756 0.0197260062 0.7359978661 -0.676693321054 +1413393941305760512.0000000000 1.3789606635 0.7457589123 1.7565453201 0.0028254027 0.0164163647 0.7411565928 -0.671125491311 +1413393941355760384.0000000000 1.3433402623 0.7501104523 1.7649801542 0.0024388527 0.0137156497 0.7542954527 -0.656387311745 +1413393941405760512.0000000000 1.3072852595 0.7594028719 1.7721622864 0.0017188047 0.0113538974 0.7725447643 -0.634856457676 +1413393941455760384.0000000000 1.2708684133 0.7720648775 1.7788842258 0.0008910257 0.0094003809 0.7922369262 -0.61014055073 +1413393941505760512.0000000000 1.2336477335 0.7867455335 1.7849995799 0.0007310101 0.0070552077 0.8134531073 -0.581587252127 +1413393941555760384.0000000000 1.1958605907 0.8013292809 1.7918458955 0.0005684284 0.0051202026 0.8324371758 -0.554095487074 +1413393941605760512.0000000000 1.1576928769 0.8139959751 1.7998356908 0.0001576602 0.0035012987 0.8484612426 -0.529245912538 +1413393941655760384.0000000000 1.1190759399 0.8228309079 1.8092008842 0.0002037965 0.0018759141 0.8602548195 -0.509860848623 +1413393941705760512.0000000000 1.0798951254 0.8267336113 1.8183386926 0.0011387541 0.0018229001 0.8691184728 -0.494599292842 +1413393941755760384.0000000000 1.0401890100 0.8250494197 1.8257318332 0.0037137531 0.0025001289 0.8760568291 -0.482187089732 +1413393941805760512.0000000000 1.0001580149 0.8175340661 1.8312220119 0.0070072359 0.0031552667 0.8804820633 -0.474017171793 +1413393941855760384.0000000000 0.9600813993 0.8026843277 1.8358608737 0.0103942809 0.0043688590 0.8798082568 -0.475195016052 +1413393941905760512.0000000000 0.9201681009 0.7802771266 1.8407124503 0.0127785402 0.0060204210 0.8717451517 -0.489755912572 +1413393941955760384.0000000000 0.8803127579 0.7519468375 1.8457024760 0.0153825071 0.0077112779 0.8593980434 -0.511017531692 +1413393942005760512.0000000000 0.8407349055 0.7189411299 1.8517452703 0.0174766690 0.0095651965 0.8423676467 -0.538534883522 +1413393942055760384.0000000000 0.8013809857 0.6832038341 1.8593372769 0.0197402288 0.0113014384 0.8207603625 -0.57081961097 +1413393942105760512.0000000000 0.7622225468 0.6474949971 1.8674030832 0.0225394716 0.0126378218 0.7982628075 -0.601754724043 +1413393942155760384.0000000000 0.7236563252 0.6138150132 1.8753272459 0.0252454176 0.0135858962 0.7771990970 -0.628601348936 +1413393942205760512.0000000000 0.6857295951 0.5837713747 1.8831154553 0.0279260778 0.0141595313 0.7586606103 -0.65073321739 +1413393942255760384.0000000000 0.6484165120 0.5586805627 1.8901138092 0.0316804788 0.0135704789 0.7459676156 -0.665089847939 +1413393942305760512.0000000000 0.6120637367 0.5394178674 1.8974527264 0.0336277811 0.0138144764 0.7370677057 -0.674840373551 +1413393942355760384.0000000000 0.5766500907 0.5266858540 1.9047307972 0.0355463441 0.0136251903 0.7335625365 -0.678554947396 +1413393942405760512.0000000000 0.5423623490 0.5208584533 1.9112431895 0.0374338355 0.0129943387 0.7366342289 -0.675129519419 +1413393942455760384.0000000000 0.5092780777 0.5215591552 1.9171022669 0.0391154434 0.0128208967 0.7460728688 -0.664590762195 +1413393942505760512.0000000000 0.4776065537 0.5279240851 1.9228163034 0.0403746927 0.0120197766 0.7590721864 -0.649642074543 +1413393942555760384.0000000000 0.4472117784 0.5386587694 1.9275140002 0.0412403515 0.0113652781 0.7763830369 -0.62880795474 +1413393942605760512.0000000000 0.4178366900 0.5526188604 1.9304033595 0.0413113380 0.0117035731 0.7964192619 -0.603218665983 +1413393942655760384.0000000000 0.3896480339 0.5678898442 1.9318466570 0.0400526354 0.0127069404 0.8154782562 -0.577260369061 +1413393942705760512.0000000000 0.3624378314 0.5833896724 1.9319438379 0.0399776332 0.0124847073 0.8321864292 -0.552911989298 +1413393942755760384.0000000000 0.3362427726 0.5963650805 1.9313996978 0.0387868336 0.0129136153 0.8458346723 -0.531876420924 +1413393942805760512.0000000000 0.3106404725 0.6056724141 1.9291381947 0.0387359131 0.0119389693 0.8566357905 -0.514326853828 +1413393942855760384.0000000000 0.2857584110 0.6110289414 1.9243792646 0.0383381196 0.0113089810 0.8643624924 -0.501278143646 +1413393942905760512.0000000000 0.2615755239 0.6118430878 1.9174786998 0.0380556512 0.0103802922 0.8702341985 -0.491056470027 +1413393942955760384.0000000000 0.2380578110 0.6071204474 1.9090574091 0.0367108601 0.0102718611 0.8740628795 -0.484314860708 +1413393943005760512.0000000000 0.2150059001 0.5962199404 1.8997326862 0.0367278497 0.0092415212 0.8731689212 -0.485944126806 +1413393943055760384.0000000000 0.1927255594 0.5781322374 1.8919098777 0.0362003514 0.0080765024 0.8640242998 -0.502081979411 +1413393943105760512.0000000000 0.1711601389 0.5543633017 1.8859627107 0.0368850730 0.0062113267 0.8497230166 -0.525900851685 +1413393943155760384.0000000000 0.1506208552 0.5268490861 1.8822437097 0.0360296748 0.0056690076 0.8307590367 -0.555435997921 +1413393943205760512.0000000000 0.1310787483 0.4980937710 1.8795012108 0.0356384980 0.0043019269 0.8106307843 -0.584456262153 +1413393943255760384.0000000000 0.1123506882 0.4700861421 1.8774474300 0.0364232199 0.0032244846 0.7901131346 -0.611869419323 +1413393943305760512.0000000000 0.0947315738 0.4444881706 1.8754790253 0.0347458905 0.0042813042 0.7725880411 -0.633941726253 +1413393943355760384.0000000000 0.0782431230 0.4228442065 1.8742378116 0.0329021799 0.0042830383 0.7561580559 -0.653547317838 +1413393943405760512.0000000000 0.0624866287 0.4064139948 1.8726931596 0.0313231024 0.0054578593 0.7442279848 -0.667168480747 +1413393943455760384.0000000000 0.0474643728 0.3955408585 1.8712217923 0.0304295130 0.0061941866 0.7367499180 -0.675451874783 +1413393943505760512.0000000000 0.0332858703 0.3900856574 1.8680093532 0.0314459140 0.0059856275 0.7398076609 -0.672056509246 +1413393943555760384.0000000000 0.0195177661 0.3916435226 1.8620579809 0.0341626871 0.0059828885 0.7534097626 -0.656636006867 +1413393943605760512.0000000000 0.0066422489 0.3983160195 1.8560932128 0.0369348701 0.0056222035 0.7688875571 -0.638291571841 +1413393943655760384.0000000000 -0.0051801749 0.4089781383 1.8490751610 0.0388737157 0.0056683518 0.7890610664 -0.613057368839 +1413393943705760512.0000000000 -0.0160405981 0.4214775404 1.8428367013 0.0407114616 0.0062684979 0.8086034871 -0.586910285742 +1413393943755760384.0000000000 -0.0254773123 0.4343320935 1.8377490271 0.0407063501 0.0080081707 0.8264952403 -0.561412931904 +1413393943805760512.0000000000 -0.0340379814 0.4457412162 1.8336276755 0.0413813992 0.0095178390 0.8419480671 -0.53788515771 +1413393943855760384.0000000000 -0.0421790551 0.4538005245 1.8313189486 0.0434767285 0.0127073978 0.8525972559 -0.520601781899 +1413393943905760512.0000000000 -0.0498828131 0.4570583976 1.8312732695 0.0460952246 0.0180652653 0.8596098648 -0.50854671052 +1413393943955760384.0000000000 -0.0573369200 0.4537827642 1.8336611214 0.0511199498 0.0229487568 0.8620458355 -0.50372322034 +1413393944005760512.0000000000 -0.0641873791 0.4439761438 1.8401185775 0.0542737193 0.0312485160 0.8579359408 -0.509925303478 +1413393944055760384.0000000000 -0.0705564656 0.4296382433 1.8474757537 0.0575579548 0.0408615547 0.8495293217 -0.522797615438 +1413393944105760512.0000000000 -0.0764070076 0.4107900860 1.8566996664 0.0580556174 0.0532943311 0.8381864364 -0.539659853483 +1413393944155760384.0000000000 -0.0822070800 0.3894992998 1.8674901209 0.0560331565 0.0685653173 0.8242265997 -0.559293835925 +1413393944205760512.0000000000 -0.0886129760 0.3673593374 1.8793175397 0.0541398702 0.0842785720 0.8084775699 -0.579939665544 +1413393944255760384.0000000000 -0.0961262768 0.3456397358 1.8917939139 0.0558563442 0.0973384013 0.7912689274 -0.601081349735 +1413393944305760512.0000000000 -0.1048391617 0.3259954141 1.9044091301 0.0589633771 0.1095316063 0.7742558119 -0.620527263774 +1413393944355760384.0000000000 -0.1148186827 0.3093867522 1.9160386153 0.0648638227 0.1197347252 0.7590207692 -0.6366661229 +1413393944405760512.0000000000 -0.1255897786 0.2968709909 1.9265699692 0.0728960180 0.1276303453 0.7474701725 -0.64783100173 +1413393944455760384.0000000000 -0.1363505625 0.2891824624 1.9363644224 0.0788954493 0.1352122729 0.7402151401 -0.653891960232 +1413393944505760512.0000000000 -0.1473016886 0.2868852003 1.9440941477 0.0895709275 0.1385669843 0.7401069002 -0.651934058053 +1413393944555760384.0000000000 -0.1580215959 0.2900961886 1.9495476601 0.1007360057 0.1401868777 0.7486698060 -0.64007297875 +1413393944605760512.0000000000 -0.1683415654 0.2977718981 1.9536412354 0.1116054142 0.1412161230 0.7621255038 -0.621905904875 +1413393944655760384.0000000000 -0.1776538151 0.3087830090 1.9573118122 0.1178762105 0.1438107062 0.7783911763 -0.599608919543 +1413393944705760512.0000000000 -0.1858698679 0.3219011518 1.9608959696 0.1214001142 0.1465827737 0.7957085635 -0.574998595349 +1413393944755760384.0000000000 -0.1934468770 0.3349561133 1.9654408666 0.1235273224 0.1496841805 0.8110121574 -0.551901193453 +1413393944805760512.0000000000 -0.2005848641 0.3466945407 1.9713453873 0.1232933587 0.1530253715 0.8241212894 -0.531230725547 +1413393944855760384.0000000000 -0.2080363980 0.3557538329 1.9786227955 0.1230357194 0.1558992053 0.8342399708 -0.514394129611 +1413393944905760512.0000000000 -0.2161256980 0.3611615100 1.9873659567 0.1223994559 0.1584350657 0.8417462434 -0.501378065756 +1413393944955760384.0000000000 -0.2252334061 0.3618721179 1.9980218591 0.1207685833 0.1622114389 0.8465552086 -0.492388745991 +1413393945005760512.0000000000 -0.2361413041 0.3569787679 2.0109366239 0.1216565005 0.1655897927 0.8464919062 -0.491152897945 +1413393945055760384.0000000000 -0.2490915975 0.3461906859 2.0265129768 0.1265784284 0.1674736495 0.8388280836 -0.502292667986 +1413393945105760512.0000000000 -0.2635618803 0.3309453914 2.0428194661 0.1344374889 0.1688129054 0.8248671462 -0.522515986063 +1413393945155760384.0000000000 -0.2788301236 0.3132295423 2.0582866121 0.1438743374 0.1708178403 0.8066963242 -0.54714027547 +1413393945205760512.0000000000 -0.2942418224 0.2944482279 2.0716430652 0.1548420003 0.1731484321 0.7854861348 -0.573633251714 +1413393945255760384.0000000000 -0.3088288326 0.2766465920 2.0820439755 0.1659429094 0.1766064944 0.7636003283 -0.598487790723 +1413393945305760512.0000000000 -0.3217697678 0.2612866168 2.0885151391 0.1759696899 0.1814099337 0.7441955267 -0.618302613818 +1413393945355760384.0000000000 -0.3329448593 0.2492131501 2.0904916971 0.1857679244 0.1879284057 0.7301261161 -0.630150019566 +1413393945405760512.0000000000 -0.3417231041 0.2410695447 2.0878683980 0.1936847014 0.1969072380 0.7221102417 -0.634248038909 +1413393945455760384.0000000000 -0.3477755125 0.2368639242 2.0811824791 0.1995212357 0.2078763422 0.7192970233 -0.632131707074 +1413393945505760512.0000000000 -0.3512613623 0.2363752036 2.0702824495 0.2012753089 0.2225052749 0.7225568836 -0.622809122213 +1413393945555760384.0000000000 -0.3525350759 0.2396876027 2.0566939571 0.2026936282 0.2377157718 0.7296777002 -0.608257312965 +1413393945605760512.0000000000 -0.3521271923 0.2460038293 2.0428161009 0.2056895783 0.2514944723 0.7377184985 -0.591788598061 +1413393945655760384.0000000000 -0.3502129714 0.2552091674 2.0290727718 0.2103268598 0.2644017812 0.7455123976 -0.574513337736 +1413393945705760512.0000000000 -0.3473540703 0.2661258986 2.0158470095 0.2151259682 0.2769726184 0.7536478468 -0.555897391091 +1413393945755760384.0000000000 -0.3439719683 0.2780812418 2.0031813023 0.2197994551 0.2899641447 0.7615789235 -0.536289602397 +1413393945805760512.0000000000 -0.3406218332 0.2894004763 1.9910816523 0.2240275439 0.3029208642 0.7690139165 -0.516399269833 +1413393945855760384.0000000000 -0.3378766285 0.2991598697 1.9800302938 0.2279153215 0.3163266721 0.7747213532 -0.497794001253 +1413393945905760512.0000000000 -0.3367677023 0.3064997398 1.9706179909 0.2339651552 0.3275380292 0.7775799490 -0.483061661191 +1413393945955760384.0000000000 -0.3378926888 0.3102398892 1.9648434425 0.2414491015 0.3374935472 0.7725705931 -0.480557088948 +1413393946005760512.0000000000 -0.3416191682 0.3108458827 1.9619142647 0.2542626796 0.3438913056 0.7619119746 -0.486394287216 +1413393946055760384.0000000000 -0.3468446956 0.3088332531 1.9611098870 0.2686880373 0.3484284408 0.7469081466 -0.498530421129 +1413393946105760512.0000000000 -0.3526149996 0.3054835661 1.9612103568 0.2844211398 0.3519717715 0.7293850464 -0.513047698947 +1413393946155760384.0000000000 -0.3576787361 0.3016406385 1.9620515555 0.3003678150 0.3551057530 0.7101947043 -0.528490834234 +1413393946205760512.0000000000 -0.3610030448 0.2980370744 1.9630223042 0.3159467844 0.3587434151 0.6908372892 -0.542424770276 +1413393946255760384.0000000000 -0.3614192982 0.2956454719 1.9625348791 0.3287377175 0.3646166641 0.6749025651 -0.550901741707 +1413393946305760512.0000000000 -0.3583933426 0.2949725931 1.9599642591 0.3386333698 0.3735981349 0.6648281353 -0.55114011374 +1413393946355760384.0000000000 -0.3512212374 0.2957298936 1.9569441464 0.3413532059 0.3880131901 0.6574471167 -0.548349379379 +1413393946405760512.0000000000 -0.3401266770 0.2983978351 1.9519399353 0.3404738213 0.4062538304 0.6548724162 -0.538681279363 +1413393946455760384.0000000000 -0.3262807752 0.3025868247 1.9467230108 0.3371852452 0.4262183052 0.6530921124 -0.527365868692 +1413393946505760512.0000000000 -0.3106938179 0.3087236343 1.9412516085 0.3357513167 0.4458974897 0.6524835184 -0.512554134 +1413393946555760384.0000000000 -0.2937588667 0.3164990119 1.9356168098 0.3342191217 0.4659712554 0.6534952894 -0.494077194915 +1413393946605760512.0000000000 -0.2767538854 0.3255550396 1.9296161384 0.3341591392 0.4847695662 0.6560307371 -0.472186201968 +1413393946655760384.0000000000 -0.2605497966 0.3354956758 1.9233246099 0.3351985268 0.5034283332 0.6584454106 -0.447941404854 +1413393946705760512.0000000000 -0.2467248368 0.3456773360 1.9176094948 0.3388714654 0.5202727467 0.6599064169 -0.423090911991 +1413393946755760384.0000000000 -0.2355419966 0.3555874661 1.9135930144 0.3452213862 0.5349696201 0.6587740387 -0.400807267867 +1413393946805760512.0000000000 -0.2285543605 0.3642486779 1.9125652367 0.3541421269 0.5479160036 0.6528601561 -0.384896120396 +1413393946855760384.0000000000 -0.2255432986 0.3712958778 1.9139464302 0.3653556903 0.5587466557 0.6434982872 -0.374469422927 +1413393946905760512.0000000000 -0.2267356770 0.3763833177 1.9178775833 0.3808936729 0.5654201020 0.6300483427 -0.371832225781 +1413393946955760384.0000000000 -0.2315345570 0.3796216016 1.9241056879 0.4005640863 0.5683234681 0.6120719412 -0.376729063445 +1413393947005760512.0000000000 -0.2388553535 0.3812205725 1.9313944177 0.4237562374 0.5675593612 0.5902164287 -0.387235832711 +1413393947055760384.0000000000 -0.2465316732 0.3818180919 1.9366885140 0.4462337050 0.5661629412 0.5679799185 -0.397157168854 +1413393947105760512.0000000000 -0.2533175966 0.3815580017 1.9381506806 0.4661582350 0.5656735968 0.5470734040 -0.404253104516 +1413393947155760384.0000000000 -0.2582811514 0.3803742881 1.9353317971 0.4813727550 0.5686679786 0.5288266701 -0.40649643771 +1413393947205760512.0000000000 -0.2600914781 0.3782714577 1.9276446297 0.4914386279 0.5756340018 0.5144470717 -0.403085327717 +1413393947255760384.0000000000 -0.2583100042 0.3750305229 1.9163181043 0.4990748957 0.5841571139 0.5019971317 -0.397093936619 +1413393947305760512.0000000000 -0.2536215039 0.3708108739 1.9017258776 0.5048332750 0.5942574891 0.4904333242 -0.389199891564 +1413393947355760384.0000000000 -0.2461367502 0.3655689652 1.8846754193 0.5101289642 0.6046224001 0.4782906020 -0.381363728222 +1413393947405760512.0000000000 -0.2359820700 0.3591610636 1.8650189810 0.5120946399 0.6172531394 0.4657417537 -0.373954891107 +1413393947455760384.0000000000 -0.2232551757 0.3516078290 1.8428085127 0.5072882157 0.6346951960 0.4516323020 -0.368576909576 +1413393947505760512.0000000000 -0.2081742025 0.3437470828 1.8193051222 0.4999179981 0.6536116262 0.4369806342 -0.363210355961 +1413393947555760384.0000000000 -0.1908092559 0.3363811326 1.7960775410 0.4927043557 0.6716048295 0.4217751304 -0.35818306803 +1413393947605760512.0000000000 -0.1715072606 0.3305008829 1.7733907700 0.4853258517 0.6894795479 0.4061529770 -0.352301759697 +1413393947655760384.0000000000 -0.1503371335 0.3264080561 1.7509507129 0.4764483624 0.7077757177 0.3921363136 -0.343918017802 +1413393947705760512.0000000000 -0.1276000319 0.3252730273 1.7285220711 0.4679323498 0.7252029138 0.3824204255 -0.329961616 +1413393947755760384.0000000000 -0.1038514009 0.3279041209 1.7067326480 0.4636869190 0.7397743007 0.3761480655 -0.310227429467 +1413393947805760512.0000000000 -0.0796239142 0.3343242213 1.6860344478 0.4641531826 0.7505041839 0.3729451765 -0.286735397843 +1413393947855760384.0000000000 -0.0561435468 0.3445864521 1.6676666780 0.4698112318 0.7570122900 0.3702305855 -0.262943174056 +1413393947905760512.0000000000 -0.0343674225 0.3578149494 1.6520131514 0.4782690856 0.7607978723 0.3657553550 -0.242215398961 +1413393947955760384.0000000000 -0.0149363561 0.3733216101 1.6389642950 0.4900765394 0.7613011517 0.3598255464 -0.225324472885 +1413393948005760512.0000000000 0.0018062551 0.3909169753 1.6281492206 0.5099546506 0.7548550620 0.3561628061 -0.208058033413 +1413393948055760384.0000000000 0.0156860630 0.4087121152 1.6189232088 0.5298319328 0.7469900225 0.3521917776 -0.192989588002 +1413393948105760512.0000000000 0.0270244945 0.4253756080 1.6107935996 0.5462972586 0.7405040504 0.3472162209 -0.180704046813 +1413393948155760384.0000000000 0.0358040014 0.4398046735 1.6042186814 0.5592624265 0.7362393923 0.3389884712 -0.17396526073 +1413393948205760512.0000000000 0.0421640959 0.4517047051 1.5991757833 0.5708315292 0.7326033732 0.3283864510 -0.172063946504 +1413393948255760384.0000000000 0.0466831498 0.4607232721 1.5952887239 0.5813775311 0.7292269145 0.3165240740 -0.17332277407 +1413393948305760512.0000000000 0.0501289626 0.4662705127 1.5926961083 0.5903921961 0.7265633492 0.3027741937 -0.178523225354 +1413393948355760384.0000000000 0.0535557020 0.4687996256 1.5911093645 0.6002751138 0.7227001944 0.2888805341 -0.184179949526 +1413393948405760512.0000000000 0.0578205605 0.4679737200 1.5899495591 0.6101366345 0.7184796414 0.2761073086 -0.187843142633 +1413393948455760384.0000000000 0.0634236015 0.4633274243 1.5886545985 0.6166713569 0.7165896142 0.2647534296 -0.190056265 +1413393948505760512.0000000000 0.0707269966 0.4549946175 1.5870933643 0.6197278426 0.7175774019 0.2550075536 -0.189713523751 +1413393948555760384.0000000000 0.0802109367 0.4425931650 1.5848813379 0.6153663514 0.7245538557 0.2470964769 -0.187854451095 +1413393948605760512.0000000000 0.0916782867 0.4272806012 1.5806294082 0.6052161763 0.7362368490 0.2431186109 -0.18044950306 +1413393948655760384.0000000000 0.1043454834 0.4102519819 1.5754941557 0.5899141795 0.7518424075 0.2410179020 -0.169247233314 +1413393948705760512.0000000000 0.1182636535 0.3909303854 1.5709558730 0.5738727078 0.7673131047 0.2391768913 -0.157146839857 +1413393948755760384.0000000000 0.1326088596 0.3706384271 1.5661102111 0.5581747459 0.7820477533 0.2365294235 -0.144554821338 +1413393948805760512.0000000000 0.1460374583 0.3507508546 1.5626852227 0.5435183403 0.7955935274 0.2320072083 -0.133384437908 +1413393948855760384.0000000000 0.1577263814 0.3324785271 1.5602197642 0.5304681398 0.8077454132 0.2248538148 -0.12486657708 +1413393948905760512.0000000000 0.1672714157 0.3172380488 1.5608125360 0.5224580366 0.8164713100 0.2156592228 -0.117912253679 +1413393948955760384.0000000000 0.1752650146 0.3042395139 1.5628196670 0.5197495310 0.8217923178 0.2046466005 -0.11241699267 +1413393949005760512.0000000000 0.1814743583 0.2944367368 1.5664873751 0.5264510499 0.8211986398 0.1919269207 -0.10791729789 +1413393949055760384.0000000000 0.1868245498 0.2871274817 1.5708976800 0.5379550055 0.8171198665 0.1807807349 -0.1011823194 +1413393949105760512.0000000000 0.1905490710 0.2831912885 1.5774570394 0.5523313835 0.8108674238 0.1685378905 -0.0949686439709 +1413393949155760384.0000000000 0.1934717675 0.2804639199 1.5856171910 0.5676726210 0.8033255840 0.1571139133 -0.0879262171134 +1413393949205760512.0000000000 0.1961958928 0.2770443624 1.5939909684 0.5829964506 0.7951993146 0.1451604877 -0.0818634320156 +1413393949255760384.0000000000 0.1983991574 0.2730644604 1.6021560490 0.5964091814 0.7878607278 0.1332656766 -0.0762353024349 +1413393949305760512.0000000000 0.2003100868 0.2683148913 1.6113559566 0.6109604766 0.7790428449 0.1221078876 -0.0700657240497 +1413393949355760384.0000000000 0.2021574352 0.2613113581 1.6205311903 0.6230012954 0.7716310719 0.1106329512 -0.0649247640929 +1413393949405760512.0000000000 0.2040796450 0.2513041803 1.6298992619 0.6350145812 0.7637669449 0.0986794248 -0.0606539918881 +1413393949455760384.0000000000 0.2060892929 0.2377794578 1.6391788494 0.6445090022 0.7574748574 0.0860101444 -0.0586706192927 +1413393949505760512.0000000000 0.2085157955 0.2198292795 1.6472588368 0.6471855998 0.7564840065 0.0725064774 -0.0602126077161 +1413393949555760384.0000000000 0.2116579160 0.1973457877 1.6531234087 0.6394452353 0.7638331092 0.0596287178 -0.0641341432736 +1413393949605760512.0000000000 0.2162520450 0.1709843157 1.6576768269 0.6275847924 0.7740117337 0.0482343193 -0.0686776154312 +1413393949655760384.0000000000 0.2224723006 0.1418991872 1.6616827408 0.6145866849 0.7844332541 0.0386940298 -0.0738271535424 +1413393949705760512.0000000000 0.2310328833 0.1110348460 1.6657625229 0.6015326069 0.7942256282 0.0281419411 -0.0810691399574 +1413393949755760384.0000000000 0.2426344428 0.0796159810 1.6705940286 0.5902146008 0.8022135765 0.0161196082 -0.0885452477574 +1413393949805760512.0000000000 0.2578848288 0.0479881414 1.6763078542 0.5804858090 0.8085421719 0.0029794912 -0.0963685865454 +1413393949855760384.0000000000 0.2775079479 0.0169756390 1.6830399510 0.5725074520 0.8130093219 -0.0123135659 -0.105353861439 +1413393949905760512.0000000000 0.3021544754 -0.0131361111 1.6895838400 0.5647282701 0.8171314313 -0.0258211620 -0.112745166378 +1413393949955760384.0000000000 0.3323815743 -0.0420189788 1.6967638139 0.5582518872 0.8202651133 -0.0369165202 -0.118983801075 +1413393950005760512.0000000000 0.3690667837 -0.0676768493 1.7045734383 0.5530840671 0.8233649844 -0.0433519132 -0.119535470837 +1413393950055760384.0000000000 0.4125220933 -0.0901336252 1.7122231859 0.5496807272 0.8273071996 -0.0397319478 -0.108790017904 +1413393950105760512.0000000000 0.4622666039 -0.1118393251 1.7189452125 0.5484159296 0.8312254148 -0.0267017415 -0.0871280374693 +1413393950155760384.0000000000 0.5166329130 -0.1316073264 1.7255995999 0.5430009843 0.8371287263 -0.0124736467 -0.0648832402746 +1413393950205760512.0000000000 0.5741008088 -0.1487872066 1.7330706114 0.5376729011 0.8420673002 0.0027051210 -0.042698895437 +1413393950255760384.0000000000 0.6331650759 -0.1632761556 1.7410574175 0.5320288680 0.8462632598 0.0174235250 -0.0219134539596 +1413393950305760512.0000000000 0.6921929433 -0.1743278358 1.7500026219 0.5270205987 0.8493775032 0.0276959212 -0.00633100637419 +1413393950355760384.0000000000 0.7497857848 -0.1822482857 1.7583680794 0.5221721756 0.8522565882 0.0315289610 0.000922747699294 +1413393950405760512.0000000000 0.8060185529 -0.1867523125 1.7654049734 0.5188358039 0.8542579300 0.0322178735 0.00384788629881 +1413393950455760384.0000000000 0.8608103585 -0.1878840081 1.7713419620 0.5180630789 0.8547529748 0.0313805938 0.00482252370296 +1413393950505760512.0000000000 0.9141589040 -0.1852448397 1.7756251708 0.5216587106 0.8526703094 0.0285254198 0.00343998298096 +1413393950555760384.0000000000 0.9665796149 -0.1786915553 1.7778090200 0.5282483390 0.8487048099 0.0254916974 0.00200284277539 +1413393950605760512.0000000000 1.0180281299 -0.1687496852 1.7781939378 0.5378014703 0.8427497051 0.0232693367 0.00102522785826 +1413393950655760384.0000000000 1.0686965607 -0.1557661577 1.7765706839 0.5490229559 0.8355470429 0.0208549876 5.00376337105e-05 +1413393950705760512.0000000000 1.1186859728 -0.1411201366 1.7726232508 0.5597964168 0.8284090811 0.0191383668 -0.00029828472843 +1413393950755760384.0000000000 1.1680837548 -0.1256949855 1.7658054548 0.5676536435 0.8230552258 0.0186816720 0.000656860896146 +1413393950805760512.0000000000 1.2168743679 -0.1103466884 1.7558100277 0.5736306889 0.8189042232 0.0183716064 0.00248798696636 +1413393950855760384.0000000000 1.2647057010 -0.0946233668 1.7423694412 0.5778535697 0.8159228150 0.0184153928 0.00401064771572 +1413393950905760512.0000000000 1.3120276032 -0.0788465065 1.7255711785 0.5797060994 0.8145276105 0.0203980894 0.0083383483076 +1413393950955760384.0000000000 1.3586261835 -0.0632262108 1.7067593451 0.5803825846 0.8137897710 0.0249003397 0.0167999135136 +1413393951005760512.0000000000 1.4035375778 -0.0478501700 1.6874111466 0.5790623165 0.8143166593 0.0303591269 0.0255643394829 +1413393951055760384.0000000000 1.4461868189 -0.0325000580 1.6689543782 0.5771869582 0.8152673008 0.0341224196 0.0320952325251 +1413393951105760512.0000000000 1.4859258271 -0.0170850866 1.6521139656 0.5749289005 0.8168880525 0.0332369998 0.0323414722674 +1413393951155760384.0000000000 1.5229789796 -0.0011082363 1.6374345019 0.5750765778 0.8170257623 0.0302811932 0.028963472642 +1413393951205760512.0000000000 1.5577352187 0.0153362004 1.6239887176 0.5756707912 0.8168529880 0.0266450618 0.0253845774004 +1413393951255760384.0000000000 1.5905587943 0.0320195960 1.6116861893 0.5765671766 0.8164292200 0.0229789489 0.0220360490397 +1413393951305760512.0000000000 1.6218221550 0.0489497502 1.6005624184 0.5768178871 0.8163861027 0.0197658849 0.0201038853411 +1413393951355760384.0000000000 1.6516323262 0.0659434689 1.5906717303 0.5761279039 0.8169585841 0.0170000366 0.0191391990676 +1413393951405760512.0000000000 1.6802079712 0.0830310608 1.5818087148 0.5736955684 0.8187036604 0.0148201525 0.0194441353385 +1413393951455760384.0000000000 1.7076656510 0.1002933143 1.5731307838 0.5692826464 0.8217582374 0.0135919450 0.0211169800642 +1413393951505760512.0000000000 1.7337927308 0.1178632018 1.5634766320 0.5644260491 0.8250705286 0.0128478938 0.0227330059137 +1413393951555760384.0000000000 1.7586516803 0.1366078920 1.5520374932 0.5603297038 0.8278103527 0.0122616325 0.0247041553223 +1413393951605760512.0000000000 1.7822195636 0.1568727009 1.5385621288 0.5578030498 0.8294477376 0.0119340097 0.0270145828956 +1413393951655760384.0000000000 1.8043755520 0.1783424390 1.5233896104 0.5580099151 0.8292486768 0.0112105045 0.0290842115741 +1413393951705760512.0000000000 1.8252480912 0.2004320179 1.5067593113 0.5601312080 0.8277135971 0.0113292542 0.0318571645562 +1413393951755760384.0000000000 1.8448144075 0.2230051609 1.4883740011 0.5625637529 0.8259335692 0.0113503160 0.0350276108964 +1413393951805760512.0000000000 1.8625850328 0.2468220747 1.4698026395 0.5656251054 0.8238167514 0.0095243096 0.0361038487387 +1413393951855760384.0000000000 1.8785962559 0.2716487658 1.4520021284 0.5688978418 0.8215830336 0.0067628679 0.0362053614816 +1413393951905760512.0000000000 1.8930902201 0.2971332688 1.4346565846 0.5711248186 0.8200360229 0.0039986807 0.0366247621408 +1413393951955760384.0000000000 1.9060814492 0.3234533584 1.4183327256 0.5724697333 0.8190980269 0.0009939680 0.0368217177743 +1413393952005760512.0000000000 1.9176093226 0.3505282057 1.4031810479 0.5740202442 0.8179782024 -0.0015985860 0.037548157886 +1413393952055760384.0000000000 1.9277795390 0.3779367771 1.3896293705 0.5753063985 0.8170162002 -0.0040734603 0.0386067780713 +1413393952105760512.0000000000 1.9363085674 0.4056495647 1.3790285167 0.5768122823 0.8159679544 -0.0072972803 0.0378237759993 +1413393952155760384.0000000000 1.9438088600 0.4333802058 1.3713674696 0.5779670218 0.8150615309 -0.0091185727 0.0393150630213 +1413393952205760512.0000000000 1.9498132250 0.4611040492 1.3674939336 0.5786105458 0.8146030584 -0.0124728033 0.0384203419963 +1413393952255760384.0000000000 1.9546726512 0.4883657231 1.3667861924 0.5794879770 0.8139792475 -0.0157916437 0.0371765123844 +1413393952305760512.0000000000 1.9584553039 0.5150074872 1.3691246012 0.5797537213 0.8138091302 -0.0176998304 0.0358753151665 +1413393952355760384.0000000000 1.9609610741 0.5407684262 1.3740986931 0.5804844843 0.8134039534 -0.0174153933 0.0332937866267 +1413393952405760512.0000000000 1.9625916826 0.5663892971 1.3794007840 0.5810312365 0.8131764621 -0.0143240192 0.0306849516003 +1413393952455760384.0000000000 1.9635479413 0.5921589317 1.3850100865 0.5820812049 0.8125708738 -0.0083902085 0.0289767195633 +1413393952505760512.0000000000 1.9635730822 0.6173540055 1.3903921679 0.5820503128 0.8127385943 -0.0009266891 0.025933605694 +1413393952555760384.0000000000 1.9626851597 0.6422175220 1.3958315747 0.5816793252 0.8130745897 0.0076884499 0.0223553557667 +1413393952605760512.0000000000 1.9610324556 0.6668624528 1.4014678730 0.5819170157 0.8128443710 0.0174526745 0.0187621840593 +1413393952655760384.0000000000 1.9582944428 0.6914483838 1.4071895200 0.5814163329 0.8130352577 0.0273547820 0.0134325528699 +1413393952705760512.0000000000 1.9544290071 0.7157177032 1.4126878592 0.5812354638 0.8128346472 0.0375043224 0.00765491498624 +1413393952755760384.0000000000 1.9493443551 0.7396323600 1.4180047860 0.5804527843 0.8129416765 0.0469064762 0.000422151699111 +1413393952805760512.0000000000 1.9435491535 0.7632273399 1.4230799500 0.5798045383 0.8128506677 0.0553436650 -0.00612928247586 +1413393952855760384.0000000000 1.9372391247 0.7866696006 1.4282059391 0.5788060586 0.8129983482 0.0621253769 -0.0125566713109 +1413393952905760512.0000000000 1.9302403653 0.8097543256 1.4341014070 0.5781065157 0.8130855491 0.0648968516 -0.0217518979476 +1413393952955760384.0000000000 1.9227428291 0.8327380671 1.4404211159 0.5766458250 0.8137042619 0.0659887339 -0.0317876332173 +1413393953005760512.0000000000 1.9151586500 0.8559558274 1.4472782257 0.5751377114 0.8143758152 0.0657375022 -0.0410758487918 +1413393953055760384.0000000000 1.9079621007 0.8795205910 1.4541442346 0.5735904629 0.8150461126 0.0653843566 -0.0491802910403 +1413393953105760512.0000000000 1.9015620536 0.9035483365 1.4599333352 0.5723575703 0.8155382910 0.0647254585 -0.055809700541 +1413393953155760384.0000000000 1.8961559361 0.9278168206 1.4619418954 0.5712424651 0.8160188874 0.0639916721 -0.0608299880048 +1413393953205760512.0000000000 1.8917381537 0.9522615751 1.4589317392 0.5706076843 0.8161768733 0.0634615264 -0.0650754703946 +1413393953255760384.0000000000 1.8885549115 0.9773320222 1.4515627719 0.5703420186 0.8161401038 0.0622102584 -0.068957933363 +1413393953305760512.0000000000 1.8865034374 1.0031228904 1.4427301500 0.5696148993 0.8163607478 0.0593423295 -0.0746490717124 +1413393953355760384.0000000000 1.8863814359 1.0296346918 1.4349813966 0.5704409203 0.8155554781 0.0565453421 -0.079177287705 +1413393953405760512.0000000000 1.8884986636 1.0567934633 1.4300018791 0.5732097017 0.8134725334 0.0541154628 -0.0822471395011 +1413393953455760384.0000000000 1.8930198643 1.0844319027 1.4283378273 0.5762165699 0.8112932297 0.0524881880 -0.0838018510505 +1413393953505760512.0000000000 1.9005161291 1.1125244486 1.4308907620 0.5814228005 0.8077948976 0.0538642202 -0.0807067301336 +1413393953555760384.0000000000 1.9107076411 1.1400822162 1.4359390514 0.5868361693 0.8042966035 0.0572944823 -0.0738080369928 +1413393953605760512.0000000000 1.9229497455 1.1668724698 1.4422816262 0.5926204875 0.8005326545 0.0636411277 -0.0624358376929 +1413393953655760384.0000000000 1.9360710386 1.1928004355 1.4499287446 0.5970732962 0.7974664189 0.0690622615 -0.0527370249183 +1413393953705760512.0000000000 1.9497784565 1.2174184243 1.4582084404 0.6018478862 0.7940007252 0.0734707269 -0.0440910714215 +1413393953755760384.0000000000 1.9632755324 1.2407444294 1.4654295982 0.6062640894 0.7906931337 0.0762401641 -0.037890097785 +1413393953805760512.0000000000 1.9763300100 1.2619666824 1.4703639789 0.6088780188 0.7886163389 0.0784535944 -0.0345956909932 +1413393953855760384.0000000000 1.9887097336 1.2807576678 1.4727321625 0.6108791910 0.7868193880 0.0813911861 -0.0334266279866 +1413393953905760512.0000000000 2.0003214657 1.2969324404 1.4725781225 0.6121054212 0.7854574057 0.0845120935 -0.0352324178938 +1413393953955760384.0000000000 2.0113522538 1.3107318810 1.4697195532 0.6099118286 0.7865654370 0.0891089274 -0.037174907372 +1413393954005760512.0000000000 2.0219501024 1.3221277618 1.4649909047 0.6025500253 0.7914627488 0.0947468851 -0.0392837380447 +1413393954055760384.0000000000 2.0316533650 1.3313254452 1.4607252531 0.5954248940 0.7958721409 0.1013910534 -0.0421495586084 +1413393954105760512.0000000000 2.0404116462 1.3392107753 1.4569686650 0.5859198867 0.8018965256 0.1071159267 -0.0467549672748 +1413393954155760384.0000000000 2.0485285838 1.3462253304 1.4538082320 0.5747860429 0.8086894913 0.1145550169 -0.0501942185796 +1413393954205760512.0000000000 2.0555079454 1.3528971033 1.4515829610 0.5628208001 0.8156538654 0.1222929652 -0.054643841836 +1413393954255760384.0000000000 2.0612747013 1.3599768604 1.4508649533 0.5509763072 0.8220288185 0.1307373213 -0.0600123596196 +1413393954305760512.0000000000 2.0656267333 1.3684035381 1.4520256312 0.5411269779 0.8265640113 0.1401195745 -0.0658789331262 +1413393954355760384.0000000000 2.0683593975 1.3787642304 1.4541800737 0.5326953778 0.8297438063 0.1500957840 -0.0723332987509 +1413393954405760512.0000000000 2.0694984051 1.3912845736 1.4569680369 0.5261772913 0.8311931874 0.1613326700 -0.0789120581717 +1413393954455760384.0000000000 2.0688889531 1.4062348679 1.4603678758 0.5212705334 0.8311333585 0.1734292789 -0.0861200133635 +1413393954505760512.0000000000 2.0666982211 1.4231616697 1.4643402964 0.5177557628 0.8297723570 0.1863153531 -0.093238376633 +1413393954555760384.0000000000 2.0625443477 1.4425478150 1.4687660123 0.5137568721 0.8283056046 0.1997174188 -0.100382540612 +1413393954605760512.0000000000 2.0566740402 1.4642984184 1.4739322034 0.5104572279 0.8263454313 0.2119376876 -0.108023438088 +1413393954655760384.0000000000 2.0487619372 1.4891959696 1.4793126283 0.5087281099 0.8234340195 0.2235377497 -0.114817247022 +1413393954705760512.0000000000 2.0386861686 1.5174295436 1.4844758764 0.5059853608 0.8214217907 0.2340725275 -0.120229398688 +1413393954755760384.0000000000 2.0267218948 1.5487028246 1.4900228913 0.5036478208 0.8197454485 0.2424575422 -0.124782260197 +1413393954805760512.0000000000 2.0127827976 1.5825851607 1.4952859407 0.5014269204 0.8183358449 0.2495764301 -0.128876273934 +1413393954855760384.0000000000 1.9967819499 1.6192376402 1.5005335304 0.4997551911 0.8170853319 0.2554703306 -0.131724028081 +1413393954905760512.0000000000 1.9784410907 1.6588170375 1.5059232743 0.4986804586 0.8158191105 0.2605423270 -0.13369620395 +1413393954955760384.0000000000 1.9577136168 1.7011919030 1.5117335096 0.5003899340 0.8132834553 0.2641842120 -0.135597335441 +1413393955005760512.0000000000 1.9341857030 1.7462834205 1.5187430666 0.5062075109 0.8085257245 0.2661840915 -0.138514036049 +1413393955055760384.0000000000 1.9080051520 1.7934529290 1.5266056504 0.5155617259 0.8011950429 0.2683675047 -0.142342869535 +1413393955105760512.0000000000 1.8798473442 1.8416493937 1.5338754161 0.5234965327 0.7944220156 0.2709526574 -0.146388862037 +1413393955155760384.0000000000 1.8498285014 1.8904350957 1.5405157516 0.5307369242 0.7877045247 0.2743395853 -0.150258746597 +1413393955205760512.0000000000 1.8180299603 1.9394058339 1.5473480155 0.5353220431 0.7827268048 0.2755821962 -0.157554791642 +1413393955255760384.0000000000 1.7848613725 1.9879341644 1.5542370700 0.5371257944 0.7792409299 0.2766444742 -0.166575175305 +1413393955305760512.0000000000 1.7508735042 2.0365623037 1.5612497445 0.5381255024 0.7761359601 0.2773727022 -0.17634709851 +1413393955355760384.0000000000 1.7166502658 2.0848297164 1.5677712973 0.5373306395 0.7734201491 0.2811612407 -0.184513992879 +1413393955405760512.0000000000 1.6822411438 2.1326467306 1.5741156958 0.5363615824 0.7700584414 0.2872617880 -0.19185128346 +1413393955455760384.0000000000 1.6473836570 2.1805601356 1.5814682018 0.5385269365 0.7633307209 0.2957078868 -0.199679229747 +1413393955505760512.0000000000 1.6124126543 2.2278515494 1.5896549732 0.5420902652 0.7541685874 0.3057937704 -0.209423150841 +1413393955555760384.0000000000 1.5779718181 2.2741096986 1.5970406649 0.5462770356 0.7432155957 0.3173179383 -0.22027551993 +1413393955605760512.0000000000 1.5444722841 2.3191373791 1.6021454905 0.5518448924 0.7298037941 0.3317877629 -0.229718343348 +1413393955655760384.0000000000 1.5120287440 2.3627524553 1.6040130811 0.5563192141 0.7163449938 0.3482257580 -0.236849326149 +1413393955705760512.0000000000 1.4805997291 2.4052172943 1.6025682484 0.5590325351 0.7045024864 0.3669158317 -0.237763840451 +1413393955755760384.0000000000 1.4503229446 2.4458825706 1.5982593526 0.5613838764 0.6934397245 0.3861536237 -0.234253859421 +1413393955805760512.0000000000 1.4208873420 2.4838473491 1.5914495198 0.5624496684 0.6839266222 0.4042574333 -0.2290647803 +1413393955855760384.0000000000 1.3915735534 2.5184321927 1.5822227317 0.5600776345 0.6782209957 0.4201023457 -0.223256228236 +1413393955905760512.0000000000 1.3616694908 2.5484985676 1.5725217322 0.5522569713 0.6780246873 0.4313016296 -0.221976722561 +1413393955955760384.0000000000 1.3299158413 2.5736262572 1.5647027606 0.5397544112 0.6826739832 0.4358046789 -0.229555418419 +1413393956005760512.0000000000 1.2965744845 2.5949574235 1.5584278779 0.5260516865 0.6888528390 0.4370480513 -0.240292301642 +1413393956055760384.0000000000 1.2616935409 2.6136225852 1.5539721707 0.5137981990 0.6936990710 0.4368732948 -0.252853186257 +1413393956105760512.0000000000 1.2254285894 2.6306182007 1.5508082432 0.5037510716 0.6965894714 0.4365300659 -0.265404347832 +1413393956155760384.0000000000 1.1881144885 2.6462588321 1.5484841765 0.4951526236 0.6973775948 0.4379891338 -0.276864386077 +1413393956205760512.0000000000 1.1500971039 2.6610738371 1.5468439875 0.4884290552 0.6956060058 0.4414744765 -0.287523267487 +1413393956255760384.0000000000 1.1112459915 2.6757268017 1.5466838363 0.4870815966 0.6890230423 0.4460186700 -0.298439460366 +1413393956305760512.0000000000 1.0720241576 2.6900301790 1.5472058628 0.4882486067 0.6794893870 0.4521675661 -0.308953011095 +1413393956355760384.0000000000 1.0329942915 2.7037350451 1.5487052796 0.4900732216 0.6681992494 0.4588766501 -0.320577947765 +1413393956405760512.0000000000 0.9947881713 2.7166648209 1.5508266875 0.4915413741 0.6562134501 0.4665401689 -0.33183016185 +1413393956455760384.0000000000 0.9577210309 2.7284607380 1.5529930441 0.4919142748 0.6440585301 0.4751426451 -0.342707488748 +1413393956505760512.0000000000 0.9220934719 2.7390133120 1.5544600314 0.4885148903 0.6334098020 0.4854870642 -0.352771222228 +1413393956555760384.0000000000 0.8880325726 2.7483175495 1.5555722096 0.4815575481 0.6245974185 0.4972027314 -0.36162112307 +1413393956605760512.0000000000 0.8553992364 2.7565778478 1.5563175739 0.4723216788 0.6166041550 0.5097645091 -0.369934714594 +1413393956655760384.0000000000 0.8238286222 2.7640342478 1.5567620218 0.4611016038 0.6090357255 0.5238656657 -0.37686278707 +1413393956705760512.0000000000 0.7933008762 2.7708315010 1.5564743510 0.4484545615 0.6023223078 0.5383401391 -0.382473840161 +1413393956755760384.0000000000 0.7640318715 2.7770372341 1.5559199065 0.4350633934 0.5959223664 0.5529110570 -0.387150797582 +1413393956805760512.0000000000 0.7351731203 2.7826806817 1.5562509433 0.4226533641 0.5883170774 0.5662209293 -0.393244210908 +1413393956855760384.0000000000 0.7062530607 2.7880355053 1.5575524926 0.4100243174 0.5810864135 0.5773954637 -0.401040045053 +1413393956905760512.0000000000 0.6770807185 2.7933161745 1.5594442018 0.3980442805 0.5730295254 0.5872569413 -0.410276977921 +1413393956955760384.0000000000 0.6477878737 2.7989220129 1.5614330863 0.3864652189 0.5647998949 0.5960585273 -0.419952313157 +1413393957005760512.0000000000 0.6182106826 2.8051301120 1.5633366199 0.3767030883 0.5553258928 0.6053369137 -0.42810647852 +1413393957055760384.0000000000 0.5884493272 2.8118946096 1.5652261575 0.3669342344 0.5452503855 0.6150836740 -0.435583928419 +1413393957105760512.0000000000 0.5582375132 2.8194225792 1.5667396709 0.3594453455 0.5325200989 0.6266055798 -0.441119978193 +1413393957155760384.0000000000 0.5270606561 2.8272261239 1.5681621520 0.3523644423 0.5187285788 0.6382005681 -0.446609444788 +1413393957205760512.0000000000 0.4948334158 2.8348909897 1.5699621493 0.3447808636 0.5039410153 0.6494492631 -0.453194509949 +1413393957255760384.0000000000 0.4624529663 2.8428284017 1.5718901287 0.3361786604 0.4887264745 0.6607797395 -0.45989181049 +1413393957305760512.0000000000 0.4297157004 2.8508187938 1.5739278507 0.3265050030 0.4733861153 0.6719388614 -0.466688585004 +1413393957355760384.0000000000 0.3965280904 2.8588753931 1.5764702298 0.3171423695 0.4574832069 0.6822623472 -0.473970381295 +1413393957405760512.0000000000 0.3626422813 2.8671334248 1.5786556702 0.3082294414 0.4419673577 0.6916195633 -0.480959297457 +1413393957455760384.0000000000 0.3281218224 2.8749979226 1.5806805477 0.2999818119 0.4260605328 0.6993161900 -0.489326272932 +1413393957505760512.0000000000 0.2929461518 2.8827151316 1.5810125759 0.2926040012 0.4106379635 0.7061983000 -0.497034528511 +1413393957555760384.0000000000 0.2579694129 2.8904141429 1.5791020670 0.2847239663 0.3956936845 0.7122602521 -0.505018914864 +1413393957605760512.0000000000 0.2234073479 2.8981848247 1.5745914862 0.2767954818 0.3802119584 0.7177482191 -0.5134789401 +1413393957655760384.0000000000 0.1892787373 2.9059891626 1.5675604982 0.2689242031 0.3643187405 0.7214532838 -0.52388623529 +1413393957705760512.0000000000 0.1556231275 2.9139495714 1.5579172100 0.2624176539 0.3468842076 0.7239826639 -0.535403981931 +1413393957755760384.0000000000 0.1227483016 2.9224622079 1.5451176123 0.2551223726 0.3294770391 0.7272940313 -0.545344705425 +1413393957805760512.0000000000 0.0908222529 2.9320551131 1.5293233876 0.2503095255 0.3104358130 0.7322898524 -0.552020216575 +1413393957855760384.0000000000 0.0603561320 2.9422757046 1.5113511304 0.2458232620 0.2913087390 0.7388494950 -0.555708166424 +1413393957905760512.0000000000 0.0319050562 2.9538317423 1.4929238070 0.2427047752 0.2726885655 0.7463400479 -0.556517628795 +1413393957955760384.0000000000 0.0057009594 2.9662780248 1.4747030991 0.2407655926 0.2540494579 0.7549199137 -0.554605018234 +1413393958005760512.0000000000 -0.0181791094 2.9791491953 1.4586905072 0.2381735858 0.2387389502 0.7639027284 -0.550208758767 +1413393958055760384.0000000000 -0.0394215550 2.9915259829 1.4463774902 0.2346663462 0.2266270668 0.7721871685 -0.545251185547 +1413393958105760512.0000000000 -0.0578480927 3.0027488973 1.4393037838 0.2297675858 0.2182543096 0.7781805580 -0.542224060631 +1413393958155760384.0000000000 -0.0738589112 3.0118820647 1.4370261997 0.2232859133 0.2131335121 0.7825891518 -0.540621611171 +1413393958205760512.0000000000 -0.0881643558 3.0179787867 1.4398488168 0.2178264520 0.2092366331 0.7853805089 -0.5403231667 +1413393958255760384.0000000000 -0.1006143768 3.0211160702 1.4469252311 0.2100545669 0.2088761901 0.7859339463 -0.542729811357 +1413393958305760512.0000000000 -0.1111836980 3.0220942006 1.4572183071 0.2005341489 0.2115073846 0.7863857199 -0.544654184725 +1413393958355760384.0000000000 -0.1203088319 3.0218100619 1.4700380762 0.1897336125 0.2166224180 0.7859137902 -0.547188631654 +1413393958405760512.0000000000 -0.1286652531 3.0207970896 1.4817554217 0.1810306515 0.2213546367 0.7865476503 -0.547332460027 +1413393958455760384.0000000000 -0.1366849232 3.0192799079 1.4909290003 0.1749120513 0.2248825068 0.7874769171 -0.54654710454 +1413393958505760512.0000000000 -0.1449641244 3.0169997210 1.4974662989 0.1698617169 0.2282955360 0.7898936349 -0.54322756827 +1413393958555760384.0000000000 -0.1536164124 3.0142788976 1.5006112507 0.1659824691 0.2312174966 0.7935447486 -0.537842933602 +1413393958605760512.0000000000 -0.1625221521 3.0111350229 1.5004927986 0.1630784797 0.2337949253 0.7974819517 -0.531759230297 +1413393958655760384.0000000000 -0.1721149334 3.0070193449 1.4972000810 0.1615448111 0.2357601682 0.8009087260 -0.526180225543 +1413393958705760512.0000000000 -0.1826713524 3.0016052631 1.4912555880 0.1609003438 0.2372608704 0.8034718968 -0.52177703073 +1413393958755760384.0000000000 -0.1946774282 2.9939803881 1.4838059890 0.1620847685 0.2380516910 0.8025965492 -0.5223970707 +1413393958805760512.0000000000 -0.2080134849 2.9844645449 1.4747348228 0.1653027449 0.2377593098 0.7990815163 -0.526891111534 +1413393958855760384.0000000000 -0.2221963063 2.9734707631 1.4639068688 0.1692289269 0.2371153731 0.7943854060 -0.533000653684 +1413393958905760512.0000000000 -0.2370435674 2.9611194065 1.4503857121 0.1734765945 0.2362543146 0.7897726275 -0.538840390835 +1413393958955760384.0000000000 -0.2523050719 2.9476664596 1.4338943023 0.1760930242 0.2365792073 0.7856526087 -0.543848787754 +1413393959005760512.0000000000 -0.2677165873 2.9332148100 1.4155450218 0.1767675424 0.2382407667 0.7811848651 -0.549313006999 +1413393959055760384.0000000000 -0.2826689646 2.9183915331 1.3957866501 0.1738654856 0.2425015847 0.7757251981 -0.556070311478 +1413393959105760512.0000000000 -0.2977366113 2.9037150255 1.3755017859 0.1696163978 0.2475042481 0.7699664166 -0.563137320781 +1413393959155760384.0000000000 -0.3131653088 2.8899685955 1.3558875191 0.1666263732 0.2514305721 0.7638007782 -0.570637091691 +1413393959205760512.0000000000 -0.3291621926 2.8777090335 1.3365821638 0.1674936383 0.2522909793 0.7590347579 -0.576334433415 +1413393959255760384.0000000000 -0.3456525780 2.8674243172 1.3173662400 0.1731245919 0.2502131789 0.7565833288 -0.578794356799 +1413393959305760512.0000000000 -0.3619305498 2.8589075739 1.2981440585 0.1775545329 0.2488832897 0.7576964915 -0.576565280592 +1413393959355760384.0000000000 -0.3780378435 2.8518122686 1.2795600146 0.1811447162 0.2477796068 0.7606937290 -0.571958834916 +1413393959405760512.0000000000 -0.3939805792 2.8457504766 1.2623174700 0.1841153916 0.2467779252 0.7636078329 -0.567543175184 +1413393959455760384.0000000000 -0.4095083739 2.8405134521 1.2464491763 0.1860747137 0.2464063532 0.7660358787 -0.563781112266 +1413393959505760512.0000000000 -0.4246844691 2.8358793531 1.2322738323 0.1894531396 0.2450711488 0.7664328753 -0.562697332135 +1413393959555760384.0000000000 -0.4391550141 2.8315309353 1.2194301040 0.1917858430 0.2439163768 0.7653845891 -0.563834569962 +1413393959605760512.0000000000 -0.4531571101 2.8274499963 1.2096278417 0.1965423520 0.2408414734 0.7583986104 -0.572885709626 +1413393959655760384.0000000000 -0.4660425833 2.8243297853 1.2018092821 0.2026166938 0.2366386485 0.7483624289 -0.585578603181 +1413393959705760512.0000000000 -0.4768308130 2.8231734149 1.1946359738 0.2062480062 0.2340446298 0.7395479072 -0.596450973835 +1413393959755760384.0000000000 -0.4853591431 2.8245100649 1.1876644397 0.2096488326 0.2318794328 0.7328073296 -0.604377955723 +1413393959805760512.0000000000 -0.4912296309 2.8288068895 1.1793317411 0.2105600081 0.2318130308 0.7335931168 -0.603132108785 +1413393959855760384.0000000000 -0.4943592529 2.8359406791 1.1697087012 0.2074018799 0.2350306502 0.7415154712 -0.593211479646 +1413393959905760512.0000000000 -0.4955322596 2.8452697767 1.1608898694 0.2050726361 0.2378556535 0.7502660730 -0.581782366259 +1413393959955760384.0000000000 -0.4949850735 2.8559971924 1.1530589842 0.2029256535 0.2401526840 0.7594133461 -0.569595678777 +1413393960005760512.0000000000 -0.4931654632 2.8673447911 1.1465322789 0.2001134029 0.2428071746 0.7671927518 -0.558940590326 +1413393960055760384.0000000000 -0.4904073605 2.8787102953 1.1410579223 0.1977783417 0.2450335626 0.7738743980 -0.549509505712 +1413393960105760512.0000000000 -0.4871177150 2.8894844232 1.1368890940 0.1960347508 0.2465799433 0.7794433310 -0.541513436468 +1413393960155760384.0000000000 -0.4836058763 2.8994166196 1.1333073986 0.1936846503 0.2483570373 0.7852983931 -0.533021080252 +1413393960205760512.0000000000 -0.4802274501 2.9081038194 1.1301402614 0.1913007231 0.2504827855 0.7910211999 -0.524354716564 +1413393960255760384.0000000000 -0.4770727561 2.9151522276 1.1266162880 0.1877520648 0.2529134223 0.7981272231 -0.513592152178 +1413393960305760512.0000000000 -0.4748099249 2.9197267070 1.1240532362 0.1855394216 0.2543845043 0.8025220120 -0.506776151044 +1413393960355760384.0000000000 -0.4738258716 2.9212754839 1.1227140517 0.1846341248 0.2546110876 0.8036496282 -0.505203631427 +1413393960405760512.0000000000 -0.4740895190 2.9194848763 1.1232353492 0.1858067599 0.2516011183 0.8003073470 -0.511547530095 +1413393960455760384.0000000000 -0.4748240568 2.9148419597 1.1238113262 0.1865568861 0.2467435424 0.7959192028 -0.520410198887 +1413393960505760512.0000000000 -0.4757680821 2.9082018126 1.1225057186 0.1861186084 0.2399176602 0.7918030748 -0.529950253038 +1413393960555760384.0000000000 -0.4761909184 2.9005795754 1.1167041533 0.1834753711 0.2314617413 0.7900874779 -0.537144326851 +1413393960605760512.0000000000 -0.4758610124 2.8920547345 1.1055879606 0.1787184393 0.2210993470 0.7894355660 -0.544027835093 +1413393960655760384.0000000000 -0.4747004705 2.8828455683 1.0887464694 0.1722018011 0.2095135365 0.7899512878 -0.549934160225 +1413393960705760512.0000000000 -0.4727385480 2.8735269486 1.0658196723 0.1644296422 0.1968874291 0.7919003443 -0.554158892131 +1413393960755760384.0000000000 -0.4702475300 2.8638752743 1.0380267138 0.1556464536 0.1838361202 0.7950223999 -0.556702654987 +1413393960805760512.0000000000 -0.4672170936 2.8540037612 1.0069167281 0.1458335232 0.1708200380 0.7987800291 -0.558125042652 +1413393960855760384.0000000000 -0.4639932714 2.8440070864 0.9731435383 0.1359663195 0.1600706868 0.8054043628 -0.55426920142 +1413393960905760512.0000000000 -0.4608541201 2.8332021718 0.9399021102 0.1264344616 0.1512352431 0.8134037765 -0.547281028873 +1413393960955760384.0000000000 -0.4579691854 2.8205503998 0.9103189279 0.1153479829 0.1457869674 0.8194104720 -0.542224567237 +1413393961005760512.0000000000 -0.4560343845 2.8057853549 0.8841843067 0.1059592380 0.1420690023 0.8245385318 -0.537331599661 +1413393961055760384.0000000000 -0.4553457838 2.7890635619 0.8617003518 0.1001374709 0.1376784167 0.8268657452 -0.536013227332 +1413393961105760512.0000000000 -0.4561013587 2.7698326678 0.8435117133 0.0985375877 0.1327228204 0.8250686062 -0.540311754369 +1413393961155760384.0000000000 -0.4579440454 2.7487077624 0.8290244640 0.0990890618 0.1282780085 0.8210858402 -0.547306270247 +1413393961205760512.0000000000 -0.4604687041 2.7255726640 0.8202595893 0.0985844934 0.1259481982 0.8138577951 -0.558617613774 +1413393961255760384.0000000000 -0.4630865441 2.7023685021 0.8183700968 0.0953115121 0.1273738256 0.7991587747 -0.579686878499 +1413393961305760512.0000000000 -0.4658634346 2.6798109900 0.8205818057 0.0909017149 0.1299101664 0.7821435117 -0.60258754884 +1413393961355760384.0000000000 -0.4687444447 2.6598253611 0.8269968700 0.0855123379 0.1331954503 0.7631118087 -0.626583577413 +1413393961405760512.0000000000 -0.4724126138 2.6433377662 0.8347399329 0.0838922081 0.1337021949 0.7471404665 -0.645652339757 +1413393961455760384.0000000000 -0.4770103593 2.6316220983 0.8457175664 0.0854824372 0.1323501421 0.7387577985 -0.655296198665 +1413393961505760512.0000000000 -0.4818864904 2.6257786018 0.8581461681 0.0894891531 0.1298487214 0.7418142676 -0.651799504007 +1413393961555760384.0000000000 -0.4864658101 2.6269705492 0.8722747107 0.0971729541 0.1257504245 0.7505139332 -0.641461677573 +1413393961605760512.0000000000 -0.4894601706 2.6348249911 0.8884737123 0.1020508051 0.1232542381 0.7623782499 -0.627035429663 +1413393961655760384.0000000000 -0.4919921799 2.6452384481 0.9086389332 0.1069572678 0.1208597193 0.7757857080 -0.610007874004 +1413393961705760512.0000000000 -0.4936685207 2.6580546935 0.9352848482 0.1099967745 0.1193982700 0.7839044209 -0.599281754742 +1413393961755760384.0000000000 -0.4945274737 2.6716522996 0.9681942694 0.1132488647 0.1175363844 0.7863745835 -0.595797706796 +1413393961805760512.0000000000 -0.4939586127 2.6868673860 1.0051180853 0.1138565401 0.1178013107 0.7903022322 -0.590408266568 +1413393961855760384.0000000000 -0.4920167540 2.7033852448 1.0457998608 0.1141111915 0.1180434549 0.7938999380 -0.585463292783 +1413393961905760512.0000000000 -0.4889203762 2.7208663892 1.0892463338 0.1137929275 0.1187895519 0.7981075454 -0.579624497331 +1413393961955760384.0000000000 -0.4847406032 2.7387109682 1.1361613682 0.1134499859 0.1189963502 0.8017459210 -0.574606341345 +1413393962005760512.0000000000 -0.4797239733 2.7566369102 1.1853963983 0.1128550814 0.1196540350 0.8056785821 -0.569059456395 +1413393962055760384.0000000000 -0.4738951644 2.7737440699 1.2381855187 0.1110703131 0.1206387585 0.8094623113 -0.563808870165 +1413393962105760512.0000000000 -0.4677932253 2.7892505711 1.2955795361 0.1104061792 0.1206099821 0.8129675597 -0.558880537113 +1413393962155760384.0000000000 -0.4613135334 2.8029857956 1.3560995179 0.1088275622 0.1217933612 0.8165666852 -0.553662160095 +1413393962205760512.0000000000 -0.4543172447 2.8151216101 1.4201355418 0.1070508152 0.1222814641 0.8195298358 -0.549507247246 +1413393962255760384.0000000000 -0.4473465953 2.8253850495 1.4865541996 0.1060180883 0.1222970016 0.8217940483 -0.546313234807 +1413393962305760512.0000000000 -0.4404824196 2.8336821670 1.5542840153 0.1051128978 0.1228326853 0.8244703723 -0.542320952328 +1413393962355760384.0000000000 -0.4335732786 2.8402693772 1.6206705690 0.1044961222 0.1230215654 0.8287533596 -0.535830312529 +1413393962405760512.0000000000 -0.4267903715 2.8450309116 1.6835600935 0.1040462829 0.1234453742 0.8339726763 -0.527660104345 +1413393962455760384.0000000000 -0.4204257495 2.8477742967 1.7404952394 0.1040215511 0.1253215674 0.8409465026 -0.516026163494 +1413393962505760512.0000000000 -0.4149563460 2.8475749098 1.7915980628 0.1048882640 0.1288763486 0.8473300606 -0.504401731978 +1413393962555760384.0000000000 -0.4106293239 2.8441510233 1.8369465452 0.1073456305 0.1342577219 0.8524156647 -0.493800885349 +1413393962605760512.0000000000 -0.4076959659 2.8367717537 1.8769039058 0.1128410570 0.1401758921 0.8548464872 -0.486677612454 +1413393962655760384.0000000000 -0.4062685209 2.8249990986 1.9129698774 0.1223615793 0.1462830661 0.8544329773 -0.483294109037 +1413393962705760512.0000000000 -0.4064799585 2.8080116453 1.9465973741 0.1352919731 0.1529669455 0.8511627724 -0.48354847794 +1413393962755760384.0000000000 -0.4076787069 2.7862726763 1.9783000858 0.1504786169 0.1604574749 0.8447684960 -0.487827605519 +1413393962805760512.0000000000 -0.4097030866 2.7598838714 2.0083347461 0.1687553121 0.1679468437 0.8362468105 -0.493970418388 +1413393962855760384.0000000000 -0.4117918995 2.7294190544 2.0362069913 0.1885135384 0.1766011227 0.8269213791 -0.499475446991 +1413393962905760512.0000000000 -0.4132048973 2.6954259445 2.0623449413 0.2087587866 0.1857826087 0.8161934528 -0.505700345004 +1413393962955760384.0000000000 -0.4130885704 2.6590821913 2.0855149482 0.2281389186 0.1972415326 0.8055354556 -0.510059841056 +1413393963005760512.0000000000 -0.4111975654 2.6199948805 2.1058155181 0.2455890232 0.2110600274 0.7951754038 -0.512675115128 +1413393963055760384.0000000000 -0.4068308238 2.5785004060 2.1235002006 0.2614461553 0.2264240865 0.7845671398 -0.514618736626 +1413393963105760512.0000000000 -0.4002070329 2.5347171928 2.1387211661 0.2775174826 0.2417447754 0.7734142525 -0.51611423579 +1413393963155760384.0000000000 -0.3907981045 2.4887597316 2.1515370747 0.2903983805 0.2589332160 0.7619716462 -0.517708007122 +1413393963205760512.0000000000 -0.3780293568 2.4407879505 2.1617259267 0.2987601364 0.2787233175 0.7501450844 -0.519940424916 +1413393963255760384.0000000000 -0.3620951687 2.3916753363 2.1694975356 0.3054665996 0.2990600322 0.7375732122 -0.522722689684 +1413393963305760512.0000000000 -0.3435578697 2.3418473743 2.1743273698 0.3116357730 0.3187553112 0.7260436556 -0.523582664602 +1413393963355760384.0000000000 -0.3230705180 2.2913848559 2.1762918564 0.3188043204 0.3375450381 0.7150729104 -0.522587681904 +1413393963405760512.0000000000 -0.3004253558 2.2408599536 2.1747996555 0.3260961183 0.3553572229 0.7056886304 -0.519024202375 +1413393963455760384.0000000000 -0.2758465898 2.1904960153 2.1706161584 0.3343442009 0.3719980964 0.6971933120 -0.513568746454 +1413393963505760512.0000000000 -0.2492473027 2.1397597917 2.1641365159 0.3413176844 0.3882272247 0.6882857749 -0.508964195639 +1413393963555760384.0000000000 -0.2210550199 2.0888172415 2.1552055159 0.3480397685 0.4032076738 0.6798448861 -0.504086125712 +1413393963605760512.0000000000 -0.1914758678 2.0376666744 2.1443351558 0.3553982056 0.4166931566 0.6707574788 -0.500143312707 +1413393963655760384.0000000000 -0.1601274805 1.9867361005 2.1309361190 0.3633516444 0.4284405616 0.6622170426 -0.495865764308 +1413393963705760512.0000000000 -0.1271156014 1.9359273392 2.1149582728 0.3714201096 0.4393500261 0.6538063501 -0.491483380514 +1413393963755760384.0000000000 -0.0926992247 1.8852542434 2.0967669574 0.3801025526 0.4492960924 0.6460450008 -0.48608736642 +1413393963805760512.0000000000 -0.0564225918 1.8346644398 2.0770144297 0.3890821388 0.4585545107 0.6388902308 -0.479752147511 +1413393963855760384.0000000000 -0.0180611426 1.7841376425 2.0545689476 0.3970023446 0.4681145884 0.6328358918 -0.471992165812 +1413393963905760512.0000000000 0.0222480202 1.7336209303 2.0299148057 0.4044038598 0.4778714043 0.6273181883 -0.463215208981 +1413393963955760384.0000000000 0.0640976183 1.6831241733 2.0029114173 0.4113273497 0.4879782312 0.6224514130 -0.453035645083 +1413393964005760512.0000000000 0.1073038195 1.6318785330 1.9734924130 0.4172682078 0.4982447631 0.6175555920 -0.443017482234 +1413393964055760384.0000000000 0.1514627379 1.5798597273 1.9432591861 0.4233524982 0.5083515921 0.6114821917 -0.434097742723 +1413393964105760512.0000000000 0.1968404866 1.5267836346 1.9116809798 0.4291332628 0.5186158789 0.6040163456 -0.426669037013 +1413393964155760384.0000000000 0.2426924673 1.4726339600 1.8783888040 0.4327059349 0.5302529305 0.5950457213 -0.421328842132 +1413393964205760512.0000000000 0.2890757145 1.4177212174 1.8446338809 0.4355337674 0.5421117154 0.5846978381 -0.41779619869 +1413393964255760384.0000000000 0.3361771203 1.3624496079 1.8111939692 0.4370094774 0.5549844329 0.5737108948 -0.414573039548 +1413393964305760512.0000000000 0.3841189324 1.3069971124 1.7784268616 0.4370952150 0.5682183820 0.5631477144 -0.411023472772 +1413393964355760384.0000000000 0.4324349540 1.2518180217 1.7466202836 0.4384595568 0.5796658366 0.5537863316 -0.406277533037 +1413393964405760512.0000000000 0.4812694987 1.1971902939 1.7163352365 0.4393805087 0.5914122544 0.5436657754 -0.401999799386 +1413393964455760384.0000000000 0.5306591375 1.1433783725 1.6873141986 0.4409671783 0.6018181788 0.5341346117 -0.397571432363 +1413393964505760512.0000000000 0.5801102329 1.0905905596 1.6597028788 0.4424579191 0.6117135476 0.5250244118 -0.392920974971 +1413393964555760384.0000000000 0.6296997111 1.0390178480 1.6339172702 0.4443494344 0.6210200104 0.5146129938 -0.389950244846 +1413393964605760512.0000000000 0.6796851044 0.9890356326 1.6089912314 0.4453987670 0.6303464594 0.5043736181 -0.387156987332 +1413393964655760384.0000000000 0.7300731843 0.9409788271 1.5853062309 0.4468086042 0.6390055957 0.4936203299 -0.38519201681 +1413393964705760512.0000000000 0.7804818523 0.8955235503 1.5631845180 0.4502663639 0.6462104746 0.4829802886 -0.382625489079 +1413393964755760384.0000000000 0.8314647707 0.8523849533 1.5421431766 0.4511423223 0.6548130818 0.4727694737 -0.379709701777 +1413393964805760512.0000000000 0.8830641662 0.8118190871 1.5220239809 0.4504083355 0.6643290390 0.4632685586 -0.375741269786 +1413393964855760384.0000000000 0.9354395323 0.7741657867 1.5025785441 0.4491063848 0.6737781514 0.4555835305 -0.369824424051 +1413393964905760512.0000000000 0.9882944336 0.7398592731 1.4838962512 0.4458047290 0.6849681149 0.4479746352 -0.362485242999 +1413393964955760384.0000000000 1.0414561173 0.7086975248 1.4660812670 0.4387636913 0.6979162067 0.4410950267 -0.354731685939 +1413393965005760512.0000000000 1.0944051426 0.6810423275 1.4495324406 0.4288539476 0.7122963050 0.4322968577 -0.34905256399 +1413393965055760384.0000000000 1.1461248196 0.6579666156 1.4344719676 0.4184495491 0.7266771194 0.4221720631 -0.344399605242 +1413393965105760512.0000000000 1.1966509943 0.6399959555 1.4206325244 0.4068351217 0.7412658264 0.4111931896 -0.34048541701 +1413393965155760384.0000000000 1.2453704198 0.6285337776 1.4085707123 0.3973159379 0.7543493129 0.4000280072 -0.33626589646 +1413393965205760512.0000000000 1.2926129984 0.6240694104 1.3972167684 0.3905285714 0.7655540443 0.3912374461 -0.329162119531 +1413393965255760384.0000000000 1.3369760920 0.6279793229 1.3873045138 0.3854307255 0.7753446821 0.3871744062 -0.316827648802 +1413393965305760512.0000000000 1.3798643460 0.6392311029 1.3795457013 0.3837609740 0.7819549857 0.3870173293 -0.302475622335 +1413393965355760384.0000000000 1.4195400131 0.6581779297 1.3725350886 0.3859475222 0.7851087596 0.3921171805 -0.284416705699 +1413393965405760512.0000000000 1.4553705828 0.6844316783 1.3672541760 0.3945010330 0.7830576659 0.4019494839 -0.263867844373 +1413393965455760384.0000000000 1.4862340905 0.7169791801 1.3641427575 0.4070533269 0.7769464405 0.4142905197 -0.242950988631 +1413393965505760512.0000000000 1.5118569858 0.7543438199 1.3629316547 0.4254005972 0.7651773760 0.4296078477 -0.221302987682 +1413393965555760384.0000000000 1.5310534903 0.7947667730 1.3631893875 0.4438065753 0.7514462355 0.4452594854 -0.200270490693 +1413393965605760512.0000000000 1.5433383814 0.8357735353 1.3652181557 0.4598349647 0.7386511289 0.4567428307 -0.185289777441 +1413393965655760384.0000000000 1.5483642256 0.8761084880 1.3685829177 0.4731832135 0.7274185558 0.4651767467 -0.174844174949 +1413393965705760512.0000000000 1.5455027368 0.9142461238 1.3743068300 0.4838045220 0.7196695824 0.4665547437 -0.17417103011 +1413393965755760384.0000000000 1.5354423267 0.9493210042 1.3819752193 0.4903232538 0.7167166701 0.4605492258 -0.183833436128 +1413393965805760512.0000000000 1.5190191605 0.9822345653 1.3912916777 0.4992301168 0.7122670454 0.4518896340 -0.198092668052 +1413393965855760384.0000000000 1.4980039683 1.0132303004 1.4010785407 0.5091332455 0.7067568589 0.4422149068 -0.213831842608 +1413393965905760512.0000000000 1.4746127937 1.0424755036 1.4076394926 0.5166832541 0.7019996519 0.4365929413 -0.222758854573 +1413393965955760384.0000000000 1.4491907345 1.0703318998 1.4103707725 0.5248098929 0.6959313884 0.4361910026 -0.223587764051 +1413393966005760512.0000000000 1.4218148316 1.0961836836 1.4102822139 0.5317730102 0.6902863689 0.4379986180 -0.221086872357 +1413393966055760384.0000000000 1.3918648660 1.1191399392 1.4103122043 0.5360990786 0.6866029584 0.4399358923 -0.218244280547 +1413393966105760512.0000000000 1.3593001812 1.1378294674 1.4132036412 0.5360263373 0.6867451749 0.4384120470 -0.221024223813 +1413393966155760384.0000000000 1.3248724208 1.1526374600 1.4190034932 0.5330835452 0.6894837135 0.4358519583 -0.224649088618 +1413393966205760512.0000000000 1.2878556963 1.1644449890 1.4282003692 0.5313672622 0.6911581827 0.4339313599 -0.227272466517 +1413393966255760384.0000000000 1.2489092055 1.1732330278 1.4409434949 0.5295283214 0.6925598818 0.4331925979 -0.228702295641 +1413393966305760512.0000000000 1.2077153251 1.1800414276 1.4562082970 0.5309663487 0.6910126798 0.4361792595 -0.224329816438 +1413393966355760384.0000000000 1.1638531786 1.1843685807 1.4752338916 0.5359117222 0.6863356329 0.4401560666 -0.219099662537 +1413393966405760512.0000000000 1.1177892172 1.1849448599 1.4989256507 0.5449694648 0.6782397015 0.4432754227 -0.215652705357 +1413393966455760384.0000000000 1.0697095158 1.1808245295 1.5257018364 0.5530784789 0.6713887060 0.4425871380 -0.217848633269 +1413393966505760512.0000000000 1.0195619433 1.1721043579 1.5544938121 0.5605671210 0.6653537737 0.4383096533 -0.225728833952 +1413393966555760384.0000000000 0.9685057051 1.1590321949 1.5821933837 0.5667039485 0.6601984952 0.4322036195 -0.237032936324 +1413393966605760512.0000000000 0.9175350837 1.1422815571 1.6070084722 0.5716369092 0.6559386585 0.4263757568 -0.247344768154 +1413393966655760384.0000000000 0.8669240599 1.1220354473 1.6283960714 0.5751767646 0.6529091478 0.4212392813 -0.25581009008 +1413393966705760512.0000000000 0.8179650468 1.0978783837 1.6463453255 0.5781606002 0.6503715528 0.4166292725 -0.262996602548 +1413393966755760384.0000000000 0.7706594287 1.0702205327 1.6612209599 0.5801758864 0.6487651946 0.4127875156 -0.268525846094 +1413393966805760512.0000000000 0.7252571580 1.0390685154 1.6729055716 0.5815979699 0.6475993182 0.4103377927 -0.2719959932 +1413393966855760384.0000000000 0.6819142155 1.0044806147 1.6814265363 0.5793071366 0.6498726218 0.4083227069 -0.274483850147 +1413393966905760512.0000000000 0.6406932839 0.9665792256 1.6867956020 0.5714323932 0.6570742100 0.4068667611 -0.276003516733 +1413393966955760384.0000000000 0.6015722698 0.9257022777 1.6900292277 0.5607194447 0.6670412386 0.4031344870 -0.279521512212 +1413393967005760512.0000000000 0.5641784304 0.8828410747 1.6910587966 0.5475328276 0.6799005839 0.3973204774 -0.282983103599 +1413393967055760384.0000000000 0.5279791494 0.8391629851 1.6904231471 0.5364815269 0.6910505275 0.3911470811 -0.285728368699 +1413393967105760512.0000000000 0.4930960953 0.7951841253 1.6876988242 0.5277571659 0.7002147393 0.3854916536 -0.287346267982 +1413393967155760384.0000000000 0.4596100692 0.7515528747 1.6833059362 0.5225372952 0.7069439521 0.3804502767 -0.287128212993 +1413393967205760512.0000000000 0.4274099588 0.7085541941 1.6775234395 0.5189368238 0.7125321019 0.3752659494 -0.286667130678 +1413393967255760384.0000000000 0.3966922466 0.6667872799 1.6704581281 0.5201116904 0.7153800925 0.3695158352 -0.284909108647 +1413393967305760512.0000000000 0.3675661237 0.6261321886 1.6614732920 0.5226502135 0.7179638901 0.3631448456 -0.281940468783 +1413393967355760384.0000000000 0.3398259380 0.5870330999 1.6507344166 0.5279516562 0.7195346008 0.3563457939 -0.276685167939 +1413393967405760512.0000000000 0.3137844886 0.5490463377 1.6384148284 0.5344293866 0.7211866466 0.3475970822 -0.271019039885 +1413393967455760384.0000000000 0.2892159871 0.5118500669 1.6245941969 0.5407972214 0.7235704166 0.3365123917 -0.265976742852 +1413393967505760512.0000000000 0.2662960964 0.4750971167 1.6096524516 0.5451220451 0.7275446402 0.3239056920 -0.26192719444 +1413393967555760384.0000000000 0.2456553646 0.4389148837 1.5945374151 0.5493652475 0.7320160158 0.3123677374 -0.254512817175 +1413393967605760512.0000000000 0.2271699192 0.4029520042 1.5802543746 0.5515304059 0.7379716115 0.2997495765 -0.247714156456 +1413393967655760384.0000000000 0.2110940463 0.3673562319 1.5668674976 0.5534974841 0.7439823755 0.2873023378 -0.239975262965 +1413393967705760512.0000000000 0.1969389780 0.3329824597 1.5549447638 0.5567432696 0.7491669244 0.2758329346 -0.229569256289 +1413393967755760384.0000000000 0.1850528695 0.2988092592 1.5445531806 0.5590644197 0.7546743955 0.2643810476 -0.2191259753 +1413393967805760512.0000000000 0.1757594401 0.2644135533 1.5368292391 0.5611952252 0.7598921426 0.2532582846 -0.208528396463 +1413393967855760384.0000000000 0.1688577781 0.2295807463 1.5313630284 0.5613206006 0.7659184230 0.2432236920 -0.197814024713 +1413393967905760512.0000000000 0.1639962507 0.1941451918 1.5282313486 0.5551554316 0.7756456937 0.2350178370 -0.186929989483 +1413393967955760384.0000000000 0.1598940132 0.1596559188 1.5288120597 0.5460804508 0.7862561753 0.2290353748 -0.176465762044 +1413393968005760512.0000000000 0.1562848297 0.1265641752 1.5332840951 0.5357116488 0.7967071799 0.2241815698 -0.167371809543 +1413393968055760384.0000000000 0.1529624439 0.0959690280 1.5429885271 0.5313329422 0.8023955364 0.2212556691 -0.157774004685 +1413393968105760512.0000000000 0.1492657609 0.0674520985 1.5574027821 0.5295302708 0.8056710747 0.2182753394 -0.151154516979 +1413393968155760384.0000000000 0.1448244487 0.0414640697 1.5760251894 0.5296218059 0.8072171742 0.2147053644 -0.147657654655 +1413393968205760512.0000000000 0.1395575458 0.0176450645 1.5969028909 0.5293916577 0.8087140676 0.2094966687 -0.147774068441 +1413393968255760384.0000000000 0.1340022586 -0.0044562552 1.6175267491 0.5274334570 0.8108619468 0.2048442094 -0.149518231557 +1413393968305760512.0000000000 0.1285090290 -0.0245956190 1.6361052728 0.5251318643 0.8128164920 0.2032294461 -0.149210145577 +1413393968355760384.0000000000 0.1232430971 -0.0419359367 1.6517670756 0.5243802495 0.8135158958 0.2071835298 -0.142450784808 +1413393968405760512.0000000000 0.1175934143 -0.0568642534 1.6649535844 0.5247195619 0.8130659648 0.2144717694 -0.132646064375 +1413393968455760384.0000000000 0.1108191762 -0.0696510848 1.6762746936 0.5262139946 0.8116252657 0.2213825417 -0.123907344789 +1413393968505760512.0000000000 0.1023873888 -0.0806122556 1.6860774675 0.5315909700 0.8074510538 0.2269327564 -0.118048127454 +1413393968555760384.0000000000 0.0921135107 -0.0901404221 1.6935293092 0.5370803623 0.8032474127 0.2308867202 -0.114147276751 +1413393968605760512.0000000000 0.0798560254 -0.0981818024 1.6980224269 0.5399581668 0.8009743517 0.2338919794 -0.110362167179 +1413393968655760384.0000000000 0.0656480895 -0.1050848414 1.6999306547 0.5408289481 0.8005653265 0.2346140761 -0.107496242839 +1413393968705760512.0000000000 0.0495377075 -0.1113154812 1.6997321670 0.5398568235 0.8020446134 0.2325484727 -0.105831262191 +1413393968755760384.0000000000 0.0313250789 -0.1166522050 1.6974079386 0.5393038228 0.8035075315 0.2294029984 -0.104409280586 +1413393968805760512.0000000000 0.0110328028 -0.1203710575 1.6930980237 0.5426233733 0.8029092591 0.2240387099 -0.103456526419 +1413393968855760384.0000000000 -0.0109744617 -0.1227245442 1.6870104536 0.5496529104 0.8002734959 0.2165684706 -0.102674764911 +1413393968905760512.0000000000 -0.0345910612 -0.1239184693 1.6792694918 0.5588965624 0.7965792662 0.2061913447 -0.102865127833 +1413393968955760384.0000000000 -0.0593857702 -0.1247671920 1.6688740961 0.5669558486 0.7940526437 0.1921211475 -0.105503219926 +1413393969005760512.0000000000 -0.0846763795 -0.1253718391 1.6559193397 0.5733101009 0.7928281631 0.1762103569 -0.108115410842 +1413393969055760384.0000000000 -0.1095146059 -0.1263450397 1.6405843544 0.5796907042 0.7914905931 0.1606182395 -0.108180911421 +1413393969105760512.0000000000 -0.1334106349 -0.1281393233 1.6239964758 0.5858181947 0.7902211698 0.1459012432 -0.105263349471 +1413393969155760384.0000000000 -0.1560379708 -0.1303717305 1.6060947598 0.5916661295 0.7890647050 0.1336352858 -0.0972095313936 +1413393969205760512.0000000000 -0.1776546859 -0.1329838309 1.5883298186 0.5952377962 0.7894537973 0.1221151801 -0.0868478596623 +1413393969255760384.0000000000 -0.1982036961 -0.1367595765 1.5719146905 0.5983875370 0.7899272161 0.1102328295 -0.0761319387993 +1413393969305760512.0000000000 -0.2182116002 -0.1414832909 1.5557931300 0.5978802826 0.7929016763 0.0975043387 -0.0658711123574 +1413393969355760384.0000000000 -0.2377099473 -0.1475164968 1.5407872756 0.5970445681 0.7957326370 0.0838440415 -0.0575980111527 +1413393969405760512.0000000000 -0.2568076554 -0.1547147827 1.5271887837 0.5954734415 0.7987378092 0.0683577761 -0.0525024476939 +1413393969455760384.0000000000 -0.2753252291 -0.1630800551 1.5153320085 0.5943471559 0.8009480918 0.0507619936 -0.0515444719601 +1413393969505760512.0000000000 -0.2928330651 -0.1724488148 1.5047057694 0.5933084484 0.8025053368 0.0309333415 -0.054894424052 +1413393969555760384.0000000000 -0.3081380444 -0.1826163399 1.4944033028 0.5925507906 0.8035366178 0.0130976338 -0.0551445047695 +1413393969605760512.0000000000 -0.3209605440 -0.1938870928 1.4841017175 0.5883614494 0.8067736140 -0.0029121714 -0.0542094072249 +1413393969655760384.0000000000 -0.3304609743 -0.2048182857 1.4751012177 0.5848167060 0.8094057586 -0.0174653374 -0.0504648421281 +1413393969705760512.0000000000 -0.3364499882 -0.2149081118 1.4692652989 0.5808777260 0.8121790029 -0.0296728366 -0.0454517033322 +1413393969755760384.0000000000 -0.3393833576 -0.2252274575 1.4659382350 0.5765066548 0.8150432933 -0.0402235652 -0.0415520370325 +1413393969805760512.0000000000 -0.3386235810 -0.2348014708 1.4683888179 0.5728461412 0.8172686012 -0.0493466629 -0.0385258221444 +1413393969855760384.0000000000 -0.3340477597 -0.2443610863 1.4748825361 0.5708537578 0.8183157514 -0.0566898040 -0.0356592815912 +1413393969905760512.0000000000 -0.3255093291 -0.2531357159 1.4854636952 0.5704599737 0.8184277335 -0.0613099780 -0.0315047630512 +1413393969955760384.0000000000 -0.3128134537 -0.2617643725 1.5003881235 0.5719036274 0.8176491983 -0.0618628753 -0.0234310524837 +1413393970005760512.0000000000 -0.2965763362 -0.2698000687 1.5179915350 0.5708676671 0.8189071226 -0.0580372087 -0.0115288131212 +1413393970055760384.0000000000 -0.2773015380 -0.2768450763 1.5381994621 0.5705749209 0.8197792454 -0.0487364995 0.0055679548717 +1413393970105760512.0000000000 -0.2562997860 -0.2835128520 1.5587564758 0.5679349421 0.8218561187 -0.0385497927 0.0227230122609 +1413393970155760384.0000000000 -0.2351223413 -0.2892941414 1.5785334898 0.5645305122 0.8240567735 -0.0303538120 0.036254391824 +1413393970205760512.0000000000 -0.2146202378 -0.2944471563 1.5964273721 0.5608395206 0.8263310613 -0.0246258722 0.0450508130473 +1413393970255760384.0000000000 -0.1950771538 -0.2986321812 1.6118546243 0.5585715831 0.8276653676 -0.0211616259 0.0501997153509 +1413393970305760512.0000000000 -0.1766434575 -0.3014707368 1.6243764896 0.5573056302 0.8284011897 -0.0189364737 0.0529463255756 +1413393970355760384.0000000000 -0.1595362611 -0.3026977734 1.6344671156 0.5558931416 0.8293204770 -0.0176685907 0.0538347696862 +1413393970405760512.0000000000 -0.1438661766 -0.3025313088 1.6437471188 0.5550582255 0.8298603339 -0.0161120134 0.0546131433635 +1413393970455760384.0000000000 -0.1296136297 -0.3003421994 1.6528784379 0.5557943645 0.8293501917 -0.0144053847 0.05534770854 +1413393970505760512.0000000000 -0.1166236203 -0.2961033285 1.6631271500 0.5607885843 0.8259679840 -0.0129344451 0.0559084365697 +1413393970555760384.0000000000 -0.1051934918 -0.2903755496 1.6741671564 0.5672311741 0.8216115505 -0.0120949953 0.0552898396642 +1413393970605760512.0000000000 -0.0951786214 -0.2836613575 1.6848306688 0.5728146223 0.8176792998 -0.0098892238 0.0564462075729 +1413393970655760384.0000000000 -0.0865682463 -0.2759841266 1.6948663602 0.5793082273 0.8128855677 -0.0065417261 0.0598016501477 +1413393970705760512.0000000000 -0.0792374933 -0.2679968757 1.7017906946 0.5847333243 0.8085717195 -0.0019105419 0.065536735376 +1413393970755760384.0000000000 -0.0732002782 -0.2604138884 1.7042467294 0.5876531182 0.8055458928 0.0051509201 0.0757172066698 +1413393970805760512.0000000000 -0.0692537350 -0.2534874582 1.7029916125 0.5875997462 0.8041766527 0.0140975938 0.0884743318814 +1413393970855760384.0000000000 -0.0684020271 -0.2473314588 1.6986838634 0.5857439921 0.8039183879 0.0218067028 0.100715783312 +1413393970905760512.0000000000 -0.0716510349 -0.2417180334 1.6925798218 0.5841994704 0.8035694030 0.0280615565 0.110452444272 +1413393970955760384.0000000000 -0.0800598728 -0.2364075083 1.6868111562 0.5841016901 0.8028066400 0.0313301890 0.115521139791 +1413393971005760512.0000000000 -0.0943073722 -0.2308603724 1.6821727339 0.5857047713 0.8017180326 0.0311540612 0.11501105002 +1413393971055760384.0000000000 -0.1145413280 -0.2256448827 1.6794025237 0.5899685928 0.7998832641 0.0264930850 0.106873475862 +1413393971105760512.0000000000 -0.1398600871 -0.2208742875 1.6789410149 0.5962617164 0.7968579486 0.0200691514 0.0953236825135 +1413393971155760384.0000000000 -0.1692653489 -0.2171182323 1.6819893789 0.6072836290 0.7896630181 0.0160178052 0.0859205541774 +1413393971205760512.0000000000 -0.2024111840 -0.2151110785 1.6890308969 0.6205014422 0.7804312216 0.0119924851 0.0759028910048 +1413393971255760384.0000000000 -0.2384389064 -0.2155712527 1.6991814000 0.6335257629 0.7706112533 0.0097938393 0.0686111120301 +1413393971305760512.0000000000 -0.2767418350 -0.2198615251 1.7112095694 0.6470118931 0.7597860701 0.0091394502 0.0633814507109 +1413393971355760384.0000000000 -0.3166546082 -0.2281803943 1.7215009358 0.6585983674 0.7500370192 0.0092837031 0.0600539190744 +1413393971405760512.0000000000 -0.3581649901 -0.2414124584 1.7281760599 0.6664562869 0.7432820626 0.0091762684 0.0573026098216 +1413393971455760384.0000000000 -0.4014601228 -0.2598870012 1.7307892856 0.6666943559 0.7434699715 0.0073165330 0.0521297001664 +1413393971505760512.0000000000 -0.4460556555 -0.2834419505 1.7288358103 0.6592588399 0.7505629805 0.0035939634 0.0449452741077 +1413393971555760384.0000000000 -0.4916868224 -0.3119909428 1.7241404562 0.6466902799 0.7619541881 -0.0028374187 0.0347770935524 +1413393971605760512.0000000000 -0.5381290488 -0.3444765558 1.7194434236 0.6333606121 0.7735171623 -0.0143710159 0.0178608123461 +1413393971655760384.0000000000 -0.5843395436 -0.3799387107 1.7157855699 0.6211728638 0.7831617627 -0.0282489385 -0.00198095702906 +1413393971705760512.0000000000 -0.6285453837 -0.4174930590 1.7144394016 0.6130269776 0.7885247373 -0.0439430454 -0.0222636973064 +1413393971755760384.0000000000 -0.6693950466 -0.4568077900 1.7153421602 0.6064587076 0.7915902415 -0.0611090457 -0.0431092817178 +1413393971805760512.0000000000 -0.7053697767 -0.4976582653 1.7176504117 0.6006089093 0.7936872909 -0.0759946161 -0.0596174522468 +1413393971855760384.0000000000 -0.7354796824 -0.5397884804 1.7207603097 0.5954048635 0.7955532873 -0.0872915469 -0.0704854695055 +1413393971905760512.0000000000 -0.7588541783 -0.5828532768 1.7248965670 0.5919041210 0.7975697092 -0.0916634103 -0.0716232478956 +1413393971955760384.0000000000 -0.7754091918 -0.6266234310 1.7298040342 0.5886129350 0.8008131368 -0.0900982347 -0.0641517003813 +1413393972005760512.0000000000 -0.7858489409 -0.6705954998 1.7362506549 0.5861713102 0.8037709390 -0.0865788227 -0.0534750429636 +1413393972055760384.0000000000 -0.7910772898 -0.7147757905 1.7435692257 0.5837997831 0.8068589782 -0.0807097484 -0.0405257837965 +1413393972105760512.0000000000 -0.7924257903 -0.7591416718 1.7506117385 0.5800334887 0.8101813571 -0.0782107527 -0.0324098557302 +1413393972155760384.0000000000 -0.7909784158 -0.8038340801 1.7536893050 0.5721977472 0.8158112197 -0.0786625630 -0.0292231597924 +1413393972205760512.0000000000 -0.7867928768 -0.8485140004 1.7515625790 0.5626250338 0.8224638594 -0.0791363788 -0.0272709542948 +1413393972255760384.0000000000 -0.7796246014 -0.8921639191 1.7447178250 0.5544456131 0.8283037459 -0.0773219929 -0.0228970738922 +1413393972305760512.0000000000 -0.7687252164 -0.9338189946 1.7350404072 0.5531846131 0.8301500309 -0.0689472010 -0.00916480151951 +1413393972355760384.0000000000 -0.7553596783 -0.9731842918 1.7255715914 0.5572987543 0.8282860171 -0.0574995798 0.00736007030456 +1413393972405760512.0000000000 -0.7406183126 -1.0116745928 1.7167102301 0.5603467970 0.8266383174 -0.0468303535 0.0220788879662 +1413393972455760384.0000000000 -0.7255029449 -1.0490121390 1.7088955836 0.5635957277 0.8244785214 -0.0366440480 0.035386963505 +1413393972505760512.0000000000 -0.7106945329 -1.0856275325 1.7010219450 0.5610854390 0.8260039966 -0.0278399563 0.0461027608744 +1413393972555760384.0000000000 -0.6968174179 -1.1209284720 1.6935148087 0.5533626908 0.8309102043 -0.0218784268 0.0538451413256 +1413393972605760512.0000000000 -0.6843533245 -1.1537422010 1.6877186079 0.5469284792 0.8348952741 -0.0181362233 0.0590778928151 +1413393972655760384.0000000000 -0.6736497583 -1.1840482494 1.6829445396 0.5435802625 0.8369110861 -0.0167595019 0.0618017087588 +1413393972705760512.0000000000 -0.6646843726 -1.2114813892 1.6786419148 0.5425519805 0.8374199539 -0.0159111757 0.0641249079352 +1413393972755760384.0000000000 -0.6575469064 -1.2368550359 1.6736662061 0.5424228473 0.8373719107 -0.0159093559 0.0658227184003 +1413393972805760512.0000000000 -0.6522278694 -1.2596945367 1.6685352023 0.5448091877 0.8356840490 -0.0161799414 0.0674783573437 +1413393972855760384.0000000000 -0.6486028810 -1.2804682951 1.6630357822 0.5473300507 0.8338743816 -0.0170420626 0.0692307694866 +1413393972905760512.0000000000 -0.6467641861 -1.2990528100 1.6566588792 0.5491824692 0.8324312039 -0.0169540140 0.0718990109402 +1413393972955760384.0000000000 -0.6466233797 -1.3149343068 1.6501680100 0.5513351339 0.8306806710 -0.0170222054 0.0755608197355 +1413393973005760512.0000000000 -0.6485934000 -1.3285274945 1.6439436312 0.5531427899 0.8290824800 -0.0158697085 0.0800215452298 +1413393973055760384.0000000000 -0.6532632848 -1.3403755872 1.6384664710 0.5578069222 0.8257033881 -0.0149857687 0.0827090025119 +1413393973105760512.0000000000 -0.6605239123 -1.3507059787 1.6328468147 0.5639315681 0.8213932007 -0.0148309333 0.0841096894725 +1413393973155760384.0000000000 -0.6703966322 -1.3596926349 1.6276658828 0.5715922376 0.8160527281 -0.0145515171 0.0844305172465 +1413393973205760512.0000000000 -0.6829302167 -1.3685429199 1.6222084470 0.5804739963 0.8097944868 -0.0139209698 0.0841964098964 +1413393973255760384.0000000000 -0.6980211355 -1.3777330594 1.6172558427 0.5912939410 0.8019821109 -0.0131936065 0.083797958161 +1413393973305760512.0000000000 -0.7157773671 -1.3874956087 1.6122815470 0.6035095285 0.7929690842 -0.0126511306 0.0825604592377 +1413393973355760384.0000000000 -0.7357951701 -1.3983009279 1.6069726334 0.6144695557 0.7846746058 -0.0120643916 0.0810393645199 +1413393973405760512.0000000000 -0.7583161402 -1.4107175541 1.6020892024 0.6254523309 0.7761785680 -0.0114806688 0.0788949083218 +1413393973455760384.0000000000 -0.7832095882 -1.4257950841 1.5972321414 0.6348337691 0.7686891663 -0.0100414086 0.0774740038512 +1413393973505760512.0000000000 -0.8103334468 -1.4441321186 1.5924783762 0.6442962783 0.7608426673 -0.0083762310 0.0770102597934 +1413393973555760384.0000000000 -0.8397526968 -1.4667394232 1.5867667420 0.6505124082 0.7557098286 -0.0077723035 0.0753382573114 +1413393973605760512.0000000000 -0.8714498307 -1.4937893629 1.5810462548 0.6542841901 0.7527728867 -0.0082511475 0.07195205473 +1413393973655760384.0000000000 -0.9056835578 -1.5252344347 1.5760890196 0.6556229004 0.7523602958 -0.0125345242 0.0628926349534 +1413393973705760512.0000000000 -0.9418579878 -1.5616556504 1.5710597112 0.6512063889 0.7570892475 -0.0207497265 0.0481202572994 +1413393973755760384.0000000000 -0.9790359579 -1.6027110807 1.5662129903 0.6420498318 0.7654528129 -0.0313996703 0.0294629490921 +1413393973805760512.0000000000 -1.0158594366 -1.6476501680 1.5619473042 0.6305137653 0.7749129885 -0.0433064523 0.0093168256978 +1413393973855760384.0000000000 -1.0512500657 -1.6956543688 1.5588306042 0.6161631263 0.7853057719 -0.0584170565 -0.0150097948967 +1413393973905760512.0000000000 -1.0832683618 -1.7456099681 1.5570176891 0.6011346458 0.7947256968 -0.0738232657 -0.0399791182274 +1413393973955760384.0000000000 -1.1100740414 -1.7966828072 1.5554142843 0.5827914797 0.8057553650 -0.0865953248 -0.0601134994526 +1413393974005760512.0000000000 -1.1305897840 -1.8484030693 1.5533538905 0.5580845876 0.8214334046 -0.0928916552 -0.0718324110522 +1413393974055760384.0000000000 -1.1440456003 -1.8993881518 1.5514998475 0.5303309823 0.8387460525 -0.0961907202 -0.0774690516119 +1413393974105760512.0000000000 -1.1498805401 -1.9489899770 1.5504869889 0.5005382209 0.8567364194 -0.0962431618 -0.0787492907972 +1413393974155760384.0000000000 -1.1476700977 -1.9936431078 1.5510901690 0.4719474006 0.8734147601 -0.0935820824 -0.0751977512106 +1413393974205760512.0000000000 -1.1371444617 -2.0316495991 1.5535181840 0.4475944691 0.8881684985 -0.0834981723 -0.0619997154456 +1413393974255760384.0000000000 -1.1191288970 -2.0607958904 1.5585774815 0.4292225760 0.8998140786 -0.0668128747 -0.0404801678917 +1413393974305760512.0000000000 -1.0954086638 -2.0799273258 1.5666401825 0.4163991904 0.9077009068 -0.0490783908 -0.0167955225297 +1413393974355760384.0000000000 -1.0684139095 -2.0873867987 1.5783539480 0.4066426797 0.9129883723 -0.0327911283 0.00432493362813 +1413393974405760512.0000000000 -1.0398701314 -2.0828611978 1.5914907174 0.4002155537 0.9159361200 -0.0175394503 0.0241019159965 +1413393974455760384.0000000000 -1.0111766437 -2.0666177665 1.6064766239 0.3993577491 0.9157402902 -0.0010248927 0.0439551903125 +1413393974505760512.0000000000 -0.9840337178 -2.0382751975 1.6242343963 0.4039062550 0.9125057527 0.0162946377 0.0626695569052 +1413393974555760384.0000000000 -0.9599144481 -1.9983304434 1.6439523066 0.4142152383 0.9061051877 0.0329454101 0.0794589522873 +1413393974605760512.0000000000 -0.9405733108 -1.9474931024 1.6657526389 0.4299240488 0.8970199094 0.0461434991 0.0916044314135 +1413393974655760384.0000000000 -0.9268083385 -1.8874656197 1.6888904674 0.4506410031 0.8852696812 0.0569606575 0.0998787334061 +1413393974705760512.0000000000 -0.9190724268 -1.8200805520 1.7127315090 0.4757031751 0.8708309997 0.0653618894 0.105298065774 +1413393974755760384.0000000000 -0.9175922937 -1.7477624922 1.7363844257 0.4999737551 0.8565347380 0.0703024184 0.106920796451 +1413393974805760512.0000000000 -0.9219843086 -1.6722277975 1.7581619554 0.5222767172 0.8428168637 0.0734735894 0.10718393851 +1413393974855760384.0000000000 -0.9325353758 -1.5952061400 1.7774917561 0.5429250573 0.8308338183 0.0700432685 0.100207230219 +1413393974905760512.0000000000 -0.9483821619 -1.5174354239 1.7939698305 0.5603649801 0.8211694663 0.0621523503 0.0883678784447 +1413393974955760384.0000000000 -0.9679793701 -1.4395695939 1.8066102282 0.5757165934 0.8122148813 0.0537811155 0.0772332977972 +1413393975005760512.0000000000 -0.9909892459 -1.3625356018 1.8155011380 0.5891189606 0.8041435492 0.0447145141 0.0655180491446 +1413393975055760384.0000000000 -1.0166794522 -1.2874967196 1.8198546846 0.5985434153 0.7984835351 0.0354644532 0.0539638461568 +1413393975105760512.0000000000 -1.0442453070 -1.2145042444 1.8205711220 0.6055175596 0.7941489497 0.0271068516 0.044058474962 +1413393975155760384.0000000000 -1.0734631976 -1.1439823429 1.8183278779 0.6092075799 0.7920818793 0.0185477534 0.0335916942478 +1413393975205760512.0000000000 -1.1033922155 -1.0757570002 1.8135785816 0.6094157102 0.7923039866 0.0123425283 0.0267310117824 +1413393975255760384.0000000000 -1.1339199262 -1.0102930131 1.8083792324 0.6078455645 0.7937415080 0.0072861760 0.0210973880118 +1413393975305760512.0000000000 -1.1646818705 -0.9471327393 1.8038258030 0.6056988198 0.7954854366 0.0042516774 0.0177139235998 +1413393975355760384.0000000000 -1.1953757809 -0.8857329108 1.8016366096 0.6071928964 0.7942944816 0.0051587518 0.0196583409678 +1413393975405760512.0000000000 -1.2263218810 -0.8269057980 1.8000254098 0.6101904875 0.7918922299 0.0070753163 0.0228955237922 +1413393975455760384.0000000000 -1.2576915502 -0.7708799264 1.7991210175 0.6138919092 0.7888014496 0.0113580469 0.0282841244283 +1413393975505760512.0000000000 -1.2900232168 -0.7174099328 1.7992677207 0.6181227213 0.7852871808 0.0145628777 0.0321911112339 +1413393975555760384.0000000000 -1.3233585961 -0.6676747471 1.7996559941 0.6216555318 0.7822674235 0.0175764596 0.0359603381806 +1413393975605760512.0000000000 -1.3580728008 -0.6211217530 1.8007946616 0.6245294173 0.7798545628 0.0192263705 0.0376857336445 +1413393975655760384.0000000000 -1.3943479487 -0.5783247118 1.8023023226 0.6262648040 0.7785055301 0.0190466736 0.0368613502321 +1413393975705760512.0000000000 -1.4322565560 -0.5392882751 1.8039785581 0.6258610031 0.7791975480 0.0144784186 0.0306522668923 +1413393975755760384.0000000000 -1.4711193793 -0.5035602194 1.8058431557 0.6243564402 0.7807646195 0.0079010386 0.0228739606075 +1413393975805760512.0000000000 -1.5103333116 -0.4712029878 1.8079556364 0.6225449492 0.7824223706 0.0009521614 0.0158780829001 +1413393975855760384.0000000000 -1.5494615969 -0.4417706995 1.8110473061 0.6226834456 0.7823983994 -0.0070863962 0.00823736569779 +1413393975905760512.0000000000 -1.5879946384 -0.4155775008 1.8143060953 0.6224597092 0.7824941900 -0.0156847220 0.000861700227961 +1413393975955760384.0000000000 -1.6250222319 -0.3918265094 1.8170331418 0.6200769359 0.7842757884 -0.0203734346 -0.00100221603062 +1413393976005760512.0000000000 -1.6603974693 -0.3708170485 1.8189223506 0.6154195437 0.7878519257 -0.0234107734 0.000253368288498 +1413393976055760384.0000000000 -1.6942708912 -0.3523092319 1.8176863734 0.6097767343 0.7921922437 -0.0240572821 0.0050030454934 +1413393976105760512.0000000000 -1.7270833078 -0.3359011394 1.8142531967 0.6043897815 0.7962468465 -0.0246070631 0.00992189139751 +1413393976155760384.0000000000 -1.7592145419 -0.3211351314 1.8092019187 0.6008955461 0.7987985815 -0.0259795198 0.0130550190643 +1413393976205760512.0000000000 -1.7909016264 -0.3081916093 1.8015843718 0.5974275860 0.8012849796 -0.0288972710 0.0136970308288 +1413393976255760384.0000000000 -1.8219931819 -0.2965827782 1.7922142562 0.5959743283 0.8022458932 -0.0328582486 0.0116817092079 +1413393976305760512.0000000000 -1.8522292463 -0.2858938015 1.7814408037 0.5962861744 0.8018534872 -0.0375176982 0.00813668317635 +1413393976355760384.0000000000 -1.8811860904 -0.2763872144 1.7712705290 0.5994612018 0.7992870665 -0.0420901419 0.00385651779892 +1413393976405760512.0000000000 -1.9086935354 -0.2686550485 1.7630281975 0.6032611483 0.7962901888 -0.0446976656 -0.000202183439193 +1413393976455760384.0000000000 -1.9344514120 -0.2629451376 1.7573502098 0.6053230176 0.7946636827 -0.0454236233 -0.0055109140529 +1413393976505760512.0000000000 -1.9583052329 -0.2603018529 1.7537705580 0.6034224639 0.7961521359 -0.0436111570 -0.011007883448 +1413393976555760384.0000000000 -1.9799080329 -0.2589475882 1.7523766667 0.6006135447 0.7984496733 -0.0388555921 -0.015222750113 +1413393976605760512.0000000000 -1.9990334571 -0.2589931513 1.7511942375 0.5967955250 0.8014647597 -0.0336379653 -0.0189163319633 +1413393976655760384.0000000000 -2.0158910650 -0.2602575384 1.7484897364 0.5934460490 0.8040471434 -0.0286156217 -0.0226080577621 +1413393976705760512.0000000000 -2.0309586965 -0.2622658738 1.7443655535 0.5918783623 0.8050823951 -0.0258921742 -0.0291879544904 +1413393976755760384.0000000000 -2.0437099294 -0.2648522514 1.7378687978 0.5902634093 0.8061067782 -0.0232618781 -0.0352115725214 +1413393976805760512.0000000000 -2.0539769621 -0.2677787991 1.7285563771 0.5868913646 0.8083765112 -0.0211575298 -0.0404759339966 +1413393976855760384.0000000000 -2.0612637505 -0.2711503395 1.7172379200 0.5802131354 0.8131505414 -0.0178035139 -0.0426842983575 +1413393976905760512.0000000000 -2.0653542087 -0.2752317587 1.7054381174 0.5703671219 0.8202365358 -0.0126714455 -0.0416269872482 +1413393976955760384.0000000000 -2.0666654377 -0.2788075685 1.6947170040 0.5615159051 0.8265052137 -0.0077365149 -0.039104555429 +1413393977005760512.0000000000 -2.0652938935 -0.2823739809 1.6844448448 0.5534971026 0.8322274299 -0.0003057462 -0.0322237321752 +1413393977055760384.0000000000 -2.0618283683 -0.2840402346 1.6750092417 0.5492784953 0.8352871872 0.0074970499 -0.0230704088734 +1413393977105760512.0000000000 -2.0571944833 -0.2834393017 1.6677242116 0.5474943611 0.8365651560 0.0147022835 -0.0138746983522 +1413393977155760384.0000000000 -2.0524231195 -0.2798850788 1.6650220737 0.5496573190 0.8351135027 0.0202116789 -0.00733193664091 +1413393977205760512.0000000000 -2.0476969206 -0.2735984621 1.6668684223 0.5535053074 0.8324779354 0.0247262513 -0.000987032480601 +1413393977255760384.0000000000 -2.0437924011 -0.2653042075 1.6728532760 0.5582803030 0.8291966016 0.0273590524 0.00275344835705 +1413393977305760512.0000000000 -2.0409198549 -0.2555295064 1.6820657766 0.5633722084 0.8256630720 0.0293671648 0.00546040049669 +1413393977355760384.0000000000 -2.0389060984 -0.2453880143 1.6940735316 0.5671082668 0.8230510819 0.0302061268 0.00791961082192 +1413393977405760512.0000000000 -2.0377896935 -0.2346731369 1.7096088597 0.5703731593 0.8207367681 0.0308263326 0.0107402912047 +1413393977455760384.0000000000 -2.0378577321 -0.2236491406 1.7266371583 0.5720665422 0.8195524072 0.0304103729 0.0122037816863 +1413393977505760512.0000000000 -2.0388553967 -0.2124417055 1.7440410441 0.5726863909 0.8190196199 0.0312787594 0.0160872347167 +1413393977555760384.0000000000 -2.0411443242 -0.2011885538 1.7613147645 0.5726498904 0.8190116283 0.0308397319 0.0184652849743 +1413393977605760512.0000000000 -2.0447146904 -0.1900339432 1.7767947950 0.5722398766 0.8192845381 0.0300204841 0.0203258426506 +1413393977655760384.0000000000 -2.0495163238 -0.1790228166 1.7893938031 0.5719813471 0.8194603309 0.0290804949 0.0218272664309 +1413393977705760512.0000000000 -2.0554798620 -0.1675853187 1.7986536301 0.5718501224 0.8195376479 0.0280954442 0.0235823497622 +1413393977755760384.0000000000 -2.0627423374 -0.1555275246 1.8056814000 0.5712585876 0.8199881242 0.0261951534 0.0244318680571 +1413393977805760512.0000000000 -2.0715081769 -0.1430599450 1.8111120658 0.5715141452 0.8198525910 0.0242168710 0.0250370522965 +1413393977855760384.0000000000 -2.0816149580 -0.1304869723 1.8155306649 0.5717089477 0.8197111716 0.0229642139 0.0263651126433 +1413393977905760512.0000000000 -2.0931185113 -0.1178198457 1.8202295375 0.5721581352 0.8194152918 0.0211512412 0.0273179950247 +1413393977955760384.0000000000 -2.1059934481 -0.1050905219 1.8254268235 0.5720048242 0.8195586937 0.0188111710 0.0279314966472 +1413393978005760512.0000000000 -2.1201690068 -0.0921080103 1.8312618264 0.5715156471 0.8199662029 0.0158147863 0.0278421222937 +1413393978055760384.0000000000 -2.1355885237 -0.0789335424 1.8376655089 0.5707626470 0.8205829990 0.0118249223 0.0270871521795 +1413393978105760512.0000000000 -2.1522199352 -0.0654732449 1.8446672646 0.5699934694 0.8212130926 0.0074890029 0.0256985655023 +1413393978155760384.0000000000 -2.1699013235 -0.0517554644 1.8520076150 0.5698476866 0.8214118128 0.0029413509 0.0234007757174 +1413393978205760512.0000000000 -2.1880758027 -0.0375478103 1.8596021325 0.5703849583 0.8210979898 -0.0020081750 0.0213320801288 +1413393978255760384.0000000000 -2.2062956919 -0.0229025852 1.8674730205 0.5715556599 0.8202828726 -0.0079951341 0.0199051364839 +1413393978305760512.0000000000 -2.2244202273 -0.0079541465 1.8756144014 0.5730509287 0.8191550543 -0.0145952936 0.0196114134587 +1413393978355760384.0000000000 -2.2420498365 0.0074506690 1.8844623213 0.5761481448 0.8167845757 -0.0234432422 0.0191490609141 +1413393978405760512.0000000000 -2.2589259475 0.0228435383 1.8933063724 0.5783134021 0.8149190399 -0.0322493810 0.0205071900633 +1413393978455760384.0000000000 -2.2748816849 0.0381391883 1.9029039038 0.5819441652 0.8117796999 -0.0431097209 0.0222768800777 +1413393978505760512.0000000000 -2.2897063538 0.0528856949 1.9125179478 0.5846115078 0.8090790987 -0.0545819861 0.0253220015189 +1413393978555760384.0000000000 -2.3029970903 0.0669536031 1.9226043822 0.5879306236 0.8056278627 -0.0660332362 0.0306747526779 +1413393978605760512.0000000000 -2.3147481604 0.0798009087 1.9319062704 0.5876472237 0.8044152139 -0.0786243058 0.0374849654684 +1413393978655760384.0000000000 -2.3250628487 0.0912359835 1.9412414954 0.5869650758 0.8031718108 -0.0914451941 0.0449979835593 +1413393978705760512.0000000000 -2.3339984573 0.1015791766 1.9500756969 0.5842003893 0.8030927417 -0.1045128741 0.0531884616864 +1413393978755760384.0000000000 -2.3415999891 0.1106685104 1.9588802768 0.5801307870 0.8035066265 -0.1184627374 0.0615788195746 +1413393978805760512.0000000000 -2.3482177883 0.1188940564 1.9681914656 0.5763556616 0.8034983705 -0.1319451754 0.0692458715444 +1413393978855760384.0000000000 -2.3533276707 0.1264405209 1.9782511498 0.5735811159 0.8022703609 -0.1464613608 0.076915806622 +1413393978905760512.0000000000 -2.3568675582 0.1333369539 1.9887802187 0.5718669640 0.7999876563 -0.1602740969 0.0854408511014 +1413393978955760384.0000000000 -2.3589021304 0.1397012757 1.9997559884 0.5706483165 0.7970309453 -0.1744428395 0.0931228587363 +1413393979005760512.0000000000 -2.3593505366 0.1451643762 2.0108334211 0.5691172833 0.7938645508 -0.1896879618 0.0995141695713 +1413393979055760384.0000000000 -2.3578034819 0.1496074366 2.0217268844 0.5676522694 0.7902710353 -0.2046308068 0.106624691252 +1413393979105760512.0000000000 -2.3542434100 0.1531159465 2.0328370535 0.5665163404 0.7859781725 -0.2199539101 0.113656613923 +1413393979155760384.0000000000 -2.3484594570 0.1554334395 2.0436224544 0.5643191413 0.7818847070 -0.2347731492 0.122807899079 +1413393979205760512.0000000000 -2.3407323130 0.1566088645 2.0528914209 0.5619466785 0.7774959040 -0.2486461848 0.133757708308 +1413393979255760384.0000000000 -2.3311898507 0.1566310237 2.0596924561 0.5594959227 0.7728382650 -0.2625130411 0.144125750141 +1413393979305760512.0000000000 -2.3202429241 0.1552028419 2.0633812114 0.5573485381 0.7674097421 -0.2770786921 0.153858029071 +1413393979355760384.0000000000 -2.3080749790 0.1520266705 2.0641644169 0.5557146690 0.7612248096 -0.2921121553 0.162445328466 +1413393979405760512.0000000000 -2.2944561862 0.1472636126 2.0619990824 0.5536843708 0.7549446007 -0.3076453037 0.169842970007 +1413393979455760384.0000000000 -2.2795142811 0.1404064430 2.0567482252 0.5519286801 0.7481189691 -0.3229055553 0.177270252771 +1413393979505760512.0000000000 -2.2633641852 0.1313139067 2.0489699346 0.5501188720 0.7410580592 -0.3385026169 0.183352551151 +1413393979555760384.0000000000 -2.2450928160 0.1202500340 2.0391384786 0.5478215117 0.7338502585 -0.3539868008 0.189865042158 +1413393979605760512.0000000000 -2.2242931400 0.1074074389 2.0272927001 0.5444374874 0.7270678018 -0.3686253128 0.197675523768 +1413393979655760384.0000000000 -2.2015302367 0.0919466414 2.0140481671 0.5401305823 0.7208044802 -0.3814273777 0.207877393946 +1413393979705760512.0000000000 -2.1768423993 0.0738679432 2.0015863784 0.5356735003 0.7142704800 -0.3932115660 0.219673045324 +1413393979755760384.0000000000 -2.1505274538 0.0533520415 1.9902152386 0.5302218127 0.7086064527 -0.4039479012 0.231447224374 +1413393979805760512.0000000000 -2.1224427796 0.0300327740 1.9801202395 0.5235065019 0.7037002552 -0.4128477493 0.245567972759 +1413393979855760384.0000000000 -2.0930931298 0.0044376416 1.9713769646 0.5149479121 0.6997402453 -0.4220509261 0.258969597977 +1413393979905760512.0000000000 -2.0626138153 -0.0229974535 1.9640818721 0.5063012234 0.6956727467 -0.4316181840 0.270932175896 +1413393979955760384.0000000000 -2.0311896620 -0.0520322369 1.9577582937 0.4972438011 0.6915596602 -0.4415972573 0.281932085642 +1413393980005760512.0000000000 -1.9989294640 -0.0822507894 1.9523757831 0.4884760403 0.6868609843 -0.4522221495 0.291733223709 +1413393980055760384.0000000000 -1.9660276023 -0.1138095781 1.9466103117 0.4766691335 0.6841513855 -0.4622845087 0.301689330045 +1413393980105760512.0000000000 -1.9322634829 -0.1461348818 1.9411209695 0.4633401274 0.6825006519 -0.4715111849 0.311746674291 +1413393980155760384.0000000000 -1.8973862022 -0.1783970068 1.9358529862 0.4490097902 0.6817159669 -0.4788989444 0.322969580459 +1413393980205760512.0000000000 -1.8615032223 -0.2099806301 1.9306032242 0.4338610735 0.6819088312 -0.4861225058 0.332339922561 +1413393980255760384.0000000000 -1.8246100828 -0.2401379781 1.9257654227 0.4207799833 0.6820054014 -0.4919489683 0.340292595758 +1413393980305760512.0000000000 -1.7865052086 -0.2685099356 1.9214241437 0.4102280778 0.6818211498 -0.4968725394 0.346338741055 +1413393980355760384.0000000000 -1.7470792994 -0.2946088634 1.9176678080 0.4026015077 0.6812649712 -0.5006095283 0.350970319384 +1413393980405760512.0000000000 -1.7053674992 -0.3181108991 1.9144919950 0.3984732038 0.6798921210 -0.5021907020 0.356048182838 +1413393980455760384.0000000000 -1.6617686046 -0.3387525600 1.9121756043 0.3977744915 0.6773472714 -0.5031046564 0.360363472738 +1413393980505760512.0000000000 -1.6165874002 -0.3567130998 1.9100444410 0.4004468658 0.6735466649 -0.5017781037 0.366327630103 +1413393980555760384.0000000000 -1.5700617693 -0.3721466851 1.9085282530 0.4064116749 0.6684653400 -0.4992558014 0.372461118142 +1413393980605760512.0000000000 -1.5225478083 -0.3854045072 1.9071520507 0.4130297878 0.6632463054 -0.4953743618 0.379624781142 +1413393980655760384.0000000000 -1.4745513894 -0.3964453401 1.9057935116 0.4181729622 0.6593737907 -0.4917963831 0.385349056584 +1413393980705760512.0000000000 -1.4267544312 -0.4052744605 1.9046427690 0.4220430840 0.6567454591 -0.4896802225 0.388301837255 +1413393980755760384.0000000000 -1.3795446526 -0.4121671580 1.9037726525 0.4221143772 0.6566515228 -0.4895685628 0.388523940593 +1413393980805760512.0000000000 -1.3331151809 -0.4169162731 1.9032849884 0.4204397061 0.6580690829 -0.4921608133 0.384646941247 +1413393980855760384.0000000000 -1.2875023770 -0.4198550776 1.9031961667 0.4182530546 0.6598327316 -0.4962226334 0.378745622778 +1413393980905760512.0000000000 -1.2418290694 -0.4208518161 1.9034513657 0.4146358506 0.6624172748 -0.5018786263 0.370672780167 +1413393980955760384.0000000000 -1.1954783413 -0.4200494327 1.9051767363 0.4138530964 0.6631493439 -0.5075612423 0.36240881282 +1413393981005760512.0000000000 -1.1477681965 -0.4180261662 1.9078866264 0.4147027657 0.6624241307 -0.5137175499 0.35399175999 +1413393981055760384.0000000000 -1.0981517381 -0.4149650171 1.9121433741 0.4178007967 0.6604295785 -0.5181372856 0.347575918789 +1413393981105760512.0000000000 -1.0466807439 -0.4115383361 1.9181616556 0.4224334452 0.6572769859 -0.5216946656 0.342595423307 +1413393981155760384.0000000000 -0.9931330377 -0.4079710160 1.9271785778 0.4284893407 0.6530528256 -0.5231689637 0.340900465304 +1413393981205760512.0000000000 -0.9378939229 -0.4046736666 1.9393209169 0.4350291610 0.6486019674 -0.5238414492 0.340081244805 +1413393981255760384.0000000000 -0.8809054094 -0.4019702170 1.9548479519 0.4390702500 0.6462301444 -0.5241763822 0.338884989961 +1413393981305760512.0000000000 -0.8223290806 -0.4001017047 1.9732130475 0.4405350301 0.6459756277 -0.5243045053 0.337267195776 +1413393981355760384.0000000000 -0.7626803696 -0.3991338161 1.9924987232 0.4407650785 0.6464713290 -0.5252470155 0.334539293962 +1413393981405760512.0000000000 -0.7020292808 -0.3992499507 2.0112724692 0.4390595481 0.6487173706 -0.5247114412 0.333272245881 +1413393981455760384.0000000000 -0.6404619838 -0.4006271918 2.0283164674 0.4357703174 0.6521048466 -0.5221354508 0.335019507814 +1413393981505760512.0000000000 -0.5776314595 -0.4028306002 2.0430998950 0.4324820168 0.6556304073 -0.5181263607 0.338604708362 +1413393981555760384.0000000000 -0.5137725789 -0.4055220528 2.0544549549 0.4288380993 0.6595358372 -0.5129835554 0.34345048539 +1413393981605760512.0000000000 -0.4490196190 -0.4080096659 2.0626494884 0.4266090270 0.6623806448 -0.5087803740 0.346985807361 +1413393981655760384.0000000000 -0.3830157599 -0.4097196412 2.0676552399 0.4243810479 0.6649987252 -0.5056282454 0.349310032959 +1413393981705760512.0000000000 -0.3158929826 -0.4104100325 2.0699063679 0.4227819909 0.6672476007 -0.5027118313 0.351164978544 +1413393981755760384.0000000000 -0.2477563749 -0.4100681889 2.0693622978 0.4212692227 0.6692699744 -0.4993267685 0.353952993465 +1413393981805760512.0000000000 -0.1785432932 -0.4082083349 2.0664297687 0.4215802396 0.6701871098 -0.4954402800 0.357292972794 +1413393981855760384.0000000000 -0.1091004039 -0.4048942087 2.0610411734 0.4221169484 0.6724057014 -0.4898306289 0.360213560944 +1413393981905760512.0000000000 -0.0392556364 -0.3995347998 2.0535302577 0.4241766280 0.6749399474 -0.4828454432 0.362478321529 +1413393981955760384.0000000000 0.0308628053 -0.3917566182 2.0456738353 0.4278391994 0.6778383777 -0.4745100372 0.363770501478 +1413393982005760512.0000000000 0.1001672550 -0.3817620736 2.0383152537 0.4332168097 0.6808198454 -0.4656350078 0.36330644558 +1413393982055760384.0000000000 0.1683851030 -0.3696131464 2.0312200016 0.4382748384 0.6851081699 -0.4566534123 0.360568471404 +1413393982105760512.0000000000 0.2358892907 -0.3549432694 2.0249119207 0.4447470315 0.6899905239 -0.4459843361 0.356666688703 +1413393982155760384.0000000000 0.3024258433 -0.3378856653 2.0192660291 0.4523638303 0.6950308156 -0.4344759718 0.351468007545 +1413393982205760512.0000000000 0.3677591557 -0.3184604878 2.0143580714 0.4598280565 0.7011973807 -0.4227331929 0.343768874922 +1413393982255760384.0000000000 0.4317283700 -0.2968249366 2.0104908899 0.4684386693 0.7077319966 -0.4095383142 0.334602754385 +1413393982305760512.0000000000 0.4945698033 -0.2732811709 2.0073326899 0.4767154051 0.7149531468 -0.3951591433 0.324705515625 +1413393982355760384.0000000000 0.5553618970 -0.2483666810 2.0045261510 0.4831015148 0.7241328163 -0.3804999677 0.312192833535 +1413393982405760512.0000000000 0.6144407839 -0.2221843025 2.0026491975 0.4886758986 0.7341216280 -0.3643090930 0.299232662172 +1413393982455760384.0000000000 0.6715408913 -0.1948456820 2.0007309809 0.4941539574 0.7442628295 -0.3468047948 0.285676637698 +1413393982505760512.0000000000 0.7264420132 -0.1665597140 1.9989463284 0.4994684545 0.7545423095 -0.3279247192 0.271408446271 +1413393982555760384.0000000000 0.7799732318 -0.1367296682 1.9981060413 0.5054521227 0.7642929593 -0.3078445157 0.256137030042 +1413393982605760512.0000000000 0.8323934109 -0.1054610165 1.9977191771 0.5115041792 0.7736669043 -0.2857201711 0.241178315219 +1413393982655760384.0000000000 0.8837246647 -0.0727056812 1.9969850947 0.5177278501 0.7823973605 -0.2617340573 0.226511648086 +1413393982705760512.0000000000 0.9338207834 -0.0386929082 1.9957643525 0.5232872042 0.7907362573 -0.2362826783 0.212313846226 +1413393982755760384.0000000000 0.9821437157 -0.0032479067 1.9946234009 0.5290809842 0.7983203635 -0.2088683923 0.197817855687 +1413393982805760512.0000000000 1.0290302462 0.0335583604 1.9936565592 0.5347259055 0.8046984758 -0.1805804396 0.184171859505 +1413393982855760384.0000000000 1.0740391362 0.0717127521 1.9929094656 0.5405972479 0.8097265617 -0.1519013615 0.170362810372 +1413393982905760512.0000000000 1.1164337062 0.1105810004 1.9918776726 0.5455905591 0.8141945655 -0.1224437203 0.156287192885 +1413393982955760384.0000000000 1.1562072594 0.1501269959 1.9902865734 0.5491403983 0.8182772508 -0.0944257688 0.141247788923 +1413393983005760512.0000000000 1.1930583275 0.1903723889 1.9882492675 0.5522566859 0.8214300415 -0.0674907652 0.125340481892 +1413393983055760384.0000000000 1.2269398532 0.2313646095 1.9859803632 0.5545901215 0.8238529772 -0.0399239562 0.110009757218 +1413393983105760512.0000000000 1.2575614362 0.2731411770 1.9838876802 0.5570571547 0.8248873070 -0.0125326536 0.0953477309326 +1413393983155760384.0000000000 1.2850674113 0.3157736362 1.9816102419 0.5584020528 0.8253678526 0.0153550925 0.0819711926725 +1413393983205760512.0000000000 1.3089708017 0.3589360885 1.9790138128 0.5594455705 0.8248874294 0.0429496996 0.0688237297805 +1413393983255760384.0000000000 1.3289776352 0.4024822818 1.9763836433 0.5607910109 0.8231011035 0.0700138364 0.0558218446672 +1413393983305760512.0000000000 1.3447379163 0.4460629773 1.9736756642 0.5611320524 0.8209717122 0.0966690641 0.0423244548452 +1413393983355760384.0000000000 1.3561085257 0.4898857002 1.9713949949 0.5628964652 0.8167872645 0.1230135463 0.0295601323215 +1413393983405760512.0000000000 1.3626249734 0.5333984803 1.9698025254 0.5653143055 0.8112504691 0.1484406376 0.0160558255105 +1413393983455760384.0000000000 1.3640505338 0.5762123781 1.9688222545 0.5674105824 0.8051693366 0.1724688079 0.00144242970826 +1413393983505760512.0000000000 1.3602796736 0.6180765601 1.9692003131 0.5709745641 0.7972596555 0.1953939590 -0.0136487969036 +1413393983555760384.0000000000 1.3513950850 0.6581920231 1.9703278714 0.5732931132 0.7893712297 0.2176768015 -0.0290667867684 +1413393983605760512.0000000000 1.3375763793 0.6961594813 1.9725044568 0.5759237572 0.7803263781 0.2396644731 -0.0443115092776 +1413393983655760384.0000000000 1.3192016749 0.7315186837 1.9752636729 0.5769225233 0.7718106929 0.2606460846 -0.0594329453823 +1413393983705760512.0000000000 1.2962731686 0.7639997175 1.9791485782 0.5779580173 0.7627507325 0.2799738402 -0.0760953290222 +1413393983755760384.0000000000 1.2693287803 0.7931467339 1.9834199334 0.5767599475 0.7547879185 0.2985475660 -0.0922632744819 +1413393983805760512.0000000000 1.2385810885 0.8187487783 1.9883951049 0.5742538223 0.7475904840 0.3153460271 -0.109077490946 +1413393983855760384.0000000000 1.2042792610 0.8407879427 1.9943451121 0.5713816131 0.7401415903 0.3315226269 -0.12572281538 +1413393983905760512.0000000000 1.1667857588 0.8593587386 2.0011065546 0.5681520079 0.7327806351 0.3466514540 -0.141663707738 +1413393983955760384.0000000000 1.1265482223 0.8745428732 2.0084789757 0.5663109024 0.7235974409 0.3629791966 -0.154741100412 +1413393984005760512.0000000000 1.0836984796 0.8859267107 2.0159772105 0.5634864165 0.7148485663 0.3785881568 -0.167766483902 +1413393984055760384.0000000000 1.0382322736 0.8936315326 2.0239265047 0.5612520701 0.7048915090 0.3947565376 -0.179697942082 +1413393984105760512.0000000000 0.9903149220 0.8971206573 2.0325672637 0.5588983760 0.6942896966 0.4108857855 -0.191747995335 +1413393984155760384.0000000000 0.9402156261 0.8962036204 2.0418239173 0.5561732195 0.6833712409 0.4270123682 -0.203311422296 +1413393984205760512.0000000000 0.8882841261 0.8906735283 2.0516716775 0.5530876133 0.6721507071 0.4427326433 -0.215163485609 +1413393984255760384.0000000000 0.8346984056 0.8804307414 2.0622832300 0.5494513886 0.6610589260 0.4577854987 -0.227016970976 +1413393984305760512.0000000000 0.7795127143 0.8654089990 2.0736528922 0.5443453316 0.6513928357 0.4707499174 -0.240354007203 +1413393984355760384.0000000000 0.7232731024 0.8459902674 2.0854514854 0.5388623816 0.6424807265 0.4822925267 -0.253455654007 +1413393984405760512.0000000000 0.6661573363 0.8222481791 2.0981158524 0.5346244679 0.6330176678 0.4927301567 -0.26586143621 +1413393984455760384.0000000000 0.6086263665 0.7944132038 2.1111192761 0.5304613293 0.6240114402 0.5028441316 -0.276348113564 +1413393984505760512.0000000000 0.5507919888 0.7624086291 2.1247241741 0.5271963767 0.6153010430 0.5112747275 -0.286472965526 +1413393984555760384.0000000000 0.4930490976 0.7261697600 2.1384801927 0.5246257936 0.6063632839 0.5191228911 -0.295977648851 +1413393984605760512.0000000000 0.4356601353 0.6858730266 2.1515877904 0.5191596067 0.6007214599 0.5259432613 -0.304943792034 +1413393984655760384.0000000000 0.3786598051 0.6413774442 2.1634917450 0.5096440637 0.5994865420 0.5301429195 -0.315954584093 +1413393984705760512.0000000000 0.3222394462 0.5935064971 2.1734698594 0.4975352447 0.6019440086 0.5305135249 -0.329662692192 +1413393984755760384.0000000000 0.2659211150 0.5437345922 2.1807704118 0.4872919735 0.6045354500 0.5296666035 -0.341374737433 +1413393984805760512.0000000000 0.2096108617 0.4927610667 2.1853085114 0.4779183432 0.6078406937 0.5278133764 -0.351478004962 +1413393984855760384.0000000000 0.1538599124 0.4411232551 2.1870445481 0.4661353372 0.6148083695 0.5244948371 -0.360046777607 +1413393984905760512.0000000000 0.0986804983 0.3899791860 2.1857139476 0.4540912787 0.6249295046 0.5188523027 -0.366137286819 +1413393984955760384.0000000000 0.0436543613 0.3398766635 2.1817688244 0.4436943679 0.6362719734 0.5112522819 -0.370019442733 +1413393985005760512.0000000000 -0.0111070949 0.2917036944 2.1755115798 0.4371393242 0.6472112113 0.5021972666 -0.371247578639 +1413393985055760384.0000000000 -0.0657876332 0.2461892488 2.1665199459 0.4359456953 0.6567335800 0.4933527950 -0.367770818967 +1413393985105760512.0000000000 -0.1208536017 0.2034148428 2.1555143664 0.4401659298 0.6641314656 0.4836245912 -0.362340455258 +1413393985155760384.0000000000 -0.1762343599 0.1636842597 2.1427505716 0.4502675847 0.6687675680 0.4741664238 -0.353801137236 +1413393985205760512.0000000000 -0.2311091977 0.1261814253 2.1277994992 0.4621950383 0.6727206059 0.4638958690 -0.344417414937 +1413393985255760384.0000000000 -0.2852567710 0.0904889575 2.1110153946 0.4746747739 0.6767062600 0.4534377820 -0.333386674181 +1413393985305760512.0000000000 -0.3387018309 0.0560745693 2.0936497183 0.4875172851 0.6806080427 0.4427606697 -0.321033609385 +1413393985355760384.0000000000 -0.3911734137 0.0222945715 2.0762609802 0.4991947647 0.6853099289 0.4323498328 -0.30696662746 +1413393985405760512.0000000000 -0.4431040107 -0.0112529491 2.0599666993 0.5099812945 0.6903652465 0.4207876742 -0.293687995764 +1413393985455760384.0000000000 -0.4940153888 -0.0451226720 2.0440865354 0.5187361319 0.6968150685 0.4082200591 -0.280567227422 +1413393985505760512.0000000000 -0.5443396857 -0.0795204573 2.0291842526 0.5271744923 0.7028962916 0.3950036035 -0.268320724217 +1413393985555760384.0000000000 -0.5940018662 -0.1149814192 2.0148829516 0.5317361818 0.7113040855 0.3806179155 -0.257746257582 +1413393985605760512.0000000000 -0.6431591908 -0.1511861252 2.0010337619 0.5328942048 0.7216579139 0.3655596419 -0.248193009534 +1413393985655760384.0000000000 -0.6915431418 -0.1880733339 1.9873324017 0.5305915439 0.7337364458 0.3505875997 -0.23914802247 +1413393985705760512.0000000000 -0.7393941561 -0.2252783945 1.9741196564 0.5264489303 0.7464141970 0.3350533707 -0.23120685352 +1413393985755760384.0000000000 -0.7867028266 -0.2620584055 1.9610027491 0.5219138916 0.7588122696 0.3201015134 -0.22213700809 +1413393985805760512.0000000000 -0.8338446950 -0.2979181396 1.9485131715 0.5180137058 0.7699316770 0.3055111947 -0.213377419916 +1413393985855760384.0000000000 -0.8810295361 -0.3321189150 1.9374410789 0.5141812216 0.7804182431 0.2906186691 -0.205197042859 +1413393985905760512.0000000000 -0.9286117550 -0.3637717966 1.9279742460 0.5112992518 0.7898689014 0.2743058930 -0.198586179457 +1413393985955760384.0000000000 -0.9761834869 -0.3923084763 1.9200243519 0.5095890029 0.7980568919 0.2586112396 -0.191166085066 +1413393986005760512.0000000000 -1.0240747417 -0.4170750985 1.9143677757 0.5098800986 0.8045548881 0.2421833966 -0.1845560065 +1413393986055760384.0000000000 -1.0716645669 -0.4387505433 1.9092504359 0.5111178947 0.8098594628 0.2267165687 -0.177442231924 +1413393986105760512.0000000000 -1.1179388522 -0.4579671969 1.9050744988 0.5124415544 0.8149033829 0.2094294529 -0.17168411151 +1413393986155760384.0000000000 -1.1631367731 -0.4739595950 1.9025139124 0.5144963324 0.8188818070 0.1923865550 -0.166473792438 +1413393986205760512.0000000000 -1.2069372199 -0.4868228384 1.9008309564 0.5161198680 0.8227179771 0.1732690938 -0.163503006281 +1413393986255760384.0000000000 -1.2487673812 -0.4961187952 1.8995739666 0.5185347020 0.8257125953 0.1534391764 -0.160551835437 +1413393986305760512.0000000000 -1.2884052994 -0.5016253386 1.8991385028 0.5204432276 0.8286445173 0.1338033237 -0.156792159799 +1413393986355760384.0000000000 -1.3249743561 -0.5038143384 1.8991115301 0.5226041486 0.8310283204 0.1149833023 -0.15184095189 +1413393986405760512.0000000000 -1.3588519348 -0.5012525847 1.8995953180 0.5255440730 0.8326395470 0.0957099281 -0.14613152225 +1413393986455760384.0000000000 -1.3888906764 -0.4956876280 1.9001803817 0.5275303893 0.8345104909 0.0783283553 -0.138450704952 +1413393986505760512.0000000000 -1.4145832145 -0.4870662819 1.9017308693 0.5325538199 0.8344219296 0.0645004698 -0.126357278128 +1413393986555760384.0000000000 -1.4357066520 -0.4759969116 1.9039470498 0.5407371463 0.8324083205 0.0549623492 -0.108068805216 +1413393986605760512.0000000000 -1.4535311260 -0.4617895511 1.9062779342 0.5504944217 0.8289946517 0.0493094106 -0.0853952057344 +1413393986655760384.0000000000 -1.4690202411 -0.4449746232 1.9090602024 0.5590666461 0.8256220067 0.0451185445 -0.0612952214104 +1413393986705760512.0000000000 -1.4829440183 -0.4270668204 1.9131864117 0.5692363113 0.8202861603 0.0385924483 -0.0401405030543 +1413393986755760384.0000000000 -1.4961396209 -0.4087189433 1.9179827761 0.5781454760 0.8150660578 0.0317460638 -0.0201821053372 +1413393986805760512.0000000000 -1.5090040783 -0.3907540557 1.9236471798 0.5868924081 0.8092957233 0.0244218579 -0.00114301148898 +1413393986855760384.0000000000 -1.5222369851 -0.3742044103 1.9294812024 0.5942473494 0.8039257511 0.0174417945 0.0164090892271 +1413393986905760512.0000000000 -1.5366138690 -0.3593593725 1.9354052797 0.5994364456 0.7997667681 0.0107357926 0.0305582566578 +1413393986955760384.0000000000 -1.5526602764 -0.3464332601 1.9409612520 0.6001533517 0.7988751400 0.0031110514 0.0400597876736 +1413393987005760512.0000000000 -1.5704590543 -0.3353490322 1.9456682601 0.5966946215 0.8011487563 -0.0050563780 0.0457234292935 +1413393987055760384.0000000000 -1.5898077179 -0.3257157320 1.9486669998 0.5925426601 0.8038920560 -0.0122926650 0.049996486258 +1413393987105760512.0000000000 -1.6105968466 -0.3170866944 1.9498211465 0.5881587857 0.8068019833 -0.0181857162 0.053000774967 +1413393987155760384.0000000000 -1.6325830792 -0.3091149395 1.9485322947 0.5842828434 0.8093488277 -0.0230997492 0.05508571175 +1413393987205760512.0000000000 -1.6556917694 -0.3015070906 1.9456297459 0.5811783074 0.8113502090 -0.0273580326 0.0565168243213 +1413393987255760384.0000000000 -1.6799166097 -0.2936106724 1.9424650082 0.5774013108 0.8138677552 -0.0301023147 0.0576268505929 +1413393987305760512.0000000000 -1.7051105369 -0.2853792483 1.9404991496 0.5747911778 0.8155712000 -0.0324823804 0.0583405058192 +1413393987355760384.0000000000 -1.7313797115 -0.2769757917 1.9396943241 0.5726342716 0.8170350275 -0.0339183363 0.0582520496859 +1413393987405760512.0000000000 -1.7585288807 -0.2681533425 1.9402287308 0.5708221726 0.8182693378 -0.0343939003 0.0584328481274 +1413393987455760384.0000000000 -1.7868002222 -0.2589959575 1.9422670149 0.5700919533 0.8188535655 -0.0347476042 0.057154239926 +1413393987505760512.0000000000 -1.8156861293 -0.2493889690 1.9450919562 0.5697540011 0.8190828031 -0.0350061495 0.0570816029635 +1413393987555760384.0000000000 -1.8449742239 -0.2391880996 1.9488356743 0.5710649217 0.8180635632 -0.0350100175 0.0585761082474 +1413393987605760512.0000000000 -1.8746483555 -0.2286237846 1.9526697171 0.5721042321 0.8170867165 -0.0358664885 0.0614787799823 +1413393987655760384.0000000000 -1.9049364456 -0.2174093072 1.9567858935 0.5733979307 0.8158476108 -0.0380546335 0.064492898879 +1413393987705760512.0000000000 -1.9357728379 -0.2058776169 1.9612454104 0.5738126140 0.8151091437 -0.0419077217 0.0676750374581 +1413393987755760384.0000000000 -1.9672883355 -0.1941519056 1.9659184582 0.5748852501 0.8138558762 -0.0474381707 0.0699655768937 +1413393987805760512.0000000000 -1.9995959941 -0.1829767219 1.9699068974 0.5742692283 0.8138522419 -0.0527677019 0.071238693156 +1413393987855760384.0000000000 -2.0326402538 -0.1717783621 1.9731692674 0.5741555190 0.8135571640 -0.0590997574 0.0705506879215 +1413393987905760512.0000000000 -2.0661475014 -0.1607582685 1.9735754799 0.5727517708 0.8142108416 -0.0645650060 0.0696238062196 +1413393987955760384.0000000000 -2.0998676317 -0.1498054449 1.9708277741 0.5723302743 0.8141552976 -0.0688619174 0.0696221579295 +1413393988005760512.0000000000 -2.1336681407 -0.1386607353 1.9644731793 0.5724959590 0.8137031289 -0.0723027655 0.0700564419319 +1413393988055760384.0000000000 -2.1675950601 -0.1273380146 1.9552419531 0.5721824841 0.8135936353 -0.0750365856 0.0710078320911 +1413393988105760512.0000000000 -2.2014189791 -0.1158895582 1.9436618976 0.5729350423 0.8127175338 -0.0766509633 0.0732139150946 +1413393988155760384.0000000000 -2.2352176910 -0.1043948324 1.9290171629 0.5748533262 0.8110359242 -0.0769349430 0.0764551999298 +1413393988205760512.0000000000 -2.2692142377 -0.0933606550 1.9114747036 0.5765368319 0.8094601945 -0.0765964603 0.0806997972306 +1413393988255760384.0000000000 -2.3036586717 -0.0827592449 1.8922845667 0.5787869256 0.8075145401 -0.0753993292 0.0850934977982 +1413393988305760512.0000000000 -2.3387469098 -0.0724192607 1.8717025801 0.5803001439 0.8061414223 -0.0741856298 0.0887932575917 +1413393988355760384.0000000000 -2.3747425024 -0.0625138998 1.8513421765 0.5822345475 0.8044486141 -0.0722312203 0.0929946764095 +1413393988405760512.0000000000 -2.4117495669 -0.0528763636 1.8312270308 0.5828601471 0.8036106270 -0.0694048115 0.0983208073839 +1413393988455760384.0000000000 -2.4498675683 -0.0438475614 1.8114817581 0.5819384033 0.8036945970 -0.0647995736 0.105941987585 +1413393988505760512.0000000000 -2.4895660182 -0.0353851420 1.7919382737 0.5789364400 0.8049554878 -0.0588721312 0.115815945369 +1413393988555760384.0000000000 -2.5317748488 -0.0270604818 1.7736399326 0.5767189048 0.8055844791 -0.0532520516 0.124872618453 +1413393988605760512.0000000000 -2.5770001949 -0.0187034672 1.7568513248 0.5758695980 0.8053016706 -0.0488555954 0.132198926957 +1413393988655760384.0000000000 -2.6261544943 -0.0103736073 1.7417831170 0.5756395566 0.8056164527 -0.0514134018 0.130299248447 +1413393988705760512.0000000000 -2.6783521884 -0.0022138784 1.7275645988 0.5741894127 0.8070260404 -0.0559227800 0.126048130058 +1413393988755760384.0000000000 -2.7336854994 0.0057331479 1.7148330487 0.5732302073 0.8085576093 -0.0656892550 0.115441082843 +1413393988805760512.0000000000 -2.7904498580 0.0137090053 1.7028280247 0.5701289245 0.8110997985 -0.0779229768 0.104871998372 +1413393988855760384.0000000000 -2.8481188135 0.0221043614 1.6931155245 0.5638405368 0.8154158079 -0.0945911257 0.0907382401104 +1413393988905760512.0000000000 -2.9051428384 0.0316994694 1.6876259952 0.5568435665 0.8192900892 -0.1135124478 0.076183439281 +1413393988955760384.0000000000 -2.9599704690 0.0425912988 1.6857001379 0.5496324391 0.8223595943 -0.1316255637 0.0656017567713 +1413393989005760512.0000000000 -3.0118155419 0.0543241512 1.6874349764 0.5426400211 0.8246462784 -0.1492851721 0.0566944471246 +1413393989055760384.0000000000 -3.0598949483 0.0667515878 1.6928790416 0.5352191643 0.8268677405 -0.1653806135 0.0497939608318 +1413393989105760512.0000000000 -3.1032035107 0.0806449970 1.7025906390 0.5274726112 0.8289313955 -0.1811233890 0.0428917702749 +1413393989155760384.0000000000 -3.1407320966 0.0958758754 1.7160388823 0.5194809091 0.8311433477 -0.1945070273 0.0388244376235 +1413393989205760512.0000000000 -3.1716201607 0.1131858100 1.7340662067 0.5120857722 0.8333595145 -0.2044215812 0.038625103654 +1413393989255760384.0000000000 -3.1953940804 0.1329877075 1.7554283252 0.5072135729 0.8348746604 -0.2091172109 0.0445946747743 +1413393989305760512.0000000000 -3.2117447026 0.1553493991 1.7798233896 0.5129306119 0.8318789646 -0.2010057694 0.0669048296209 +1413393989355760384.0000000000 -3.2235357061 0.1800242811 1.8061337414 0.5243602043 0.8249858013 -0.1894877929 0.0924076840238 +1413393989405760512.0000000000 -3.2324384000 0.2066104474 1.8340982102 0.5391377578 0.8148230670 -0.1783617020 0.116537337259 +1413393989455760384.0000000000 -3.2403422049 0.2343899048 1.8611599062 0.5548047655 0.8030626322 -0.1682370003 0.1377620873 +1413393989505760512.0000000000 -3.2488920197 0.2623190105 1.8860151182 0.5679292979 0.7926072350 -0.1603920978 0.153311638611 +1413393989555760384.0000000000 -3.2588452914 0.2893771745 1.9075427385 0.5782026418 0.7840449796 -0.1554221054 0.16370444133 +1413393989605760512.0000000000 -3.2709046812 0.3151492350 1.9248641791 0.5829656411 0.7796823980 -0.1531496700 0.169680871238 +1413393989655760384.0000000000 -3.2849507317 0.3396262796 1.9386220342 0.5847461590 0.7777233155 -0.1521582367 0.173396208038 +1413393989705760512.0000000000 -3.3006406861 0.3632489690 1.9487659595 0.5825524583 0.7785584273 -0.1544082587 0.175035705578 +1413393989755760384.0000000000 -3.3180322243 0.3860248899 1.9560293722 0.5796585235 0.7797312651 -0.1588073206 0.175486139942 +1413393989805760512.0000000000 -3.3371176276 0.4079136732 1.9607863401 0.5768803389 0.7805642357 -0.1657527511 0.174512389278 +1413393989855760384.0000000000 -3.3575103366 0.4290421071 1.9637244112 0.5762110524 0.7795167557 -0.1761698783 0.171168410179 +1413393989905760512.0000000000 -3.3787752275 0.4491644123 1.9644776648 0.5757184769 0.7778064577 -0.1884743282 0.167459778357 +1413393989955760384.0000000000 -3.4002954018 0.4687970546 1.9636486129 0.5770583803 0.7740498152 -0.2026907254 0.163606170866 +1413393990005760512.0000000000 -3.4217662653 0.4869278702 1.9607554436 0.5789327863 0.7687773764 -0.2191580395 0.16058620155 +1413393990055760384.0000000000 -3.4421105551 0.5032752010 1.9555291588 0.5796868233 0.7631254879 -0.2340958015 0.163712651737 +1413393990105760512.0000000000 -3.4613655667 0.5174334179 1.9479888244 0.5791205842 0.7574478862 -0.2487859061 0.170286880086 +1413393990155760384.0000000000 -3.4797245360 0.5291565194 1.9381720620 0.5773356544 0.7516318822 -0.2638773549 0.179169744418 +1413393990205760512.0000000000 -3.4973155458 0.5387730706 1.9262099568 0.5744409716 0.7457033465 -0.2796940799 0.188984949041 +1413393990255760384.0000000000 -3.5143158117 0.5458780124 1.9120017739 0.5696097083 0.7403844353 -0.2963323767 0.198903973423 +1413393990305760512.0000000000 -3.5308861359 0.5502215593 1.8960726509 0.5633399880 0.7352777036 -0.3146296815 0.207419671324 +1413393990355760384.0000000000 -3.5470075595 0.5520739096 1.8795944543 0.5552084040 0.7308615460 -0.3337486175 0.214934615647 +1413393990405760512.0000000000 -3.5621305898 0.5514971217 1.8642615675 0.5475343888 0.7253643411 -0.3528424734 0.222609197376 +1413393990455760384.0000000000 -3.5760495456 0.5486427611 1.8506612596 0.5410148567 0.7184235547 -0.3727476267 0.228538241068 +1413393990505760512.0000000000 -3.5887856120 0.5434619568 1.8379671552 0.5335671580 0.7119136665 -0.3924642718 0.233359839616 +1413393990555760384.0000000000 -3.6000985491 0.5359162617 1.8261866452 0.5242819656 0.7067534059 -0.4118594902 0.236642777315 +1413393990605760512.0000000000 -3.6096956982 0.5258582232 1.8144951170 0.5103362442 0.7048834770 -0.4313855981 0.237913151089 +1413393990655760384.0000000000 -3.6168655244 0.5134713190 1.8029881987 0.4917094532 0.7067079147 -0.4489735116 0.239183032208 +1413393990705760512.0000000000 -3.6211652404 0.4990331080 1.7908313319 0.4662446653 0.7143558621 -0.4622414356 0.242166202326 +1413393990755760384.0000000000 -3.6208370002 0.4834427707 1.7797287542 0.4402701528 0.7234943590 -0.4690250195 0.25046683621 +1413393990805760512.0000000000 -3.6158262200 0.4680255598 1.7701533076 0.4157162767 0.7325764215 -0.4721750912 0.259927773078 +1413393990855760384.0000000000 -3.6054373367 0.4544472067 1.7621236876 0.3938452764 0.7408853898 -0.4726117867 0.269467691133 +1413393990905760512.0000000000 -3.5893831251 0.4440619258 1.7569518324 0.3793446111 0.7457291432 -0.4707106604 0.280030686152 +1413393990955760384.0000000000 -3.5667416804 0.4378375290 1.7546594040 0.3742092660 0.7466330650 -0.4632068962 0.296556677303 +1413393991005760512.0000000000 -3.5386127750 0.4368252735 1.7555249936 0.3799208993 0.7427901601 -0.4520201686 0.315595715285 +1413393991055760384.0000000000 -3.5056619950 0.4414207230 1.7589758427 0.3929188742 0.7349201382 -0.4394033064 0.335308638419 +1413393991105760512.0000000000 -3.4699876002 0.4516860115 1.7645852390 0.4133248721 0.7224419084 -0.4270113955 0.353414073117 +1413393991155760384.0000000000 -3.4340543264 0.4665841565 1.7719838627 0.4388808424 0.7064859428 -0.4142966721 0.369620733092 +1413393991205760512.0000000000 -3.3993622814 0.4848851831 1.7802040579 0.4666963612 0.6880026741 -0.4039575200 0.381661039223 +1413393991255760384.0000000000 -3.3679573220 0.5051752315 1.7886719308 0.4939417213 0.6692928724 -0.3932179174 0.391724771227 +1413393991305760512.0000000000 -3.3413129457 0.5261993574 1.7963595203 0.5186577846 0.6514420789 -0.3834259469 0.399502019401 +1413393991355760384.0000000000 -3.3209385508 0.5472231654 1.8027326557 0.5382536944 0.6381886219 -0.3801138881 0.398135247621 +1413393991405760512.0000000000 -3.3069555687 0.5671243161 1.8077310489 0.5514341537 0.6301021519 -0.3806556687 0.392419309088 +1413393991455760384.0000000000 -3.2994754346 0.5851502148 1.8101322432 0.5529744404 0.6324613208 -0.3886410143 0.378378260271 +1413393991505760512.0000000000 -3.2980241501 0.6007740629 1.8114345083 0.5470625766 0.6409733616 -0.4020053218 0.358144395866 +1413393991555760384.0000000000 -3.3012141250 0.6139617684 1.8133240018 0.5402213959 0.6495143898 -0.4164187090 0.335987142172 +1413393991605760512.0000000000 -3.3072458859 0.6244157967 1.8152128720 0.5303343936 0.6593679990 -0.4318626506 0.312208142005 +1413393991655760384.0000000000 -3.3145110752 0.6316760132 1.8177414315 0.5183756096 0.6693592813 -0.4468085681 0.289148721882 +1413393991705760512.0000000000 -3.3210743788 0.6358742571 1.8212431882 0.5053509175 0.6787754162 -0.4586742729 0.27111306849 +1413393991755760384.0000000000 -3.3252633093 0.6370900413 1.8265559724 0.4942813239 0.6858519047 -0.4674478514 0.2584291854 +1413393991805760512.0000000000 -3.3259235263 0.6353641870 1.8336316972 0.4851204325 0.6911916324 -0.4724723542 0.25235325985 +1413393991855760384.0000000000 -3.3215384839 0.6313421050 1.8438336654 0.4832778433 0.6919658600 -0.4698842808 0.258523765691 +1413393991905760512.0000000000 -3.3129251540 0.6251436819 1.8556349881 0.4849455419 0.6910941637 -0.4587446997 0.277073959076 +1413393991955760384.0000000000 -3.3012009253 0.6176576653 1.8694599309 0.4915645554 0.6864286885 -0.4423747358 0.302464107922 +1413393992005760512.0000000000 -3.2891014669 0.6095691865 1.8848073202 0.5021130807 0.6784675531 -0.4266359612 0.324878423797 +1413393992055760384.0000000000 -3.2783383121 0.6009519897 1.8997317892 0.5115301306 0.6707215709 -0.4124904766 0.343978351859 +1413393992105760512.0000000000 -3.2701708831 0.5916511731 1.9136440261 0.5184787226 0.6644111100 -0.4022674411 0.357657094157 +1413393992155760384.0000000000 -3.2657870412 0.5817533257 1.9250575096 0.5185033282 0.6639277053 -0.3989903858 0.362161528538 +1413393992205760512.0000000000 -3.2652227253 0.5712025421 1.9333218699 0.5074166292 0.6721723238 -0.4025969149 0.358648094506 +1413393992255760384.0000000000 -3.2678897930 0.5604910479 1.9404733621 0.4924920110 0.6831432773 -0.4092173270 0.351152475595 +1413393992305760512.0000000000 -3.2726687741 0.5502511313 1.9476694686 0.4775799821 0.6936496338 -0.4181613957 0.340453511409 +1413393992355760384.0000000000 -3.2784875628 0.5417795319 1.9562764056 0.4675967749 0.7003773564 -0.4322330816 0.322489345533 +1413393992405760512.0000000000 -3.2836858385 0.5344422681 1.9653972943 0.4610822312 0.7043516527 -0.4460627789 0.30384193697 +1413393992455760384.0000000000 -3.2871724246 0.5276736079 1.9739752081 0.4595311756 0.7043824541 -0.4585750343 0.287028561191 +1413393992505760512.0000000000 -3.2876733148 0.5208566858 1.9817170449 0.4621429513 0.7015240360 -0.4665894505 0.276734898744 +1413393992555760384.0000000000 -3.2847033232 0.5135833602 1.9879503316 0.4687437875 0.6964846714 -0.4687690154 0.274670665381 +1413393992605760512.0000000000 -3.2781870463 0.5054211729 1.9914700976 0.4777337197 0.6902042083 -0.4657984031 0.280036589789 +1413393992655760384.0000000000 -3.2688793449 0.4956481091 1.9935969259 0.4885665485 0.6830117255 -0.4553319418 0.295754176978 +1413393992705760512.0000000000 -3.2583322973 0.4848577769 1.9951670582 0.5013669537 0.6742157892 -0.4408118428 0.315830914644 +1413393992755760384.0000000000 -3.2480308960 0.4731055235 1.9963010144 0.5134195546 0.6652899295 -0.4250699908 0.336311126218 +1413393992805760512.0000000000 -3.2399632913 0.4602089203 1.9967393006 0.5222515575 0.6580341366 -0.4113039616 0.353657230802 +1413393992855760384.0000000000 -3.2353810684 0.4463288880 1.9965960667 0.5255777072 0.6548633989 -0.4011880696 0.366019310117 +1413393992905760512.0000000000 -3.2352468611 0.4316292073 1.9957213097 0.5234609501 0.6563049421 -0.3968486847 0.371165162899 +1413393992955760384.0000000000 -3.2395868506 0.4161617648 1.9938682911 0.5140720395 0.6633300300 -0.3986970488 0.369815998531 +1413393993005760512.0000000000 -3.2480292642 0.4003744193 1.9919133847 0.5006202516 0.6734796816 -0.4035382141 0.364638714062 +1413393993055760384.0000000000 -3.2596651804 0.3846876659 1.9904628328 0.4862635097 0.6841204659 -0.4090362584 0.358073074336 +1413393993105760512.0000000000 -3.2732780066 0.3702788302 1.9903378924 0.4748764971 0.6920598683 -0.4155852602 0.350477306926 +1413393993155760384.0000000000 -3.2886700345 0.3571660706 1.9903555498 0.4620737463 0.7010279209 -0.4251680772 0.338052974101 +1413393993205760512.0000000000 -3.3042972649 0.3456369511 1.9907300098 0.4481935005 0.7101271542 -0.4366489534 0.322768806613 +1413393993255760384.0000000000 -3.3184733357 0.3355632465 1.9908150507 0.4310771686 0.7203134893 -0.4480227947 0.307565484511 +1413393993305760512.0000000000 -3.3300501287 0.3276312144 1.9918953963 0.4144694386 0.7297706892 -0.4581643933 0.292805762325 +1413393993355760384.0000000000 -3.3373122060 0.3219538021 1.9944005879 0.4009819674 0.7370601659 -0.4642125310 0.283659125822 +1413393993405760512.0000000000 -3.3392407672 0.3188322283 1.9983316585 0.3907591598 0.7425752299 -0.4659654898 0.280651864942 +1413393993455760384.0000000000 -3.3352036468 0.3190664079 2.0041318578 0.3862549305 0.7454363150 -0.4635649097 0.28326560568 +1413393993505760512.0000000000 -3.3245919009 0.3232889248 2.0124739626 0.3910441450 0.7432511457 -0.4582691064 0.290949543971 +1413393993555760384.0000000000 -3.3087225539 0.3313541859 2.0235284864 0.4042615874 0.7360165463 -0.4507388040 0.302798188779 +1413393993605760512.0000000000 -3.2894574048 0.3428811228 2.0366065980 0.4236550332 0.7248139676 -0.4413331904 0.316837719348 +1413393993655760384.0000000000 -3.2678136152 0.3571335679 2.0511645428 0.4469521336 0.7104736694 -0.4297153671 0.332874839303 +1413393993705760512.0000000000 -3.2460470080 0.3732676657 2.0660221513 0.4706700091 0.6944187569 -0.4179011236 0.348727663887 +1413393993755760384.0000000000 -3.2253361355 0.3905083363 2.0792388115 0.4930586215 0.6781408346 -0.4059495591 0.363625026134 +1413393993805760512.0000000000 -3.2074876664 0.4075796677 2.0867432231 0.5109657191 0.6642588959 -0.3957185406 0.375607494194 +1413393993855760384.0000000000 -3.1930915098 0.4240859088 2.0882313134 0.5254071734 0.6522510243 -0.3872737457 0.385402321379 +1413393993905760512.0000000000 -3.1827383002 0.4398212053 2.0837233676 0.5369325905 0.6422524502 -0.3805554628 0.392928394455 +1413393993955760384.0000000000 -3.1774616765 0.4546799257 2.0747472040 0.5478124491 0.6325271804 -0.3748345634 0.399136488911 +1413393994005760512.0000000000 -3.1785146156 0.4682378441 2.0635417594 0.5573833517 0.6242424423 -0.3717314731 0.401821956141 +1413393994055760384.0000000000 -3.1872763891 0.4802039874 2.0541458347 0.5666397267 0.6170910892 -0.3720301581 0.399639298889 +1413393994105760512.0000000000 -3.2047848270 0.4893004579 2.0484591722 0.5720622047 0.6133277971 -0.3762655385 0.393697970243 +1413393994155760384.0000000000 -3.2319592108 0.4949906811 2.0475754164 0.5758527998 0.6117479315 -0.3823221142 0.384691853761 +1413393994205760512.0000000000 -3.2673152731 0.4970481553 2.0505272140 0.5773227619 0.6122292954 -0.3904054332 0.373439842873 +1413393994255760384.0000000000 -3.3089507110 0.4953868297 2.0576177075 0.5731468789 0.6172853283 -0.3999616414 0.361236991679 +1413393994305760512.0000000000 -3.3561991049 0.4900797362 2.0680699971 0.5644156738 0.6264406889 -0.4122550409 0.345040275367 +1413393994355760384.0000000000 -3.4070996505 0.4804800721 2.0812451585 0.5465358433 0.6416453337 -0.4236289898 0.331855867307 +1413393994405760512.0000000000 -3.4611773566 0.4673775468 2.0930529911 0.5256166204 0.6583737473 -0.4357238092 0.316884741359 +1413393994455760384.0000000000 -3.5163083553 0.4520035929 2.0993720976 0.4992234137 0.6777637306 -0.4485704071 0.300327985105 +1413393994505760512.0000000000 -3.5712484148 0.4347052184 2.1004723086 0.4711613129 0.6964873726 -0.4604432250 0.284436976385 +1413393994555760384.0000000000 -3.6247662516 0.4166293048 2.0963258436 0.4436392740 0.7131479211 -0.4713198629 0.269187339904 +1413393994605760512.0000000000 -3.6753868298 0.3983639311 2.0867750418 0.4172573786 0.7273876765 -0.4814053543 0.255053588303 +1413393994655760384.0000000000 -3.7213790235 0.3805214843 2.0728552417 0.3940972829 0.7382512726 -0.4905740632 0.242918666681 +1413393994705760512.0000000000 -3.7609810675 0.3643447079 2.0560932620 0.3740602475 0.7467124228 -0.4980745873 0.233283506468 +1413393994755760384.0000000000 -3.7911782052 0.3505902762 2.0388173888 0.3593960267 0.7525371315 -0.5010464242 0.231246281169 +1413393994805760512.0000000000 -3.8105404365 0.3399755509 2.0230846749 0.3531854030 0.7552953869 -0.4974499313 0.23944209195 +1413393994855760384.0000000000 -3.8192336248 0.3338157776 2.0111435592 0.3602895701 0.7520620368 -0.4888681379 0.256128995209 +1413393994905760512.0000000000 -3.8194836972 0.3319452156 2.0019500184 0.3747791753 0.7447111591 -0.4780527148 0.276426230735 +1413393994955760384.0000000000 -3.8139103328 0.3341881058 1.9935885554 0.3929782819 0.7344699802 -0.4688766678 0.293728766894 +1413393995005760512.0000000000 -3.8037717967 0.3397312636 1.9852438367 0.4112725412 0.7230149133 -0.4627390572 0.306556514902 +1413393995055760384.0000000000 -3.7913076162 0.3478463191 1.9765432300 0.4296281244 0.7109944408 -0.4591832757 0.314733695634 +1413393995105760512.0000000000 -3.7772511281 0.3576603038 1.9669769149 0.4479458735 0.6990154583 -0.4574812270 0.318485180862 +1413393995155760384.0000000000 -3.7624089899 0.3684634807 1.9558850644 0.4628066242 0.6901140874 -0.4566008386 0.317912329318 +1413393995205760512.0000000000 -3.7474888181 0.3799133879 1.9432232339 0.4780237911 0.6821556762 -0.4584111717 0.309864625534 +1413393995255760384.0000000000 -3.7322236468 0.3906495547 1.9288634469 0.4905293048 0.6778829299 -0.4575636145 0.300817674214 +1413393995305760512.0000000000 -3.7169596050 0.3999058922 1.9126269316 0.4994527615 0.6774380067 -0.4553485422 0.290314297211 +1413393995355760384.0000000000 -3.7014999725 0.4074238928 1.8961139983 0.5075371845 0.6793468374 -0.4504838990 0.279209845023 +1413393995405760512.0000000000 -3.6851530719 0.4126468675 1.8795853735 0.5138862690 0.6836974130 -0.4428622441 0.268982867251 +1413393995455760384.0000000000 -3.6675922996 0.4155960574 1.8641655336 0.5200593149 0.6890818349 -0.4328699088 0.259476734868 +1413393995505760512.0000000000 -3.6489328861 0.4158566675 1.8493080855 0.5248066521 0.6963321288 -0.4202820215 0.251122612884 +1413393995555760384.0000000000 -3.6287235373 0.4136835632 1.8357961735 0.5300509019 0.7036511596 -0.4051974471 0.244409729281 +1413393995605760512.0000000000 -3.6073174588 0.4091892748 1.8229919374 0.5351365870 0.7114871644 -0.3876785674 0.238998277314 +1413393995655760384.0000000000 -3.5853504171 0.4024453896 1.8107592495 0.5403645918 0.7198250520 -0.3674278566 0.234210957624 +1413393995705760512.0000000000 -3.5629261066 0.3936247638 1.7992155713 0.5465435885 0.7274122751 -0.3443828256 0.231434563689 +1413393995755760384.0000000000 -3.5405054522 0.3833082555 1.7888506402 0.5532581413 0.7343851081 -0.3205082073 0.227724463062 +1413393995805760512.0000000000 -3.5189123880 0.3714078550 1.7794866865 0.5602818708 0.7408310407 -0.2968823902 0.221617780805 +1413393995855760384.0000000000 -3.4984034561 0.3579623243 1.7709540406 0.5681729094 0.7460304931 -0.2744031575 0.21288718976 +1413393995905760512.0000000000 -3.4792061486 0.3427412651 1.7627589948 0.5757308220 0.7507727914 -0.2533088505 0.201764373496 +1413393995955760384.0000000000 -3.4608982285 0.3256775198 1.7547584466 0.5828378134 0.7547864454 -0.2325173990 0.19113650699 +1413393996005760512.0000000000 -3.4436874898 0.3063352525 1.7466405170 0.5891655753 0.7580857054 -0.2138041518 0.180215906331 +1413393996055760384.0000000000 -3.4274201496 0.2847853974 1.7383346741 0.5940716865 0.7609846900 -0.1977091940 0.169977079403 +1413393996105760512.0000000000 -3.4121317306 0.2610225473 1.7302485295 0.5984605286 0.7628583204 -0.1846745903 0.160584788797 +1413393996155760384.0000000000 -3.3978870733 0.2353109365 1.7227944795 0.6023977846 0.7640784495 -0.1759604062 0.149462261269 +1413393996205760512.0000000000 -3.3845108836 0.2073083633 1.7148939141 0.6031923327 0.7670085859 -0.1702672955 0.137353147101 +1413393996255760384.0000000000 -3.3714313742 0.1766870290 1.7056590395 0.5981167634 0.7736647588 -0.1663140133 0.126644491702 +1413393996305760512.0000000000 -3.3581253753 0.1439605920 1.6961317342 0.5919103707 0.7804046001 -0.1621657831 0.119637084754 +1413393996355760384.0000000000 -3.3444888223 0.1095953801 1.6854475074 0.5841877086 0.7876714607 -0.1582249218 0.115166250404 +1413393996405760512.0000000000 -3.3303730646 0.0743797297 1.6730681000 0.5774304632 0.7936557581 -0.1540354025 0.113831861112 +1413393996455760384.0000000000 -3.3159806835 0.0385708813 1.6580576619 0.5706436898 0.7992861372 -0.1508174557 0.112967009116 +1413393996505760512.0000000000 -3.3014087001 0.0025634963 1.6404618926 0.5644728903 0.8041416402 -0.1488576963 0.112106935098 +1413393996555760384.0000000000 -3.2864899336 -0.0330147544 1.6202523702 0.5577801211 0.8089817467 -0.1478968887 0.112055256083 +1413393996605760512.0000000000 -3.2713997087 -0.0680947604 1.5982879058 0.5518473923 0.8131492041 -0.1471008835 0.112312766854 +1413393996655760384.0000000000 -3.2563830177 -0.1020652567 1.5762988936 0.5468490307 0.8168707584 -0.1456863940 0.111596488741 +1413393996705760512.0000000000 -3.2413148007 -0.1345618114 1.5553429212 0.5436354781 0.8195299317 -0.1434751163 0.110661868192 +1413393996755760384.0000000000 -3.2261730527 -0.1652864709 1.5358893825 0.5419632628 0.8213541377 -0.1404246550 0.109243390951 +1413393996805760512.0000000000 -3.2107709283 -0.1941368110 1.5178939932 0.5426193075 0.8218885171 -0.1348050026 0.109046613163 +1413393996855760384.0000000000 -3.1956879481 -0.2211768092 1.5013134764 0.5436860734 0.8223504999 -0.1281885402 0.108225723065 +1413393996905760512.0000000000 -3.1808704046 -0.2466100645 1.4859235083 0.5448472999 0.8228188418 -0.1210830616 0.107002175331 +1413393996955760384.0000000000 -3.1666313280 -0.2706020355 1.4715330489 0.5451913398 0.8239444915 -0.1131833156 0.105220791493 +1413393997005760512.0000000000 -3.1528172005 -0.2929165043 1.4584747803 0.5455351642 0.8250193996 -0.1056784501 0.102793190944 +1413393997055760384.0000000000 -3.1393524802 -0.3135042600 1.4467082271 0.5454677182 0.8262205067 -0.0997401072 0.0993808518067 +1413393997105760512.0000000000 -3.1261341173 -0.3321881507 1.4357075088 0.5452285382 0.8273126888 -0.0936188749 0.0975451808779 +1413393997155760384.0000000000 -3.1134032051 -0.3489970258 1.4260262656 0.5461429845 0.8274956206 -0.0892258524 0.0949609692417 +1413393997205760512.0000000000 -3.1011364271 -0.3636684869 1.4179351344 0.5494101110 0.8259769371 -0.0854675314 0.0927681539927 +1413393997255760384.0000000000 -3.0894041273 -0.3767793179 1.4105826842 0.5532480338 0.8239744806 -0.0819614555 0.0909119807198 +1413393997305760512.0000000000 -3.0782506938 -0.3886655094 1.4034086544 0.5567791656 0.8220773481 -0.0783332960 0.0897200606916 +1413393997355760384.0000000000 -3.0677754576 -0.3996505456 1.3950132338 0.5601091310 0.8202172911 -0.0753188959 0.0885913129144 +1413393997405760512.0000000000 -3.0578407151 -0.4097054503 1.3831312186 0.5625908823 0.8188504849 -0.0733654203 0.0871372352723 +1413393997455760384.0000000000 -3.0484107394 -0.4192826194 1.3666109210 0.5641296401 0.8180440046 -0.0714962390 0.0863136342799 +1413393997505760512.0000000000 -3.0394713248 -0.4285850693 1.3464941771 0.5650964251 0.8175839184 -0.0703749041 0.085263940581 +1413393997555760384.0000000000 -3.0313184199 -0.4378136017 1.3245327432 0.5670918208 0.8163158594 -0.0691982294 0.0851286644224 +1413393997605760512.0000000000 -3.0242493384 -0.4468538027 1.3030814535 0.5689882946 0.8151520855 -0.0683828964 0.0842803513346 +1413393997655760384.0000000000 -3.0180242398 -0.4554708610 1.2830808563 0.5712376568 0.8136000749 -0.0676922496 0.0846180644546 +1413393997705760512.0000000000 -3.0129642894 -0.4640288766 1.2645289844 0.5714040269 0.8135352691 -0.0677929203 0.0840352541958 +1413393997755760384.0000000000 -3.0087253610 -0.4723440429 1.2478768629 0.5707357270 0.8140237521 -0.0676677299 0.0839472411132 +1413393997805760512.0000000000 -3.0052859963 -0.4804529483 1.2329330924 0.5691654565 0.8150119532 -0.0679029250 0.084825657442 +1413393997855760384.0000000000 -3.0029329746 -0.4884142243 1.2197024768 0.5677035098 0.8159579535 -0.0681078965 0.0853619202648 +1413393997905760512.0000000000 -3.0016069724 -0.4960247511 1.2075849658 0.5663042346 0.8168159367 -0.0684460470 0.0861764355211 +1413393997955760384.0000000000 -3.0012584951 -0.5031517848 1.1965179074 0.5650189133 0.8175403912 -0.0691094776 0.0872078928903 +1413393998005760512.0000000000 -3.0019340209 -0.5096949460 1.1865331672 0.5642237433 0.8179578691 -0.0693713239 0.0882276108604 +1413393998055760384.0000000000 -3.0035769574 -0.5156490242 1.1771389765 0.5626482054 0.8188722760 -0.0700019315 0.0893024194033 +1413393998105760512.0000000000 -3.0062146348 -0.5209317070 1.1684444452 0.5617601452 0.8192601230 -0.0709340790 0.090591095889 +1413393998155760384.0000000000 -3.0098098133 -0.5254180890 1.1602348599 0.5613235421 0.8192715562 -0.0723490137 0.0920631226649 +1413393998205760512.0000000000 -3.0144563867 -0.5292582169 1.1528754121 0.5619413232 0.8185109019 -0.0737875628 0.0939002036034 +1413393998255760384.0000000000 -3.0201326161 -0.5327132644 1.1462070882 0.5619452405 0.8181850283 -0.0755162910 0.09533150538 +1413393998305760512.0000000000 -3.0269612125 -0.5355332703 1.1408316908 0.5629922139 0.8171715643 -0.0777493726 0.0960491361814 +1413393998355760384.0000000000 -3.0349777138 -0.5377887121 1.1365388265 0.5631845290 0.8168006324 -0.0797063030 0.0964718526083 +1413393998405760512.0000000000 -3.0441395945 -0.5395111168 1.1331849474 0.5604364712 0.8184793287 -0.0822452844 0.09611588555 +1413393998455760384.0000000000 -3.0544479605 -0.5404481041 1.1314876505 0.5570839833 0.8206559474 -0.0860915216 0.093645616148 +1413393998505760512.0000000000 -3.0655723858 -0.5403241414 1.1317323073 0.5553876495 0.8217046523 -0.0913641547 0.0894349727635 +1413393998555760384.0000000000 -3.0770472353 -0.5391723023 1.1328949378 0.5549611428 0.8218736691 -0.0959878607 0.0856045128438 +1413393998605760512.0000000000 -3.0889647616 -0.5370786437 1.1342719333 0.5568262416 0.8205123606 -0.1019758883 0.0794035324581 +1413393998655760384.0000000000 -3.1005893693 -0.5343602607 1.1347237303 0.5597955419 0.8183510955 -0.1071428640 0.0738298210765 +1413393998705760512.0000000000 -3.1116289696 -0.5314342799 1.1340958855 0.5627352408 0.8161886230 -0.1123621404 0.0673790009214 +1413393998755760384.0000000000 -3.1213692407 -0.5284136586 1.1324165335 0.5649797458 0.8144893136 -0.1165781625 0.061762260914 +1413393998805760512.0000000000 -3.1295522462 -0.5253832667 1.1302426862 0.5675998857 0.8125905729 -0.1188322047 0.0583595556683 +1413393998855760384.0000000000 -3.1359437936 -0.5227406172 1.1267157077 0.5691007676 0.8115715847 -0.1188665620 0.0578499752311 +1413393998905760512.0000000000 -3.1406357068 -0.5207066127 1.1220690917 0.5692040532 0.8116332508 -0.1169030074 0.0599324522691 +1413393998955760384.0000000000 -3.1434856905 -0.5189486097 1.1166687701 0.5693634997 0.8117263283 -0.1119916037 0.0662076566934 +1413393999005760512.0000000000 -3.1450523000 -0.5171918587 1.1110747148 0.5705904793 0.8109897655 -0.1059592904 0.0741264734236 +1413393999055760384.0000000000 -3.1460289944 -0.5154921739 1.1050769059 0.5719716138 0.8099811395 -0.0996430617 0.0827664603577 +1413393999105760512.0000000000 -3.1469894227 -0.5142216529 1.0981177760 0.5710059925 0.8105008015 -0.0931870111 0.0914154702121 +1413393999155760384.0000000000 -3.1485169454 -0.5134137942 1.0903749756 0.5671579459 0.8129876940 -0.0889116523 0.0973529245476 +1413393999205760512.0000000000 -3.1508196211 -0.5127408637 1.0823503441 0.5630542316 0.8156610424 -0.0868793012 0.100593157078 +1413393999255760384.0000000000 -3.1542080817 -0.5113583305 1.0741709424 0.5588605395 0.8185164134 -0.0870309247 0.100654838517 +1413393999305760512.0000000000 -3.1587135156 -0.5089887057 1.0664187900 0.5551741733 0.8211766854 -0.0905691298 0.0961650735197 +1413393999355760384.0000000000 -3.1639237499 -0.5055899634 1.0594234271 0.5536667862 0.8223777280 -0.0962097615 0.0888349269241 +1413393999405760512.0000000000 -3.1692411270 -0.5010946911 1.0525251285 0.5531017579 0.8228467492 -0.1015770865 0.0817543162826 +1413393999455760384.0000000000 -3.1742233321 -0.4961949860 1.0451858558 0.5520969960 0.8235156099 -0.1056920056 0.0764208555827 +1413393999505760512.0000000000 -3.1785234308 -0.4905224473 1.0385939801 0.5530375788 0.8227966353 -0.1093160713 0.0721465860116 +1413393999555760384.0000000000 -3.1818851431 -0.4838555234 1.0325001812 0.5542715697 0.8218278936 -0.1128227690 0.0682126320626 +1413393999605760512.0000000000 -3.1841478008 -0.4761789479 1.0265257720 0.5572707378 0.8196288940 -0.1160784346 0.0646807383106 +1413393999655760384.0000000000 -3.1849736841 -0.4678008180 1.0210107170 0.5593454231 0.8181238874 -0.1179595791 0.0623822110506 +1413393999705760512.0000000000 -3.1843491593 -0.4594888777 1.0151884395 0.5611027361 0.8168238929 -0.1196521299 0.0603805873664 +1413393999755760384.0000000000 -3.1821163228 -0.4513098111 1.0078765178 0.5622347291 0.8160046235 -0.1208241898 0.0585668766173 +1413393999805760512.0000000000 -3.1784493665 -0.4431278140 0.9984241816 0.5638193412 0.8149225866 -0.1213459386 0.0573069934234 +1413393999855760384.0000000000 -3.1733724603 -0.4352326930 0.9864594828 0.5636677571 0.8150235645 -0.1221478158 0.0556341620456 +1413393999905760512.0000000000 -3.1668321222 -0.4276409754 0.9728376729 0.5641575018 0.8147565571 -0.1221554259 0.0545538059776 +1413393999955760384.0000000000 -3.1584641143 -0.4203430420 0.9572406636 0.5646695900 0.8146436832 -0.1192309607 0.0573402263305 +1413394000005760512.0000000000 -3.1483252728 -0.4133453589 0.9413046618 0.5679961578 0.8125874740 -0.1115505881 0.0681060064154 +1413394000055760384.0000000000 -3.1421882771 -0.4091724191 0.9339073092 0.5717548578 0.8095240688 -0.0995237649 0.0886689619846 +1413394000105760512.0000000000 -3.1455155820 -0.4095720548 0.9414178044 0.5715047046 0.8098952964 -0.1038077505 0.0817063795856 +1413394000155760384.0000000000 -3.1465873842 -0.4100254516 0.9505229520 0.5772430439 0.8053394803 -0.0981084090 0.0927012932507 +1413394000205760512.0000000000 -3.1478390841 -0.4112750024 0.9542755897 0.5795662815 0.8029769509 -0.0923866115 0.103902145181 +1413394000255760384.0000000000 -3.1496493295 -0.4136647470 0.9489815267 0.5774258796 0.8036719512 -0.0875064634 0.114163774432 +1413394000305760512.0000000000 -3.1509003359 -0.4157206110 0.9359811578 0.5755304536 0.8041453705 -0.0935855899 0.11557100604 +1413394000355760384.0000000000 -3.1477539500 -0.4174516139 0.9333945997 0.5809524519 0.8006357124 -0.1159966641 0.0895627074003 +1413394000405760512.0000000000 -3.1439619748 -0.4186671526 0.9390927463 0.5812834403 0.8005019551 -0.1079290856 0.0982725514553 +1413394000455760384.0000000000 -3.1451635325 -0.4181923736 0.9379800481 0.5787149237 0.8023321177 -0.1071163170 0.0993896601803 +1413394000505760512.0000000000 -3.1456610310 -0.4179705555 0.9326722320 0.5766909942 0.8037642624 -0.1081889918 0.0984156982467 +1413394000555760384.0000000000 -3.1443424208 -0.4185838879 0.9348748099 0.5790650969 0.8020868544 -0.1082212423 0.0981246874209 +1413394000605760512.0000000000 -3.1450013618 -0.4185981763 0.9360118440 0.5809722938 0.8007562934 -0.1105998329 0.0950169955684 +1413394000655760384.0000000000 -3.1449600822 -0.4184296777 0.9336519459 0.5792931463 0.8019049077 -0.1072124785 0.0993652564861 +1413394000705760512.0000000000 -3.1453766143 -0.4179983103 0.9346057052 0.5792019798 0.8020213054 -0.1096628203 0.0962338716346 +1413394000755760384.0000000000 -3.1446858523 -0.4182395860 0.9340542586 0.5789179342 0.8022174761 -0.1082478994 0.0978955501842 +1413394000805760512.0000000000 -3.1453489060 -0.4182132923 0.9344235142 0.5802368083 0.8012748930 -0.1095485998 0.0963477883671 +1413394000855760384.0000000000 -3.1451143522 -0.4183008021 0.9343067084 0.5796813905 0.8016655375 -0.1083213531 0.0978178714515 +1413394000905760512.0000000000 -3.1450554903 -0.4182433729 0.9342659449 0.5795805875 0.8017515368 -0.1095854821 0.0962903830896 +1413394000955760384.0000000000 -3.1450314768 -0.4183220956 0.9342914045 0.5795428496 0.8017730790 -0.1087866758 0.09723926411 +1413394001005760512.0000000000 -3.1451481914 -0.4183750905 0.9343119520 0.5799391615 0.8015003400 -0.1094383321 0.0963899651463 +1413394001055760384.0000000000 -3.1448525156 -0.4183759859 0.9342504167 0.5797080156 0.8016537897 -0.1090208039 0.0969756791123 +1413394001105760512.0000000000 -3.1451198629 -0.4183160527 0.9341681367 0.5795214152 0.8018001262 -0.1095533285 0.0962785293653 +1413394001155760384.0000000000 -3.1449788985 -0.4184480123 0.9341790995 0.5798402620 0.8015675341 -0.1090906207 0.096819395901 +1413394001205760512.0000000000 -3.1450547069 -0.4184399031 0.9341907373 0.5797374633 0.8016303791 -0.1096230259 0.0963119983403 +1413394001255760384.0000000000 -3.1451091018 -0.4183719755 0.9341238195 0.5796072598 0.8017464778 -0.1092423879 0.0965614331044 +1413394001305760512.0000000000 -3.1451210740 -0.4183400614 0.9342167011 0.5797230532 0.8016589331 -0.1095294148 0.0962675636718 +1413394001355760384.0000000000 -3.1450489814 -0.4183371877 0.9341993187 0.5797160723 0.8016479218 -0.1093802501 0.0965704196788 +1413394001405760512.0000000000 -3.1451384095 -0.4182646388 0.9341907592 0.5797289609 0.8016679157 -0.1094913594 0.0962004523802 +1413394001455760384.0000000000 -3.1450000852 -0.4182419062 0.9340549049 0.5796488423 0.8017066022 -0.1094159828 0.0964462870652 +1413394001505760512.0000000000 -3.1450364703 -0.4181805742 0.9340411520 0.5797630351 0.8016221962 -0.1095867373 0.0962674645348 +1413394001555760384.0000000000 -3.1449971064 -0.4181457674 0.9339629348 0.5795847038 0.8017475720 -0.1095423992 0.0963476244346 +1413394001605760512.0000000000 -3.1450174506 -0.4181787898 0.9339736848 0.5796251778 0.8017175910 -0.1096947232 0.0961801707652 +1413394001655760384.0000000000 -3.1450660537 -0.4182705834 0.9339515258 0.5796669569 0.8016877213 -0.1096607509 0.096216091837 +1413394001705760512.0000000000 -3.1451042767 -0.4183527552 0.9339848275 0.5796109304 0.8017414375 -0.1096896978 0.096072925127 +1413394001755760384.0000000000 -3.1451130388 -0.4184537255 0.9339829059 0.5796285309 0.8017345803 -0.1096722586 0.0960438681223 +1413394001805760512.0000000000 -3.1451847827 -0.4186281197 0.9339683181 0.5796004518 0.8017666467 -0.1096782560 0.0959387337877 +1413394001855760384.0000000000 -3.1452219244 -0.4188213878 0.9339060583 0.5795467051 0.8018096586 -0.1096866011 0.0958944076569 +1413394001905760512.0000000000 -3.1452684966 -0.4190022737 0.9338709177 0.5795139454 0.8018331430 -0.1097533380 0.0958196367848 +1413394001955760384.0000000000 -3.1452834859 -0.4190473151 0.9337880057 0.5794836865 0.8018538602 -0.1097888521 0.095788579758 +1413394002005760512.0000000000 -3.1452552639 -0.4190436225 0.9336732924 0.5794292048 0.8018761340 -0.1098833841 0.0958232974201 +1413394002055760384.0000000000 -3.1451841471 -0.4190499919 0.9336258256 0.5794292569 0.8018633391 -0.1099216061 0.0958861944283 +1413394002105760512.0000000000 -3.1451344045 -0.4192156682 0.9336651431 0.5794340110 0.8018520667 -0.1099726228 0.0958932333677 +1413394002155760384.0000000000 -3.1450918099 -0.4193418155 0.9336302334 0.5793600812 0.8019086573 -0.1100053498 0.0958291430982 +1413394002205760512.0000000000 -3.1450415954 -0.4194915345 0.9336469871 0.5793110509 0.8019440191 -0.1100419907 0.0957875609263 +1413394002255760384.0000000000 -3.1449718332 -0.4195988215 0.9336496130 0.5793642652 0.8019082198 -0.1100160489 0.0957952204856 +1413394002305760512.0000000000 -3.1449317427 -0.4196455408 0.9336445507 0.5792889765 0.8019668565 -0.1100175458 0.095757936803 +1413394002355760384.0000000000 -3.1449274286 -0.4196514120 0.9336359700 0.5792911096 0.8019587583 -0.1100947947 0.095724064541 +1413394002405760512.0000000000 -3.1449618226 -0.4195287960 0.9335917785 0.5792560710 0.8019865988 -0.1100615657 0.0957410636064 +1413394002455760384.0000000000 -3.1450375201 -0.4192223920 0.9335525081 0.5792096374 0.8020242799 -0.1100791790 0.0956860742218 +1413394002505760512.0000000000 -3.1451665299 -0.4187147620 0.9335354000 0.5791715479 0.8020506827 -0.1100834585 0.0956904002491 +1413394002555760384.0000000000 -3.1453752275 -0.4179139563 0.9335777088 0.5791339693 0.8020733958 -0.1100941049 0.0957152099598 +1413394002605760512.0000000000 -3.1456715509 -0.4167314108 0.9336547292 0.5791123472 0.8020884335 -0.1101461216 0.0956601597234 +1413394002655760384.0000000000 -3.1460736165 -0.4151301515 0.9337574871 0.5790445857 0.8021347630 -0.1101292880 0.0957012524967 diff --git a/data/euroc_groundtruth/V2_03_difficult.txt b/data/euroc_groundtruth/V2_03_difficult.txt new file mode 100755 index 00000000..77ae6c78 --- /dev/null +++ b/data/euroc_groundtruth/V2_03_difficult.txt @@ -0,0 +1,1891 @@ +#timestamp [ns] p_RS_R_x [m] p_RS_R_y [m] p_RS_R_z [m] q_RS_w [] q_RS_x [] q_RS_y [] q_RS_z [] +1413394882805760512.0000000000 -1.0516909472 0.3626874258 1.3107838438 0.4152901805 0.5441961050 0.5791644582 -0.442666009146 +1413394882855760384.0000000000 -1.0524840899 0.3624194883 1.3108103715 0.4152349552 0.5443537473 0.5790717028 -0.442645335272 +1413394882905760512.0000000000 -1.0530694460 0.3622540670 1.3107938757 0.4153789040 0.5443891228 0.5789917527 -0.442571349537 +1413394882955760384.0000000000 -1.0534169549 0.3620659482 1.3108053606 0.4153947965 0.5444578098 0.5789449888 -0.442533113241 +1413394883005760512.0000000000 -1.0536540915 0.3619357957 1.3107673967 0.4152786315 0.5445172644 0.5789738708 -0.442531201001 +1413394883055760384.0000000000 -1.0537739491 0.3618562739 1.3107816247 0.4152438132 0.5444944474 0.5790165703 -0.442536081822 +1413394883105760512.0000000000 -1.0538496231 0.3617891972 1.3107729630 0.4152169809 0.5444929750 0.5790003899 -0.442584237659 +1413394883155760384.0000000000 -1.0539150620 0.3618298018 1.3107757320 0.4153023290 0.5444512746 0.5789843287 -0.442576470513 +1413394883205760512.0000000000 -1.0539355144 0.3618857821 1.3107835791 0.4153506940 0.5445012250 0.5788961301 -0.442585005934 +1413394883255760384.0000000000 -1.0539289489 0.3619250764 1.3108281365 0.4153164038 0.5445720170 0.5788427482 -0.442599904928 +1413394883305760512.0000000000 -1.0538682254 0.3619768252 1.3108420942 0.4152855653 0.5445895821 0.5788611809 -0.442583121581 +1413394883355760384.0000000000 -1.0537763530 0.3619736470 1.3108937394 0.4151420980 0.5446119878 0.5789003205 -0.442638950069 +1413394883405760512.0000000000 -1.0537504572 0.3620159636 1.3109193000 0.4151482978 0.5445570329 0.5789296309 -0.442662412318 +1413394883455760384.0000000000 -1.0536604323 0.3620838178 1.3109501662 0.4151437946 0.5445224733 0.5789556951 -0.442675060214 +1413394883505760512.0000000000 -1.0536265807 0.3621469739 1.3109590898 0.4152084182 0.5445154651 0.5789238065 -0.442664776009 +1413394883555760384.0000000000 -1.0536178611 0.3622453987 1.3109944468 0.4152263606 0.5445533024 0.5789288568 -0.442594791113 +1413394883605760512.0000000000 -1.0535971490 0.3621801556 1.3110306855 0.4150874625 0.5444592176 0.5793990233 -0.442225429644 +1413394883655760384.0000000000 -1.0533996202 0.3620593003 1.3111322672 0.4149151440 0.5443669380 0.5794130987 -0.442482226887 +1413394883705760512.0000000000 -1.0534077049 0.3620627616 1.3111433231 0.4148036185 0.5446236218 0.5789798327 -0.442837918452 +1413394883755760384.0000000000 -1.0534149083 0.3619905960 1.3110741633 0.4149284736 0.5445467454 0.5791114181 -0.442643388501 +1413394883805760512.0000000000 -1.0533409820 0.3619397211 1.3109213383 0.4150488472 0.5445291435 0.5791659090 -0.442480865375 +1413394883855760384.0000000000 -1.0532858608 0.3619579215 1.3109170595 0.4149995282 0.5446501366 0.5789633491 -0.442643265811 +1413394883905760512.0000000000 -1.0532719821 0.3620016256 1.3108576409 0.4150728944 0.5446571054 0.5788372151 -0.442730853061 +1413394883955760384.0000000000 -1.0532320114 0.3619605492 1.3107426356 0.4150111453 0.5446376826 0.5790432855 -0.442543125058 +1413394884005760512.0000000000 -1.0532444836 0.3620117745 1.3107359875 0.4151764537 0.5446208399 0.5788908681 -0.442608196772 +1413394884055760384.0000000000 -1.0532893379 0.3619823082 1.3107697633 0.4150292788 0.5446848197 0.5788445003 -0.442728121323 +1413394884105760512.0000000000 -1.0533811005 0.3620331840 1.3106866452 0.4151826518 0.5446311124 0.5788915364 -0.442588868122 +1413394884155760384.0000000000 -1.0534098886 0.3620235232 1.3107124583 0.4149884142 0.5447331804 0.5789127924 -0.442617619384 +1413394884205760512.0000000000 -1.0534141008 0.3620858337 1.3107577661 0.4151878597 0.5446809913 0.5787959002 -0.44264767569 +1413394884255760384.0000000000 -1.0533472943 0.3620700874 1.3107997519 0.4150078721 0.5447130166 0.5789104588 -0.442627243027 +1413394884305760512.0000000000 -1.0534000235 0.3620518172 1.3108405604 0.4150195813 0.5447184950 0.5789323003 -0.442580953069 +1413394884355760384.0000000000 -1.0534103906 0.3619822565 1.3108836242 0.4150125494 0.5446452531 0.5790730612 -0.442493527502 +1413394884405760512.0000000000 -1.0533487800 0.3619475221 1.3109225898 0.4149333208 0.5446780454 0.5789693078 -0.442663197845 +1413394884455760384.0000000000 -1.0533760241 0.3619929246 1.3109961925 0.4150101701 0.5447527401 0.5789552764 -0.442517568821 +1413394884505760512.0000000000 -1.0534521810 0.3619327938 1.3109816047 0.4148812539 0.5448201796 0.5790506516 -0.442430627304 +1413394884555760384.0000000000 -1.0534067341 0.3619125989 1.3109888376 0.4149849642 0.5447440796 0.5790288958 -0.442455540217 +1413394884605760512.0000000000 -1.0534338585 0.3619850351 1.3109701009 0.4149986417 0.5448391803 0.5789140682 -0.442475871286 +1413394884655760384.0000000000 -1.0534646570 0.3620143308 1.3109519086 0.4149889204 0.5448562297 0.5788680922 -0.442524142518 +1413394884705760512.0000000000 -1.0534137411 0.3620463035 1.3109770944 0.4150744143 0.5447931291 0.5789195665 -0.442454305718 +1413394884755760384.0000000000 -1.0534522823 0.3621100969 1.3109431811 0.4151182273 0.5448174574 0.5789118957 -0.442393278048 +1413394884805760512.0000000000 -1.0534258053 0.3620586182 1.3110501867 0.4149605458 0.5447752807 0.5789308936 -0.442568253904 +1413394884855760384.0000000000 -1.0534062806 0.3621667127 1.3110278275 0.4151400336 0.5447314632 0.5789201584 -0.442467892243 +1413394884905760512.0000000000 -1.0534547846 0.3622885968 1.3110121347 0.4150388017 0.5448929457 0.5788051872 -0.44251443616 +1413394884955760384.0000000000 -1.0534285758 0.3622017245 1.3109602256 0.4151313312 0.5447220529 0.5787968510 -0.442648922061 +1413394885005760512.0000000000 -1.0533699119 0.3622263996 1.3108884276 0.4151448499 0.5447808241 0.5787498377 -0.442625386308 +1413394885055760384.0000000000 -1.0533713350 0.3621491373 1.3108425785 0.4150228932 0.5447526998 0.5787968358 -0.442712905955 +1413394885105760512.0000000000 -1.0533575240 0.3621894316 1.3108452656 0.4150224392 0.5447976701 0.5787759182 -0.442685339923 +1413394885155760384.0000000000 -1.0533514449 0.3621727798 1.3108349639 0.4151749449 0.5447550210 0.5786980118 -0.442696672032 +1413394885205760512.0000000000 -1.0533852842 0.3620886659 1.3108367480 0.4149420957 0.5447625103 0.5788359865 -0.442725383712 +1413394885255760384.0000000000 -1.0533972351 0.3621593289 1.3108645227 0.4151269645 0.5447825598 0.5787065381 -0.442696632637 +1413394885305760512.0000000000 -1.0533497702 0.3620781267 1.3108801793 0.4150651824 0.5447420456 0.5787625008 -0.442731256828 +1413394885355760384.0000000000 -1.0533220515 0.3620594995 1.3109289507 0.4148862948 0.5447454286 0.5788643363 -0.442761629502 +1413394885405760512.0000000000 -1.0533677116 0.3620887830 1.3109482068 0.4151047118 0.5447776486 0.5786780631 -0.442760760659 +1413394885455760384.0000000000 -1.0533369665 0.3620486046 1.3109462663 0.4150655272 0.5447690607 0.5787095837 -0.442766864635 +1413394885505760512.0000000000 -1.0532949588 0.3619941871 1.3109026217 0.4148286429 0.5448111177 0.5788200133 -0.44279276793 +1413394885555760384.0000000000 -1.0532191549 0.3620787082 1.3108909976 0.4150074847 0.5447413619 0.5787848370 -0.442756986104 +1413394885605760512.0000000000 -1.0531823677 0.3621691480 1.3108936481 0.4151007569 0.5447341305 0.5787150100 -0.442769721038 +1413394885655760384.0000000000 -1.0531268899 0.3621316634 1.3108932844 0.4148802963 0.5448261663 0.5787444714 -0.442824598602 +1413394885705760512.0000000000 -1.0531336009 0.3620797209 1.3108739823 0.4149087961 0.5447390537 0.5788315309 -0.442791275 +1413394885755760384.0000000000 -1.0532049717 0.3620665170 1.3108522875 0.4149839364 0.5447841830 0.5787557770 -0.442764358391 +1413394885805760512.0000000000 -1.0532689344 0.3620460990 1.3108845339 0.4149392735 0.5448097306 0.5787244174 -0.442815769215 +1413394885855760384.0000000000 -1.0533467597 0.3620191834 1.3108524079 0.4149170678 0.5447427490 0.5788136424 -0.44280236179 +1413394885905760512.0000000000 -1.0535091812 0.3621341409 1.3108752438 0.4149905271 0.5448675142 0.5788421711 -0.442542648094 +1413394885955760384.0000000000 -1.0536246483 0.3618815309 1.3109155525 0.4146028072 0.5445773435 0.5792676525 -0.442706467021 +1413394886005760512.0000000000 -1.0537817991 0.3620562589 1.3110474497 0.4149565310 0.5451871142 0.5785699621 -0.442536876224 +1413394886055760384.0000000000 -1.0539318912 0.3619107961 1.3110697914 0.4149560221 0.5450619073 0.5787737329 -0.442425115748 +1413394886105760512.0000000000 -1.0540470308 0.3618165675 1.3112012482 0.4148253097 0.5449248932 0.5789239396 -0.442519937809 +1413394886155760384.0000000000 -1.0540408701 0.3617345870 1.3113095608 0.4147593276 0.5450261438 0.5788488110 -0.44255537142 +1413394886205760512.0000000000 -1.0539770806 0.3618328924 1.3114110606 0.4148576488 0.5450172220 0.5788673130 -0.442449989205 +1413394886255760384.0000000000 -1.0538705815 0.3618864790 1.3113959067 0.4147372419 0.5450931569 0.5789106542 -0.442412618429 +1413394886305760512.0000000000 -1.0539004274 0.3618911086 1.3113852166 0.4146369807 0.5450593582 0.5791276167 -0.442264257935 +1413394886355760384.0000000000 -1.0538123075 0.3621217111 1.3112855727 0.4142826192 0.5453521753 0.5794075791 -0.441868502566 +1413394886405760512.0000000000 -1.0537022281 0.3620667407 1.3113099113 0.4140423078 0.5454387140 0.5796157868 -0.441713839803 +1413394886455760384.0000000000 -1.0536486053 0.3619792554 1.3114412615 0.4140627025 0.5453887320 0.5795602369 -0.44182931229 +1413394886505760512.0000000000 -1.0536126652 0.3619280846 1.3113087007 0.4136262482 0.5456263991 0.5797716458 -0.441667293502 +1413394886555760384.0000000000 -1.0536319299 0.3619925723 1.3115191055 0.4132539431 0.5458367493 0.5801914101 -0.441204430241 +1413394886605760512.0000000000 -1.0537375832 0.3619670379 1.3116050350 0.4125355542 0.5462111037 0.5803818318 -0.441162981183 +1413394886655760384.0000000000 -1.0538248491 0.3619970699 1.3118009488 0.4118661485 0.5466689123 0.5804874400 -0.441082427737 +1413394886705760512.0000000000 -1.0538499908 0.3621227645 1.3119520033 0.4121806988 0.5465139978 0.5808120266 -0.440552960976 +1413394886755760384.0000000000 -1.0538092380 0.3620040223 1.3122732055 0.4112490890 0.5471173772 0.5812302341 -0.440122911653 +1413394886805760512.0000000000 -1.0538282177 0.3621303787 1.3124838682 0.4110418608 0.5472493791 0.5815577723 -0.439719527933 +1413394886855760384.0000000000 -1.0540560505 0.3620775982 1.3125581265 0.4104192037 0.5476852247 0.5821768921 -0.438938535749 +1413394886905760512.0000000000 -1.0544685551 0.3621226574 1.3126479545 0.4106117723 0.5476773767 0.5830110001 -0.437659270784 +1413394886955760384.0000000000 -1.0542288267 0.3622781060 1.3116537241 0.4079756916 0.5494609392 0.5843041320 -0.436161888166 +1413394887005760512.0000000000 -1.0535534404 0.3626217364 1.3119436113 0.4088803967 0.5490143687 0.5838300100 -0.436511813725 +1413394887055760384.0000000000 -1.0527502251 0.3634153838 1.3122520944 0.4079036238 0.5503385690 0.5856590099 -0.43329622353 +1413394887105760512.0000000000 -1.0517147079 0.3644783423 1.3142466434 0.4071695037 0.5514150245 0.5875114977 -0.430098484261 +1413394887155760384.0000000000 -1.0503618696 0.3657780914 1.3185425048 0.4072773397 0.5521629363 0.5881604776 -0.428145434281 +1413394887205760512.0000000000 -1.0489197685 0.3672190946 1.3242968042 0.4093477962 0.5519465916 0.5876145516 -0.427198408881 +1413394887255760384.0000000000 -1.0470636101 0.3683691263 1.3307904080 0.4107757476 0.5519858011 0.5883404244 -0.424771121401 +1413394887305760512.0000000000 -1.0453782215 0.3691837793 1.3390872755 0.4136831335 0.5509675068 0.5874600843 -0.424489953625 +1413394887355760384.0000000000 -1.0433251778 0.3697251429 1.3488714334 0.4141261115 0.5516348030 0.5885727829 -0.421640471467 +1413394887405760512.0000000000 -1.0410955026 0.3699239358 1.3619801313 0.4133753009 0.5534031220 0.5894810387 -0.418781506463 +1413394887455760384.0000000000 -1.0389283673 0.3699616106 1.3792016535 0.4159883086 0.5524664423 0.5896701100 -0.417161501872 +1413394887505760512.0000000000 -1.0366925539 0.3695079701 1.3995651691 0.4167390289 0.5525882247 0.5893884332 -0.41664866558 +1413394887555760384.0000000000 -1.0342397629 0.3687337894 1.4221268319 0.4159871450 0.5538926574 0.5905026215 -0.414082447558 +1413394887605760512.0000000000 -1.0316666836 0.3672509952 1.4467588024 0.4151634148 0.5551327687 0.5918663426 -0.411292086736 +1413394887655760384.0000000000 -1.0294855467 0.3649732833 1.4707999973 0.4127196495 0.5572257639 0.5945196426 -0.407072884832 +1413394887705760512.0000000000 -1.0280120486 0.3619505795 1.4939283415 0.4091298420 0.5603407382 0.5965745423 -0.403397874228 +1413394887755760384.0000000000 -1.0270853971 0.3580518060 1.5155134639 0.4055617185 0.5634565003 0.5983010772 -0.400090346984 +1413394887805760512.0000000000 -1.0274008021 0.3534719803 1.5354023558 0.4024022686 0.5656603678 0.6001704256 -0.397361576898 +1413394887855760384.0000000000 -1.0290374221 0.3484354691 1.5527521391 0.4014293881 0.5663096431 0.6027592315 -0.393483345799 +1413394887905760512.0000000000 -1.0321724094 0.3424838360 1.5676518607 0.3987995039 0.5685747756 0.6038370570 -0.391232013997 +1413394887955760384.0000000000 -1.0370168345 0.3356053310 1.5807928256 0.3978558505 0.5691171156 0.6043618887 -0.390593316003 +1413394888005760512.0000000000 -1.0436560303 0.3280042639 1.5927049621 0.3973907180 0.5694871867 0.6038132297 -0.391375197162 +1413394888055760384.0000000000 -1.0523298666 0.3196808893 1.6050609533 0.3996466256 0.5678368516 0.6022715787 -0.393843661968 +1413394888105760512.0000000000 -1.0628819605 0.3106521658 1.6181872242 0.4029105121 0.5652481422 0.6006380016 -0.39672616245 +1413394888155760384.0000000000 -1.0746689428 0.3009313421 1.6325527615 0.4057978655 0.5626209896 0.5985783201 -0.400611668735 +1413394888205760512.0000000000 -1.0874063906 0.2908997213 1.6471576888 0.4082782804 0.5605327261 0.5974009686 -0.402770395513 +1413394888255760384.0000000000 -1.1011218962 0.2800015970 1.6622930587 0.4097749217 0.5591853042 0.5961724991 -0.404937847722 +1413394888305760512.0000000000 -1.1149618778 0.2685069075 1.6769878082 0.4101518770 0.5580785621 0.5981393268 -0.403178747045 +1413394888355760384.0000000000 -1.1295612128 0.2561469078 1.6927259363 0.4092381344 0.5580996670 0.5982991009 -0.403840435082 +1413394888405760512.0000000000 -1.1447562702 0.2432545830 1.7083026508 0.4085055561 0.5583999300 0.5997027407 -0.402081274808 +1413394888455760384.0000000000 -1.1607039668 0.2293716903 1.7242885494 0.4072864884 0.5586086148 0.6007275636 -0.401497853141 +1413394888505760512.0000000000 -1.1772782575 0.2147546697 1.7401305027 0.4043323119 0.5603438030 0.6010931078 -0.401518716501 +1413394888555760384.0000000000 -1.1948023772 0.1995678315 1.7536093404 0.4017018788 0.5623944456 0.6006373664 -0.401973683438 +1413394888605760512.0000000000 -1.2131034515 0.1838246667 1.7623602885 0.3991439048 0.5637381888 0.6008383055 -0.402339071409 +1413394888655760384.0000000000 -1.2324560295 0.1678010296 1.7668175312 0.3980038199 0.5640973458 0.6000193163 -0.404183081992 +1413394888705760512.0000000000 -1.2532079409 0.1517128178 1.7684512016 0.3994514993 0.5631001233 0.5979849146 -0.407149594941 +1413394888755760384.0000000000 -1.2743647677 0.1353656468 1.7691104176 0.3989952253 0.5629775285 0.5948350957 -0.412347331092 +1413394888805760512.0000000000 -1.2967323749 0.1194139565 1.7701097268 0.4005216105 0.5621612201 0.5902463947 -0.418528846852 +1413394888855760384.0000000000 -1.3192369402 0.1034802110 1.7713531397 0.4005692412 0.5617328597 0.5874708181 -0.422940321126 +1413394888905760512.0000000000 -1.3420087925 0.0881489752 1.7734995055 0.4003739363 0.5613593069 0.5845103353 -0.427696279683 +1413394888955760384.0000000000 -1.3646074635 0.0734847132 1.7765590172 0.3998201136 0.5617764936 0.5816532525 -0.431544368364 +1413394889005760512.0000000000 -1.3868795959 0.0596236632 1.7797826772 0.3997424703 0.5612167415 0.5809050586 -0.433348634869 +1413394889055760384.0000000000 -1.4087626957 0.0470783285 1.7840455483 0.3997246604 0.5610410921 0.5789428092 -0.436209023747 +1413394889105760512.0000000000 -1.4302633493 0.0353434193 1.7884917786 0.3991722436 0.5616700664 0.5776277912 -0.437646422779 +1413394889155760384.0000000000 -1.4513063084 0.0245882656 1.7936682396 0.4010093692 0.5597404881 0.5780567438 -0.437872667356 +1413394889205760512.0000000000 -1.4720871573 0.0152687297 1.7999014637 0.4067979586 0.5558199272 0.5773609553 -0.438444930138 +1413394889255760384.0000000000 -1.4925275007 0.0065285457 1.8083462662 0.4151815845 0.5499577508 0.5722592232 -0.444623555007 +1413394889305760512.0000000000 -1.5116132017 -0.0014722857 1.8188938257 0.4269930442 0.5410226293 0.5649584702 -0.453644554422 +1413394889355760384.0000000000 -1.5285345225 -0.0089244699 1.8308661006 0.4420147748 0.5290900342 0.5544672757 -0.466103759676 +1413394889405760512.0000000000 -1.5412490417 -0.0160080396 1.8442504265 0.4554406124 0.5176131590 0.5422060610 -0.480273936002 +1413394889455760384.0000000000 -1.5490681505 -0.0222082058 1.8575155581 0.4687896009 0.5064302470 0.5318447049 -0.49082168338 +1413394889505760512.0000000000 -1.5502095193 -0.0279754787 1.8694050528 0.4750933270 0.5007822308 0.5271381750 -0.495609556328 +1413394889555760384.0000000000 -1.5449692141 -0.0331143349 1.8790392012 0.4738846276 0.5027825528 0.5320121115 -0.489495840192 +1413394889605760512.0000000000 -1.5332517541 -0.0381294278 1.8870757886 0.4619575668 0.5135120949 0.5430392609 -0.477502770752 +1413394889655760384.0000000000 -1.5162667170 -0.0428946286 1.8952330465 0.4473128716 0.5266122017 0.5572152452 -0.460545279404 +1413394889705760512.0000000000 -1.4955944954 -0.0474437183 1.9038424560 0.4300919097 0.5409492690 0.5724392500 -0.441257456157 +1413394889755760384.0000000000 -1.4727602537 -0.0520414816 1.9124895511 0.4119137187 0.5551909841 0.5880734013 -0.419832983769 +1413394889805760512.0000000000 -1.4498112051 -0.0571881837 1.9218274494 0.3938558039 0.5679562865 0.6007574620 -0.401738390313 +1413394889855760384.0000000000 -1.4288273109 -0.0623667759 1.9319434086 0.3780353474 0.5787720152 0.6113085175 -0.385245541143 +1413394889905760512.0000000000 -1.4110230505 -0.0677074426 1.9421982086 0.3637611943 0.5886915135 0.6193044439 -0.370920613055 +1413394889955760384.0000000000 -1.3974361023 -0.0736490574 1.9510170307 0.3507121335 0.5967040471 0.6256148619 -0.359932388375 +1413394890005760512.0000000000 -1.3886311567 -0.0792752097 1.9569178218 0.3407525047 0.6030871106 0.6316898767 -0.348053971773 +1413394890055760384.0000000000 -1.3853892679 -0.0854044911 1.9603105073 0.3313845616 0.6085713685 0.6364967482 -0.338669531013 +1413394890105760512.0000000000 -1.3880867913 -0.0917539994 1.9619648835 0.3237741868 0.6137366623 0.6376782666 -0.334460780354 +1413394890155760384.0000000000 -1.3981890728 -0.0981209396 1.9634434021 0.3245589467 0.6146890063 0.6338105828 -0.339268419879 +1413394890205760512.0000000000 -1.4158238905 -0.1044263873 1.9645825943 0.3345580556 0.6101797565 0.6258488256 -0.352228362978 +1413394890255760384.0000000000 -1.4396825303 -0.1107018158 1.9647615002 0.3449614638 0.6057562861 0.6134462493 -0.371139609279 +1413394890305760512.0000000000 -1.4685114278 -0.1160265531 1.9623859343 0.3582506720 0.5988391547 0.5998347583 -0.391466966149 +1413394890355760384.0000000000 -1.5013089185 -0.1203098655 1.9584989362 0.3728758484 0.5901968558 0.5846459404 -0.413304243248 +1413394890405760512.0000000000 -1.5348945976 -0.1232990476 1.9531954867 0.3869696536 0.5808773541 0.5691667217 -0.43460928388 +1413394890455760384.0000000000 -1.5684747003 -0.1244839598 1.9462179378 0.4014183779 0.5698275577 0.5557266568 -0.453131022252 +1413394890505760512.0000000000 -1.6000641235 -0.1237213720 1.9382708213 0.4160405576 0.5575718827 0.5423929535 -0.470992286651 +1413394890555760384.0000000000 -1.6283751616 -0.1202722804 1.9300239204 0.4310111341 0.5457525382 0.5310482804 -0.484119089887 +1413394890605760512.0000000000 -1.6517583908 -0.1155658611 1.9212369301 0.4419497192 0.5352052483 0.5239669695 -0.493654132765 +1413394890655760384.0000000000 -1.6697470436 -0.1084408269 1.9125761220 0.4532806721 0.5246524130 0.5207988421 -0.498041207049 +1413394890705760512.0000000000 -1.6818693973 -0.0995814115 1.9050524928 0.4615021403 0.5172183735 0.5177837060 -0.501399005212 +1413394890755760384.0000000000 -1.6871735715 -0.0895864173 1.8973165859 0.4645725391 0.5136149329 0.5208457951 -0.499090887904 +1413394890805760512.0000000000 -1.6855002777 -0.0780971006 1.8878451959 0.4608864943 0.5168855367 0.5318943532 -0.487341131339 +1413394890855760384.0000000000 -1.6778758255 -0.0661676384 1.8783386936 0.4482454915 0.5268654596 0.5457213571 -0.472944993907 +1413394890905760512.0000000000 -1.6658140163 -0.0537453009 1.8689559978 0.4322545534 0.5390549689 0.5620188023 -0.454654382357 +1413394890955760384.0000000000 -1.6510222298 -0.0410512798 1.8602136625 0.4146760814 0.5521037093 0.5792236990 -0.433272602597 +1413394891005760512.0000000000 -1.6353097239 -0.0282999399 1.8518418784 0.3961368260 0.5649117225 0.5959845500 -0.41079529826 +1413394891055760384.0000000000 -1.6207196634 -0.0158489212 1.8447777883 0.3786246048 0.5761754197 0.6092965860 -0.391692436227 +1413394891105760512.0000000000 -1.6092173481 -0.0034153485 1.8390797699 0.3654079297 0.5840762185 0.6206656406 -0.374307598765 +1413394891155760384.0000000000 -1.6019028299 0.0083228023 1.8343591790 0.3531572975 0.5915371379 0.6281787846 -0.361600818992 +1413394891205760512.0000000000 -1.6000873972 0.0195531516 1.8300914230 0.3444121479 0.5963529798 0.6343152530 -0.351265648365 +1413394891255760384.0000000000 -1.6045704088 0.0301503019 1.8261255204 0.3391216679 0.5989969273 0.6390232483 -0.343290640215 +1413394891305760512.0000000000 -1.6159217563 0.0398612135 1.8234193328 0.3364632484 0.6005029128 0.6407831458 -0.339978961486 +1413394891355760384.0000000000 -1.6344175618 0.0488206017 1.8219499275 0.3386947867 0.5987825754 0.6415248306 -0.339398233084 +1413394891405760512.0000000000 -1.6604754268 0.0569541146 1.8226644904 0.3490876563 0.5924272629 0.6385847123 -0.345510219201 +1413394891455760384.0000000000 -1.6926023500 0.0634866638 1.8251749795 0.3594922948 0.5866486403 0.6322600183 -0.356168403996 +1413394891505760512.0000000000 -1.7294524390 0.0690736112 1.8278602083 0.3717925698 0.5787124419 0.6260516184 -0.367316710516 +1413394891555760384.0000000000 -1.7699650292 0.0734224962 1.8313935819 0.3832934490 0.5718242522 0.6180686864 -0.379597491324 +1413394891605760512.0000000000 -1.8130173377 0.0766805319 1.8344353894 0.3950068560 0.5634240099 0.6132090014 -0.387940316674 +1413394891655760384.0000000000 -1.8571579751 0.0787948374 1.8375574300 0.4026421801 0.5576347581 0.6087415502 -0.395419367761 +1413394891705760512.0000000000 -1.9020442383 0.0798711279 1.8404537718 0.4088633155 0.5529780036 0.6055208148 -0.400488026833 +1413394891755760384.0000000000 -1.9471412045 0.0799116792 1.8436739694 0.4124301882 0.5501647564 0.6032764311 -0.404076265647 +1413394891805760512.0000000000 -1.9916673778 0.0784233789 1.8487078725 0.4141907276 0.5479040067 0.6023856064 -0.406667950292 +1413394891855760384.0000000000 -2.0366660149 0.0760427758 1.8580150294 0.4204834890 0.5430627694 0.5991184713 -0.411501544682 +1413394891905760512.0000000000 -2.0810505377 0.0719115130 1.8709323204 0.4284764781 0.5363942066 0.5941875296 -0.419082739419 +1413394891955760384.0000000000 -2.1243694605 0.0662969671 1.8871375071 0.4365630671 0.5295410097 0.5881641637 -0.427857364152 +1413394892005760512.0000000000 -2.1656678957 0.0594449334 1.9047501517 0.4442579489 0.5230215184 0.5828853711 -0.435118386534 +1413394892055760384.0000000000 -2.2039028285 0.0506137207 1.9225667183 0.4485715910 0.5167162851 0.5794387136 -0.442762448321 +1413394892105760512.0000000000 -2.2385195699 0.0406393126 1.9403168449 0.4511931981 0.5101583865 0.5780147345 -0.449513164856 +1413394892155760384.0000000000 -2.2689920439 0.0289874465 1.9575863305 0.4510813892 0.5036427214 0.5798508875 -0.454579517543 +1413394892205760512.0000000000 -2.2952653306 0.0155540551 1.9747200534 0.4476973875 0.4968650941 0.5846121101 -0.459261154699 +1413394892255760384.0000000000 -2.3181701497 0.0008351431 1.9911004295 0.4430858294 0.4892300817 0.5903527207 -0.464556282955 +1413394892305760512.0000000000 -2.3372645430 -0.0150736254 2.0054539874 0.4369555316 0.4818569097 0.5961475327 -0.470629260964 +1413394892355760384.0000000000 -2.3530076401 -0.0317798842 2.0149253793 0.4296572908 0.4738407758 0.6041554477 -0.475253328954 +1413394892405760512.0000000000 -2.3654236975 -0.0491715871 2.0204214717 0.4219067337 0.4650592411 0.6109314487 -0.482159076786 +1413394892455760384.0000000000 -2.3745585060 -0.0669819688 2.0218223454 0.4127099384 0.4563651523 0.6183645526 -0.488903502382 +1413394892505760512.0000000000 -2.3800103036 -0.0852696923 2.0205537299 0.4034123986 0.4461872956 0.6269399131 -0.495097646223 +1413394892555760384.0000000000 -2.3816005710 -0.1038073252 2.0191187606 0.3922058103 0.4365654827 0.6364035784 -0.500575336025 +1413394892605760512.0000000000 -2.3791032605 -0.1226907200 2.0179603147 0.3781450034 0.4274174783 0.6480884126 -0.504283714906 +1413394892655760384.0000000000 -2.3735503930 -0.1415655048 2.0176164638 0.3635281772 0.4176892511 0.6602801337 -0.507358944818 +1413394892705760512.0000000000 -2.3651343854 -0.1604720292 2.0193326005 0.3480015252 0.4071960833 0.6726639508 -0.510499262926 +1413394892755760384.0000000000 -2.3545015836 -0.1793928810 2.0221321875 0.3318625672 0.3960105642 0.6861265715 -0.512126153766 +1413394892805760512.0000000000 -2.3422649730 -0.1984313802 2.0267524933 0.3167262110 0.3833872675 0.6972219395 -0.51631412675 +1413394892855760384.0000000000 -2.3284861785 -0.2172210900 2.0324166565 0.3020177916 0.3703486129 0.7081872870 -0.519709462157 +1413394892905760512.0000000000 -2.3133587436 -0.2354346140 2.0380921355 0.2876139335 0.3577125066 0.7196993406 -0.520915393341 +1413394892955760384.0000000000 -2.2976347498 -0.2535841525 2.0437219812 0.2729257884 0.3461088256 0.7317067776 -0.5199282513 +1413394893005760512.0000000000 -2.2817570850 -0.2719208348 2.0499160829 0.2603458187 0.3338174548 0.7428253738 -0.518648653276 +1413394893055760384.0000000000 -2.2661287703 -0.2909541623 2.0568166445 0.2500475403 0.3200152929 0.7525094809 -0.518455322137 +1413394893105760512.0000000000 -2.2511056834 -0.3105609021 2.0640304249 0.2428060936 0.3048491773 0.7608977402 -0.518793609192 +1413394893155760384.0000000000 -2.2361459608 -0.3313186103 2.0715426678 0.2363971179 0.2891328894 0.7691032441 -0.518650918053 +1413394893205760512.0000000000 -2.2208849292 -0.3535394166 2.0797114294 0.2266014659 0.2757719037 0.7754130995 -0.520899374047 +1413394893255760384.0000000000 -2.2063632152 -0.3770293037 2.0880692324 0.2197964840 0.2627790566 0.7805670443 -0.522830529356 +1413394893305760512.0000000000 -2.1921233443 -0.4024613388 2.0976182239 0.2131997675 0.2521782576 0.7817765236 -0.528939932897 +1413394893355760384.0000000000 -2.1781818937 -0.4291207033 2.1075104837 0.2093033656 0.2423616602 0.7820213730 -0.534691966492 +1413394893405760512.0000000000 -2.1648677427 -0.4572039230 2.1177869561 0.2116521589 0.2308436290 0.7802601290 -0.541395154786 +1413394893455760384.0000000000 -2.1508468366 -0.4858211480 2.1267916302 0.2152581833 0.2202671149 0.7802653921 -0.54436406057 +1413394893505760512.0000000000 -2.1354275941 -0.5156355234 2.1353880698 0.2178952699 0.2108871508 0.7785240484 -0.549498468668 +1413394893555760384.0000000000 -2.1187111374 -0.5460990586 2.1408577177 0.2213825328 0.2030995391 0.7783497200 -0.551282200629 +1413394893605760512.0000000000 -2.1002888956 -0.5771205368 2.1438996509 0.2269716278 0.1958404322 0.7767670865 -0.553862165772 +1413394893655760384.0000000000 -2.0799514041 -0.6088771640 2.1436430382 0.2343680570 0.1892734743 0.7761521627 -0.553926877952 +1413394893705760512.0000000000 -2.0571023149 -0.6416567970 2.1421820511 0.2450707290 0.1817539584 0.7731630874 -0.555989817025 +1413394893755760384.0000000000 -2.0309896411 -0.6756643763 2.1393593396 0.2515991976 0.1789483086 0.7709307716 -0.557082661733 +1413394893805760512.0000000000 -2.0012855373 -0.7107877408 2.1360282669 0.2584454304 0.1768856438 0.7678879929 -0.55880717505 +1413394893855760384.0000000000 -1.9673158438 -0.7468209109 2.1321313430 0.2598548708 0.1798927857 0.7658764307 -0.559952966488 +1413394893905760512.0000000000 -1.9287573721 -0.7837237725 2.1277728823 0.2597835070 0.1821841998 0.7643549099 -0.561322561893 +1413394893955760384.0000000000 -1.8854205158 -0.8212851182 2.1235156786 0.2564696700 0.1845997226 0.7622476489 -0.564911296162 +1413394894005760512.0000000000 -1.8373466865 -0.8590415768 2.1189735138 0.2518842506 0.1847888724 0.7604311104 -0.569343414258 +1413394894055760384.0000000000 -1.7854541407 -0.8970399584 2.1136760442 0.2470711733 0.1823274098 0.7581464549 -0.575262117472 +1413394894105760512.0000000000 -1.7292178048 -0.9349067250 2.1071187309 0.2387201230 0.1801892094 0.7575028020 -0.580287908396 +1413394894155760384.0000000000 -1.6684398416 -0.9716888481 2.0997009195 0.2253805962 0.1786163241 0.7573031135 -0.586337607476 +1413394894205760512.0000000000 -1.6038942743 -1.0074309918 2.0918016554 0.2060329972 0.1790664822 0.7580513885 -0.592320598439 +1413394894255760384.0000000000 -1.5364726227 -1.0415542880 2.0831407936 0.1852540608 0.1778490216 0.7593065355 -0.597916585922 +1413394894305760512.0000000000 -1.4675911915 -1.0739595972 2.0731783332 0.1668709293 0.1740579457 0.7634338568 -0.59918834329 +1413394894355760384.0000000000 -1.3976688400 -1.1042105129 2.0629537980 0.1506258532 0.1681881122 0.7659824408 -0.601909886624 +1413394894405760512.0000000000 -1.3271444517 -1.1325946077 2.0515092961 0.1347488309 0.1609830836 0.7699692955 -0.602556622605 +1413394894455760384.0000000000 -1.2567681320 -1.1583217481 2.0389062605 0.1207702180 0.1529847620 0.7749610286 -0.601203477335 +1413394894505760512.0000000000 -1.1872172369 -1.1821296810 2.0249694100 0.1106254383 0.1428936950 0.7799933276 -0.599127543347 +1413394894555760384.0000000000 -1.1183051544 -1.2040498573 2.0100050732 0.1021250527 0.1318228691 0.7840566525 -0.597869860744 +1413394894605760512.0000000000 -1.0500307767 -1.2243058640 1.9941399175 0.0912319102 0.1228944721 0.7876916061 -0.596754238362 +1413394894655760384.0000000000 -0.9827515794 -1.2433494056 1.9778664117 0.0831305755 0.1123018895 0.7898533997 -0.597167648121 +1413394894705760512.0000000000 -0.9171218503 -1.2612612424 1.9610014844 0.0794649594 0.1007147361 0.7903339662 -0.599094386589 +1413394894755760384.0000000000 -0.8527244325 -1.2778619714 1.9428448888 0.0795325072 0.0889086237 0.7914432459 -0.599489303911 +1413394894805760512.0000000000 -0.7888252522 -1.2935086611 1.9255949987 0.0760553684 0.0813845990 0.7930862181 -0.598837522768 +1413394894855760384.0000000000 -0.7253326814 -1.3078271255 1.9089360207 0.0746306031 0.0734598189 0.7951610936 -0.597287839623 +1413394894905760512.0000000000 -0.6619241173 -1.3211749173 1.8930090293 0.0687316574 0.0705050201 0.7979745359 -0.594593677617 +1413394894955760384.0000000000 -0.5991901813 -1.3346185739 1.8772591571 0.0632502341 0.0693203475 0.8003167451 -0.592188487533 +1413394895005760512.0000000000 -0.5368330288 -1.3471820230 1.8630360326 0.0541097699 0.0725076580 0.8024993050 -0.589753879006 +1413394895055760384.0000000000 -0.4758684692 -1.3587386720 1.8481464542 0.0484581557 0.0750033294 0.8041707309 -0.58765274043 +1413394895105760512.0000000000 -0.4161663854 -1.3694003040 1.8342005669 0.0454756247 0.0760562994 0.8064566068 -0.584615384897 +1413394895155760384.0000000000 -0.3581562861 -1.3801174674 1.8217898498 0.0431026324 0.0781070655 0.8083048166 -0.581966298727 +1413394895205760512.0000000000 -0.3016762587 -1.3902211169 1.8110721756 0.0421882066 0.0803058863 0.8092289717 -0.580447750659 +1413394895255760384.0000000000 -0.2471764911 -1.3995383749 1.8028109585 0.0432078002 0.0822413347 0.8081108248 -0.581658270513 +1413394895305760512.0000000000 -0.1945882098 -1.4087376187 1.7954869994 0.0467709925 0.0833464974 0.8078179168 -0.58163222819 +1413394895355760384.0000000000 -0.1440875517 -1.4177757188 1.7876229039 0.0592300294 0.0780560758 0.8075803850 -0.581560808918 +1413394895405760512.0000000000 -0.0949766904 -1.4277547594 1.7816840167 0.0722099503 0.0730888900 0.8069077803 -0.581673079492 +1413394895455760384.0000000000 -0.0457958882 -1.4376805116 1.7787222016 0.0837171722 0.0687148817 0.8063062174 -0.581498051564 +1413394895505760512.0000000000 0.0039462706 -1.4475678544 1.7794778651 0.0915135093 0.0674654462 0.8070692953 -0.579407321171 +1413394895555760384.0000000000 0.0547783379 -1.4566239734 1.7828431186 0.0983230545 0.0664831352 0.8086188423 -0.576236182113 +1413394895605760512.0000000000 0.1070556616 -1.4661310398 1.7914394589 0.0987420439 0.0694205446 0.8081939108 -0.576414260195 +1413394895655760384.0000000000 0.1606287245 -1.4759417297 1.8034906836 0.0966922146 0.0738333976 0.8085535775 -0.575708569744 +1413394895705760512.0000000000 0.2155186281 -1.4862762013 1.8198704083 0.0914014294 0.0793461152 0.8096847047 -0.574247900856 +1413394895755760384.0000000000 0.2709797973 -1.4963277307 1.8394740553 0.0871388312 0.0834248904 0.8106700263 -0.572940852307 +1413394895805760512.0000000000 0.3265496697 -1.5070904639 1.8605020923 0.0829230901 0.0870502021 0.8105354763 -0.573217467534 +1413394895855760384.0000000000 0.3815038943 -1.5185775036 1.8805547440 0.0801085919 0.0891317099 0.8100902507 -0.57392677019 +1413394895905760512.0000000000 0.4360840821 -1.5300981575 1.8971540361 0.0783412111 0.0899759636 0.8098746273 -0.57434316284 +1413394895955760384.0000000000 0.4901421379 -1.5422554139 1.9106585428 0.0772697759 0.0896715782 0.8092084103 -0.57547383828 +1413394896005760512.0000000000 0.5433684274 -1.5544561287 1.9213640067 0.0767863484 0.0891062471 0.8084220028 -0.576730265244 +1413394896055760384.0000000000 0.5958490640 -1.5668099462 1.9293573120 0.0758181296 0.0887971907 0.8083921088 -0.576947890644 +1413394896105760512.0000000000 0.6481148491 -1.5792627792 1.9341674381 0.0743199215 0.0878833089 0.8082407821 -0.577494512086 +1413394896155760384.0000000000 0.6994692001 -1.5921352070 1.9359244408 0.0742916550 0.0868080953 0.8086156551 -0.577135882546 +1413394896205760512.0000000000 0.7500374902 -1.6055984720 1.9350694262 0.0731641040 0.0870695453 0.8088209902 -0.576952783131 +1413394896255760384.0000000000 0.8006389492 -1.6191145984 1.9324343862 0.0644522689 0.0914218603 0.8085781559 -0.577658475522 +1413394896305760512.0000000000 0.8502276716 -1.6326836931 1.9284725441 0.0521223885 0.0989771250 0.8076816951 -0.578910238975 +1413394896355760384.0000000000 0.8980537829 -1.6463364709 1.9245332800 0.0387221329 0.1082718907 0.8070016706 -0.579246146082 +1413394896405760512.0000000000 0.9434639707 -1.6597368105 1.9206354986 0.0273111744 0.1148219463 0.8068361885 -0.578865602181 +1413394896455760384.0000000000 0.9853053169 -1.6729827257 1.9172507826 0.0157515094 0.1220381725 0.8059422333 -0.579064496353 +1413394896505760512.0000000000 1.0231918910 -1.6858975614 1.9123776370 0.0064030719 0.1285657656 0.8055330967 -0.578399753325 +1413394896555760384.0000000000 1.0572722836 -1.6987329153 1.9057158057 0.0057058699 -0.1364690378 -0.8044477246 0.57810682681 +1413394896605760512.0000000000 1.0864210004 -1.7110610714 1.8970003416 0.0166489477 -0.1441098554 -0.8031216695 0.577884716902 +1413394896655760384.0000000000 1.1100782035 -1.7232982390 1.8864786682 0.0287717291 -0.1532903039 -0.8011213907 0.577822453408 +1413394896705760512.0000000000 1.1279440225 -1.7353976927 1.8736296266 0.0405565524 -0.1606490247 -0.7988391287 0.578275975082 +1413394896755760384.0000000000 1.1387835716 -1.7462878014 1.8584786317 0.0515268267 -0.1694378370 -0.7967594666 0.577763063866 +1413394896805760512.0000000000 1.1426675541 -1.7563718172 1.8417909815 0.0619313183 -0.1771090730 -0.7938478611 0.57844832225 +1413394896855760384.0000000000 1.1380844814 -1.7654386980 1.8242057488 0.0681963401 -0.1820043110 -0.7900669253 0.581393105828 +1413394896905760512.0000000000 1.1237584058 -1.7730997560 1.8067358322 0.0691713102 -0.1856923802 -0.7861855150 0.585359723357 +1413394896955760384.0000000000 1.1011444971 -1.7785919059 1.7905030288 0.0727915350 -0.1888388982 -0.7840189360 0.586818175408 +1413394897005760512.0000000000 1.0692476846 -1.7812137373 1.7756653925 0.0769300759 -0.1914341671 -0.7826148292 0.587323379601 +1413394897055760384.0000000000 1.0270995978 -1.7818740383 1.7627528845 0.0804975916 -0.1944828131 -0.7819799548 0.58668894949 +1413394897105760512.0000000000 0.9749993255 -1.7809019177 1.7507048319 0.0782750877 -0.1938411507 -0.7837153508 0.584883636131 +1413394897155760384.0000000000 0.9138032726 -1.7781028300 1.7400399399 0.0739404352 -0.1908826150 -0.7845880884 0.585250519706 +1413394897205760512.0000000000 0.8431344537 -1.7734485504 1.7306776658 0.0670054384 -0.1871034756 -0.7861249087 0.585243700186 +1413394897255760384.0000000000 0.7636276705 -1.7677281072 1.7219115575 0.0518518852 -0.1775678722 -0.7902331368 0.584219669476 +1413394897305760512.0000000000 0.6765554004 -1.7605481537 1.7136537912 0.0259041703 -0.1596744569 -0.7949160460 0.584757660522 +1413394897355760384.0000000000 0.5834840153 -1.7522069717 1.7068856719 0.0010481205 0.1415562605 0.7981465626 -0.585596098998 +1413394897405760512.0000000000 0.4867564180 -1.7432414044 1.7020468506 0.0235829074 0.1266651451 0.7992705145 -0.586997812669 +1413394897455760384.0000000000 0.3883727815 -1.7336437434 1.6989780663 0.0415154460 0.1132687686 0.7997332624 -0.588109992072 +1413394897505760512.0000000000 0.2888931897 -1.7235734735 1.6971889180 0.0551030927 0.1035514597 0.7998743022 -0.58859310653 +1413394897555760384.0000000000 0.1897745119 -1.7129112320 1.6966615773 0.0638928754 0.0971312862 0.8008906771 -0.587415812781 +1413394897605760512.0000000000 0.0913865861 -1.7022392646 1.6973998494 0.0695961833 0.0921652400 0.8014066584 -0.58686396006 +1413394897655760384.0000000000 -0.0062695815 -1.6915494378 1.7000128708 0.0733603946 0.0887695708 0.8002823901 -0.588460968829 +1413394897705760512.0000000000 -0.1027682834 -1.6805439599 1.7046208392 0.0748232456 0.0873329503 0.7977811243 -0.591878125481 +1413394897755760384.0000000000 -0.1981057384 -1.6685982163 1.7092662362 0.0761596172 0.0856493684 0.7966786389 -0.593436639186 +1413394897805760512.0000000000 -0.2922550470 -1.6561207061 1.7159801862 0.0783972542 0.0833338296 0.7935981663 -0.597587896307 +1413394897855760384.0000000000 -0.3846579659 -1.6427208069 1.7237102678 0.0776208019 0.0827834483 0.7916290860 -0.60037097026 +1413394897905760512.0000000000 -0.4759336740 -1.6283952403 1.7325498110 0.0793096922 0.0810508503 0.7895267045 -0.603148667656 +1413394897955760384.0000000000 -0.5658005765 -1.6129596709 1.7430470580 0.0804165450 0.0802704030 0.7865704831 -0.606956931652 +1413394898005760512.0000000000 -0.6538541847 -1.5960450105 1.7533397594 0.0811604713 0.0791085527 0.7869184039 -0.60655934613 +1413394898055760384.0000000000 -0.7403395432 -1.5777758689 1.7639300656 0.0820908332 0.0782563334 0.7887348103 -0.604180801109 +1413394898105760512.0000000000 -0.8248044840 -1.5584064733 1.7752818070 0.0843048655 0.0764101368 0.7897879652 -0.602734726605 +1413394898155760384.0000000000 -0.9072856470 -1.5381235946 1.7866489218 0.0884700071 0.0720806552 0.7917682053 -0.600067117908 +1413394898205760512.0000000000 -0.9874232703 -1.5170181878 1.7991714128 0.0908357848 0.0688455077 0.7924781051 -0.599155747055 +1413394898255760384.0000000000 -1.0656448996 -1.4953967575 1.8119276071 0.0985468970 0.0621933411 0.7926782935 -0.59839921493 +1413394898305760512.0000000000 -1.1407981617 -1.4730583608 1.8247698433 0.1063188884 0.0535535114 0.7928023854 -0.59773965332 +1413394898355760384.0000000000 -1.2121335755 -1.4500638548 1.8380380327 0.1127411504 0.0436388332 0.7930459711 -0.59704536933 +1413394898405760512.0000000000 -1.2794829692 -1.4266425537 1.8510095283 0.1191428853 0.0317227917 0.7937378376 -0.595633177861 +1413394898455760384.0000000000 -1.3415331780 -1.4030054270 1.8643250568 0.1205986955 0.0204167611 0.7954298396 -0.593574326225 +1413394898505760512.0000000000 -1.3982409405 -1.3789734740 1.8782752896 0.1199720934 0.0076403870 0.7972032042 -0.591620970295 +1413394898555760384.0000000000 -1.4494811855 -1.3545224124 1.8922359475 0.1170387300 -0.0052362218 0.7999221784 -0.58855673147 +1413394898605760512.0000000000 -1.4955017349 -1.3304042277 1.9070135799 0.1147512104 -0.0183456024 0.8017101886 -0.586307404058 +1413394898655760384.0000000000 -1.5363221848 -1.3066965507 1.9224638270 0.1119348763 -0.0291238155 0.8033961642 -0.584103578324 +1413394898705760512.0000000000 -1.5715121777 -1.2833831677 1.9381293106 0.1070664386 -0.0368825017 0.8068502485 -0.57980094458 +1413394898755760384.0000000000 -1.6012271733 -1.2608163136 1.9543560451 0.0994537164 -0.0409234763 0.8115137844 -0.574351464826 +1413394898805760512.0000000000 -1.6262545585 -1.2394099373 1.9711146073 0.0962623015 -0.0456852295 0.8157251375 -0.568541053224 +1413394898855760384.0000000000 -1.6462685185 -1.2192857406 1.9885075930 0.0946316834 -0.0512135111 0.8179347755 -0.565159025201 +1413394898905760512.0000000000 -1.6621069506 -1.2010410351 2.0056329376 0.1003453903 -0.0598152826 0.8193410681 -0.561278138442 +1413394898955760384.0000000000 -1.6723373965 -1.1844573339 2.0234418361 0.1044166208 -0.0664265055 0.8200689611 -0.558723176243 +1413394899005760512.0000000000 -1.6771342078 -1.1695877529 2.0404432270 0.1087055684 -0.0713851346 0.8218786734 -0.554619426434 +1413394899055760384.0000000000 -1.6757323940 -1.1565747386 2.0560879853 0.1082306071 -0.0717789057 0.8242373605 -0.551150340529 +1413394899105760512.0000000000 -1.6687253988 -1.1453623192 2.0689164002 0.1052152368 -0.0698231701 0.8289799176 -0.544836466402 +1413394899155760384.0000000000 -1.6564537194 -1.1366481327 2.0793607463 0.1017133844 -0.0671495740 0.8329724109 -0.539724267326 +1413394899205760512.0000000000 -1.6393236264 -1.1305507302 2.0866009343 0.1000436269 -0.0661130197 0.8352124671 -0.536694024665 +1413394899255760384.0000000000 -1.6177469130 -1.1274812234 2.0911028681 0.1020388603 -0.0682001834 0.8357573159 -0.535206983295 +1413394899305760512.0000000000 -1.5907962454 -1.1270215899 2.0940359655 0.1002202192 -0.0673463685 0.8353200901 -0.536340117177 +1413394899355760384.0000000000 -1.5589506351 -1.1291156398 2.0948371217 0.0957651991 -0.0643348815 0.8344838153 -0.538819832262 +1413394899405760512.0000000000 -1.5216751083 -1.1333500846 2.0937049448 0.0835898936 -0.0564156541 0.8340441714 -0.542402363448 +1413394899455760384.0000000000 -1.4798863134 -1.1395704520 2.0902525355 0.0667697546 -0.0475124404 0.8340478834 -0.545571714897 +1413394899505760512.0000000000 -1.4351707800 -1.1474438905 2.0839303693 0.0511524676 -0.0427274012 0.8339432399 -0.547810612265 +1413394899555760384.0000000000 -1.3882112848 -1.1572912247 2.0751380768 0.0373741340 -0.0427247414 0.8334168726 -0.549721826948 +1413394899605760512.0000000000 -1.3393016167 -1.1689336554 2.0647029772 0.0261890033 -0.0471808629 0.8329857103 -0.550656797578 +1413394899655760384.0000000000 -1.2886867567 -1.1821251511 2.0535359233 0.0167537700 -0.0556997089 0.8322187084 -0.551388134619 +1413394899705760512.0000000000 -1.2364088155 -1.1971436006 2.0430015762 0.0070062573 -0.0665281985 0.8323057644 -0.550265413813 +1413394899755760384.0000000000 -1.1825080537 -1.2139300721 2.0335064337 0.0021303716 0.0790426201 -0.8310794808 0.550503971196 +1413394899805760512.0000000000 -1.1266037193 -1.2323772518 2.0250037700 0.0132550050 0.0931233309 -0.8286097218 0.551867990566 +1413394899855760384.0000000000 -1.0696647707 -1.2525640782 2.0177173316 0.0231428697 0.1076678366 -0.8240144694 0.555762718084 +1413394899905760512.0000000000 -1.0109835080 -1.2735813651 2.0108131247 0.0349020984 0.1215367446 -0.8195014890 0.558952567547 +1413394899955760384.0000000000 -0.9505461488 -1.2958002111 2.0066956645 0.0511608456 0.1325238016 -0.8142656952 0.56284224038 +1413394900005760512.0000000000 -0.8892450304 -1.3188369091 2.0056058977 0.0665017639 0.1434238162 -0.8097864299 0.565024833413 +1413394900055760384.0000000000 -0.8270863622 -1.3430957892 2.0086408126 0.0816909869 0.1541101954 -0.8040701806 0.568372918929 +1413394900105760512.0000000000 -0.7653511212 -1.3667358443 2.0149972221 0.0945411113 0.1660768079 -0.7975896259 0.572128709944 +1413394900155760384.0000000000 -0.7033738383 -1.3905484736 2.0238575758 0.1092891608 0.1756251166 -0.7905793698 0.576364431366 +1413394900205760512.0000000000 -0.6420799320 -1.4138797003 2.0333464264 0.1230282807 0.1853051923 -0.7846188230 0.578704873364 +1413394900255760384.0000000000 -0.5817251861 -1.4368681443 2.0410882559 0.1354200828 0.1943936336 -0.7794204716 0.579979521122 +1413394900305760512.0000000000 -0.5227566311 -1.4595664616 2.0461854686 0.1427243786 0.2060147967 -0.7727522625 0.583130856813 +1413394900355760384.0000000000 -0.4649777291 -1.4808015996 2.0491746970 0.1504280410 0.2173329714 -0.7664212807 0.585436763908 +1413394900405760512.0000000000 -0.4086298410 -1.5008922789 2.0498165827 0.1548048232 0.2306371591 -0.7592056179 0.588599012246 +1413394900455760384.0000000000 -0.3534743591 -1.5198474086 2.0473799927 0.1550215036 0.2464590431 -0.7540486072 0.588758839872 +1413394900505760512.0000000000 -0.2991433395 -1.5370255604 2.0426874865 0.1526754875 0.2639386014 -0.7493139778 0.587839410778 +1413394900555760384.0000000000 -0.2449778962 -1.5522579039 2.0370420997 0.1507123064 0.2800612026 -0.7444199176 0.58710349147 +1413394900605760512.0000000000 -0.1908159035 -1.5656542675 2.0298059384 0.1470186959 0.2961828654 -0.7392221938 0.586695629338 +1413394900655760384.0000000000 -0.1357170647 -1.5765143038 2.0220375743 0.1449021352 0.3119550498 -0.7319102184 0.588213269442 +1413394900705760512.0000000000 -0.0794810819 -1.5842143807 2.0151726882 0.1445280516 0.3261020556 -0.7252351789 0.588899844549 +1413394900755760384.0000000000 -0.0213243445 -1.5875504648 2.0108209831 0.1468427342 0.3390598624 -0.7182696136 0.589545912756 +1413394900805760512.0000000000 0.0382254940 -1.5849846836 2.0091090113 0.1500103083 0.3533866381 -0.7134652776 0.586158757575 +1413394900855760384.0000000000 0.1005857223 -1.5780977159 2.0126163166 0.1582159972 0.3645075077 -0.7087643124 0.582885172741 +1413394900905760512.0000000000 0.1653293742 -1.5664085715 2.0200315925 0.1664997564 0.3759190111 -0.7045450927 0.578427990861 +1413394900955760384.0000000000 0.2322146148 -1.5495848601 2.0324294621 0.1763588015 0.3880273267 -0.6972522565 0.576343350561 +1413394901005760512.0000000000 0.3018151343 -1.5284538354 2.0496591960 0.1862203387 0.4003604071 -0.6904191222 0.573022657115 +1413394901055760384.0000000000 0.3725101658 -1.5028327947 2.0679061145 0.1970172878 0.4119464687 -0.6830014760 0.570081817841 +1413394901105760512.0000000000 0.4441711215 -1.4726340674 2.0865291626 0.2105992713 0.4227580939 -0.6740390386 0.567974396812 +1413394901155760384.0000000000 0.5160097624 -1.4381714447 2.1036348734 0.2269605715 0.4320368135 -0.6656700483 0.564549800786 +1413394901205760512.0000000000 0.5874268961 -1.3996272848 2.1197423923 0.2477428229 0.4373232447 -0.6586954628 0.559903706627 +1413394901255760384.0000000000 0.6580225420 -1.3578684897 2.1338486989 0.2701832946 0.4403895180 -0.6533772250 0.553313890652 +1413394901305760512.0000000000 0.7270278909 -1.3129402118 2.1460724709 0.2928823503 0.4432292644 -0.6475867742 0.546259203949 +1413394901355760384.0000000000 0.7939962193 -1.2659798497 2.1565144699 0.3164206327 0.4444398875 -0.6436822642 0.536678965902 +1413394901405760512.0000000000 0.8589856314 -1.2178891655 2.1660063629 0.3396574320 0.4442829040 -0.6382700490 0.529015004174 +1413394901455760384.0000000000 0.9208206215 -1.1692589813 2.1733479560 0.3603603148 0.4449808501 -0.6305342788 0.52398378779 +1413394901505760512.0000000000 0.9786332821 -1.1208152667 2.1775183024 0.3775176941 0.4468005314 -0.6234855608 0.518763367218 +1413394901555760384.0000000000 1.0320886850 -1.0726835367 2.1782983215 0.3894220808 0.4516897639 -0.6182544493 0.511945540129 +1413394901605760512.0000000000 1.0813342769 -1.0247382462 2.1752325923 0.3964001491 0.4611943118 -0.6144152402 0.502653599596 +1413394901655760384.0000000000 1.1261762319 -0.9774967170 2.1687861627 0.3971414053 0.4753544827 -0.6101572397 0.493988828554 +1413394901705760512.0000000000 1.1673110684 -0.9305951803 2.1597433334 0.3971814974 0.4909775168 -0.6053388093 0.48451301542 +1413394901755760384.0000000000 1.2051932907 -0.8841971896 2.1503028463 0.3956710935 0.5083261986 -0.5961238468 0.479254860047 +1413394901805760512.0000000000 1.2397940266 -0.8377582104 2.1416426420 0.3951608835 0.5256345526 -0.5848021434 0.474934360095 +1413394901855760384.0000000000 1.2715204255 -0.7906182539 2.1343355699 0.3968910792 0.5425679557 -0.5707704395 0.471506723288 +1413394901905760512.0000000000 1.3007832395 -0.7426715078 2.1294891710 0.4013166705 0.5576152579 -0.5551167224 0.46888759694 +1413394901955760384.0000000000 1.3268554279 -0.6932596038 2.1265347292 0.4070383945 0.5718883796 -0.5400894048 0.464291784899 +1413394902005760512.0000000000 1.3506027972 -0.6426098282 2.1250815536 0.4134451102 0.5847864280 -0.5267258900 0.45787313892 +1413394902055760384.0000000000 1.3713490919 -0.5902524709 2.1253263359 0.4212600587 0.5958384886 -0.5149221110 0.449857397466 +1413394902105760512.0000000000 1.3897627739 -0.5364496568 2.1274771370 0.4283030718 0.6065707401 -0.5028186096 0.442495041537 +1413394902155760384.0000000000 1.4054742728 -0.4815501129 2.1297414274 0.4354694039 0.6158397080 -0.4920007989 0.434790830508 +1413394902205760512.0000000000 1.4186558346 -0.4253059772 2.1304380949 0.4453986811 0.6228526666 -0.4810310454 0.426946956865 +1413394902255760384.0000000000 1.4292063358 -0.3685147206 2.1288314065 0.4544310182 0.6294542777 -0.4695965554 0.420426969953 +1413394902305760512.0000000000 1.4375158088 -0.3108422292 2.1261279004 0.4645139936 0.6344013712 -0.4572076576 0.415599335573 +1413394902355760384.0000000000 1.4429719335 -0.2526628888 2.1219177733 0.4744366805 0.6380084824 -0.4442772685 0.41288342336 +1413394902405760512.0000000000 1.4448788813 -0.1941079034 2.1167662646 0.4845388827 0.6403784705 -0.4320748242 0.410425184343 +1413394902455760384.0000000000 1.4422287992 -0.1349526340 2.1111729930 0.4957398919 0.6421145471 -0.4253733126 0.401233613762 +1413394902505760512.0000000000 1.4350450796 -0.0758787240 2.1065885325 0.5074960687 0.6427145326 -0.4246883613 0.38601239046 +1413394902555760384.0000000000 1.4239036757 -0.0180484855 2.1030307782 0.5199241289 0.6410016316 -0.4260708151 0.370485450623 +1413394902605760512.0000000000 1.4089885779 0.0379298267 2.1004815525 0.5306639341 0.6391612844 -0.4311043327 0.352161462917 +1413394902655760384.0000000000 1.3917145145 0.0910266186 2.0981790941 0.5384250370 0.6379133378 -0.4371318546 0.33478469896 +1413394902705760512.0000000000 1.3721083735 0.1404109431 2.0961689403 0.5436424831 0.6372321109 -0.4451168935 0.316637077006 +1413394902755760384.0000000000 1.3514358219 0.1854843015 2.0952341932 0.5472906806 0.6359975503 -0.4533195643 0.300801262366 +1413394902805760512.0000000000 1.3297390891 0.2255187097 2.0936666362 0.5476193745 0.6368675025 -0.4585535692 0.290243740691 +1413394902855760384.0000000000 1.3082593239 0.2601647835 2.0921926040 0.5443402765 0.6396176928 -0.4627988226 0.283549149471 +1413394902905760512.0000000000 1.2869625685 0.2897371776 2.0897506327 0.5372006062 0.6444940716 -0.4649245202 0.282644813928 +1413394902955760384.0000000000 1.2659311847 0.3149326284 2.0856702406 0.5306913310 0.6485586980 -0.4663755056 0.283252915535 +1413394903055760384.0000000000 1.2263165891 0.3535820496 2.0700179952 0.5171284592 0.6531358024 -0.4716143709 0.289087643348 +1413394903155760384.0000000000 1.1878203392 0.3787455344 2.0425581779 0.4994828950 0.6552771044 -0.4887228418 0.286842705765 +1413394903255760384.0000000000 1.1540609570 0.3925598581 2.0028799550 0.4761469555 0.6570772955 -0.5138140537 0.278439621377 +1413394903355760384.0000000000 1.1330764082 0.3945972807 1.9578866294 0.4558584709 0.6539469334 -0.5273548560 0.294012446516 +1413394903455760384.0000000000 1.1238920632 0.3882272831 1.9223669916 0.4517029738 0.6417871105 -0.5298574484 0.321441771809 +1413394903555760384.0000000000 1.1234629423 0.3760438727 1.9000204606 0.4521656672 0.6293237342 -0.5298352828 0.344633747619 +1413394903605760512.0000000000 1.1254080029 0.3679883953 1.8936312964 0.4503646237 0.6260494103 -0.5276753157 0.356079489369 +1413394903655760384.0000000000 1.1274152677 0.3589223138 1.8914855420 0.4485724846 0.6234312958 -0.5261841655 0.365029272103 +1413394903705760512.0000000000 1.1293440855 0.3491742347 1.8933621844 0.4467543118 0.6217133211 -0.5247777855 0.37214433632 +1413394903755760384.0000000000 1.1314930192 0.3390197580 1.8991891217 0.4428068764 0.6221530395 -0.5238658080 0.377375517014 +1413394903805760512.0000000000 1.1329862847 0.3288498603 1.9087627571 0.4401375490 0.6223095036 -0.5218222631 0.383029170373 +1413394903855760384.0000000000 1.1338878005 0.3185514457 1.9193420869 0.4337513472 0.6260602582 -0.5180558090 0.389264050091 +1413394903905760512.0000000000 1.1346075964 0.3084646653 1.9297016278 0.4269643315 0.6289174467 -0.5156735656 0.395278482388 +1413394903955760384.0000000000 1.1344370159 0.2990969014 1.9379560400 0.4204174175 0.6298023863 -0.5161043424 0.400292964056 +1413394904005760512.0000000000 1.1339344892 0.2909948681 1.9441591157 0.4168518099 0.6270041286 -0.5213120071 0.401664265955 +1413394904055760384.0000000000 1.1338946395 0.2838563872 1.9482327379 0.4133548703 0.6220307706 -0.5313435294 0.399861882922 +1413394904105760512.0000000000 1.1338657972 0.2774585750 1.9503789233 0.4107099441 0.6144597258 -0.5452824256 0.395504315312 +1413394904155760384.0000000000 1.1344388026 0.2711132086 1.9499409460 0.4065227860 0.6063594721 -0.5598620630 0.391946278774 +1413394904205760512.0000000000 1.1358736833 0.2643737468 1.9470793400 0.3994708050 0.5980441193 -0.5757216829 0.388986955017 +1413394904255760384.0000000000 1.1387673078 0.2572079538 1.9416379977 0.3906286386 0.5900531549 -0.5913041979 0.386789201843 +1413394904305760512.0000000000 1.1437298773 0.2485367472 1.9336807649 0.3787662947 0.5820802802 -0.6054288722 0.388811679464 +1413394904355760384.0000000000 1.1505518247 0.2390381260 1.9240110979 0.3673772634 0.5722148297 -0.6203464628 0.390863660364 +1413394904405760512.0000000000 1.1597879667 0.2282017470 1.9120919238 0.3548842466 0.5614462638 -0.6339029258 0.396235214411 +1413394904455760384.0000000000 1.1715721880 0.2162656477 1.8986433565 0.3425051106 0.5498370759 -0.6461940454 0.403488159467 +1413394904505760512.0000000000 1.1866359022 0.2025122327 1.8853548166 0.3307234354 0.5367324598 -0.6557759471 0.415329005867 +1413394904555760384.0000000000 1.2039122757 0.1879541421 1.8738730701 0.3224586626 0.5203094926 -0.6631142146 0.430787628819 +1413394904605760512.0000000000 1.2230427153 0.1730389718 1.8635613469 0.3157683769 0.5024082123 -0.6702216115 0.445734575554 +1413394904655760384.0000000000 1.2440186366 0.1574021876 1.8545981745 0.3105645899 0.4832051204 -0.6759344358 0.461708875412 +1413394904705760512.0000000000 1.2662502298 0.1413639636 1.8462759358 0.3043489155 0.4641264399 -0.6828100943 0.475109209072 +1413394904755760384.0000000000 1.2889715373 0.1250365077 1.8393682944 0.2958032958 0.4467421843 -0.6891569084 0.487836639143 +1413394904805760512.0000000000 1.3117142528 0.1087591369 1.8332521903 0.2878615444 0.4290855661 -0.6943150875 0.500946970695 +1413394904855760384.0000000000 1.3341887244 0.0922157642 1.8279498763 0.2784754917 0.4118212735 -0.6994063435 0.513503072881 +1413394904905760512.0000000000 1.3561721240 0.0760787409 1.8242220020 0.2706135454 0.3929027602 -0.7035930598 0.526642702656 +1413394904955760384.0000000000 1.3774966635 0.0607194970 1.8219492704 0.2640206229 0.3736759880 -0.7051805893 0.541645366563 +1413394905005760512.0000000000 1.3973163256 0.0463639695 1.8210431140 0.2591389391 0.3526094140 -0.7058950772 0.556979130112 +1413394905055760384.0000000000 1.4152430741 0.0335695450 1.8216156223 0.2553116026 0.3310731535 -0.7059138541 0.571744858474 +1413394905105760512.0000000000 1.4303471162 0.0226616417 1.8227534258 0.2508131428 0.3104214115 -0.7067690939 0.584130775316 +1413394905155760384.0000000000 1.4422570616 0.0141189284 1.8243031780 0.2460962834 0.2910035704 -0.7102050037 0.591914177892 +1413394905205760512.0000000000 1.4502570387 0.0084875769 1.8236030119 0.2394850068 0.2750655066 -0.7212153092 0.588926460999 +1413394905255760384.0000000000 1.4545617938 0.0054517062 1.8220740413 0.2307167558 0.2623402447 -0.7367823467 0.578877489776 +1413394905305760512.0000000000 1.4559912390 0.0041224313 1.8186140746 0.2189833313 0.2547031452 -0.7584392315 0.558518164968 +1413394905355760384.0000000000 1.4550083939 0.0034318916 1.8145986669 0.2039052628 0.2523384826 -0.7808571311 0.53386334849 +1413394905405760512.0000000000 1.4533942075 0.0020014848 1.8110608100 0.1918593293 0.2493268334 -0.8038166513 0.50488109391 +1413394905455760384.0000000000 1.4519231220 -0.0029723779 1.8084449828 0.1756167729 0.2516695666 -0.8218413427 0.479997901766 +1413394905505760512.0000000000 1.4518446003 -0.0125328659 1.8072691506 0.1633136293 0.2517819051 -0.8369565443 0.457644265376 +1413394905555760384.0000000000 1.4539854876 -0.0279596322 1.8069556858 0.1516907545 0.2531255638 -0.8485174994 0.439244142909 +1413394905605760512.0000000000 1.4592836038 -0.0509840778 1.8090265861 0.1409421310 0.2572718942 -0.8525772305 0.432502663792 +1413394905655760384.0000000000 1.4697420839 -0.0832001824 1.8153780286 0.1347755619 0.2608854838 -0.8456642599 0.445675074225 +1413394905705760512.0000000000 1.4847903197 -0.1220416821 1.8240850518 0.1330842157 0.2631866185 -0.8322326169 0.469478718034 +1413394905755760384.0000000000 1.5039862011 -0.1654875433 1.8360358587 0.1392855934 0.2612054587 -0.8125412579 0.502143342051 +1413394905805760512.0000000000 1.5252207036 -0.2111103892 1.8490790314 0.1463806245 0.2590411306 -0.7893053179 0.537091724478 +1413394905855760384.0000000000 1.5477813896 -0.2566027615 1.8635797186 0.1573221283 0.2539380240 -0.7628428327 0.573442273001 +1413394905905760512.0000000000 1.5699348241 -0.2995601711 1.8778564167 0.1673549808 0.2498162208 -0.7387232652 0.603218122863 +1413394905955760384.0000000000 1.5905400247 -0.3387438421 1.8923875966 0.1779686945 0.2448548189 -0.7159268617 0.629143854818 +1413394906005760512.0000000000 1.6087771366 -0.3725629161 1.9070604757 0.1904911284 0.2386583047 -0.6981368221 0.647580358913 +1413394906055760384.0000000000 1.6232402104 -0.4000489517 1.9220368884 0.2029483842 0.2328163117 -0.6824501388 0.662472887293 +1413394906105760512.0000000000 1.6328036548 -0.4206196902 1.9369228077 0.2166271725 0.2259509390 -0.6729634751 0.670178336321 +1413394906155760384.0000000000 1.6373245841 -0.4349404655 1.9533356417 0.2313317601 0.2179700509 -0.6717701277 0.669103556435 +1413394906205760512.0000000000 1.6349572872 -0.4429398890 1.9698968213 0.2391638583 0.2119899047 -0.6787387186 0.661191864038 +1413394906255760384.0000000000 1.6263954733 -0.4457451019 1.9852270654 0.2416285141 0.2094268656 -0.6974120488 0.641383257751 +1413394906305760512.0000000000 1.6115998417 -0.4449967734 1.9990245119 0.2360497238 0.2091073779 -0.7191591310 0.619164579601 +1413394906355760384.0000000000 1.5912968986 -0.4417672886 2.0101468645 0.2258977660 0.2085231150 -0.7419339205 0.595837534375 +1413394906405760512.0000000000 1.5667473322 -0.4378117671 2.0190551329 0.2107142687 0.2090332283 -0.7635298714 0.573521352601 +1413394906455760384.0000000000 1.5388237656 -0.4340676862 2.0238524467 0.1888684675 0.2115913153 -0.7856722440 0.549797182835 +1413394906505760512.0000000000 1.5087355532 -0.4321778508 2.0265756689 0.1612823727 0.2150865181 -0.8051575075 0.528627632737 +1413394906555760384.0000000000 1.4785789782 -0.4319845951 2.0276302336 0.1383450051 0.2136707245 -0.8224771367 0.508661813643 +1413394906605760512.0000000000 1.4497734381 -0.4355358422 2.0272853940 0.1161914094 0.2110314512 -0.8354271995 0.493990563927 +1413394906655760384.0000000000 1.4232353234 -0.4437149061 2.0261080267 0.0970019706 0.2054139302 -0.8423590187 0.488699313145 +1413394906705760512.0000000000 1.4002846004 -0.4568567853 2.0254473529 0.0838944372 0.1959073567 -0.8421878767 0.495279326624 +1413394906755760384.0000000000 1.3810055912 -0.4745478543 2.0250554573 0.0759154900 0.1847766430 -0.8339287276 0.514448547433 +1413394906805760512.0000000000 1.3642681070 -0.4957767901 2.0247583728 0.0710953736 0.1709813364 -0.8193805151 0.542518572913 +1413394906855760384.0000000000 1.3495667763 -0.5181920514 2.0228468189 0.0667109208 0.1585986482 -0.8009589741 0.573463899174 +1413394906905760512.0000000000 1.3365037241 -0.5395352475 2.0206117559 0.0662429542 0.1460896594 -0.7793063311 0.605765073875 +1413394906955760384.0000000000 1.3240868162 -0.5580472954 2.0189186077 0.0658083675 0.1340903182 -0.7559548756 0.637354902251 +1413394907005760512.0000000000 1.3125089567 -0.5715204469 2.0173123741 0.0658325826 0.1245472279 -0.7343181625 0.664026276082 +1413394907055760384.0000000000 1.3009085386 -0.5780378724 2.0177371054 0.0697252712 0.1145330725 -0.7120705589 0.689185084697 +1413394907105760512.0000000000 1.2884840023 -0.5764749695 2.0182779290 0.0760321995 0.1052224425 -0.6966154351 0.705602067635 +1413394907155760384.0000000000 1.2746807511 -0.5658718539 2.0181188053 0.0823979869 0.0975407552 -0.6926199271 0.709911268645 +1413394907205760512.0000000000 1.2585226281 -0.5455920974 2.0140830535 0.0819846229 0.0957548556 -0.7042131667 0.698708340542 +1413394907255760384.0000000000 1.2403780021 -0.5166800700 2.0096448540 0.0827435879 0.0940211028 -0.7240656014 0.678264355316 +1413394907305760512.0000000000 1.2203430164 -0.4813576595 2.0047541576 0.0820956021 0.0937883018 -0.7492632403 0.650437286218 +1413394907355760384.0000000000 1.1988802554 -0.4416181550 1.9994315013 0.0829246444 0.0926687300 -0.7782669062 0.615497061382 +1413394907405760512.0000000000 1.1763951616 -0.3994963919 1.9945631495 0.0905672645 0.0845187986 -0.8066226698 0.577939453406 +1413394907455760384.0000000000 1.1528764065 -0.3580056919 1.9890199812 0.1044774503 0.0689886790 -0.8327429165 0.539318328566 +1413394907505760512.0000000000 1.1274250136 -0.3203430773 1.9822888080 0.1165519554 0.0518193936 -0.8517559422 0.508175370327 +1413394907555760384.0000000000 1.0988747991 -0.2878354957 1.9735106663 0.1259843925 0.0336270137 -0.8677339198 0.479619642295 +1413394907605760512.0000000000 1.0660175857 -0.2626798472 1.9635293286 0.1254287921 0.0210430882 -0.8779616793 0.461528001558 +1413394907655760384.0000000000 1.0289260190 -0.2456257390 1.9517915940 0.1172134924 0.0136621179 -0.8847993729 0.450782002081 +1413394907705760512.0000000000 0.9870639374 -0.2385354988 1.9399971398 0.0987472466 0.0141557425 -0.8834137010 0.457852409796 +1413394907755760384.0000000000 0.9421647037 -0.2402443869 1.9287955194 0.0741900610 0.0215832477 -0.8742649635 0.479260651298 +1413394907805760512.0000000000 0.8955931366 -0.2487227518 1.9184583427 0.0502194677 0.0309727870 -0.8564923524 0.512776307851 +1413394907855760384.0000000000 0.8488537429 -0.2604331881 1.9063920013 0.0293132873 0.0400829205 -0.8345204400 0.548734658906 +1413394907905760512.0000000000 0.8032493253 -0.2733406766 1.8931377685 0.0132327472 0.0476481967 -0.8101872383 0.584081486337 +1413394907955760384.0000000000 0.7596203719 -0.2846815796 1.8788363528 0.0039705338 0.0527175226 -0.7888170462 0.612350198275 +1413394908005760512.0000000000 0.7176157962 -0.2933179074 1.8631872501 0.0022090359 -0.0567201677 0.7703746345 -0.635059733604 +1413394908055760384.0000000000 0.6774963992 -0.2979391085 1.8464963245 0.0036692592 -0.0582482822 0.7588147487 -0.648686250278 +1413394908105760512.0000000000 0.6388302127 -0.2979079793 1.8265728928 0.0056866168 -0.0606346918 0.7601497633 -0.646887497087 +1413394908155760384.0000000000 0.6020062591 -0.2932087440 1.8047004293 0.0066416524 -0.0626525557 0.7727754881 -0.631544607093 +1413394908205760512.0000000000 0.5670601015 -0.2852214501 1.7821101811 0.0063395958 -0.0637798733 0.7916104656 -0.607655171961 +1413394908255760384.0000000000 0.5339020935 -0.2753139958 1.7592482819 0.0098261582 -0.0676580421 0.8118204666 -0.579890822403 +1413394908305760512.0000000000 0.5032000260 -0.2653018871 1.7381073156 0.0100475240 -0.0694070098 0.8308709742 -0.552028204487 +1413394908355760384.0000000000 0.4750980155 -0.2573915007 1.7193918311 0.0093176358 -0.0710249349 0.8473804817 -0.526132074185 +1413394908405760512.0000000000 0.4498258217 -0.2536581157 1.7045403488 0.0063219603 -0.0705749904 0.8607231235 -0.504117950627 +1413394908455760384.0000000000 0.4278064205 -0.2561773912 1.6939676806 0.0002711281 0.0672721456 -0.8712651696 0.486180408067 +1413394908505760512.0000000000 0.4081916464 -0.2660440563 1.6880496933 0.0076055071 0.0636626879 -0.8787341661 0.472985712052 +1413394908555760384.0000000000 0.3907192712 -0.2843412269 1.6885790965 0.0128579936 0.0628314430 -0.8783957420 0.473611446394 +1413394908605760512.0000000000 0.3743592027 -0.3128752654 1.6956909346 0.0110913247 0.0687312342 -0.8676481998 0.492280002928 +1413394908655760384.0000000000 0.3599656713 -0.3477081702 1.7086943773 0.0096141015 0.0750032262 -0.8498829189 0.52151808151 +1413394908705760512.0000000000 0.3475986256 -0.3848045789 1.7265565304 0.0116240429 0.0783847207 -0.8268647341 0.556790291508 +1413394908755760384.0000000000 0.3366259971 -0.4215179640 1.7475129133 0.0109470681 0.0836427633 -0.8012890094 0.592300576741 +1413394908805760512.0000000000 0.3273723395 -0.4553075359 1.7691631279 0.0130136943 0.0861907107 -0.7791583080 0.620736768901 +1413394908855760384.0000000000 0.3198059272 -0.4859012816 1.7930863088 0.0156784782 0.0879477123 -0.7574092468 0.646800292231 +1413394908905760512.0000000000 0.3135347801 -0.5102816388 1.8194036943 0.0223561958 0.0867003780 -0.7395074483 0.667167129592 +1413394908955760384.0000000000 0.3081336158 -0.5284243254 1.8498890406 0.0317816390 0.0833100482 -0.7222983650 0.68580932866 +1413394909005760512.0000000000 0.3032195680 -0.5396599858 1.8806886698 0.0441013578 0.0780257994 -0.7151584981 0.693192157671 +1413394909055760384.0000000000 0.2971706538 -0.5438446743 1.9081933083 0.0524554183 0.0745174367 -0.7215256110 0.686364606784 +1413394909105760512.0000000000 0.2901490978 -0.5423349198 1.9356305186 0.0596129626 0.0712389597 -0.7376283063 0.668786802441 +1413394909155760384.0000000000 0.2816000896 -0.5350130654 1.9605821317 0.0655004902 0.0677335489 -0.7594931295 0.643655217029 +1413394909205760512.0000000000 0.2705044753 -0.5242077452 1.9823026682 0.0619374932 0.0658154434 -0.7827024857 0.615799393726 +1413394909255760384.0000000000 0.2579502811 -0.5114047396 2.0005070401 0.0565769139 0.0618777380 -0.8070823517 0.584455538048 +1413394909305760512.0000000000 0.2439368621 -0.4983389710 2.0166772022 0.0496634194 0.0560399238 -0.8264782468 0.557966647113 +1413394909355760384.0000000000 0.2289542224 -0.4869428163 2.0315985215 0.0449018776 0.0445414304 -0.8415244587 0.536503930744 +1413394909405760512.0000000000 0.2133613286 -0.4793193827 2.0455912276 0.0403195198 0.0310211326 -0.8506267280 0.523303158113 +1413394909455760384.0000000000 0.1965184595 -0.4762378161 2.0589942999 0.0349204799 0.0158968383 -0.8529021887 0.520658916302 +1413394909505760512.0000000000 0.1785302868 -0.4780834023 2.0721375823 0.0297544315 -0.0000582693 -0.8487940399 0.527885734032 +1413394909555760384.0000000000 0.1590199371 -0.4832294599 2.0850123492 0.0268813916 -0.0169641346 -0.8400877274 0.541518438483 +1413394909605760512.0000000000 0.1378414584 -0.4912608014 2.0988649090 0.0245587693 -0.0321906569 -0.8282321778 0.558920466731 +1413394909655760384.0000000000 0.1145503635 -0.5004928848 2.1129488266 0.0222545403 -0.0448998393 -0.8159341770 0.575968886937 +1413394909705760512.0000000000 0.0884856017 -0.5100346169 2.1274707177 0.0156060858 -0.0532225812 -0.8024380790 0.594152283808 +1413394909755760384.0000000000 0.0601171321 -0.5185033319 2.1433186774 0.0066159305 -0.0570224888 -0.7863029890 0.615168492948 +1413394909805760512.0000000000 0.0299504495 -0.5244988948 2.1592691446 0.0057677149 0.0560168677 0.7699911058 -0.635564741775 +1413394909855760384.0000000000 -0.0012681186 -0.5268498505 2.1761836298 0.0173508309 0.0539394632 0.7529333187 -0.655653033637 +1413394909905760512.0000000000 -0.0327865600 -0.5242973346 2.1923009656 0.0257558532 0.0524705037 0.7416330781 -0.668254337589 +1413394909955760384.0000000000 -0.0644448140 -0.5157198732 2.2055219086 0.0351835718 0.0481779362 0.7401622587 -0.669776704197 +1413394910005760512.0000000000 -0.0959133049 -0.5013122080 2.2151953985 0.0437678129 0.0444137773 0.7519864360 -0.656222671783 +1413394910055760384.0000000000 -0.1264524050 -0.4820024541 2.2235828008 0.0516956253 0.0401247573 0.7685860801 -0.63639060625 +1413394910105760512.0000000000 -0.1557888126 -0.4600040089 2.2305063983 0.0555728297 0.0373039585 0.7880185683 -0.612002296849 +1413394910155760384.0000000000 -0.1839185624 -0.4367398403 2.2353705913 0.0559277229 0.0368030744 0.8070068707 -0.586734636865 +1413394910205760512.0000000000 -0.2106645498 -0.4135753447 2.2382701863 0.0533769631 0.0380771159 0.8249738379 -0.561354789612 +1413394910255760384.0000000000 -0.2365191541 -0.3920526255 2.2392820091 0.0498773237 0.0390750247 0.8411022240 -0.537152160744 +1413394910305760512.0000000000 -0.2618175786 -0.3734866486 2.2389116943 0.0464626642 0.0399792915 0.8541676673 -0.5163724171 +1413394910355760384.0000000000 -0.2865916989 -0.3589112312 2.2368397867 0.0421759047 0.0412658091 0.8639384573 -0.500128651473 +1413394910405760512.0000000000 -0.3113474342 -0.3488410449 2.2320750015 0.0382982674 0.0417705037 0.8715117215 -0.487089095634 +1413394910455760384.0000000000 -0.3365404425 -0.3444432204 2.2257007926 0.0364431134 0.0414471595 0.8763313191 -0.478536781962 +1413394910505760512.0000000000 -0.3620726788 -0.3478937310 2.2203234493 0.0367270528 0.0389785032 0.8725034784 -0.485663958045 +1413394910555760384.0000000000 -0.3881757367 -0.3580344925 2.2153563403 0.0390073895 0.0349386251 0.8610653452 -0.505790655707 +1413394910605760512.0000000000 -0.4141489602 -0.3734805176 2.2108325773 0.0428004899 0.0296221252 0.8422888139 -0.536507410657 +1413394910655760384.0000000000 -0.4392861462 -0.3921108163 2.2077122573 0.0424710111 0.0270982848 0.8178744731 -0.573186917476 +1413394910705760512.0000000000 -0.4636312153 -0.4106289792 2.2040887830 0.0426344059 0.0241567465 0.7936066220 -0.606454687897 +1413394910755760384.0000000000 -0.4868063051 -0.4268222128 2.2005698903 0.0392524046 0.0236557038 0.7708405799 -0.635377412921 +1413394910805760512.0000000000 -0.5089879512 -0.4387501900 2.1970801804 0.0321972209 0.0257458212 0.7517015756 -0.658213668122 +1413394910855760384.0000000000 -0.5306430838 -0.4455030780 2.1928173060 0.0252208079 0.0271606330 0.7385906778 -0.673134475101 +1413394910905760512.0000000000 -0.5522031023 -0.4461432868 2.1879150267 0.0184822284 0.0292661684 0.7296004445 -0.682997137593 +1413394910955760384.0000000000 -0.5736299112 -0.4402177584 2.1830681258 0.0109708745 0.0319705083 0.7232860103 -0.689720866592 +1413394911005760512.0000000000 -0.5952976354 -0.4272901204 2.1772687842 0.0018372639 0.0345909856 0.7237982530 -0.689141623397 +1413394911055760384.0000000000 -0.6182288817 -0.4075694501 2.1681387714 0.0048732494 -0.0364069287 -0.7373885371 0.674469370941 +1413394911105760512.0000000000 -0.6432197044 -0.3817102407 2.1559185692 0.0021477727 0.0308851102 0.7560447542 -0.653787294723 +1413394911155760384.0000000000 -0.6693026153 -0.3511710186 2.1420894447 0.0097203571 0.0257676947 0.7806420228 -0.624371342047 +1413394911205760512.0000000000 -0.6960373722 -0.3181665206 2.1280858606 0.0185193974 0.0200934809 0.8043923450 -0.593469661659 +1413394911255760384.0000000000 -0.7225091893 -0.2846346950 2.1139169077 0.0247178327 0.0162520508 0.8248819780 -0.564530443784 +1413394911305760512.0000000000 -0.7490720558 -0.2531763955 2.0992381938 0.0294392903 0.0154054204 0.8409422154 -0.540103871074 +1413394911355760384.0000000000 -0.7754085097 -0.2249389236 2.0830007922 0.0347519216 0.0147828621 0.8540450475 -0.518826394607 +1413394911405760512.0000000000 -0.8010325917 -0.2017013405 2.0664599721 0.0378584914 0.0158646160 0.8629247567 -0.503662498906 +1413394911455760384.0000000000 -0.8258351758 -0.1841288918 2.0491493006 0.0406851066 0.0165301050 0.8677863282 -0.494993299319 +1413394911505760512.0000000000 -0.8498625881 -0.1720197279 2.0299163302 0.0430940215 0.0172549829 0.8709030549 -0.489257641656 +1413394911555760384.0000000000 -0.8732912073 -0.1665679312 2.0106715909 0.0456247359 0.0196429128 0.8678710629 -0.494299866155 +1413394911605760512.0000000000 -0.8956431831 -0.1673954761 1.9915802496 0.0477005434 0.0223489760 0.8585722714 -0.509979250684 +1413394911655760384.0000000000 -0.9173607953 -0.1739416897 1.9734810827 0.0508013988 0.0248943385 0.8433369449 -0.534398996287 +1413394911705760512.0000000000 -0.9380904935 -0.1841763779 1.9577664088 0.0539591678 0.0279047894 0.8223415230 -0.565742123665 +1413394911755760384.0000000000 -0.9569815295 -0.1951271771 1.9438999596 0.0553216285 0.0299140747 0.7997517528 -0.597027469607 +1413394911805760512.0000000000 -0.9744957067 -0.2040740390 1.9327080546 0.0585859264 0.0301487954 0.7774899260 -0.625434372509 +1413394911855760384.0000000000 -0.9903453085 -0.2079677938 1.9233175528 0.0605705948 0.0322647987 0.7585227288 -0.648022727712 +1413394911905760512.0000000000 -1.0039644059 -0.2059452255 1.9156924499 0.0623376117 0.0331259292 0.7463495860 -0.661799811444 +1413394911955760384.0000000000 -1.0158016352 -0.1983428231 1.9081489495 0.0652065400 0.0335557634 0.7472729300 -0.660458390743 +1413394912005760512.0000000000 -1.0258765696 -0.1858476066 1.9016613808 0.0666556186 0.0358805110 0.7573959386 -0.648553012193 +1413394912055760384.0000000000 -1.0340802235 -0.1697716729 1.8970018781 0.0675498513 0.0382811597 0.7758877774 -0.626074857578 +1413394912105760512.0000000000 -1.0403489958 -0.1505759623 1.8941960571 0.0674174296 0.0417926662 0.7975260530 -0.598047203827 +1413394912155760384.0000000000 -1.0456851259 -0.1303804315 1.8931856631 0.0692549971 0.0459275911 0.8168377630 -0.570850655379 +1413394912205760512.0000000000 -1.0499887591 -0.1114860840 1.8939781864 0.0717091657 0.0515663235 0.8316747463 -0.548193237955 +1413394912255760384.0000000000 -1.0538696732 -0.0958133603 1.8964990555 0.0764450898 0.0575107825 0.8420506971 -0.53084770096 +1413394912305760512.0000000000 -1.0569961749 -0.0844280400 1.9003589186 0.0813446380 0.0656277531 0.8488176050 -0.518251600476 +1413394912355760384.0000000000 -1.0596630654 -0.0774197808 1.9045282524 0.0878911222 0.0735983698 0.8520797335 -0.510703983068 +1413394912405760512.0000000000 -1.0618984148 -0.0760418270 1.9100662955 0.0916095575 0.0862918352 0.8533695413 -0.505887175219 +1413394912455760384.0000000000 -1.0644170123 -0.0814042420 1.9180174355 0.0948338367 0.1007578828 0.8520503738 -0.504841116633 +1413394912505760512.0000000000 -1.0669386676 -0.0909011958 1.9273267662 0.0993786434 0.1142083636 0.8472187653 -0.509215768348 +1413394912555760384.0000000000 -1.0699688365 -0.1054995788 1.9390514564 0.1018336321 0.1295533668 0.8388283706 -0.51885720688 +1413394912605760512.0000000000 -1.0738466433 -0.1232460734 1.9513644970 0.1058363666 0.1439989686 0.8280606861 -0.531392943739 +1413394912655760384.0000000000 -1.0786900316 -0.1434881101 1.9649240264 0.1095937055 0.1590022122 0.8156459067 -0.54537076478 +1413394912705760512.0000000000 -1.0841946983 -0.1647555703 1.9778674424 0.1125882305 0.1730485318 0.8053784428 -0.555647064144 +1413394912755760384.0000000000 -1.0908191434 -0.1865734260 1.9907326063 0.1167447919 0.1859852555 0.7964239864 -0.563461597866 +1413394912805760512.0000000000 -1.0981386906 -0.2086427658 2.0035181055 0.1195634859 0.1979239172 0.7894674017 -0.56857006377 +1413394912855760384.0000000000 -1.1058297565 -0.2306615275 2.0157790676 0.1223470325 0.2063595916 0.7848382788 -0.571380607561 +1413394912905760512.0000000000 -1.1147864799 -0.2521953985 2.0273102011 0.1278715838 0.2113772596 0.7821667541 -0.571999721139 +1413394912955760384.0000000000 -1.1248470967 -0.2729938080 2.0376700433 0.1382730825 0.2117664195 0.7823201494 -0.56921939715 +1413394913005760512.0000000000 -1.1352878753 -0.2937257217 2.0482488271 0.1486320781 0.2097510002 0.7821578909 -0.567575595876 +1413394913055760384.0000000000 -1.1456434430 -0.3142079244 2.0590685843 0.1578318895 0.2075267674 0.7820830546 -0.566010451431 +1413394913105760512.0000000000 -1.1555711043 -0.3347679801 2.0697884830 0.1658439333 0.2052975402 0.7821903939 -0.564381871947 +1413394913155760384.0000000000 -1.1641607147 -0.3558319229 2.0809018293 0.1700980843 0.2019953945 0.7825692957 -0.563781695066 +1413394913205760512.0000000000 -1.1712276816 -0.3772839476 2.0922507137 0.1713325998 0.1976264187 0.7832636312 -0.563992041541 +1413394913255760384.0000000000 -1.1764528071 -0.3991564725 2.1040255982 0.1701257659 0.1911052348 0.7841856465 -0.565321930249 +1413394913305760512.0000000000 -1.1794904998 -0.4214203282 2.1167836622 0.1655365839 0.1817400348 0.7837870977 -0.570303414531 +1413394913355760384.0000000000 -1.1810496143 -0.4440352003 2.1299712152 0.1603922081 0.1699698641 0.7825211737 -0.577100682305 +1413394913405760512.0000000000 -1.1805095761 -0.4665670019 2.1419145571 0.1535451512 0.1561176737 0.7832489914 -0.581869552405 +1413394913455760384.0000000000 -1.1777221157 -0.4888132377 2.1514491672 0.1456895193 0.1391240418 0.7849745788 -0.585861737618 +1413394913505760512.0000000000 -1.1733303525 -0.5103749256 2.1576797943 0.1390176764 0.1195966551 0.7866417312 -0.589546870456 +1413394913555760384.0000000000 -1.1669643934 -0.5312319584 2.1608232281 0.1340725583 0.0972365221 0.7889623872 -0.591699213714 +1413394913605760512.0000000000 -1.1582841735 -0.5513089028 2.1611887771 0.1287103417 0.0733907536 0.7912462255 -0.593276373895 +1413394913655760384.0000000000 -1.1470630274 -0.5708596309 2.1585225419 0.1232010064 0.0485977443 0.7938317081 -0.593541060485 +1413394913705760512.0000000000 -1.1328583654 -0.5896695192 2.1527909065 0.1141574139 0.0262984620 0.7982453306 -0.590830659226 +1413394913755760384.0000000000 -1.1154701782 -0.6079487509 2.1436909512 0.1016776141 0.0058756133 0.8039047406 -0.585972958426 +1413394913805760512.0000000000 -1.0947242185 -0.6259637835 2.1322452383 0.0848298218 -0.0121233351 0.8088891568 -0.58168312512 +1413394913855760384.0000000000 -1.0711963247 -0.6441418130 2.1182608415 0.0643737903 -0.0266832490 0.8134184381 -0.577489795506 +1413394913905760512.0000000000 -1.0454489664 -0.6628869908 2.1022636189 0.0434489478 -0.0399228081 0.8168489337 -0.573825912486 +1413394913955760384.0000000000 -1.0177311438 -0.6825941010 2.0850811669 0.0216644040 -0.0522063056 0.8180567427 -0.572353318356 +1413394914005760512.0000000000 -0.9889567419 -0.7024110635 2.0658036809 0.0015120922 -0.0647904070 0.8179466110 -0.571632100458 +1413394914055760384.0000000000 -0.9595268012 -0.7230205431 2.0449597945 0.0151710045 0.0786347094 -0.8167130259 0.5714597593 +1413394914105760512.0000000000 -0.9291949181 -0.7437902974 2.0240366598 0.0293219637 0.0946643948 -0.8141199100 0.572177985347 +1413394914155760384.0000000000 -0.8985550376 -0.7647658284 2.0050604107 0.0394684219 0.1133746383 -0.8109336901 0.572691003414 +1413394914205760512.0000000000 -0.8669622418 -0.7860819074 1.9895222801 0.0477157665 0.1333428426 -0.8062588502 0.574360129555 +1413394914255760384.0000000000 -0.8341056072 -0.8070333075 1.9776377152 0.0549950485 0.1539536561 -0.8023086653 0.574085901312 +1413394914305760512.0000000000 -0.7994026482 -0.8274494274 1.9702756350 0.0636918175 0.1737415862 -0.7970560263 0.574855551043 +1413394914355760384.0000000000 -0.7628618792 -0.8475240580 1.9660894154 0.0708451518 0.1931220197 -0.7920793936 0.574713045123 +1413394914405760512.0000000000 -0.7240310562 -0.8667981769 1.9666962601 0.0787325678 0.2122908686 -0.7864963162 0.574593173 +1413394914455760384.0000000000 -0.6834360794 -0.8849817259 1.9703986567 0.0876594517 0.2291018924 -0.7817445922 0.573326727056 +1413394914505760512.0000000000 -0.6402656322 -0.9030428625 1.9781028935 0.0947537378 0.2449825223 -0.7757587837 0.573762670855 +1413394914555760384.0000000000 -0.5947250630 -0.9190553500 1.9875317517 0.1057091231 0.2562656550 -0.7733032086 0.570224204152 +1413394914605760512.0000000000 -0.5473778929 -0.9336937893 1.9971414864 0.1198619376 0.2622676515 -0.7710574567 0.567731620943 +1413394914655760384.0000000000 -0.4988618287 -0.9471430539 2.0039650732 0.1340641714 0.2668487728 -0.7698697222 0.564020514979 +1413394914705760512.0000000000 -0.4496945889 -0.9597651747 2.0081175999 0.1461959184 0.2720325860 -0.7676390456 0.561565064157 +1413394914755760384.0000000000 -0.3994602470 -0.9716782622 2.0096641208 0.1589738876 0.2762619903 -0.7662300951 0.557940908334 +1413394914805760512.0000000000 -0.3489979787 -0.9827105727 2.0086178021 0.1693437641 0.2822404796 -0.7635709513 0.555537940674 +1413394914855760384.0000000000 -0.2981225913 -0.9938020107 2.0047964787 0.1768895466 0.2894021842 -0.7610639404 0.552935930042 +1413394914905760512.0000000000 -0.2473186722 -1.0045450110 1.9980763823 0.1809742099 0.2987098984 -0.7563027161 0.553197011607 +1413394914955760384.0000000000 -0.1965587786 -1.0143169777 1.9878112982 0.1847638699 0.3085708101 -0.7508216232 0.55399752491 +1413394915005760512.0000000000 -0.1456172181 -1.0230782647 1.9741788938 0.1867005306 0.3199394372 -0.7442287039 0.55579250141 +1413394915055760384.0000000000 -0.0942985775 -1.0294651251 1.9589287957 0.1879279085 0.3334738344 -0.7353764076 0.559195709974 +1413394915105760512.0000000000 -0.0421210579 -1.0335790200 1.9436587464 0.1901856248 0.3478263395 -0.7260714670 0.561842051136 +1413394915155760384.0000000000 0.0109259447 -1.0349048975 1.9286495925 0.1914544018 0.3644051285 -0.7179075366 0.561393697175 +1413394915205760512.0000000000 0.0652576316 -1.0337226976 1.9150256525 0.1927343684 0.3816453965 -0.7086916602 0.561209751594 +1413394915255760384.0000000000 0.1211599973 -1.0289855582 1.9022167044 0.1954578424 0.3988283487 -0.6998140251 0.559457335672 +1413394915305760512.0000000000 0.1784419763 -1.0201054749 1.8911234175 0.2005452018 0.4152750968 -0.6900349168 0.55783512759 +1413394915355760384.0000000000 0.2367699757 -1.0072992423 1.8809276937 0.2057942414 0.4303844092 -0.6803443747 0.556371748319 +1413394915405760512.0000000000 0.2966422079 -0.9897343443 1.8721250149 0.2139772083 0.4445982176 -0.6699466853 0.554723010231 +1413394915455760384.0000000000 0.3575085502 -0.9679042456 1.8641990827 0.2218003984 0.4583019868 -0.6594984863 0.553015025734 +1413394915505760512.0000000000 0.4195018400 -0.9409776888 1.8574067149 0.2312777866 0.4706913240 -0.6488428206 0.551328629021 +1413394915555760384.0000000000 0.4828910140 -0.9081825529 1.8526421234 0.2481822019 0.4802081185 -0.6388782095 0.547394182502 +1413394915605760512.0000000000 0.5467984121 -0.8698325823 1.8493179280 0.2723809943 0.4861298061 -0.6303678641 0.540483821682 +1413394915655760384.0000000000 0.6100471792 -0.8269355434 1.8465253267 0.2996451941 0.4903145569 -0.6234005217 0.530260485527 +1413394915705760512.0000000000 0.6715064794 -0.7802263279 1.8440948739 0.3270144537 0.4955731293 -0.6149953331 0.518892629454 +1413394915755760384.0000000000 0.7304494112 -0.7311402085 1.8414758677 0.3515325624 0.5028754569 -0.6053351846 0.507060594782 +1413394915805760512.0000000000 0.7863790854 -0.6807103219 1.8400759559 0.3730848897 0.5108582170 -0.5910599086 0.500479501757 +1413394915855760384.0000000000 0.8386424470 -0.6287822046 1.8394404831 0.3937174489 0.5189214904 -0.5753288163 0.494675459573 +1413394915905760512.0000000000 0.8870823331 -0.5762310109 1.8392197964 0.4109491036 0.5281920854 -0.5593636388 0.489128076041 +1413394915955760384.0000000000 0.9313323122 -0.5234799385 1.8390106275 0.4247071623 0.5383057068 -0.5445509452 0.483026976949 +1413394916005760512.0000000000 0.9712929150 -0.4702604038 1.8389316502 0.4378138975 0.5478696474 -0.5322933189 0.474153628369 +1413394916055760384.0000000000 1.0064820264 -0.4172018021 1.8392093949 0.4482414531 0.5575907422 -0.5205939313 0.46599798562 +1413394916105760512.0000000000 1.0371854803 -0.3640891171 1.8406805174 0.4597488259 0.5645368055 -0.5105704595 0.457435261169 +1413394916155760384.0000000000 1.0625367725 -0.3115378378 1.8415395117 0.4648362633 0.5750498123 -0.5033769415 0.447053259159 +1413394916205760512.0000000000 1.0834144358 -0.2593142960 1.8413364105 0.4648009894 0.5889045035 -0.5003431841 0.432213169824 +1413394916255760384.0000000000 1.1005985705 -0.2075640390 1.8416440487 0.4634330003 0.6025327265 -0.4972650781 0.418224353553 +1413394916305760512.0000000000 1.1146306384 -0.1559846557 1.8422919439 0.4606053144 0.6173413603 -0.4950108428 0.402115225643 +1413394916355760384.0000000000 1.1265546862 -0.1044518313 1.8439208678 0.4629439510 0.6280687989 -0.4935904263 0.384162690916 +1413394916405760512.0000000000 1.1369425055 -0.0533596455 1.8449928401 0.4684081882 0.6361255113 -0.4933510146 0.364064389218 +1413394916455760384.0000000000 1.1461664983 -0.0030449147 1.8443436414 0.4776562646 0.6412055501 -0.4948055574 0.340393001964 +1413394916505760512.0000000000 1.1552911064 0.0453503894 1.8416791980 0.4875472442 0.6454170306 -0.4945896782 0.317986778773 +1413394916555760384.0000000000 1.1652239011 0.0914877351 1.8374944940 0.5025856114 0.6453217205 -0.4930651874 0.29640226266 +1413394916605760512.0000000000 1.1760251555 0.1346805986 1.8313920738 0.5211136238 0.6425583414 -0.4905103979 0.273786264234 +1413394916655760384.0000000000 1.1878917436 0.1736206179 1.8224493369 0.5386882410 0.6410941389 -0.4846550458 0.252829528968 +1413394916705760512.0000000000 1.2001854358 0.2073370608 1.8086744247 0.5483805264 0.6469916595 -0.4750536971 0.234530543182 +1413394916755760384.0000000000 1.2139551956 0.2352560174 1.7916130302 0.5531436061 0.6580850668 -0.4598442274 0.222484791498 +1413394916855760384.0000000000 1.2466308757 0.2744894677 1.7488791057 0.5509380522 0.6891092239 -0.4246016481 0.20324660044 +1413394916955760384.0000000000 1.2867371878 0.2958758701 1.6942451965 0.5411572512 0.7233353724 -0.3851855628 0.188591756643 +1413394917055760384.0000000000 1.3371171874 0.3053748357 1.6354758411 0.5301653471 0.7565263920 -0.3322359201 0.190294025976 +1413394917155760384.0000000000 1.3939816733 0.3117440447 1.5801806456 0.5205423226 0.7850603946 -0.2826276836 0.18121109134 +1413394917255760384.0000000000 1.4560111793 0.3212021555 1.5287665158 0.5108082140 0.8087384354 -0.2351824471 0.172355238339 +1413394917355760384.0000000000 1.5205763700 0.3397992975 1.4832751683 0.5071271037 0.8233519031 -0.1989301069 0.159187175621 +1413394917455760384.0000000000 1.5865059097 0.3696745459 1.4417932757 0.5071673610 0.8309354015 -0.1760533712 0.146057649783 +1413394917555760384.0000000000 1.6540085083 0.4123832248 1.4040115857 0.5141878579 0.8307160454 -0.1535962515 0.148087441092 +1413394917655760384.0000000000 1.7209944519 0.4713942502 1.3711603792 0.5222705691 0.8272385811 -0.1356732381 0.156532919978 +1413394917755760384.0000000000 1.7809743458 0.5433580357 1.3482502946 0.5274586212 0.8236859093 -0.1262710139 0.165482799128 +1413394917855760384.0000000000 1.8288394900 0.6249574976 1.3372078640 0.5310498838 0.8198553435 -0.1101976724 0.183520324809 +1413394917955760384.0000000000 1.8592552604 0.7181526752 1.3341824856 0.5300567582 0.8204661490 -0.0927308290 0.193070258727 +1413394918055760384.0000000000 1.8701033148 0.8199432512 1.3268069506 0.5314313519 0.8225419470 -0.0831332954 0.18464646967 +1413394918155760384.0000000000 1.8616073881 0.9313606298 1.3141615881 0.5383878687 0.8246801732 -0.0886302501 0.148948962674 +1413394918255760384.0000000000 1.8415814902 1.0490133335 1.3012718326 0.5462582933 0.8254037707 -0.0926308145 0.108305237442 +1413394918355760384.0000000000 1.8172206118 1.1708464521 1.2895555599 0.5457218551 0.8295622351 -0.1019885697 0.0601039649205 +1413394918455760384.0000000000 1.7981121776 1.2963669438 1.2797013060 0.5475865156 0.8300303925 -0.1038035158 0.0205763341352 +1413394918555760384.0000000000 1.7913568128 1.4250044004 1.2712138801 0.5526139989 0.8286388112 -0.0893009060 -0.000914845100387 +1413394918655760384.0000000000 1.7976598315 1.5556837195 1.2628436571 0.5558411978 0.8291086011 -0.0597941068 -0.00664494525927 +1413394918755760384.0000000000 1.8140950618 1.6874935727 1.2549274687 0.5598633730 0.8282727445 -0.0226535996 -0.00201960261763 +1413394918855760384.0000000000 1.8354681032 1.8206953677 1.2515682329 0.5702273079 0.8213498854 0.0132686723 0.00700895718084 +1413394918955760384.0000000000 1.8550037225 1.9540017927 1.2602387433 0.5883406277 0.8074267090 0.0423087898 0.0112863478868 +1413394919055760384.0000000000 1.8666782998 2.0810529962 1.2870903194 0.6034470622 0.7952780316 0.0580067589 -0.00443975871781 +1413394919155760384.0000000000 1.8720929834 2.1953606087 1.3311221670 0.6144384990 0.7852080569 0.0716887613 -0.0278273216219 +1413394919255760384.0000000000 1.8746036455 2.2940742128 1.3913641993 0.6230809111 0.7751736318 0.0907169988 -0.0514436093804 +1413394919355760384.0000000000 1.8767969202 2.3765675974 1.4587677558 0.6327102737 0.7622524913 0.1197341573 -0.0656702411376 +1413394919455760384.0000000000 1.8787388146 2.4417447315 1.5281268711 0.6391557257 0.7498743048 0.1569036439 -0.0674517000646 +1413394919555760384.0000000000 1.8767735855 2.4862570821 1.5944407790 0.6252818138 0.7525800966 0.1950507749 -0.067831015772 +1413394919655760384.0000000000 1.8675987616 2.5111261856 1.6536777012 0.5963244472 0.7669709053 0.2209950318 -0.0855218105561 +1413394919755760384.0000000000 1.8498561132 2.5246889596 1.7044895941 0.5648723988 0.7818038992 0.2365893695 -0.117163588444 +1413394919855760384.0000000000 1.8253964022 2.5351921321 1.7460788296 0.5334353398 0.7940189390 0.2495696543 -0.150650756669 +1413394919955760384.0000000000 1.7961097860 2.5487899869 1.7768660302 0.5104610499 0.7961973700 0.2723723547 -0.176953567278 +1413394920055760384.0000000000 1.7630134310 2.5680296982 1.7965691690 0.4930198908 0.7904236416 0.3033581798 -0.200338884936 +1413394920155760384.0000000000 1.7253121526 2.5942133043 1.8038176588 0.4773082920 0.7805444446 0.3370359210 -0.222112476885 +1413394920255760384.0000000000 1.6820629692 2.6286689598 1.7982373749 0.4648121807 0.7664362512 0.3739284799 -0.238123080593 +1413394920355760384.0000000000 1.6310101849 2.6716241499 1.7837665396 0.4663755811 0.7428067413 0.4103777211 -0.249643923428 +1413394920455760384.0000000000 1.5700965304 2.7190900577 1.7682231571 0.4736996584 0.7165987442 0.4413725802 -0.259393752466 +1413394920555760384.0000000000 1.4990343598 2.7666760195 1.7555011135 0.4839154958 0.6900995727 0.4686674914 -0.264460120345 +1413394920655760384.0000000000 1.4186605822 2.8097774145 1.7462857378 0.4940949375 0.6685792667 0.4906365259 -0.261051252167 +1413394920755760384.0000000000 1.3284934995 2.8417849834 1.7414010319 0.4981584229 0.6567359978 0.5047389705 -0.256465566111 +1413394920855760384.0000000000 1.2292134508 2.8589887289 1.7384926184 0.4909064786 0.6589218109 0.5069374539 -0.260475131732 +1413394920955760384.0000000000 1.1203100031 2.8646524355 1.7308786074 0.4854286657 0.6636365536 0.5034560545 -0.265476056056 +1413394921055760384.0000000000 1.0003984611 2.8611439010 1.7166018798 0.4759977512 0.6750707869 0.4924317169 -0.274256408506 +1413394921155760384.0000000000 0.8729835824 2.8516181222 1.6971435002 0.4729568165 0.6838276989 0.4722952967 -0.292623786719 +1413394921255760384.0000000000 0.7409092563 2.8408368984 1.6684430866 0.4680137054 0.6940720571 0.4495973578 -0.311591666988 +1413394921355760384.0000000000 0.6081098501 2.8324311773 1.6290627796 0.4453017758 0.7158489121 0.4195696794 -0.336493607098 +1413394921455760384.0000000000 0.4763702409 2.8364406463 1.5804119535 0.4227748406 0.7354175823 0.3925486767 -0.355426434256 +1413394921555760384.0000000000 0.3492153221 2.8603475052 1.5181522058 0.4199091019 0.7428501499 0.3895024995 -0.346609007132 +1413394921655760384.0000000000 0.2250547872 2.9066533522 1.4521439037 0.4502336922 0.7294383010 0.4055335099 -0.317414492055 +1413394921755760384.0000000000 0.1020843364 2.9643572835 1.3878574654 0.4857243630 0.7084301471 0.4223650684 -0.289493210288 +1413394921855760384.0000000000 -0.0219450838 3.0206175068 1.3309971273 0.5113683265 0.6869331853 0.4319915203 -0.282857844102 +1413394921955760384.0000000000 -0.1462615737 3.0675051176 1.2850845292 0.5239987598 0.6665409691 0.4299444451 -0.310316306972 +1413394922055760384.0000000000 -0.2615943107 3.1054889079 1.2518600415 0.5193299748 0.6515003304 0.4313659940 -0.346073801427 +1413394922155760384.0000000000 -0.3618409845 3.1390303274 1.2332422802 0.5081075209 0.6361107683 0.4495547707 -0.367546386024 +1413394922255760384.0000000000 -0.4441054300 3.1701583638 1.2245330850 0.4871524301 0.6265218350 0.4840465964 -0.368580781672 +1413394922355760384.0000000000 -0.5162302955 3.2010013679 1.2307960792 0.4722142808 0.6140650711 0.5240051099 -0.354057066373 +1413394922455760384.0000000000 -0.5869968818 3.2273185460 1.2574511419 0.4652400336 0.6004702452 0.5516492476 -0.344485563466 +1413394922555760384.0000000000 -0.6605880924 3.2434410360 1.3060044251 0.4529963840 0.5963412292 0.5621492489 -0.350941072581 +1413394922655760384.0000000000 -0.7366603217 3.2516296153 1.3636957947 0.4357665736 0.6007446848 0.5601339258 -0.368053395754 +1413394922755760384.0000000000 -0.8147037626 3.2575585429 1.4196222561 0.4202267706 0.6067935587 0.5602340925 -0.375963828071 +1413394922855760384.0000000000 -0.8958512066 3.2646530653 1.4749238760 0.4080706534 0.6125559900 0.5634652954 -0.375180439004 +1413394922955760384.0000000000 -0.9822793490 3.2738688092 1.5301018031 0.4029445883 0.6153945441 0.5663710130 -0.371684125948 +1413394923055760384.0000000000 -1.0758965737 3.2845814815 1.5787764901 0.3979544890 0.6187584911 0.5692995358 -0.36697165133 +1413394923155760384.0000000000 -1.1774943437 3.2969913910 1.6165791471 0.4010540629 0.6178019637 0.5709168028 -0.362671168671 +1413394923255760384.0000000000 -1.2888263296 3.3109164697 1.6535958765 0.4236506125 0.6033636230 0.5724246185 -0.358890725785 +1413394923355760384.0000000000 -1.4048992346 3.3198379854 1.6926733496 0.4354430055 0.5959293286 0.5704734839 -0.360302135098 +1413394923455760384.0000000000 -1.5217090345 3.3203407161 1.7310938811 0.4225429454 0.6001034126 0.5727585172 -0.365076751566 +1413394923555760384.0000000000 -1.6416486938 3.3154720514 1.7693517592 0.4042322400 0.6003984192 0.5830964752 -0.368939744396 +1413394923655760384.0000000000 -1.7683289049 3.3080819628 1.8049596736 0.3967777142 0.5860321023 0.5976822249 -0.37670914334 +1413394923755760384.0000000000 -1.9012118011 3.2979730203 1.8313038888 0.3992681096 0.5596803209 0.6143771801 -0.387148027971 +1413394923855760384.0000000000 -2.0370849272 3.2818550708 1.8474120339 0.3975772817 0.5328764405 0.6300086977 -0.401327852304 +1413394923955760384.0000000000 -2.1734843426 3.2593952506 1.8536001986 0.3914676955 0.5072113018 0.6445130609 -0.417244116764 +1413394924055760384.0000000000 -2.3076892426 3.2300973346 1.8501300434 0.3807890496 0.4829589443 0.6586454014 -0.433516543122 +1413394924155760384.0000000000 -2.4387457865 3.1933808300 1.8458888369 0.3616900483 0.4629201824 0.6704029520 -0.453260516283 +1413394924255760384.0000000000 -2.5655828601 3.1509662834 1.8459209148 0.3327638197 0.4471725481 0.6815123143 -0.474179204517 +1413394924355760384.0000000000 -2.6891972993 3.1069810044 1.8489694661 0.3007282698 0.4314372075 0.6930916865 -0.492999348721 +1413394924455760384.0000000000 -2.8128063700 3.0655217297 1.8533210582 0.2817733265 0.4062495565 0.7059415192 -0.507160390627 +1413394924555760384.0000000000 -2.9357463960 3.0264096500 1.8591898762 0.2662434439 0.3788647961 0.7185410854 -0.518916759692 +1413394924655760384.0000000000 -3.0569334520 2.9892489613 1.8659590591 0.2548847256 0.3454868766 0.7352349071 -0.524501883773 +1413394924755760384.0000000000 -3.1756503266 2.9523482828 1.8754112495 0.2460930943 0.3090974510 0.7490469752 -0.531813485751 +1413394924855760384.0000000000 -3.2905932513 2.9138322680 1.8883505268 0.2455876183 0.2685309425 0.7569353604 -0.542795278996 +1413394924905760512.0000000000 -3.3448284354 2.8938590055 1.8958900671 0.2462344882 0.2487692904 0.7589327873 -0.549093290178 +1413394924955760384.0000000000 -3.3966726322 2.8737292379 1.9036395235 0.2495846042 0.2299923524 0.7609185330 -0.553004547266 +1413394925005760512.0000000000 -3.4454067826 2.8528981833 1.9125366764 0.2522584901 0.2141829321 0.7613090626 -0.557583928126 +1413394925055760384.0000000000 -3.4902367718 2.8318529724 1.9213933500 0.2578071254 0.1989318066 0.7624591528 -0.559122225175 +1413394925105760512.0000000000 -3.5296578038 2.8105601513 1.9293558107 0.2562666575 0.1901703854 0.7673299464 -0.556208034963 +1413394925155760384.0000000000 -3.5637619225 2.7879452984 1.9385375482 0.2522002684 0.1822667168 0.7731241725 -0.552677919199 +1413394925205760512.0000000000 -3.5929132951 2.7642823056 1.9483501084 0.2501381581 0.1730519944 0.7795865004 -0.54747492864 +1413394925255760384.0000000000 -3.6171347005 2.7390375229 1.9585808372 0.2469220893 0.1650426655 0.7857370695 -0.542593455528 +1413394925305760512.0000000000 -3.6370557365 2.7117030820 1.9684187088 0.2450210243 0.1569412618 0.7905095749 -0.538914417974 +1413394925355760384.0000000000 -3.6528763677 2.6820944964 1.9769016693 0.2443613594 0.1495433404 0.7936645018 -0.536675855535 +1413394925405760512.0000000000 -3.6644517597 2.6500377425 1.9833403951 0.2404779573 0.1468583679 0.7954779929 -0.536486471982 +1413394925455760384.0000000000 -3.6717228598 2.6154975126 1.9875707322 0.2338669163 0.1471782706 0.7962140119 -0.538226782535 +1413394925505760512.0000000000 -3.6754144367 2.5785988745 1.9894117464 0.2269331356 0.1496864134 0.7967226208 -0.539748455436 +1413394925555760384.0000000000 -3.6757394199 2.5393127498 1.9891112975 0.2204896559 0.1518165019 0.7965818608 -0.542027121499 +1413394925605760512.0000000000 -3.6726420098 2.4985736921 1.9860896102 0.2146654193 0.1529604504 0.7968335343 -0.543671019031 +1413394925655760384.0000000000 -3.6662215689 2.4566346976 1.9809521158 0.2076366646 0.1555618325 0.7968085111 -0.545695637109 +1413394925705760512.0000000000 -3.6564442079 2.4129306274 1.9751877553 0.1951447923 0.1628746224 0.7959479988 -0.549415280703 +1413394925755760384.0000000000 -3.6442993696 2.3680877807 1.9698551193 0.1822358891 0.1715515884 0.7947859316 -0.552879241934 +1413394925805760512.0000000000 -3.6306198936 2.3222245674 1.9649673200 0.1708615927 0.1794964428 0.7934967406 -0.555832947801 +1413394925855760384.0000000000 -3.6161881578 2.2758383535 1.9601445534 0.1625778555 0.1860903091 0.7925940935 -0.557434696373 +1413394925905760512.0000000000 -3.6009954832 2.2291950732 1.9554592078 0.1555862121 0.1899860745 0.7924058851 -0.558382606643 +1413394925955760384.0000000000 -3.5858390713 2.1825501373 1.9510803932 0.1510502491 0.1914105425 0.7923100219 -0.559276904265 +1413394926005760512.0000000000 -3.5707045914 2.1357767130 1.9466425579 0.1490512333 0.1894370499 0.7935778711 -0.558687297566 +1413394926055760384.0000000000 -3.5557152637 2.0886305964 1.9420331390 0.1504384053 0.1836709192 0.7955271754 -0.557467302053 +1413394926105760512.0000000000 -3.5406649710 2.0414399638 1.9372410072 0.1535683746 0.1771499405 0.7981702770 -0.554940412799 +1413394926155760384.0000000000 -3.5252915569 1.9938541142 1.9328310887 0.1573163545 0.1709720681 0.8000397194 -0.553133405232 +1413394926205760512.0000000000 -3.5093137211 1.9455923042 1.9285347432 0.1619090981 0.1642472453 0.8023974430 -0.55042404544 +1413394926255760384.0000000000 -3.4920512658 1.8959896085 1.9250650040 0.1634559535 0.1603411464 0.8040178988 -0.548751388619 +1413394926305760512.0000000000 -3.4734555837 1.8452635130 1.9225313732 0.1601847368 0.1607670775 0.8056042264 -0.547262850223 +1413394926355760384.0000000000 -3.4537782771 1.7933335568 1.9201042607 0.1549933597 0.1624563024 0.8078693200 -0.544914828286 +1413394926405760512.0000000000 -3.4337083693 1.7400371993 1.9180820795 0.1505550950 0.1645302300 0.8097333587 -0.5427659298 +1413394926455760384.0000000000 -3.4131062125 1.6851817959 1.9165933610 0.1451032672 0.1658251373 0.8116414264 -0.541003937783 +1413394926505760512.0000000000 -3.3921663576 1.6284547809 1.9157297401 0.1389852523 0.1649859969 0.8127110193 -0.541261045738 +1413394926555760384.0000000000 -3.3708992043 1.5701345803 1.9154009928 0.1314630313 0.1619000460 0.8128091056 -0.543918380288 +1413394926605760512.0000000000 -3.3491730855 1.5104535880 1.9156398913 0.1201781814 0.1573257820 0.8132368655 -0.547221713456 +1413394926655760384.0000000000 -3.3274949816 1.4497366715 1.9167111370 0.1063954031 0.1515334318 0.8127038370 -0.552476343827 +1413394926705760512.0000000000 -3.3058172033 1.3885737027 1.9182845233 0.0869902279 0.1465623867 0.8118059274 -0.55850094297 +1413394926755760384.0000000000 -3.2852234707 1.3275338489 1.9199926044 0.0663996514 0.1401118409 0.8113188253 -0.563667918215 +1413394926805760512.0000000000 -3.2663001512 1.2667652647 1.9221581918 0.0439974018 0.1334077209 0.8111466629 -0.567721498523 +1413394926855760384.0000000000 -3.2500112222 1.2062442602 1.9252523686 0.0197444471 0.1274618426 0.8102763385 -0.571678135619 +1413394926905760512.0000000000 -3.2372234775 1.1467797594 1.9267618935 0.0002486601 -0.1185110556 -0.8099540875 0.574394850279 +1413394926955760384.0000000000 -3.2286401571 1.0877593874 1.9263755499 0.0181503605 -0.1096149255 -0.8102288056 0.575486242291 +1413394927005760512.0000000000 -3.2248609791 1.0293174801 1.9233630685 0.0311839619 -0.0998114078 -0.8106113256 0.576172302485 +1413394927055760384.0000000000 -3.2264158786 0.9705556465 1.9169760059 0.0338758080 -0.0858724617 -0.8107213094 0.57810838821 +1413394927105760512.0000000000 -3.2328545939 0.9116944929 1.9071897529 0.0254000309 -0.0664573116 -0.8109284600 0.58080400899 +1413394927155760384.0000000000 -3.2425474917 0.8536116854 1.8944966449 0.0156545804 -0.0483067621 -0.8120987813 0.581306253362 +1413394927205760512.0000000000 -3.2550782232 0.7957346977 1.8827765108 0.0045109666 -0.0312105945 -0.8115597452 0.583417800433 +1413394927255760384.0000000000 -3.2694119336 0.7379412379 1.8729336447 0.0070485831 0.0155361370 0.8113747573 -0.584277287953 +1413394927305760512.0000000000 -3.2842813905 0.6804567035 1.8680321767 0.0146902637 0.0049912998 0.8113036568 -0.584419078742 +1413394927355760384.0000000000 -3.2989600436 0.6245051855 1.8658232997 0.0207743238 -0.0031986718 0.8130045347 -0.581877841631 +1413394927405760512.0000000000 -3.3125816296 0.5675730649 1.8683900686 0.0214773598 -0.0065883724 0.8153931060 -0.578471606082 +1413394927455760384.0000000000 -3.3253448620 0.5099622106 1.8754804292 0.0206108797 -0.0079016255 0.8166805960 -0.576667633962 +1413394927505760512.0000000000 -3.3370380085 0.4526305749 1.8857192796 0.0183243947 -0.0072217867 0.8185373017 -0.574115622619 +1413394927555760384.0000000000 -3.3478559582 0.3957845236 1.8989672593 0.0160290325 -0.0059591435 0.8207358028 -0.57105192465 +1413394927605760512.0000000000 -3.3582290144 0.3387691736 1.9160850301 0.0142019577 -0.0043114821 0.8217792622 -0.569612640025 +1413394927655760384.0000000000 -3.3680837362 0.2817351460 1.9353327803 0.0123738078 -0.0038221809 0.8214544978 -0.570126992802 +1413394927705760512.0000000000 -3.3774170012 0.2245083618 1.9546788568 0.0110813492 -0.0048966623 0.8221964491 -0.56907488569 +1413394927755760384.0000000000 -3.3863515575 0.1665009679 1.9749257982 0.0092004015 -0.0057999539 0.8210281125 -0.570784155008 +1413394927805760512.0000000000 -3.3952971222 0.1079996284 1.9930133160 0.0109284955 -0.0091804985 0.8196665705 -0.572663076963 +1413394927855760384.0000000000 -3.4036776160 0.0491878546 2.0086017566 0.0118741392 -0.0117731571 0.8184450066 -0.574341508873 +1413394927905760512.0000000000 -3.4116177722 -0.0094925877 2.0211851738 0.0118707048 -0.0130027931 0.8183978718 -0.57438222221 +1413394927955760384.0000000000 -3.4190108838 -0.0687179608 2.0310990184 0.0112367342 -0.0137974571 0.8186542208 -0.574011004018 +1413394928005760512.0000000000 -3.4260211521 -0.1282839005 2.0385961083 0.0101497864 -0.0139991926 0.8181495396 -0.574745452562 +1413394928055760384.0000000000 -3.4329387734 -0.1876442463 2.0432491219 0.0129455903 -0.0167544027 0.8161388421 -0.577467827732 +1413394928105760512.0000000000 -3.4393998634 -0.2472992610 2.0459245425 0.0181922815 -0.0211461881 0.8129959407 -0.5816007909 +1413394928155760384.0000000000 -3.4449503215 -0.3068776764 2.0467110356 0.0245103412 -0.0261865627 0.8084674798 -0.587446883688 +1413394928205760512.0000000000 -3.4490851193 -0.3659518972 2.0462223771 0.0294791483 -0.0297875150 0.8023235677 -0.595416305137 +1413394928255760384.0000000000 -3.4513664716 -0.4241662149 2.0452303536 0.0345635889 -0.0338183855 0.7965199371 -0.602675422568 +1413394928305760512.0000000000 -3.4516516994 -0.4809361361 2.0453005728 0.0385338720 -0.0357762357 0.7904685033 -0.610241548102 +1413394928355760384.0000000000 -3.4495398086 -0.5352222509 2.0461767209 0.0406144325 -0.0366971625 0.7864939816 -0.615167459343 +1413394928405760512.0000000000 -3.4447660762 -0.5868315246 2.0481692069 0.0392436786 -0.0351407555 0.7844856604 -0.617905583135 +1413394928455760384.0000000000 -3.4374687074 -0.6352853919 2.0507596280 0.0325829957 -0.0294175227 0.7864191214 -0.616131417141 +1413394928505760512.0000000000 -3.4283022205 -0.6810646882 2.0542787135 0.0236411107 -0.0219402492 0.7894554198 -0.612959919965 +1413394928555760384.0000000000 -3.4181400601 -0.7246526015 2.0586773456 0.0174388971 -0.0164920315 0.7917455758 -0.610379259892 +1413394928605760512.0000000000 -3.4072424802 -0.7661749974 2.0631461110 0.0124663503 -0.0115363701 0.7947090874 -0.60675280684 +1413394928655760384.0000000000 -3.3960304746 -0.8062101019 2.0681703421 0.0089461778 -0.0075966394 0.7965385949 -0.604473757728 +1413394928705760512.0000000000 -3.3849296667 -0.8449319341 2.0730708261 0.0077091925 -0.0050556885 0.7982498778 -0.602255876626 +1413394928755760384.0000000000 -3.3738210837 -0.8824064860 2.0779217121 0.0078042595 -0.0035732317 0.7992473069 -0.600940985426 +1413394928805760512.0000000000 -3.3628932363 -0.9186245073 2.0816265889 0.0086340599 -0.0028005412 0.8002795665 -0.599558358612 +1413394928855760384.0000000000 -3.3524839127 -0.9539235273 2.0830297722 0.0133087369 -0.0045152905 0.8003075081 -0.599425043008 +1413394928905760512.0000000000 -3.3420762042 -0.9887538305 2.0819191111 0.0194746242 -0.0075685712 0.8001822922 -0.599392821877 +1413394928955760384.0000000000 -3.3311125847 -1.0231333343 2.0782590793 0.0228015414 -0.0087700357 0.8004749480 -0.598868127229 +1413394929005760512.0000000000 -3.3195330030 -1.0559562908 2.0722744128 0.0244102850 -0.0086552131 0.8007618351 -0.598422683932 +1413394929055760384.0000000000 -3.3069915780 -1.0873282709 2.0647975151 0.0245403824 -0.0081636792 0.7996897304 -0.599856198596 +1413394929105760512.0000000000 -3.2936237739 -1.1177402983 2.0569632544 0.0237365761 -0.0070335855 0.7970124833 -0.603455222107 +1413394929155760384.0000000000 -3.2795641207 -1.1469810529 2.0493334134 0.0233334343 -0.0061914282 0.7929668450 -0.608786333393 +1413394929205760512.0000000000 -3.2646001503 -1.1742326131 2.0423979629 0.0213011019 -0.0046432877 0.7892182208 -0.613725755389 +1413394929255760384.0000000000 -3.2491666430 -1.1993625284 2.0363700388 0.0177612252 -0.0017231797 0.7866490348 -0.6171425002 +1413394929305760512.0000000000 -3.2335502233 -1.2219393893 2.0314673282 0.0117343299 0.0024151637 0.7840808730 -0.620543034015 +1413394929355760384.0000000000 -3.2181865460 -1.2419039467 2.0270998050 0.0066040035 0.0059487772 0.7830515519 -0.62189329164 +1413394929405760512.0000000000 -3.2034928632 -1.2595491470 2.0236868192 0.0028774895 0.0089714342 0.7832930787 -0.621581198439 +1413394929455760384.0000000000 -3.1895065883 -1.2745266620 2.0208687752 0.0001764260 -0.0110176419 -0.7855441595 0.618707486578 +1413394929505760512.0000000000 -3.1765814797 -1.2871698517 2.0180698235 0.0025351994 -0.0126095536 -0.7907954395 0.611945377245 +1413394929555760384.0000000000 -3.1647854552 -1.2980114816 2.0152381645 0.0038343360 -0.0138145400 -0.7980433268 0.602429502047 +1413394929605760512.0000000000 -3.1541821654 -1.3075362232 2.0128545642 0.0045286757 -0.0144577607 -0.8050793232 0.592973648392 +1413394929655760384.0000000000 -3.1450936605 -1.3166158612 2.0110885052 0.0018382358 -0.0134223561 -0.8104130895 0.585702215842 +1413394929705760512.0000000000 -3.1369589139 -1.3260380247 2.0099930336 0.0026117036 0.0112029882 0.8135812047 -0.581337505658 +1413394929755760384.0000000000 -3.1294083866 -1.3357282955 2.0084306170 0.0066027963 0.0089449249 0.8156025973 -0.578505656519 +1413394929805760512.0000000000 -3.1224550545 -1.3462707674 2.0057265962 0.0103890495 0.0070547297 0.8160638636 -0.577825292818 +1413394929855760384.0000000000 -3.1157183996 -1.3571067300 2.0005628134 0.0131717102 0.0054938932 0.8150598101 -0.579201026547 +1413394929905760512.0000000000 -3.1089744232 -1.3686686206 1.9938873552 0.0144607406 0.0051404142 0.8124447736 -0.582836128762 +1413394929955760384.0000000000 -3.1020799992 -1.3801823257 1.9854267186 0.0153540329 0.0050278652 0.8079450919 -0.58903624906 +1413394930005760512.0000000000 -3.0952387832 -1.3914874070 1.9745002080 0.0168594920 0.0047130088 0.8027977764 -0.595994358379 +1413394930055760384.0000000000 -3.0885645006 -1.4012227037 1.9610532650 0.0185474520 0.0038738424 0.7980985255 -0.602228967286 +1413394930105760512.0000000000 -3.0818807717 -1.4095354603 1.9459214863 0.0204998045 0.0028582942 0.7942032169 -0.607299628247 +1413394930155760384.0000000000 -3.0750625448 -1.4164883836 1.9316182692 0.0224341550 0.0022930635 0.7892462576 -0.613662607199 +1413394930205760512.0000000000 -3.0676802097 -1.4214933311 1.9180905989 0.0241998322 0.0010378157 0.7843881338 -0.619797181799 +1413394930255760384.0000000000 -3.0596051551 -1.4245064162 1.9068642990 0.0237166441 0.0016457355 0.7781530099 -0.627624653394 +1413394930305760512.0000000000 -3.0506165027 -1.4244997841 1.8974802190 0.0184895492 0.0051634591 0.7728442260 -0.634305350412 +1413394930355760384.0000000000 -3.0416723219 -1.4211122489 1.8882163261 0.0117491000 0.0100185832 0.7724531894 -0.634883971114 +1413394930405760512.0000000000 -3.0330607957 -1.4144852926 1.8779416645 0.0046483395 0.0150050741 0.7807697268 -0.624621384845 +1413394930455760384.0000000000 -3.0254536088 -1.4052153178 1.8669869164 0.0010968363 -0.0193720299 -0.7945069839 0.606944951313 +1413394930505760512.0000000000 -3.0189866978 -1.3945916319 1.8551183827 0.0063629630 -0.0234794418 -0.8117658790 0.583476123031 +1413394930555760384.0000000000 -3.0138128282 -1.3834432500 1.8410885421 0.0110830749 -0.0275185319 -0.8294315510 0.557820040962 +1413394930605760512.0000000000 -3.0102376671 -1.3729262081 1.8245208548 0.0151864560 -0.0314264772 -0.8460596709 0.531944340497 +1413394930655760384.0000000000 -3.0085279248 -1.3645552633 1.8049858019 0.0173577031 -0.0347947163 -0.8594213973 0.509787112199 +1413394930705760512.0000000000 -3.0094449296 -1.3607478829 1.7841958498 0.0115112999 -0.0314427214 -0.8679784447 0.495471759886 +1413394930755760384.0000000000 -3.0125427320 -1.3636342530 1.7636192815 0.0025140084 -0.0260463193 -0.8702055705 0.491993428962 +1413394930805760512.0000000000 -3.0170432811 -1.3732973574 1.7442109750 0.0085373088 0.0189804400 0.8643939059 -0.502384347531 +1413394930855760384.0000000000 -3.0222184226 -1.3877629363 1.7257666707 0.0187878164 0.0127045907 0.8543754493 -0.519161056907 +1413394930905760512.0000000000 -3.0271390790 -1.4063187987 1.7093884852 0.0259164145 0.0088728649 0.8405374429 -0.541060457677 +1413394930955760384.0000000000 -3.0313227635 -1.4273871778 1.6956493861 0.0311211922 0.0053007402 0.8239727328 -0.565749334132 +1413394931005760512.0000000000 -3.0343664172 -1.4488738837 1.6844282595 0.0339588708 0.0038752315 0.8081946459 -0.587922777216 +1413394931055760384.0000000000 -3.0362629776 -1.4694526256 1.6757749242 0.0361506942 0.0030439347 0.7954943657 -0.604874016535 +1413394931105760512.0000000000 -3.0369607752 -1.4873673886 1.6703035350 0.0369286857 0.0029047407 0.7866426948 -0.616296280455 +1413394931155760384.0000000000 -3.0365951671 -1.5022538151 1.6675417811 0.0387787252 0.0028128500 0.7811846199 -0.623088186384 +1413394931205760512.0000000000 -3.0349098439 -1.5136148702 1.6686048792 0.0402248639 0.0030049155 0.7771123092 -0.628067981736 +1413394931255760384.0000000000 -3.0316001727 -1.5210714976 1.6737287087 0.0394569079 0.0041724728 0.7737412186 -0.632258071945 +1413394931305760512.0000000000 -3.0268738049 -1.5264266803 1.6844971345 0.0404469309 0.0044893117 0.7690586298 -0.637881427716 +1413394931355760384.0000000000 -3.0209174912 -1.5286534836 1.7014642591 0.0398692199 0.0062665227 0.7638567275 -0.644122718038 +1413394931405760512.0000000000 -3.0137149207 -1.5265733238 1.7207412679 0.0372338833 0.0086559407 0.7623602067 -0.646022931342 +1413394931455760384.0000000000 -3.0058955486 -1.5199747218 1.7380216332 0.0377118312 0.0099460341 0.7679931628 -0.639269423715 +1413394931505760512.0000000000 -2.9972274191 -1.5100180866 1.7524116513 0.0383456636 0.0114672694 0.7790821722 -0.625642933894 +1413394931555760384.0000000000 -2.9878838997 -1.4973184294 1.7638066217 0.0402112737 0.0115856395 0.7909377782 -0.61046396896 +1413394931605760512.0000000000 -2.9778327112 -1.4834272167 1.7730192295 0.0419304758 0.0109874293 0.8003861977 -0.597915584467 +1413394931655760384.0000000000 -2.9668770213 -1.4687009051 1.7800875750 0.0442691460 0.0076370242 0.8077090461 -0.58786734506 +1413394931705760512.0000000000 -2.9547761461 -1.4536885680 1.7850635296 0.0473188589 0.0004615290 0.8128921781 -0.580488604 +1413394931755760384.0000000000 -2.9411781853 -1.4390807846 1.7884390194 0.0514128867 -0.0110604892 0.8162361473 -0.575319852288 +1413394931805760512.0000000000 -2.9253188033 -1.4249561749 1.7901258454 0.0543526355 -0.0251128864 0.8180628354 -0.572003786138 +1413394931855760384.0000000000 -2.9065003611 -1.4113487400 1.7905550239 0.0526706374 -0.0397419765 0.8191824206 -0.569724969637 +1413394931905760512.0000000000 -2.8842869535 -1.3985712744 1.7893702112 0.0441863141 -0.0521851209 0.8199934019 -0.568273792832 +1413394931955760384.0000000000 -2.8587887820 -1.3872211581 1.7881288474 0.0301231370 -0.0634690170 0.8199243039 -0.568144714275 +1413394932005760512.0000000000 -2.8304078734 -1.3767997887 1.7884511294 0.0126770288 -0.0747387224 0.8176382646 -0.570719795124 +1413394932055760384.0000000000 -2.7996769113 -1.3665452258 1.7921280727 0.0060917038 0.0871505544 -0.8128616076 0.575867761664 +1413394932105760512.0000000000 -2.7668929469 -1.3562319164 1.8000739520 0.0273817888 0.0995695904 -0.8058124700 0.583097245333 +1413394932155760384.0000000000 -2.7329096467 -1.3455503134 1.8116403571 0.0496434127 0.1121998879 -0.7993760905 0.588170538819 +1413394932205760512.0000000000 -2.6983724687 -1.3343742580 1.8270738362 0.0725619974 0.1242520400 -0.7923403945 0.592868354981 +1413394932255760384.0000000000 -2.6640508518 -1.3223473896 1.8451378160 0.0973194334 0.1352591849 -0.7867272673 0.594385470632 +1413394932305760512.0000000000 -2.6310540489 -1.3096008895 1.8658065921 0.1190221305 0.1482654054 -0.7788082972 0.597753074638 +1413394932355760384.0000000000 -2.5999789473 -1.2958590256 1.8867710426 0.1384411730 0.1627050863 -0.7713752087 0.599450901976 +1413394932405760512.0000000000 -2.5712725418 -1.2814786564 1.9075074782 0.1532367785 0.1790397053 -0.7622677243 0.602835956214 +1413394932455760384.0000000000 -2.5447981935 -1.2656550755 1.9261431204 0.1666830045 0.1956822040 -0.7524105212 0.606468184314 +1413394932505760512.0000000000 -2.5210601909 -1.2480521393 1.9420589614 0.1778249160 0.2129137360 -0.7428708530 0.609252768531 +1413394932555760384.0000000000 -2.5000009424 -1.2283754017 1.9550828971 0.1884258588 0.2291734778 -0.7338862321 0.611053361909 +1413394932605760512.0000000000 -2.4818039145 -1.2064816253 1.9646351612 0.1972887169 0.2459816947 -0.7258247313 0.611349840499 +1413394932655760384.0000000000 -2.4660669245 -1.1821851438 1.9710813309 0.2061599102 0.2622245583 -0.7201115222 0.608420716385 +1413394932705760512.0000000000 -2.4528000181 -1.1555335981 1.9753718864 0.2140412477 0.2778880172 -0.7161913613 0.603352739446 +1413394932755760384.0000000000 -2.4418801892 -1.1265923440 1.9789206266 0.2201927301 0.2945683283 -0.7143209931 0.595390779562 +1413394932805760512.0000000000 -2.4331365513 -1.0955182333 1.9828578854 0.2255690915 0.3102018875 -0.7155340470 0.583870192309 +1413394932855760384.0000000000 -2.4263031679 -1.0626744855 1.9872209892 0.2299209874 0.3254123646 -0.7190662490 0.569374096819 +1413394932905760512.0000000000 -2.4209073074 -1.0285652083 1.9920668308 0.2345163974 0.3393116912 -0.7223691798 0.555024687358 +1413394932955760384.0000000000 -2.4162876934 -0.9941094294 1.9963757645 0.2383555946 0.3521674702 -0.7251365426 0.541610263922 +1413394933005760512.0000000000 -2.4115814301 -0.9599572318 1.9996847052 0.2434134616 0.3637345610 -0.7263685348 0.529939437537 +1413394933055760384.0000000000 -2.4063306861 -0.9263272690 2.0012811051 0.2492193740 0.3744788856 -0.7258222358 0.520420358827 +1413394933105760512.0000000000 -2.4006169740 -0.8932614088 2.0007591570 0.2546527684 0.3854192638 -0.7233625404 0.513176961529 +1413394933155760384.0000000000 -2.3944760547 -0.8607697743 1.9982802809 0.2615211618 0.3963444316 -0.7191910620 0.507229720872 +1413394933205760512.0000000000 -2.3873580927 -0.8292657992 1.9938015489 0.2692768081 0.4060385181 -0.7133186100 0.503784957144 +1413394933255760384.0000000000 -2.3800816380 -0.7982792847 1.9867474891 0.2781950100 0.4152425282 -0.7067243491 0.500721353199 +1413394933305760512.0000000000 -2.3726643333 -0.7678662379 1.9769912577 0.2859118473 0.4247757086 -0.6989811345 0.499244816339 +1413394933355760384.0000000000 -2.3650130437 -0.7381346362 1.9643499729 0.2930758637 0.4339418231 -0.6912002269 0.498039434749 +1413394933405760512.0000000000 -2.3571965504 -0.7089852534 1.9491408434 0.3005359719 0.4424141940 -0.6836632130 0.496540453279 +1413394933455760384.0000000000 -2.3497400068 -0.6800934048 1.9307957761 0.3071397345 0.4508560033 -0.6764551812 0.494775136481 +1413394933505760512.0000000000 -2.3423165163 -0.6512870328 1.9101052328 0.3139671229 0.4585606770 -0.6698404615 0.492402789765 +1413394933555760384.0000000000 -2.3348266504 -0.6226689529 1.8871473028 0.3206467687 0.4663578437 -0.6634412897 0.489429940241 +1413394933605760512.0000000000 -2.3273023333 -0.5941865315 1.8644805295 0.3280576493 0.4737204005 -0.6562807210 0.487096269866 +1413394933655760384.0000000000 -2.3200138182 -0.5658394621 1.8430424976 0.3370650783 0.4798887826 -0.6479076049 0.486116883865 +1413394933705760512.0000000000 -2.3130808173 -0.5378309993 1.8229222592 0.3460224941 0.4854884431 -0.6387521565 0.486379571776 +1413394933755760384.0000000000 -2.3068922748 -0.5098286517 1.8043304729 0.3553180969 0.4897492203 -0.6303410223 0.486379426844 +1413394933805760512.0000000000 -2.3021010188 -0.4819612743 1.7864853404 0.3625378144 0.4937329008 -0.6231858329 0.486244355675 +1413394933855760384.0000000000 -2.2993630531 -0.4539916877 1.7691494904 0.3675519744 0.4983286278 -0.6180230484 0.484377576414 +1413394933905760512.0000000000 -2.2987314111 -0.4257479241 1.7518450835 0.3701806871 0.5054013821 -0.6145397118 0.479454528001 +1413394933955760384.0000000000 -2.3002217762 -0.3972079703 1.7341805510 0.3693724284 0.5153768562 -0.6131275585 0.471195609388 +1413394934005760512.0000000000 -2.3031666845 -0.3683176432 1.7175079127 0.3694579702 0.5256941129 -0.6112392299 0.462096431259 +1413394934055760384.0000000000 -2.3066752539 -0.3390567654 1.7019318938 0.3710478401 0.5359759121 -0.6083594451 0.452716365444 +1413394934105760512.0000000000 -2.3096285155 -0.3096863325 1.6888037423 0.3768675698 0.5436434562 -0.6022137513 0.446946557428 +1413394934155760384.0000000000 -2.3120337729 -0.2804382851 1.6774699034 0.3862080119 0.5497064918 -0.5923884629 0.444681968889 +1413394934205760512.0000000000 -2.3147222394 -0.2511638661 1.6652178498 0.3966806875 0.5551444397 -0.5817318911 0.442772052018 +1413394934255760384.0000000000 -2.3186795662 -0.2217874095 1.6503252225 0.4059404361 0.5618690949 -0.5711525873 0.439659191372 +1413394934305760512.0000000000 -2.3239215994 -0.1923347736 1.6319436277 0.4130457299 0.5708582192 -0.5612226900 0.434215627064 +1413394934355760384.0000000000 -2.3304594035 -0.1628184901 1.6106639205 0.4195204936 0.5809164016 -0.5533687746 0.424643013626 +1413394934405760512.0000000000 -2.3382354033 -0.1333589496 1.5867006817 0.4254570414 0.5909481108 -0.5478024108 0.411921297031 +1413394934455760384.0000000000 -2.3466389741 -0.1045524788 1.5602124766 0.4309741387 0.6000030065 -0.5429023359 0.399392961487 +1413394934505760512.0000000000 -2.3552973964 -0.0769686357 1.5306484763 0.4347377842 0.6081260677 -0.5379693785 0.389582715989 +1413394934555760384.0000000000 -2.3627445008 -0.0504848045 1.4991433309 0.4367507650 0.6156912188 -0.5323151511 0.383162722914 +1413394934605760512.0000000000 -2.3698839641 -0.0249900041 1.4669776009 0.4376822572 0.6229941300 -0.5261048110 0.378848628943 +1413394934655760384.0000000000 -2.3763543263 -0.0003832276 1.4367268674 0.4377409766 0.6293222548 -0.5200631655 0.376657192789 +1413394934705760512.0000000000 -2.3829554540 0.0233388601 1.4105453252 0.4389585856 0.6337455957 -0.5147161432 0.375165526091 +1413394934755760384.0000000000 -2.3907882141 0.0465176748 1.3875617423 0.4424348338 0.6356589349 -0.5118561158 0.371742455338 +1413394934805760512.0000000000 -2.3985539511 0.0690634865 1.3689539363 0.4451650794 0.6368186239 -0.5092014768 0.370140443995 +1413394934855760384.0000000000 -2.4054563383 0.0911152477 1.3544596026 0.4476158408 0.6370611452 -0.5069631287 0.369839887752 +1413394934905760512.0000000000 -2.4120134150 0.1125978303 1.3434902082 0.4492280459 0.6373553840 -0.5056826662 0.369130489627 +1413394934955760384.0000000000 -2.4182012352 0.1337345461 1.3365273778 0.4505716820 0.6374057378 -0.5044322808 0.369116727799 +1413394935005760512.0000000000 -2.4237234860 0.1543682285 1.3343550159 0.4525874253 0.6360057219 -0.5032870887 0.370625755289 +1413394935055760384.0000000000 -2.4296147329 0.1745666570 1.3354535603 0.4556174843 0.6336719247 -0.5028904255 0.3714482735 +1413394935105760512.0000000000 -2.4346468021 0.1939875310 1.3391046248 0.4585574481 0.6298122368 -0.5035546057 0.373489454044 +1413394935155760384.0000000000 -2.4403655582 0.2123429122 1.3424606567 0.4611222706 0.6245738413 -0.5059168210 0.375928102828 +1413394935205760512.0000000000 -2.4468603582 0.2294322907 1.3444338455 0.4618744377 0.6196465514 -0.5083351851 0.379875630612 +1413394935255760384.0000000000 -2.4544313690 0.2452859488 1.3443948202 0.4622104259 0.6144211026 -0.5110497492 0.384286852166 +1413394935305760512.0000000000 -2.4633998134 0.2599205141 1.3419671941 0.4625763530 0.6094819767 -0.5127475057 0.389416015544 +1413394935355760384.0000000000 -2.4737167354 0.2733444505 1.3371590474 0.4624906649 0.6051412087 -0.5129267355 0.395995790915 +1413394935405760512.0000000000 -2.4852370488 0.2859247867 1.3292497425 0.4616887368 0.6015968622 -0.5135509456 0.401484933677 +1413394935455760384.0000000000 -2.4984842226 0.2977373556 1.3186230396 0.4588784636 0.6001717734 -0.5146054317 0.405469663103 +1413394935505760512.0000000000 -2.5134319608 0.3089375752 1.3050149497 0.4539080401 0.6006017184 -0.5171946774 0.407129871982 +1413394935555760384.0000000000 -2.5302528212 0.3198254849 1.2888376996 0.4473970481 0.6024875059 -0.5209753306 0.406730121231 +1413394935605760512.0000000000 -2.5486365132 0.3305337228 1.2720675467 0.4415178902 0.6041898728 -0.5245683458 0.406010592096 +1413394935655760384.0000000000 -2.5683008092 0.3409742499 1.2567560051 0.4364675238 0.6052140518 -0.5276114884 0.406002671655 +1413394935705760512.0000000000 -2.5888042200 0.3514949644 1.2448720387 0.4330937147 0.6054915429 -0.5298292203 0.406313700362 +1413394935755760384.0000000000 -2.6111409960 0.3618818886 1.2357857467 0.4310274203 0.6047208003 -0.5309009190 0.408255227434 +1413394935805760512.0000000000 -2.6323888536 0.3723828700 1.2306108936 0.4303013263 0.6035103296 -0.5309100762 0.410792577248 +1413394935855760384.0000000000 -2.6533359403 0.3834613642 1.2311444776 0.4305947394 0.6018348268 -0.5318471165 0.411730076972 +1413394935905760512.0000000000 -2.6757287900 0.3946369279 1.2325253454 0.4291864669 0.6012982812 -0.5337523628 0.411518856042 +1413394935955760384.0000000000 -2.6988514646 0.4058727825 1.2325140683 0.4270812842 0.6017507379 -0.5357600394 0.410437335385 +1413394936005760512.0000000000 -2.7228299458 0.4172326860 1.2288886292 0.4231104270 0.6044641783 -0.5378591830 0.407808929534 +1413394936055760384.0000000000 -2.7480120511 0.4289812957 1.2212862986 0.4171612234 0.6106075012 -0.5405886759 0.401122022226 +1413394936105760512.0000000000 -2.7736965548 0.4413534867 1.2103872166 0.4109843927 0.6193547568 -0.5421365201 0.391892214439 +1413394936205760512.0000000000 -2.8229153040 0.4687952734 1.1832937436 0.4089665410 0.6378397410 -0.5353057601 0.373302258627 +1413394936255760384.0000000000 -2.8452466071 0.4838472454 1.1685597581 0.4154715459 0.6460313092 -0.5241610954 0.367807134533 +1413394936305760512.0000000000 -2.8669846795 0.4997538564 1.1528985755 0.4255245172 0.6545570620 -0.5087417514 0.362857779537 +1413394936405760512.0000000000 -2.9085222669 0.5342649332 1.1238309850 0.4527512040 0.6714010740 -0.4695933536 0.351737156509 +1413394936505760512.0000000000 -2.9499832236 0.5708422399 1.0974631696 0.4754124287 0.6942708901 -0.4230015134 0.336215218938 +1413394936605760512.0000000000 -2.9937647730 0.6093765027 1.0746381695 0.4900018953 0.7196951522 -0.3765434767 0.316468071937 +1413394936705760512.0000000000 -3.0405039768 0.6506791251 1.0558133073 0.5010803082 0.7411308758 -0.3422655606 0.287224364813 +1413394936805760512.0000000000 -3.0882863809 0.6949612231 1.0412056059 0.5100912906 0.7573347086 -0.3128618116 0.261473710316 +1413394936905760512.0000000000 -3.1375550629 0.7423966277 1.0291030648 0.5154753751 0.7717810898 -0.2846976680 0.239971508619 +1413394937005760512.0000000000 -3.1885422721 0.7938923512 1.0175961297 0.5175244084 0.7865563402 -0.2564312143 0.218496321802 +1413394937105760512.0000000000 -3.2407356668 0.8507887533 1.0077348144 0.5182459758 0.8012540418 -0.2260376895 0.195755030257 +1413394937205760512.0000000000 -3.2927396143 0.9144897993 0.9992241086 0.5214993741 0.8118943095 -0.1957878567 0.174737369127 +1413394937255760384.0000000000 -3.3186081009 0.9488748113 0.9952298824 0.5225848002 0.8162063957 -0.1859524208 0.161659962044 +1413394937305760512.0000000000 -3.3439648149 0.9852435895 0.9916777882 0.5232249692 0.8199519084 -0.1791687069 0.14769249784 +1413394937355760384.0000000000 -3.3681638612 1.0240128411 0.9890496364 0.5248333995 0.8221289947 -0.1736393645 0.136026431159 +1413394937455760384.0000000000 -3.4124476738 1.1059842369 0.9838813086 0.5296617566 0.8230693083 -0.1652632665 0.121257536263 +1413394937555760384.0000000000 -3.4509313286 1.1941724048 0.9790123283 0.5344569988 0.8221191481 -0.1591843436 0.114613121024 +1413394937655760384.0000000000 -3.4847728228 1.2875662035 0.9744223922 0.5394870361 0.8195684873 -0.1567608030 0.112637840776 +1413394937755760384.0000000000 -3.5145324487 1.3854033223 0.9727608838 0.5450706856 0.8155233945 -0.1597863893 0.110850577471 +1413394937855760384.0000000000 -3.5399053644 1.4850285102 0.9729327878 0.5478890215 0.8119955866 -0.1677547714 0.111081609854 +1413394937955760384.0000000000 -3.5591487238 1.5858474637 0.9756150321 0.5465104488 0.8090921672 -0.1852873055 0.111197161409 +1413394938055760384.0000000000 -3.5714895090 1.6875966569 0.9844741063 0.5417223979 0.8070492811 -0.2083716791 0.108579670496 +1413394938155760384.0000000000 -3.5742279059 1.7897282433 1.0042955516 0.5357761860 0.8054876794 -0.2297695408 0.106486783398 +1413394938255760384.0000000000 -3.5622343591 1.8931418303 1.0379879561 0.5314022507 0.8024910060 -0.2477601366 0.110610794549 +1413394938355760384.0000000000 -3.5337171802 1.9960157694 1.0887969049 0.5306718452 0.7972293699 -0.2552479103 0.132895556134 +1413394938455760384.0000000000 -3.4937906554 2.0986547039 1.1521042229 0.5354383088 0.7870585782 -0.2641645279 0.155118387367 +1413394938555760384.0000000000 -3.4465951065 2.1995272750 1.2143948825 0.5337917638 0.7796435278 -0.2726434829 0.181350086087 +1413394938655760384.0000000000 -3.3961284724 2.2985984064 1.2644031918 0.5222783803 0.7757403401 -0.2887255658 0.205157904609 +1413394938755760384.0000000000 -3.3433845659 2.3978809208 1.3028004841 0.5077973392 0.7707512179 -0.3134347423 0.223255648916 +1413394938855760384.0000000000 -3.2882097661 2.4986574540 1.3318887162 0.4964478209 0.7603561940 -0.3468562168 0.234710000277 +1413394938955760384.0000000000 -3.2282056216 2.6007265480 1.3526906863 0.4958872019 0.7378390297 -0.3914025039 0.237683674563 +1413394939055760384.0000000000 -3.1600104028 2.6985089674 1.3646566197 0.5012381146 0.7057709712 -0.4374546103 0.243477211692 +1413394939155760384.0000000000 -3.0829058347 2.7860607498 1.3660586476 0.5014224563 0.6746484780 -0.4762500858 0.258090695707 +1413394939255760384.0000000000 -2.9988828884 2.8601503280 1.3565215305 0.4910120434 0.6526361850 -0.5035912695 0.281725072773 +1413394939355760384.0000000000 -2.9097081560 2.9212102213 1.3392101750 0.4764024578 0.6378109005 -0.5209004685 0.308059499608 +1413394939455760384.0000000000 -2.8173482684 2.9700826293 1.3249025132 0.4545546846 0.6361167257 -0.5227323481 0.339832962216 +1413394939555760384.0000000000 -2.7230442106 3.0130342930 1.3264453939 0.4369239651 0.6375362500 -0.5164953186 0.368615741087 +1413394939655760384.0000000000 -2.6288153574 3.0574659995 1.3465829436 0.4383145795 0.6275356572 -0.5237921157 0.373792921179 +1413394939755760384.0000000000 -2.5347998272 3.0998984995 1.3792485044 0.4449061839 0.6111369778 -0.5422127107 0.366845278439 +1413394939855760384.0000000000 -2.4398408770 3.1352967376 1.4171904139 0.4512047660 0.5910247748 -0.5661641004 0.355755795691 +1413394939955760384.0000000000 -2.3430946955 3.1576610897 1.4455151712 0.4348138585 0.5878905959 -0.5780110318 0.362249641596 +1413394940055760384.0000000000 -2.2445252175 3.1693948560 1.4587732529 0.4012198231 0.5978417229 -0.5812923767 0.379087193971 +1413394940155760384.0000000000 -2.1418467399 3.1775012009 1.4637886819 0.3838875331 0.5911187025 -0.5934383687 0.388638577628 +1413394940255760384.0000000000 -2.0333053974 3.1830011059 1.4592917268 0.3780295251 0.5708309533 -0.6079142517 0.402101931662 +1413394940355760384.0000000000 -1.9183193683 3.1839103837 1.4454720476 0.3732116975 0.5443311591 -0.6225372557 0.420551998382 +1413394940455760384.0000000000 -1.8027654348 3.1801861727 1.4246713825 0.3642911032 0.5158460178 -0.6394861224 0.438465936386 +1413394940555760384.0000000000 -1.6886265730 3.1706390297 1.4032956291 0.3462115473 0.4924925930 -0.6528423968 0.459766696581 +1413394940655760384.0000000000 -1.5760699121 3.1571190262 1.3845150336 0.3151035358 0.4790150648 -0.6605864640 0.484644047763 +1413394940755760384.0000000000 -1.4643368347 3.1464087059 1.3739564401 0.2862361481 0.4696400468 -0.6666603476 0.503061700934 +1413394940855760384.0000000000 -1.3508846148 3.1448597423 1.3790349336 0.2759893985 0.4579605839 -0.6741617572 0.509517301625 +1413394940955760384.0000000000 -1.2350441141 3.1516932493 1.4005093428 0.2832918284 0.4417797794 -0.6868429736 0.502815170847 +1413394941005760512.0000000000 -1.1766981649 3.1560322053 1.4142418455 0.2884154137 0.4325950717 -0.6962005756 0.49495738356 +1413394941055760384.0000000000 -1.1184169529 3.1596304625 1.4282839784 0.2929509283 0.4233854184 -0.7062346650 0.485960017932 +1413394941105760512.0000000000 -1.0603372593 3.1619029360 1.4421311028 0.2970972413 0.4133734703 -0.7175426801 0.475382062715 +1413394941205760512.0000000000 -0.9445865551 3.1585345302 1.4711105988 0.2999637826 0.3961703124 -0.7360302120 0.459706797578 +1413394941305760512.0000000000 -0.8291123895 3.1411782872 1.5026621895 0.2965932483 0.3873527602 -0.7469773429 0.451680344423 +1413394941405760512.0000000000 -0.7135973934 3.1079362272 1.5351612990 0.2853890825 0.3889703668 -0.7521088930 0.448984786338 +1413394941505760512.0000000000 -0.5947907574 3.0585081311 1.5695666615 0.2619621478 0.4044749131 -0.7416576303 0.466604583358 +1413394941605760512.0000000000 -0.4703360859 2.9996520035 1.6058657201 0.2383710983 0.4198201988 -0.7280988766 0.48662331021 +1413394941705760512.0000000000 -0.3375117623 2.9383337724 1.6439920397 0.2250973419 0.4214261060 -0.7203497745 0.502819476772 +1413394941755760384.0000000000 -0.2676275334 2.9083130346 1.6637623455 0.2242316145 0.4165748352 -0.7183013672 0.510126195757 +1413394941805760512.0000000000 -0.1957927416 2.8792906141 1.6833205706 0.2258500074 0.4100288371 -0.7180810173 0.515002698476 +1413394941855760384.0000000000 -0.1223885117 2.8518883284 1.7034857274 0.2357049589 0.3975725789 -0.7223526919 0.514379048279 +1413394941905760512.0000000000 -0.0484302736 2.8251372336 1.7239117286 0.2496954673 0.3828512883 -0.7287661840 0.509879312801 +1413394941955760384.0000000000 0.0256474597 2.7981160240 1.7449039371 0.2658583533 0.3658561411 -0.7368257683 0.502549905128 +1413394942005760512.0000000000 0.0986366371 2.7695958013 1.7662267650 0.2816040193 0.3493019185 -0.7448856354 0.49379422454 +1413394942055760384.0000000000 0.1701072540 2.7380254602 1.7883225427 0.2958129278 0.3341172652 -0.7518987781 0.485292275142 +1413394942105760512.0000000000 0.2393234797 2.7026067513 1.8112140560 0.3101754104 0.3182734578 -0.7586921093 0.476318700215 +1413394942155760384.0000000000 0.3052666093 2.6622603114 1.8347766538 0.3210471896 0.3037801170 -0.7653386750 0.46787076756 +1413394942205760512.0000000000 0.3673148394 2.6156423516 1.8593695171 0.3287610630 0.2901475788 -0.7709421739 0.461929334842 +1413394942255760384.0000000000 0.4249834583 2.5619512895 1.8855397907 0.3332994358 0.2767017210 -0.7767459752 0.457179760776 +1413394942305760512.0000000000 0.4776343304 2.5011326297 1.9119366457 0.3344021547 0.2645112593 -0.7827477757 0.453337525775 +1413394942355760384.0000000000 0.5250384187 2.4326814580 1.9396840592 0.3309709191 0.2529612361 -0.7873736797 0.454435421351 +1413394942405760512.0000000000 0.5668773292 2.3574109551 1.9671674190 0.3237218913 0.2437608187 -0.7915837165 0.457362022981 +1413394942455760384.0000000000 0.6044694097 2.2738909026 1.9950804477 0.3138851649 0.2339962836 -0.7941800965 0.464757804502 +1413394942505760512.0000000000 0.6374643873 2.1845825135 2.0202241247 0.3019066823 0.2238477827 -0.7965045868 0.473629568839 +1413394942555760384.0000000000 0.6661133625 2.0904351701 2.0413512611 0.2899594022 0.2123367240 -0.7985035327 0.48293764503 +1413394942605760512.0000000000 0.6907860887 1.9915954482 2.0580389611 0.2762343792 0.2003761217 -0.8006327129 0.492474605115 +1413394942655760384.0000000000 0.7114135615 1.8889151080 2.0702270393 0.2624530829 0.1871045679 -0.8015510433 0.503613130193 +1413394942705760512.0000000000 0.7276963303 1.7830265371 2.0777700690 0.2462779447 0.1745904271 -0.8012350063 0.516611867254 +1413394942755760384.0000000000 0.7396575353 1.6744074092 2.0805121419 0.2238658099 0.1663288585 -0.7978393924 0.534482098799 +1413394942805760512.0000000000 0.7476782021 1.5640938630 2.0792766105 0.1962127419 0.1612882048 -0.7904677030 0.55735759208 +1413394942855760384.0000000000 0.7521980153 1.4535581900 2.0735518354 0.1657904952 0.1579929405 -0.7802778958 0.58199497236 +1413394942905760512.0000000000 0.7540709878 1.3442502035 2.0626370532 0.1337098055 0.1556338467 -0.7681330682 0.606524017057 +1413394942955760384.0000000000 0.7544482278 1.2378746086 2.0472843173 0.1034487964 0.1517484498 -0.7554665208 0.628920575637 +1413394943005760512.0000000000 0.7539858118 1.1354490609 2.0277525948 0.0771684683 0.1448023747 -0.7448431869 0.646750281502 +1413394943055760384.0000000000 0.7533608039 1.0379705835 2.0049086371 0.0547082465 0.1354246478 -0.7368284262 0.660114416491 +1413394943105760512.0000000000 0.7536359988 0.9458926201 1.9803086682 0.0348435701 0.1233460410 -0.7311295209 0.670090518827 +1413394943155760384.0000000000 0.7547563619 0.8600737517 1.9538099175 0.0167131382 0.1098350633 -0.7268902625 0.677707515154 +1413394943205760512.0000000000 0.7569869837 0.7814223493 1.9255114715 0.0002890402 0.0955692095 -0.7235218207 0.683653872722 +1413394943255760384.0000000000 0.7604735654 0.7101092841 1.8949385108 0.0155716230 -0.0803531503 0.7213130425 -0.687756054557 +1413394943305760512.0000000000 0.7657903652 0.6462172566 1.8637842394 0.0294473601 -0.0641171217 0.7200066858 -0.690371074166 +1413394943355760384.0000000000 0.7735357342 0.5907634425 1.8338128535 0.0422467237 -0.0479608023 0.7200621170 -0.69095985665 +1413394943405760512.0000000000 0.7837108990 0.5446248944 1.8064347999 0.0548345647 -0.0323504560 0.7213235587 -0.689665819164 +1413394943455760384.0000000000 0.7965117274 0.5075598210 1.7817276701 0.0684558790 -0.0182625048 0.7239144558 -0.686242037633 +1413394943505760512.0000000000 0.8124159563 0.4783876395 1.7602754147 0.0821577870 -0.0044517664 0.7274020749 -0.681260964086 +1413394943555760384.0000000000 0.8318539012 0.4562111459 1.7417125618 0.0940541720 0.0089607251 0.7339456930 -0.672604815502 +1413394943605760512.0000000000 0.8549732332 0.4408233332 1.7254030734 0.1030861734 0.0221145375 0.7427246916 -0.66124444846 +1413394943655760384.0000000000 0.8822176250 0.4316683894 1.7113874730 0.1086417094 0.0347542404 0.7540217874 -0.646869589536 +1413394943705760512.0000000000 0.9129182191 0.4265317850 1.6986852534 0.1077720074 0.0496924185 0.7645896533 -0.633497056012 +1413394943755760384.0000000000 0.9459206391 0.4243193073 1.6856873394 0.1075696451 0.0629061765 0.7728073021 -0.622286476035 +1413394943805760512.0000000000 0.9813373098 0.4243466178 1.6719775339 0.1041679467 0.0753487861 0.7779405234 -0.615044828748 +1413394943855760384.0000000000 1.0183108340 0.4252389236 1.6575745552 0.0965390651 0.0880063366 0.7803065977 -0.611601755348 +1413394943905760512.0000000000 1.0560980295 0.4274870826 1.6420187944 0.0880756557 0.0998674863 0.7815599265 -0.609453234748 +1413394943955760384.0000000000 1.0940537916 0.4316380633 1.6240238499 0.0789695752 0.1100478064 0.7835558611 -0.606377356999 +1413394944005760512.0000000000 1.1309568806 0.4375581772 1.6050689349 0.0749807672 0.1156663457 0.7856279430 -0.603148336801 +1413394944055760384.0000000000 1.1665877382 0.4446632458 1.5863707240 0.0764512353 0.1171414970 0.7881690203 -0.599351878073 +1413394944105760512.0000000000 1.2010271860 0.4531016629 1.5689785996 0.0787552283 0.1161691487 0.7904685277 -0.596206214043 +1413394944155760384.0000000000 1.2343665626 0.4625707635 1.5537716703 0.0817111626 0.1147971702 0.7921757261 -0.593803430921 +1413394944205760512.0000000000 1.2668677856 0.4729813238 1.5406509992 0.0839798648 0.1146459240 0.7932492716 -0.592080473854 +1413394944255760384.0000000000 1.2983320643 0.4842206124 1.5290113328 0.0848457471 0.1167858604 0.7958044610 -0.588096524341 +1413394944305760512.0000000000 1.3290585043 0.4958798025 1.5195012348 0.0858048577 0.1191261634 0.7995291738 -0.582408433844 +1413394944355760384.0000000000 1.3582344318 0.5066446247 1.5147123798 0.0870677294 0.1213853656 0.8043870679 -0.575018476726 +1413394944405760512.0000000000 1.3862573601 0.5173685227 1.5143398524 0.0902056269 0.1234206590 0.8099581987 -0.566213742435 +1413394944455760384.0000000000 1.4125880738 0.5267191723 1.5170847492 0.0951335890 0.1254937303 0.8157972739 -0.556485158666 +1413394944505760512.0000000000 1.4376126054 0.5345771736 1.5196380015 0.1004566156 0.1305697949 0.8205585011 -0.547305895595 +1413394944555760384.0000000000 1.4614018900 0.5404303040 1.5203982830 0.1034137454 0.1413604437 0.8236695008 -0.539343467242 +1413394944605760512.0000000000 1.4836809300 0.5438833517 1.5185489974 0.1054559572 0.1554004626 0.8262462427 -0.53108086371 +1413394944655760384.0000000000 1.5043336299 0.5451590735 1.5137233296 0.1079261366 0.1717084713 0.8291594712 -0.520924871035 +1413394944705760512.0000000000 1.5225691604 0.5436826559 1.5063533557 0.1116860740 0.1892340497 0.8316424638 -0.509987752461 +1413394944755760384.0000000000 1.5379018273 0.5391186532 1.4962742753 0.1173360148 0.2077122689 0.8328060673 -0.499521698429 +1413394944805760512.0000000000 1.5504840060 0.5314631388 1.4843489460 0.1240505338 0.2270025445 0.8324641871 -0.489984374311 +1413394944855760384.0000000000 1.5594627163 0.5201395592 1.4709389482 0.1317357597 0.2461889886 0.8302534225 -0.482406390903 +1413394944905760512.0000000000 1.5644462331 0.5051039570 1.4565565742 0.1412883376 0.2654431945 0.8259557044 -0.476838222592 +1413394944955760384.0000000000 1.5652922111 0.4863552329 1.4409056524 0.1523069408 0.2850196305 0.8197873941 -0.472773766665 +1413394945005760512.0000000000 1.5617183068 0.4640955791 1.4244388816 0.1657357492 0.3027809041 0.8116196843 -0.471305499204 +1413394945055760384.0000000000 1.5537207039 0.4387558410 1.4075328072 0.1827877325 0.3175177536 0.8018572717 -0.472012750647 +1413394945105760512.0000000000 1.5419099651 0.4104801670 1.3896524758 0.2018207319 0.3316213931 0.7912362651 -0.47248366814 +1413394945155760384.0000000000 1.5268562350 0.3795432190 1.3718662954 0.2207286553 0.3446590611 0.7803764385 -0.472759565239 +1413394945205760512.0000000000 1.5091287762 0.3461915724 1.3549115735 0.2391310852 0.3574502762 0.7690357104 -0.472895020369 +1413394945255760384.0000000000 1.4892747826 0.3106408320 1.3387159630 0.2569436763 0.3707297393 0.7565854785 -0.473410837719 +1413394945305760512.0000000000 1.4671706598 0.2730918746 1.3240185249 0.2750012879 0.3828365751 0.7445604770 -0.472694557311 +1413394945355760384.0000000000 1.4437846430 0.2337320035 1.3113198504 0.2930707259 0.3942932366 0.7306870032 -0.474066341964 +1413394945405760512.0000000000 1.4196625304 0.1928226571 1.3000727601 0.3117162184 0.4050018991 0.7136807524 -0.479026350502 +1413394945455760384.0000000000 1.3959229162 0.1506874009 1.2899542650 0.3259959927 0.4184454778 0.6949668264 -0.485439084698 +1413394945505760512.0000000000 1.3732095556 0.1079911754 1.2806598162 0.3324046098 0.4369681907 0.6752344915 -0.492569139504 +1413394945555760384.0000000000 1.3514610220 0.0658781023 1.2716286979 0.3356777597 0.4575907031 0.6556584399 -0.498039356226 +1413394945605760512.0000000000 1.3309594732 0.0255989147 1.2625301324 0.3383473016 0.4781970225 0.6379625052 -0.499852531339 +1413394945655760384.0000000000 1.3112176965 -0.0124343493 1.2539275921 0.3405468650 0.4991732744 0.6199113095 -0.500563525654 +1413394945705760512.0000000000 1.2920156476 -0.0474445313 1.2457175645 0.3437366226 0.5193255657 0.6034733309 -0.497961876088 +1413394945755760384.0000000000 1.2738182399 -0.0788128573 1.2379517220 0.3470370452 0.5393695721 0.5870356345 -0.493998904696 +1413394945805760512.0000000000 1.2552936002 -0.1060025261 1.2299204684 0.3523948772 0.5584121907 0.5711495760 -0.487628790853 +1413394945855760384.0000000000 1.2359851709 -0.1289551145 1.2218617259 0.3589302691 0.5770330998 0.5544003799 -0.480460281812 +1413394945905760512.0000000000 1.2178794960 -0.1473663192 1.2133786271 0.3656508453 0.5955465695 0.5365752000 -0.472980758285 +1413394945955760384.0000000000 1.2014641854 -0.1605223495 1.2049173620 0.3746540945 0.6127230597 0.5194242439 -0.463036949416 +1413394946005760512.0000000000 1.1853213537 -0.1682628001 1.1968700595 0.3871186060 0.6275675158 0.5040557107 -0.449695495328 +1413394946055760384.0000000000 1.1706912416 -0.1707998941 1.1889979921 0.4028009765 0.6402657814 0.4908679213 -0.432272814779 +1413394946155760384.0000000000 1.1441609791 -0.1624751729 1.1765025703 0.4344034526 0.6635176165 0.4631027935 -0.395694093442 +1413394946205760512.0000000000 1.1339557077 -0.1536499011 1.1711260044 0.4493876415 0.6742655756 0.4468435205 -0.37914054056 +1413394946255760384.0000000000 1.1246182783 -0.1423424643 1.1663775704 0.4620706487 0.6859287482 0.4281368440 -0.364268185482 +1413394946355760384.0000000000 1.1102042510 -0.1130454369 1.1572422226 0.4796127483 0.7114612634 0.3861483053 -0.338650215955 +1413394946455760384.0000000000 1.1021898514 -0.0745260375 1.1486965131 0.4917132415 0.7369688571 0.3422884121 -0.312943500771 +1413394946555760384.0000000000 1.1023124997 -0.0265385735 1.1420846214 0.5037245981 0.7586309241 0.2972428469 -0.287031949868 +1413394946655760384.0000000000 1.1133028727 0.0307073590 1.1353653769 0.5263565527 0.7704264630 0.2587631874 -0.249866879422 +1413394946755760384.0000000000 1.1324533771 0.0953912835 1.1291337653 0.5547456384 0.7748887959 0.2234758309 -0.204604945327 +1413394946855760384.0000000000 1.1592257660 0.1597163118 1.1237303050 0.5745201959 0.7810294472 0.1845312707 -0.160834564834 +1413394946955760384.0000000000 1.1914185992 0.2209762581 1.1209008246 0.5891085705 0.7864528010 0.1417238765 -0.119822480761 +1413394947055760384.0000000000 1.2277687012 0.2764227279 1.1224801225 0.6001287208 0.7899771548 0.0985116087 -0.0779556045424 +1413394947155760384.0000000000 1.2660531297 0.3236982149 1.1326341776 0.6014037724 0.7961119573 0.0555229434 -0.0379006163932 +1413394947255760384.0000000000 1.3042490677 0.3631302363 1.1580239260 0.5937491306 0.8045270459 0.0140746891 -0.000324685075509 +1413394947355760384.0000000000 1.3407037996 0.3950227557 1.2012302921 0.5969835072 0.8011809453 -0.0238537023 0.0339232361668 +1413394947455760384.0000000000 1.3716812968 0.4214258813 1.2598110866 0.6015745758 0.7949951547 -0.0521465119 0.0580644048624 +1413394947555760384.0000000000 1.3959396740 0.4401675477 1.3230497229 0.5951252613 0.7973585735 -0.0717011680 0.0700297882599 +1413394947655760384.0000000000 1.4149717407 0.4523346324 1.3773952299 0.5717794909 0.8127073095 -0.0818875840 0.076612443892 +1413394947755760384.0000000000 1.4302068674 0.4641493895 1.4184636850 0.5417410529 0.8329205067 -0.0836809974 0.0758785328417 +1413394947855760384.0000000000 1.4419024494 0.4824611720 1.4524243237 0.5195194186 0.8486441746 -0.0735885716 0.0669877653886 +1413394947955760384.0000000000 1.4518217220 0.5159542108 1.4936346972 0.5114370130 0.8559852530 -0.0535293802 0.0534418724163 +1413394948055760384.0000000000 1.4600501388 0.5657057485 1.5457968737 0.5063999560 0.8610459766 -0.0289807052 0.0363184448774 +1413394948155760384.0000000000 1.4680358956 0.6316584535 1.5971258759 0.4969530843 0.8674935602 -0.0052768448 0.0215571322991 +1413394948255760384.0000000000 1.4757338185 0.7151942255 1.6407045250 0.5064125654 0.8619794393 0.0177081658 0.0149726645553 +1413394948355760384.0000000000 1.4805728539 0.8164607686 1.6805861048 0.5457212045 0.8371195269 0.0359950342 0.011118550658 +1413394948455760384.0000000000 1.4812505147 0.9217300843 1.7157937663 0.5970109937 0.8008792506 0.0462742564 0.00538448383897 +1413394948555760384.0000000000 1.4783591397 1.0180385412 1.7476568958 0.6451055789 0.7624456034 0.0501545675 -0.000115466913101 +1413394948655760384.0000000000 1.4722013558 1.0950796156 1.7796229918 0.6744781681 0.7366387601 0.0491356499 -0.0053127994631 +1413394948755760384.0000000000 1.4635290861 1.1414024676 1.8137143482 0.6906199728 0.7216115125 0.0478810249 -0.00531842140235 +1413394948855760384.0000000000 1.4527400579 1.1568366725 1.8482939583 0.6732894426 0.7379185353 0.0464045698 -0.00204390649553 +1413394948955760384.0000000000 1.4389134015 1.1485200473 1.8833719895 0.6343690026 0.7717276513 0.0447896287 0.00250798335216 +1413394949055760384.0000000000 1.4218634352 1.1255870868 1.9086510024 0.5808767556 0.8127377109 0.0439179346 0.0105272528963 +1413394949155760384.0000000000 1.4000186355 1.0970900466 1.9198763916 0.5273197153 0.8484331029 0.0427888008 0.0162575020595 +1413394949255760384.0000000000 1.3726173644 1.0791978790 1.9226085643 0.4907057483 0.8701070594 0.0413110323 0.0203708680564 +1413394949355760384.0000000000 1.3384235412 1.0829139338 1.9180823666 0.4688949922 0.8820919758 0.0387674450 0.0234161856134 +1413394949455760384.0000000000 1.2970334999 1.1127936741 1.9094164557 0.4678600109 0.8827128616 0.0362999259 0.0246440556093 +1413394949555760384.0000000000 1.2478753163 1.1719704740 1.9099654908 0.5105749370 0.8587190829 0.0356334004 0.0253974637132 +1413394949655760384.0000000000 1.1919290767 1.2481112125 1.9197327443 0.5730336892 0.8184815365 0.0342488734 0.0233961556223 +1413394949755760384.0000000000 1.1305389772 1.3212229980 1.9325974248 0.6234193940 0.7810743617 0.0304543710 0.018537311658 +1413394949855760384.0000000000 1.0645762066 1.3795056175 1.9439048602 0.6478362194 0.7613325610 0.0246237348 0.00863921503337 +1413394949955760384.0000000000 0.9961102485 1.4174245074 1.9530983997 0.6478207340 0.7614601607 0.0192511404 -0.0116667815732 +1413394950055760384.0000000000 0.9290835633 1.4362758044 1.9637955188 0.6449318370 0.7630899633 0.0195147868 -0.0370918662486 +1413394950155760384.0000000000 0.8679177741 1.4372795715 1.9741676358 0.6331588570 0.7706579155 0.0236223023 -0.0681045217145 +1413394950255760384.0000000000 0.8182812684 1.4249712136 1.9794770365 0.5955396346 0.7972709132 0.0320891068 -0.0930694563142 +1413394950355760384.0000000000 0.7851794564 1.4106448726 1.9813343097 0.5511910213 0.8283887258 0.0566025467 -0.0821993228059 +1413394950455760384.0000000000 0.7625922422 1.4045824238 1.9858122200 0.5173410345 0.8497523216 0.0838960963 -0.0569270668337 +1413394950555760384.0000000000 0.7400894479 1.4145829492 1.9954454303 0.4962941666 0.8614232185 0.1007477653 -0.0386267614094 +1413394950655760384.0000000000 0.7106823030 1.4452998994 2.0117902342 0.4951299780 0.8614798736 0.1087282081 -0.0296126505907 +1413394950755760384.0000000000 0.6706772328 1.4970981409 2.0374895594 0.5318143287 0.8384651583 0.1154069130 -0.0288260750041 +1413394950855760384.0000000000 0.6204927280 1.5574406292 2.0696397248 0.5888951294 0.7980276232 0.1210436216 -0.0412659758247 +1413394950955760384.0000000000 0.5647056857 1.6100207435 2.1031640460 0.6440206772 0.7515844208 0.1297243137 -0.0594123571583 +1413394951055760384.0000000000 0.5072498228 1.6405837578 2.1368947738 0.6826147519 0.7122578512 0.1425165376 -0.0800930109781 +1413394951155760384.0000000000 0.4522546782 1.6387487119 2.1713703696 0.6946917015 0.6940728201 0.1544869629 -0.108628442745 +1413394951255760384.0000000000 0.4054860527 1.6028984627 2.2039162248 0.6729321884 0.7065217548 0.1695441129 -0.138723010773 +1413394951355760384.0000000000 0.3711853666 1.5411869093 2.2330513462 0.6170733284 0.7481218617 0.1883520834 -0.155105383925 +1413394951455760384.0000000000 0.3473694760 1.4682146164 2.2601783076 0.5423679256 0.7991608198 0.2090518694 -0.153219885431 +1413394951555760384.0000000000 0.3256958407 1.4023974798 2.2916937592 0.4755340137 0.8387186603 0.2235292314 -0.143014311662 +1413394951655760384.0000000000 0.2981539640 1.3579453239 2.3290685544 0.4313387921 0.8625685961 0.2273581055 -0.135020574063 +1413394951755760384.0000000000 0.2584967870 1.3471732262 2.3705395106 0.4088792668 0.8746656276 0.2276057886 -0.126385877414 +1413394951855760384.0000000000 0.2019339558 1.3802286195 2.4234498054 0.4434255653 0.8580841115 0.2287174412 -0.121465047206 +1413394951955760384.0000000000 0.1311192427 1.4414812381 2.4819464892 0.5040597379 0.8244668416 0.2246441717 -0.125352318581 +1413394952055760384.0000000000 0.0533244432 1.5126176346 2.5416318627 0.5673228500 0.7832943717 0.2141824232 -0.1368232464 +1413394952155760384.0000000000 -0.0238209811 1.5791993570 2.5895304203 0.6128655720 0.7490827211 0.2050563156 -0.145680386943 +1413394952255760384.0000000000 -0.0954315893 1.6319848517 2.6196139846 0.6225794877 0.7411990206 0.1992859200 -0.152656200119 +1413394952355760384.0000000000 -0.1612223889 1.6701202303 2.6301146163 0.5945360110 0.7620218585 0.2014462179 -0.158962385873 +1413394952455760384.0000000000 -0.2225447903 1.7002721318 2.6324372994 0.5586270232 0.7842291300 0.2057167867 -0.174931770576 +1413394952555760384.0000000000 -0.2781028714 1.7320245054 2.6391327442 0.5314976624 0.7976627031 0.2189496691 -0.182497915813 +1413394952655760384.0000000000 -0.3278650654 1.7719166727 2.6571693762 0.5248188294 0.7977666499 0.2414687512 -0.172703244843 +1413394952755760384.0000000000 -0.3790338344 1.8220984487 2.6889767201 0.5368245760 0.7859569324 0.2573325556 -0.16694619167 +1413394952855760384.0000000000 -0.4342430424 1.8766640528 2.7234931341 0.5677536320 0.7608919072 0.2613764646 -0.174303363871 +1413394952955760384.0000000000 -0.4894436576 1.9271570887 2.7521002138 0.6058911047 0.7286704291 0.2578537382 -0.188273271145 +1413394953055760384.0000000000 -0.5381065250 1.9643186345 2.7684844623 0.6351628272 0.7022108471 0.2520057240 -0.199903037237 +1413394953155760384.0000000000 -0.5755794223 1.9828517509 2.7767823261 0.6529408820 0.6853616566 0.2471000105 -0.207097052439 +1413394953255760384.0000000000 -0.5970663672 1.9758101538 2.7940379539 0.6637560892 0.6750750353 0.2432351235 -0.211040814857 +1413394953355760384.0000000000 -0.5988012114 1.9379544873 2.8337816893 0.6765919958 0.6631155730 0.2376776708 -0.214500193038 +1413394953455760384.0000000000 -0.5806097404 1.8700381094 2.8792778960 0.6678961771 0.6728737141 0.2376684762 -0.211351264326 +1413394953555760384.0000000000 -0.5477219684 1.7805767854 2.8980374811 0.6157122540 0.7220333479 0.2524503311 -0.189301598141 +1413394953655760384.0000000000 -0.5083317693 1.6797848277 2.8802976005 0.5532753752 0.7717183308 0.2680649461 -0.1627217312 +1413394953755760384.0000000000 -0.4715563645 1.5791229480 2.8262165662 0.5015056120 0.8069697528 0.2777074090 -0.142023006179 +1413394953855760384.0000000000 -0.4447930657 1.4873133115 2.7419333111 0.4672224837 0.8277015935 0.2833420675 -0.127790827745 +1413394953955760384.0000000000 -0.4347871453 1.4121921101 2.6474882931 0.4691363295 0.8267285143 0.2834674159 -0.126796262213 +1413394954055760384.0000000000 -0.4429098367 1.3544441919 2.5576471001 0.5078937321 0.8031241065 0.2784844367 -0.139578096214 +1413394954155760384.0000000000 -0.4629728438 1.3057926099 2.4728289774 0.5554983189 0.7701706494 0.2724639722 -0.154990878167 +1413394954255760384.0000000000 -0.4868516488 1.2546537206 2.3921118645 0.6003368569 0.7348049866 0.2649112615 -0.171695408779 +1413394954355760384.0000000000 -0.5071156310 1.1915709079 2.3159762527 0.6307172914 0.7080610571 0.2587187733 -0.184146230115 +1413394954455760384.0000000000 -0.5189028952 1.1096296352 2.2520732141 0.6350233514 0.7038037283 0.2542153560 -0.191781667703 +1413394954555760384.0000000000 -0.5202483906 1.0082504470 2.1997992297 0.6022539068 0.7316589250 0.2562202484 -0.190569235464 +1413394954655760384.0000000000 -0.5132731661 0.8946117017 2.1506757154 0.5411792706 0.7792475855 0.2595877738 -0.180311910992 +1413394954755760384.0000000000 -0.5057089792 0.7850698762 2.1012045215 0.4801526294 0.8213799974 0.2572758757 -0.169107883323 +1413394954855760384.0000000000 -0.5048544840 0.6945142261 2.0474715323 0.4487132857 0.8424113495 0.2533805505 -0.157473178988 +1413394954955760384.0000000000 -0.5152746075 0.6317189053 1.9918859865 0.4732260126 0.8304106432 0.2539610045 -0.148253542248 +1413394955055760384.0000000000 -0.5366986007 0.5862167216 1.9329686973 0.5220337293 0.7988139301 0.2572325481 -0.152343384322 +1413394955155760384.0000000000 -0.5656533534 0.5451811917 1.8752673144 0.5667772278 0.7621657560 0.2646983470 -0.166738476332 +1413394955255760384.0000000000 -0.5957918647 0.4974015495 1.8216168516 0.5985645016 0.7278734830 0.2771005246 -0.187446070642 +1413394955355760384.0000000000 -0.6221959582 0.4348275658 1.7768485381 0.5942136931 0.7177277121 0.2907774797 -0.217314232085 +1413394955455760384.0000000000 -0.6406020434 0.3600712721 1.7440797450 0.5401345979 0.7430581468 0.3009821360 -0.255986250592 +1413394955555760384.0000000000 -0.6487796189 0.2904377088 1.7223380588 0.4721431839 0.7766763585 0.3145485514 -0.273703958423 +1413394955655760384.0000000000 -0.6515611537 0.2445338636 1.7147686111 0.4262186811 0.7977269337 0.3357980221 -0.263076155262 +1413394955755760384.0000000000 -0.6624044261 0.2310723508 1.7162231454 0.4227855902 0.7961188164 0.3642549557 -0.234020302669 +1413394955855760384.0000000000 -0.6893133764 0.2430206013 1.7256252682 0.4508006032 0.7779945444 0.3812237775 -0.214876095687 +1413394955905760512.0000000000 -0.7094506695 0.2545939636 1.7327940413 0.4683955502 0.7671146449 0.3830362037 -0.213129061295 +1413394955955760384.0000000000 -0.7335058020 0.2683997153 1.7415970042 0.4866198955 0.7560849599 0.3808098324 -0.215686073295 +1413394956005760512.0000000000 -0.7607741125 0.2834305032 1.7522593276 0.5062576614 0.7438370639 0.3758668810 -0.221661206696 +1413394956105760512.0000000000 -0.8205290259 0.3126454714 1.7768440579 0.5489111089 0.7140867931 0.3626142300 -0.239348212339 +1413394956205760512.0000000000 -0.8787812120 0.3327801269 1.8027865775 0.5772490660 0.6884098986 0.3520393409 -0.262571189908 +1413394956305760512.0000000000 -0.9267672157 0.3380578369 1.8280723886 0.5862293016 0.6706677538 0.3508187867 -0.28890508631 +1413394956405760512.0000000000 -0.9602426559 0.3290760016 1.8476130742 0.5736297519 0.6640023954 0.3612986238 -0.315456860805 +1413394956505760512.0000000000 -0.9778559243 0.3106696851 1.8540518266 0.5396009708 0.6712647365 0.3891962846 -0.326742555987 +1413394956605760512.0000000000 -0.9832819459 0.2903579864 1.8475344417 0.4987850640 0.6828715480 0.4292162545 -0.31729058554 +1413394956655760384.0000000000 -0.9841621792 0.2813359927 1.8409300930 0.4757082139 0.6908676515 0.4499714656 -0.306478814107 +1413394956705760512.0000000000 -0.9855840580 0.2733267231 1.8349594552 0.4535513739 0.6986721137 0.4679507062 -0.295246617753 +1413394956755760384.0000000000 -0.9895886234 0.2667353793 1.8302429043 0.4341763126 0.7051346935 0.4826061930 -0.285249463111 +1413394956805760512.0000000000 -0.9978750955 0.2620746405 1.8276062698 0.4207247479 0.7084590763 0.4934048822 -0.27861810056 +1413394956855760384.0000000000 -1.0120126747 0.2598066593 1.8277306668 0.4172255640 0.7064836412 0.4999776078 -0.277175188516 +1413394956905760512.0000000000 -1.0321630956 0.2595476784 1.8306051845 0.4224674154 0.7005022492 0.5013362621 -0.281921680737 +1413394956955760384.0000000000 -1.0571693559 0.2607432306 1.8347486489 0.4306536237 0.6933508336 0.5005784228 -0.288484523975 +1413394957005760512.0000000000 -1.0858553822 0.2630594701 1.8394352593 0.4397059192 0.6859417332 0.4989299327 -0.295316043477 +1413394957055760384.0000000000 -1.1181129433 0.2663215140 1.8456216651 0.4518361376 0.6771355802 0.4947062847 -0.304297884648 +1413394957105760512.0000000000 -1.1527585982 0.2697108615 1.8533566667 0.4653597353 0.6674323922 0.4879868324 -0.315979698573 +1413394957155760384.0000000000 -1.1885184378 0.2730317320 1.8623031635 0.4795233314 0.6571049008 0.4792961588 -0.329462768909 +1413394957205760512.0000000000 -1.2240783742 0.2761787715 1.8723421636 0.4949470489 0.6457043903 0.4696872656 -0.342763959132 +1413394957255760384.0000000000 -1.2578634069 0.2784679414 1.8829082373 0.5080229934 0.6348675163 0.4603940747 -0.356220677108 +1413394957305760512.0000000000 -1.2888894077 0.2799994624 1.8948557675 0.5210626975 0.6237338896 0.4492527720 -0.370973917006 +1413394957355760384.0000000000 -1.3159175445 0.2804071640 1.9078679707 0.5334662970 0.6125272243 0.4371301711 -0.386188196439 +1413394957405760512.0000000000 -1.3373939843 0.2796355292 1.9206624510 0.5432046851 0.6030205217 0.4277833812 -0.397864674476 +1413394957455760384.0000000000 -1.3525993810 0.2777722000 1.9327273436 0.5466166779 0.5993255698 0.4226252736 -0.404236251429 +1413394957505760512.0000000000 -1.3611063552 0.2745139882 1.9434485500 0.5414664394 0.6028331326 0.4231933562 -0.405356253791 +1413394957555760384.0000000000 -1.3627817680 0.2701668829 1.9536142809 0.5282263573 0.6128078763 0.4301635820 -0.400503077321 +1413394957605760512.0000000000 -1.3583065938 0.2647477164 1.9624083229 0.5096440989 0.6263313166 0.4421794149 -0.390447614051 +1413394957655760384.0000000000 -1.3492858556 0.2591002229 1.9708343785 0.4899084323 0.6393820640 0.4574682586 -0.376700274123 +1413394957705760512.0000000000 -1.3376474116 0.2537839776 1.9772606242 0.4687170985 0.6517625020 0.4740116584 -0.361694443169 +1413394957755760384.0000000000 -1.3251070752 0.2489042707 1.9808816696 0.4463130837 0.6633565345 0.4908806215 -0.346119856186 +1413394957805760512.0000000000 -1.3137496717 0.2450022876 1.9838000735 0.4269132400 0.6714914274 0.5050603464 -0.334302849038 +1413394957855760384.0000000000 -1.3050465309 0.2423401705 1.9863999934 0.4133983193 0.6749347051 0.5148945052 -0.32931538359 +1413394957905760512.0000000000 -1.3000619082 0.2410571373 1.9891103213 0.4070986530 0.6731817245 0.5212071683 -0.330817382066 +1413394957955760384.0000000000 -1.2987131686 0.2409847937 1.9914297022 0.4047022874 0.6678822654 0.5249057556 -0.338560608937 +1413394958005760512.0000000000 -1.3011795677 0.2424226482 1.9936680757 0.4074915361 0.6584782491 0.5254795383 -0.352460349952 +1413394958055760384.0000000000 -1.3059354576 0.2454203622 1.9957174511 0.4143236803 0.6451033082 0.5235383914 -0.371598119491 +1413394958105760512.0000000000 -1.3120613383 0.2500163599 1.9977616341 0.4250039573 0.6273014698 0.5209136838 -0.393081971428 +1413394958155760384.0000000000 -1.3179776652 0.2556907385 2.0002826001 0.4366213237 0.6074649011 0.5176423031 -0.415204358901 +1413394958205760512.0000000000 -1.3223959290 0.2621703380 2.0027934738 0.4471377050 0.5865368998 0.5145109954 -0.437402301715 +1413394958255760384.0000000000 -1.3232729571 0.2697790996 2.0049817686 0.4549964423 0.5664988112 0.5140260243 -0.455888781097 +1413394958305760512.0000000000 -1.3200023758 0.2785595309 2.0081997593 0.4618593951 0.5469930747 0.5149190318 -0.471532465618 +1413394958355760384.0000000000 -1.3118487418 0.2884116288 2.0123243460 0.4646827038 0.5308563539 0.5170024777 -0.484736995034 +1413394958405760512.0000000000 -1.2972952125 0.2995022614 2.0144107871 0.4595443266 0.5217708333 0.5283287201 -0.487281205163 +1413394958455760384.0000000000 -1.2768462980 0.3115734457 2.0143913381 0.4425083832 0.5233057361 0.5480917302 -0.479513182996 +1413394958505760512.0000000000 -1.2515875610 0.3246451108 2.0141503254 0.4212283123 0.5283836505 0.5720789582 -0.464868898081 +1413394958555760384.0000000000 -1.2228388768 0.3384471278 2.0138639274 0.3948431521 0.5365809579 0.5971576659 -0.446746553268 +1413394958605760512.0000000000 -1.1931984990 0.3528029657 2.0138030749 0.3674767667 0.5447818832 0.6220973568 -0.425638819104 +1413394958655760384.0000000000 -1.1647614137 0.3674096986 2.0147371953 0.3405803814 0.5519901966 0.6443492966 -0.405124438494 +1413394958705760512.0000000000 -1.1405314578 0.3818555757 2.0174972302 0.3189460990 0.5553360646 0.6616262723 -0.390033225553 +1413394958755760384.0000000000 -1.1218793309 0.3957127643 2.0213420817 0.3031206642 0.5554581832 0.6753410864 -0.378811940979 +1413394958805760512.0000000000 -1.1101703932 0.4088372130 2.0264652295 0.2938921736 0.5506610212 0.6864383412 -0.373098155489 +1413394958855760384.0000000000 -1.1060242276 0.4210011338 2.0324405227 0.2906033770 0.5430863515 0.6945344218 -0.371791378422 +1413394958905760512.0000000000 -1.1094950419 0.4317102942 2.0391354234 0.2950523494 0.5306327967 0.7010510854 -0.37403251446 +1413394958955760384.0000000000 -1.1202872014 0.4404764370 2.0475245380 0.3069317427 0.5127754976 0.7042046293 -0.38334062457 +1413394959005760512.0000000000 -1.1365096531 0.4465926972 2.0568718050 0.3216931011 0.4937063803 0.7025821001 -0.398931010915 +1413394959055760384.0000000000 -1.1563850960 0.4496783031 2.0673797754 0.3365496942 0.4741294279 0.6971178700 -0.419478562306 +1413394959105760512.0000000000 -1.1777242426 0.4500681789 2.0781968136 0.3469816108 0.4566134705 0.6901985173 -0.441286649557 +1413394959155760384.0000000000 -1.1995954371 0.4479696192 2.0902639974 0.3552026267 0.4408920193 0.6801505863 -0.465661358947 +1413394959205760512.0000000000 -1.2197711003 0.4442823288 2.1031629039 0.3604964562 0.4263468486 0.6684722980 -0.491340469012 +1413394959255760384.0000000000 -1.2373955439 0.4402024951 2.1170912196 0.3647618493 0.4112970937 0.6563092512 -0.516760738451 +1413394959305760512.0000000000 -1.2514313818 0.4366192746 2.1310142860 0.3672847612 0.3977258819 0.6462615276 -0.53783088886 +1413394959355760384.0000000000 -1.2605260516 0.4342913172 2.1434973960 0.3644129618 0.3887046059 0.6430978990 -0.550033648824 +1413394959405760512.0000000000 -1.2644878986 0.4339755944 2.1523848982 0.3534031553 0.3874814613 0.6534809202 -0.545826908309 +1413394959455760384.0000000000 -1.2637574682 0.4352474926 2.1600032715 0.3362870156 0.3913335321 0.6713655598 -0.53201258901 +1413394959505760512.0000000000 -1.2593491852 0.4378827889 2.1663432688 0.3156676078 0.3974875139 0.6937345216 -0.510969716465 +1413394959555760384.0000000000 -1.2534134669 0.4407906060 2.1727572028 0.2940984758 0.4038536584 0.7174928950 -0.485399067504 +1413394959605760512.0000000000 -1.2479672073 0.4427234960 2.1798217735 0.2725743128 0.4082461093 0.7388906883 -0.46160471072 +1413394959655760384.0000000000 -1.2450053360 0.4431534930 2.1879828357 0.2543101467 0.4103452707 0.7565839577 -0.441048549651 +1413394959705760512.0000000000 -1.2456199898 0.4410743061 2.1972988960 0.2405077459 0.4086046182 0.7707059310 -0.425688451858 +1413394959755760384.0000000000 -1.2513454543 0.4357840254 2.2061803824 0.2337206822 0.4005419645 0.7814586828 -0.417448325403 +1413394959805760512.0000000000 -1.2628384089 0.4263675189 2.2142523921 0.2361019096 0.3859014167 0.7879625455 -0.417673331468 +1413394959855760384.0000000000 -1.2793615916 0.4122037141 2.2217860625 0.2452405945 0.3653038407 0.7898816023 -0.427196920715 +1413394959905760512.0000000000 -1.2989450763 0.3933890534 2.2282135056 0.2527891481 0.3463004267 0.7863974960 -0.444693871606 +1413394959955760384.0000000000 -1.3205550319 0.3698176278 2.2340321242 0.2573271634 0.3300984305 0.7771966473 -0.469875652279 +1413394960005760512.0000000000 -1.3426566901 0.3426959561 2.2384597065 0.2594837407 0.3142777571 0.7634940413 -0.50097358079 +1413394960055760384.0000000000 -1.3636742443 0.3137945115 2.2415925819 0.2587058176 0.2982258263 0.7478410230 -0.53372882702 +1413394960105760512.0000000000 -1.3827285000 0.2849924707 2.2424685967 0.2569402088 0.2816773836 0.7333740658 -0.562851721413 +1413394960155760384.0000000000 -1.3985538559 0.2575523481 2.2418359850 0.2508885332 0.2665002142 0.7236552841 -0.585111621373 +1413394960205760512.0000000000 -1.4110185712 0.2323957751 2.2400671339 0.2439062526 0.2515057042 0.7193968788 -0.599768915032 +1413394960255760384.0000000000 -1.4194508026 0.2105675051 2.2379045716 0.2323626584 0.2389415066 0.7217078444 -0.606673172874 +1413394960305760512.0000000000 -1.4242298559 0.1917118884 2.2356339857 0.2193221753 0.2271020975 0.7289363631 -0.607432464796 +1413394960355760384.0000000000 -1.4255855836 0.1762633583 2.2317658516 0.2036140881 0.2170543545 0.7412272240 -0.601673426894 +1413394960405760512.0000000000 -1.4246204691 0.1637187485 2.2257416060 0.1876192900 0.2066326807 0.7575722752 -0.590073033698 +1413394960455760384.0000000000 -1.4220987700 0.1531352392 2.2173483234 0.1707569024 0.1966241574 0.7758815945 -0.574620546422 +1413394960505760512.0000000000 -1.4185619580 0.1436922871 2.2053939515 0.1535442310 0.1871956764 0.7967042889 -0.5537546604 +1413394960555760384.0000000000 -1.4148245880 0.1339209361 2.1913601527 0.1359677729 0.1773261621 0.8165295069 -0.532304200012 +1413394960605760512.0000000000 -1.4120748703 0.1222194200 2.1761046735 0.1200028911 0.1669592028 0.8332792207 -0.513195548514 +1413394960655760384.0000000000 -1.4112323717 0.1068287132 2.1593921621 0.1068131436 0.1559286819 0.8472675894 -0.496401884051 +1413394960705760512.0000000000 -1.4121295190 0.0872734612 2.1435795203 0.0974779577 0.1421268729 0.8562229773 -0.487011512086 +1413394960755760384.0000000000 -1.4156619629 0.0616576560 2.1298547421 0.0944618752 0.1246039240 0.8578355153 -0.489560052505 +1413394960805760512.0000000000 -1.4209828139 0.0293633489 2.1194725542 0.0934522362 0.1087627050 0.8518879582 -0.503710492441 +1413394960855760384.0000000000 -1.4269750274 -0.0082861908 2.1121648530 0.0929380614 0.0942274334 0.8392407986 -0.527407422741 +1413394960905760512.0000000000 -1.4332166792 -0.0491734524 2.1067433896 0.0904872557 0.0845925938 0.8234500909 -0.553702173942 +1413394960955760384.0000000000 -1.4390604927 -0.0915529002 2.1028262691 0.0881263334 0.0771145645 0.8066934390 -0.579251921709 +1413394961005760512.0000000000 -1.4442854735 -0.1333810540 2.1001770484 0.0858082316 0.0723232658 0.7904415930 -0.602169727517 +1413394961055760384.0000000000 -1.4484977446 -0.1728161312 2.0974219236 0.0832509643 0.0696746149 0.7784421764 -0.618257634795 +1413394961105760512.0000000000 -1.4518178162 -0.2094707976 2.0943689899 0.0807637937 0.0680408563 0.7703570246 -0.628806572868 +1413394961155760384.0000000000 -1.4543039579 -0.2430761421 2.0900450632 0.0794511005 0.0678848789 0.7692506498 -0.630343242731 +1413394961205760512.0000000000 -1.4558308328 -0.2727759361 2.0834958054 0.0782811312 0.0691164238 0.7768923279 -0.620913275154 +1413394961255760384.0000000000 -1.4563246940 -0.2991442730 2.0761180393 0.0772426372 0.0695672345 0.7912355415 -0.602611228546 +1413394961305760512.0000000000 -1.4559544242 -0.3232881583 2.0675002593 0.0756367926 0.0702482281 0.8090406885 -0.57861682168 +1413394961355760384.0000000000 -1.4548524705 -0.3474019160 2.0589068144 0.0730054128 0.0712446757 0.8262040024 -0.55405897905 +1413394961405760512.0000000000 -1.4536687745 -0.3729412244 2.0510385235 0.0735148812 0.0707604109 0.8404280571 -0.532230408167 +1413394961455760384.0000000000 -1.4530656122 -0.4018057218 2.0443925405 0.0805227372 0.0652070722 0.8479083502 -0.519918797663 +1413394961505760512.0000000000 -1.4524402006 -0.4354463133 2.0401361757 0.0902666260 0.0575645490 0.8480348826 -0.519013580528 +1413394961555760384.0000000000 -1.4507313278 -0.4735108446 2.0371597923 0.1009369441 0.0488464229 0.8424690067 -0.526945664175 +1413394961605760512.0000000000 -1.4469673076 -0.5153569310 2.0365758167 0.1078448952 0.0432234524 0.8316588236 -0.542996144379 +1413394961655760384.0000000000 -1.4398440044 -0.5596874726 2.0374843432 0.1072496434 0.0435828559 0.8181816523 -0.563184545691 +1413394961705760512.0000000000 -1.4302636748 -0.6048353160 2.0399328689 0.1040004758 0.0453741763 0.8015742712 -0.587029618464 +1413394961755760384.0000000000 -1.4182121179 -0.6491285673 2.0429148225 0.0980421684 0.0499033146 0.7839032744 -0.611058956929 +1413394961805760512.0000000000 -1.4042976511 -0.6907630383 2.0456364719 0.0916816344 0.0553283007 0.7684489711 -0.630887815582 +1413394961855760384.0000000000 -1.3887942684 -0.7288439640 2.0473373878 0.0849969320 0.0615764628 0.7576011671 -0.644223821597 +1413394961905760512.0000000000 -1.3719027184 -0.7624544228 2.0491401634 0.0790724653 0.0676339381 0.7501549292 -0.653024331752 +1413394961955760384.0000000000 -1.3539143598 -0.7909987956 2.0504915821 0.0735072783 0.0733586494 0.7477095182 -0.655854911556 +1413394962005760512.0000000000 -1.3353975942 -0.8143035216 2.0513323279 0.0694488857 0.0781627787 0.7509848955 -0.651988588143 +1413394962055760384.0000000000 -1.3159803610 -0.8322511207 2.0507393748 0.0639359479 0.0836341487 0.7626526479 -0.638183721475 +1413394962105760512.0000000000 -1.2970949899 -0.8461697034 2.0487336711 0.0660904637 0.0842177004 0.7776384983 -0.619530302349 +1413394962155760384.0000000000 -1.2785435761 -0.8577775703 2.0473066700 0.0684405391 0.0840108447 0.7918850364 -0.600979333896 +1413394962205760512.0000000000 -1.2601294256 -0.8680061282 2.0470438048 0.0717129218 0.0837432524 0.8042935582 -0.583914545719 +1413394962255760384.0000000000 -1.2417319414 -0.8780042855 2.0478218492 0.0752566047 0.0832161948 0.8133148986 -0.570903130219 +1413394962305760512.0000000000 -1.2232243623 -0.8886257764 2.0503779957 0.0779040795 0.0825176304 0.8186477042 -0.562972229724 +1413394962355760384.0000000000 -1.2047372480 -0.9010512137 2.0549422693 0.0817643364 0.0818459121 0.8177246313 -0.563863695752 +1413394962405760512.0000000000 -1.1860875631 -0.9159226311 2.0635955685 0.0871980186 0.0791865433 0.8064683669 -0.579426242169 +1413394962455760384.0000000000 -1.1663505837 -0.9311883511 2.0744306581 0.0900690724 0.0780060576 0.7897272134 -0.601775328164 +1413394962505760512.0000000000 -1.1455296378 -0.9450584554 2.0871250538 0.0938067253 0.0758616583 0.7691393115 -0.627590652141 +1413394962555760384.0000000000 -1.1230990514 -0.9552404661 2.0997057324 0.0945862045 0.0751156329 0.7505433797 -0.649688946172 +1413394962605760512.0000000000 -1.0987833107 -0.9604797883 2.1110523246 0.0925378002 0.0759053277 0.7386494073 -0.663379370973 +1413394962655760384.0000000000 -1.0725709411 -0.9596379265 2.1202638609 0.0887009439 0.0779528868 0.7362391797 -0.666338772867 +1413394962705760512.0000000000 -1.0448465147 -0.9527637367 2.1267557289 0.0839601614 0.0804167638 0.7459601123 -0.655764703452 +1413394962755760384.0000000000 -1.0158551981 -0.9406089235 2.1317478162 0.0767292047 0.0845364837 0.7618495637 -0.637613875647 +1413394962805760512.0000000000 -0.9864749536 -0.9247114989 2.1351035763 0.0715603411 0.0868901997 0.7795202117 -0.616179722395 +1413394962855760384.0000000000 -0.9569262495 -0.9068497149 2.1365078065 0.0669030126 0.0866764011 0.7968824254 -0.594129269117 +1413394962905760512.0000000000 -0.9278365556 -0.8883351149 2.1360036624 0.0654904385 0.0825756275 0.8107533555 -0.575822250944 +1413394962955760384.0000000000 -0.8990529881 -0.8702940813 2.1352183891 0.0657055169 0.0758293863 0.8183190099 -0.565938766388 +1413394963005760512.0000000000 -0.8707766211 -0.8539457856 2.1343428507 0.0672235572 0.0690156571 0.8171048041 -0.568381536913 +1413394963055760384.0000000000 -0.8424887162 -0.8400218159 2.1343623292 0.0695682687 0.0620345103 0.8072500001 -0.582803065213 +1413394963105760512.0000000000 -0.8142273688 -0.8272947004 2.1338931080 0.0717312119 0.0556754972 0.7917210766 -0.604096523051 +1413394963155760384.0000000000 -0.7851364231 -0.8127474285 2.1307466848 0.0705600378 0.0518792652 0.7751938771 -0.625623110017 +1413394963205760512.0000000000 -0.7553102311 -0.7949997703 2.1239419364 0.0695202780 0.0489384960 0.7618354578 -0.642167182096 +1413394963255760384.0000000000 -0.7245355866 -0.7739256073 2.1126911408 0.0675902866 0.0472917586 0.7564032636 -0.648882998316 +1413394963305760512.0000000000 -0.6930761701 -0.7488120652 2.0961986431 0.0659419689 0.0464742611 0.7614591688 -0.643173175819 +1413394963355760384.0000000000 -0.6610402234 -0.7200505769 2.0748959744 0.0657539677 0.0454276312 0.7749898871 -0.626899849257 +1413394963405760512.0000000000 -0.6283202453 -0.6885803412 2.0501544310 0.0654090761 0.0451316339 0.7930672484 -0.603928081684 +1413394963455760384.0000000000 -0.5950008876 -0.6562043843 2.0240457864 0.0641422739 0.0456094476 0.8115866771 -0.578906393621 +1413394963505760512.0000000000 -0.5614943306 -0.6240287340 1.9962838612 0.0639707551 0.0457028261 0.8281245585 -0.555003342146 +1413394963555760384.0000000000 -0.5276434935 -0.5932348084 1.9679862236 0.0646957706 0.0460408464 0.8412978520 -0.534707978168 +1413394963605760512.0000000000 -0.4936605572 -0.5663304567 1.9423330993 0.0653483862 0.0466792245 0.8476792914 -0.524395325431 +1413394963655760384.0000000000 -0.4597963418 -0.5450143888 1.9204826475 0.0671900822 0.0468658729 0.8448982239 -0.528617133763 +1413394963705760512.0000000000 -0.4258012046 -0.5281883577 1.9017290979 0.0695748381 0.0469152835 0.8346682564 -0.544322698234 +1413394963755760384.0000000000 -0.3913203559 -0.5147134421 1.8850755853 0.0731598692 0.0457390358 0.8184122460 -0.568117038738 +1413394963805760512.0000000000 -0.3556289992 -0.5022171965 1.8700570509 0.0739437987 0.0464486282 0.7992494898 -0.594621806341 +1413394963855760384.0000000000 -0.3190454535 -0.4885668277 1.8547335213 0.0731101768 0.0484096043 0.7831631362 -0.6156028869 +1413394963905760512.0000000000 -0.2811722162 -0.4723385994 1.8380764588 0.0676391887 0.0536375188 0.7734914067 -0.627900470163 +1413394963955760384.0000000000 -0.2427407795 -0.4523621606 1.8180633988 0.0627593182 0.0587882420 0.7775361438 -0.622930779224 +1413394964005760512.0000000000 -0.2042570511 -0.4300198639 1.7965029088 0.0603496645 0.0625792809 0.7887545810 -0.608529344054 +1413394964055760384.0000000000 -0.1658001772 -0.4057691165 1.7734448685 0.0603005531 0.0650833873 0.8060522541 -0.585156183956 +1413394964105760512.0000000000 -0.1273257608 -0.3809746737 1.7518772115 0.0601281034 0.0667524734 0.8228668692 -0.561087189385 +1413394964155760384.0000000000 -0.0895586118 -0.3574511987 1.7309036028 0.0620326456 0.0674616745 0.8378663532 -0.538127166734 +1413394964205760512.0000000000 -0.0522114601 -0.3374163586 1.7129539586 0.0640690586 0.0679414584 0.8473269928 -0.522796405123 +1413394964255760384.0000000000 -0.0159998568 -0.3225254730 1.6993911473 0.0694976744 0.0652339490 0.8477814795 -0.52170985061 +1413394964305760512.0000000000 0.0200830510 -0.3130420673 1.6901049110 0.0742044508 0.0630867249 0.8409763317 -0.532233571046 +1413394964355760384.0000000000 0.0565567893 -0.3077448640 1.6847600805 0.0771816288 0.0612237036 0.8270773076 -0.553387550889 +1413394964405760512.0000000000 0.0937256402 -0.3045997160 1.6822845472 0.0775087606 0.0614086905 0.8093003000 -0.579011562225 +1413394964455760384.0000000000 0.1317659635 -0.3014957949 1.6819078710 0.0742226347 0.0633370723 0.7899297877 -0.605384461487 +1413394964505760512.0000000000 0.1700224675 -0.2960672261 1.6811865154 0.0702175415 0.0656422735 0.7744538045 -0.625285449657 +1413394964555760384.0000000000 0.2090690045 -0.2872278350 1.6789405768 0.0625520794 0.0702769605 0.7688916862 -0.632419133977 +1413394964605760512.0000000000 0.2481791072 -0.2744579765 1.6747842544 0.0526860447 0.0756406836 0.7754081795 -0.624695784224 +1413394964655760384.0000000000 0.2867242168 -0.2586749442 1.6697035046 0.0428426228 0.0818932072 0.7893638161 -0.60692897287 +1413394964705760512.0000000000 0.3241734845 -0.2410602986 1.6643044922 0.0348020907 0.0864535567 0.8076213088 -0.582290665023 +1413394964755760384.0000000000 0.3596048296 -0.2231469539 1.6602926768 0.0278681957 0.0903746659 0.8252099373 -0.556852173252 +1413394964805760512.0000000000 0.3923524261 -0.2065930596 1.6577171583 0.0224027398 0.0943204027 0.8410549147 -0.532192079422 +1413394964855760384.0000000000 0.4220355154 -0.1934720918 1.6567943645 0.0181361423 0.0978013959 0.8525751027 -0.513051324481 +1413394964905760512.0000000000 0.4481932352 -0.1846796063 1.6585360896 0.0123797810 0.1029215995 0.8608519183 -0.498184564284 +1413394964955760384.0000000000 0.4706609900 -0.1814188265 1.6619447295 0.0057336427 0.1100688717 0.8651185378 -0.489307556042 +1413394965005760512.0000000000 0.4879700760 -0.1847393256 1.6682984671 0.0048532319 0.1127697639 0.8626098004 -0.493116374475 +1413394965055760384.0000000000 0.4995359738 -0.1949817390 1.6775735743 0.0121024216 0.1098111574 0.8529187119 -0.510220258375 +1413394965105760512.0000000000 0.5073068244 -0.2096840251 1.6889244157 0.0231163948 0.1021734831 0.8373356481 -0.536558686501 +1413394965155760384.0000000000 0.5129066683 -0.2263282276 1.7025481850 0.0319653166 0.0918624355 0.8189056604 -0.565626228862 +1413394965205760512.0000000000 0.5175014908 -0.2434138057 1.7176546304 0.0366104086 0.0816813548 0.7981188970 -0.595813780052 +1413394965255760384.0000000000 0.5217365200 -0.2588610799 1.7322088361 0.0378613661 0.0700604044 0.7823308084 -0.617751214413 +1413394965305760512.0000000000 0.5259783947 -0.2708218297 1.7454159295 0.0388882179 0.0564010426 0.7730380485 -0.630649510033 +1413394965355760384.0000000000 0.5304419595 -0.2789189048 1.7561770409 0.0379810463 0.0411607287 0.7739236692 -0.630797422994 +1413394965405760512.0000000000 0.5352374805 -0.2829922226 1.7650448613 0.0359557924 0.0256689982 0.7818803540 -0.621861235021 +1413394965455760384.0000000000 0.5408757698 -0.2843309553 1.7741732303 0.0301762967 0.0115149143 0.7905136863 -0.611592110447 +1413394965505760512.0000000000 0.5470313571 -0.2840029475 1.7846514709 0.0233379364 -0.0030491508 0.7964871852 -0.604197159183 +1413394965555760384.0000000000 0.5543100903 -0.2829875089 1.7973003207 0.0125063865 -0.0154846439 0.7978515260 -0.602525317735 +1413394965605760512.0000000000 0.5627032377 -0.2806742507 1.8125865775 0.0028787584 0.0269369789 -0.7939786798 0.607341722508 +1413394965655760384.0000000000 0.5714206443 -0.2765106589 1.8298648462 0.0210684619 0.0386959756 -0.7849321111 0.618013205688 +1413394965705760512.0000000000 0.5799639786 -0.2701815355 1.8474431009 0.0390325202 0.0511701787 -0.7747961264 0.628926893821 +1413394965755760384.0000000000 0.5873801509 -0.2602762229 1.8620610007 0.0541132169 0.0670937775 -0.7697224292 0.632532660688 +1413394965805760512.0000000000 0.5931018222 -0.2467719596 1.8718739952 0.0636819362 0.0862555341 -0.7707637366 0.628034916375 +1413394965855760384.0000000000 0.5977029937 -0.2305731569 1.8770248635 0.0710245460 0.1054735052 -0.7758663464 0.617950051408 +1413394965905760512.0000000000 0.6012989013 -0.2125680296 1.8795902924 0.0760849492 0.1256628895 -0.7798951271 0.608427078119 +1413394965955760384.0000000000 0.6048267310 -0.1934797037 1.8825010136 0.0837688020 0.1430750386 -0.7770484525 0.607213326284 +1413394966005760512.0000000000 0.6085676676 -0.1733453335 1.8859533500 0.0957819429 0.1566894309 -0.7673705555 0.614342471393 +1413394966055760384.0000000000 0.6119551118 -0.1510830066 1.8890691765 0.1098712484 0.1672280392 -0.7535822280 0.626160456484 +1413394966105760512.0000000000 0.6145149058 -0.1255517659 1.8897191907 0.1245757668 0.1769293834 -0.7414166494 0.635199357418 +1413394966155760384.0000000000 0.6151216112 -0.0964209368 1.8856508059 0.1342454865 0.1887996631 -0.7400736315 0.631366657737 +1413394966205760512.0000000000 0.6142296253 -0.0637543229 1.8772235691 0.1396987646 0.2027307382 -0.7483650026 0.615901230617 +1413394966255760384.0000000000 0.6121560403 -0.0279999807 1.8667319131 0.1441883716 0.2168497349 -0.7615920627 0.59343359858 +1413394966305760512.0000000000 0.6088503774 0.0100634818 1.8535928039 0.1455355716 0.2322122667 -0.7795466627 0.563208541576 +1413394966355760384.0000000000 0.6055003304 0.0483248622 1.8388400938 0.1453866233 0.2478482627 -0.7982616937 0.529350769117 +1413394966405760512.0000000000 0.6033665779 0.0850761194 1.8241678961 0.1458408320 0.2621445083 -0.8135972219 0.498066530764 +1413394966455760384.0000000000 0.6033278586 0.1182687319 1.8108100831 0.1467392566 0.2754769945 -0.8244177011 0.472139248651 +1413394966505760512.0000000000 0.6071177248 0.1456293296 1.8007263197 0.1520053071 0.2857552463 -0.8262272477 0.461071427212 +1413394966555760384.0000000000 0.6155378460 0.1660445533 1.7953426362 0.1616133332 0.2932049011 -0.8179885512 0.467767834029 +1413394966605760512.0000000000 0.6274130013 0.1808711113 1.7918835888 0.1737719467 0.2980507154 -0.8040750405 0.484182208221 +1413394966655760384.0000000000 0.6419137708 0.1914530543 1.7909319503 0.1878001514 0.3010926729 -0.7841156133 0.509153228858 +1413394966705760512.0000000000 0.6575715581 0.2004805848 1.7909165874 0.2026395042 0.3034382593 -0.7624542401 0.534346316429 +1413394966755760384.0000000000 0.6731168477 0.2097262216 1.7909876285 0.2177614168 0.3049445259 -0.7410416582 0.557176868013 +1413394966805760512.0000000000 0.6873461836 0.2203810847 1.7899190493 0.2319533827 0.3073813490 -0.7241119391 0.572168012244 +1413394966855760384.0000000000 0.6991643644 0.2329990380 1.7878921022 0.2428130553 0.3120954704 -0.7130671128 0.578941732944 +1413394966905760512.0000000000 0.7079782754 0.2480966097 1.7836554803 0.2483247093 0.3213446143 -0.7100931917 0.575187045014 +1413394966955760384.0000000000 0.7139690510 0.2650633704 1.7777274013 0.2479552737 0.3353722804 -0.7136710129 0.562776421929 +1413394967005760512.0000000000 0.7178386708 0.2834544325 1.7713885978 0.2439961401 0.3524664010 -0.7216881006 0.54350676649 +1413394967055760384.0000000000 0.7212427639 0.3024841583 1.7658855883 0.2389579867 0.3698557011 -0.7312491842 0.520941908059 +1413394967105760512.0000000000 0.7245198061 0.3217514700 1.7603448184 0.2331667141 0.3874843638 -0.7387970639 0.499667939311 +1413394967155760384.0000000000 0.7292450753 0.3402899866 1.7579862469 0.2312444559 0.4030398123 -0.7409134435 0.484904300441 +1413394967205760512.0000000000 0.7375575372 0.3571996263 1.7598493565 0.2375060950 0.4128738148 -0.7360162920 0.48104686443 +1413394967255760384.0000000000 0.7493991024 0.3724657586 1.7647851561 0.2493367171 0.4193775299 -0.7242052590 0.487319640238 +1413394967305760512.0000000000 0.7639351604 0.3866685831 1.7722255354 0.2659983933 0.4224118799 -0.7083689493 0.499025540478 +1413394967355760384.0000000000 0.7798441451 0.4005619272 1.7819927269 0.2854963303 0.4225039810 -0.6888033315 0.515298168007 +1413394967405760512.0000000000 0.7950211960 0.4150543144 1.7935092457 0.3063344565 0.4209354643 -0.6670943131 0.532876827252 +1413394967455760384.0000000000 0.8079804216 0.4312290326 1.8052289216 0.3256506706 0.4199301950 -0.6494244650 0.54392842937 +1413394967505760512.0000000000 0.8167738611 0.4496836136 1.8157843571 0.3410029766 0.4224700884 -0.6391968734 0.54466811128 +1413394967555760384.0000000000 0.8212027191 0.4699204414 1.8239713644 0.3495424547 0.4307311943 -0.6387090315 0.533236798905 +1413394967605760512.0000000000 0.8208110762 0.4914791454 1.8302961406 0.3476543629 0.4470977673 -0.6442607593 0.513972863482 +1413394967655760384.0000000000 0.8171465232 0.5135164236 1.8356352246 0.3398501914 0.4668526378 -0.6530879796 0.489925048319 +1413394967705760512.0000000000 0.8121720459 0.5354074091 1.8416982972 0.3307274417 0.4868381351 -0.6603339624 0.466440829748 +1413394967755760384.0000000000 0.8080675463 0.5564792490 1.8517141860 0.3290319430 0.5011407268 -0.6609139808 0.451429576301 +1413394967805760512.0000000000 0.8056006405 0.5766771766 1.8643103932 0.3334795328 0.5112686132 -0.6552324136 0.445046391441 +1413394967855760384.0000000000 0.8053019394 0.5962569009 1.8792647304 0.3437853562 0.5177807587 -0.6437218836 0.446471557073 +1413394967905760512.0000000000 0.8063726374 0.6157337117 1.8953353365 0.3584638788 0.5222368668 -0.6278959930 0.452237685919 +1413394967955760384.0000000000 0.8078798523 0.6352854127 1.9127286259 0.3755261439 0.5249414070 -0.6100621995 0.45960934192 +1413394968005760512.0000000000 0.8080916569 0.6552933360 1.9304633947 0.3908791861 0.5293705840 -0.5937871923 0.463030254935 +1413394968055760384.0000000000 0.8056927272 0.6753361057 1.9449173159 0.3988946413 0.5387307784 -0.5836900379 0.458211908562 +1413394968105760512.0000000000 0.8006390582 0.6956613331 1.9552725825 0.3999248873 0.5523272179 -0.5799940524 0.445647425732 +1413394968155760384.0000000000 0.7935634475 0.7154549346 1.9608896774 0.3948326692 0.5684050288 -0.5811082674 0.428177612843 +1413394968205760512.0000000000 0.7865259401 0.7347963261 1.9640934345 0.3891754212 0.5821766795 -0.5832884536 0.411566987695 +1413394968255760384.0000000000 0.7809808387 0.7536451054 1.9655698915 0.3851836550 0.5932796986 -0.5836008284 0.398826809774 +1413394968305760512.0000000000 0.7774791250 0.7722100189 1.9663709833 0.3854546314 0.6000324261 -0.5808108169 0.392485171318 +1413394968355760384.0000000000 0.7754877015 0.7909858151 1.9649885928 0.3885442124 0.6050822088 -0.5757087842 0.389189300145 +1413394968405760512.0000000000 0.7747540100 0.8095016180 1.9615239246 0.3931309708 0.6099025021 -0.5690082804 0.386906390029 +1413394968455760384.0000000000 0.7760428067 0.8281197016 1.9573298319 0.3989690614 0.6133606517 -0.5625484474 0.384904719742 +1413394968505760512.0000000000 0.7785559507 0.8468519634 1.9532690238 0.4049115289 0.6170905252 -0.5563521573 0.381730552249 +1413394968555760384.0000000000 0.7819507769 0.8654100589 1.9486942220 0.4075609891 0.6225070388 -0.5524392141 0.375752500277 +1413394968605760512.0000000000 0.7869827795 0.8834930657 1.9440857838 0.4067690837 0.6283810168 -0.5505012421 0.369627640632 +1413394968655760384.0000000000 0.7937377188 0.9012496370 1.9397492711 0.4040740979 0.6345385783 -0.5485977195 0.364863615985 +1413394968705760512.0000000000 0.8026785723 0.9186441290 1.9359118586 0.4005232222 0.6407723015 -0.5441926381 0.364480971634 +1413394968755760384.0000000000 0.8141930385 0.9359269979 1.9328769789 0.3970593683 0.6455287886 -0.5369769680 0.370529589872 +1413394968805760512.0000000000 0.8278929531 0.9542595621 1.9306581487 0.3959313655 0.6482127993 -0.5302688200 0.376660987131 +1413394968855760384.0000000000 0.8431732238 0.9740643943 1.9297626355 0.3987180993 0.6477332591 -0.5262172232 0.380211699349 +1413394968905760512.0000000000 0.8598887447 0.9957802422 1.9296621304 0.4042723408 0.6454611639 -0.5240656406 0.381181013101 +1413394968955760384.0000000000 0.8774098675 1.0193067281 1.9309772146 0.4140373546 0.6415267879 -0.5219700070 0.380215414222 +1413394969005760512.0000000000 0.8950548674 1.0437862252 1.9326444864 0.4251857358 0.6378336307 -0.5184096412 0.378994450512 +1413394969055760384.0000000000 0.9124065509 1.0688390692 1.9343378011 0.4363184224 0.6349696419 -0.5138144651 0.377404933232 +1413394969155760384.0000000000 0.9470556905 1.1189825605 1.9318913464 0.4536899701 0.6338801579 -0.5039108320 0.372068850902 +1413394969255760384.0000000000 0.9794958939 1.1664723377 1.9129031941 0.4664858334 0.6338306214 -0.4936057589 0.370139251315 +1413394969355760384.0000000000 1.0083344027 1.2096670976 1.8789209726 0.4780984904 0.6316226206 -0.4840475340 0.371715863878 +1413394969455760384.0000000000 1.0304710275 1.2485012900 1.8366144674 0.4863746639 0.6290008453 -0.4732668943 0.379230892448 +1413394969555760384.0000000000 1.0438585574 1.2828662871 1.7908501654 0.4736398792 0.6390664115 -0.4665567492 0.386761149002 +1413394969655760384.0000000000 1.0475471049 1.3165384468 1.7455215100 0.4458412535 0.6578248190 -0.4656955162 0.389383834191 +1413394969755760384.0000000000 1.0458126017 1.3554371628 1.7064440743 0.4214875254 0.6720132812 -0.4623469674 0.396209158929 +1413394969855760384.0000000000 1.0410416519 1.4066644564 1.6744535597 0.4095122799 0.6784962692 -0.4633203907 0.396581291609 +1413394969955760384.0000000000 1.0350358826 1.4728342906 1.6512455876 0.4080136599 0.6781856949 -0.4779179063 0.381029515065 +1413394970055760384.0000000000 1.0313871006 1.5501162209 1.6415850396 0.4097637223 0.6752418331 -0.4935844028 0.364028290183 +1413394970155760384.0000000000 1.0345749701 1.6343227110 1.6480877936 0.4133185867 0.6713880552 -0.5039093083 0.352818982273 +1413394970255760384.0000000000 1.0458285976 1.7223905493 1.6648349314 0.4260183625 0.6625921207 -0.5040694216 0.354110229395 +1413394970355760384.0000000000 1.0634180854 1.8115335417 1.6802100617 0.4562352088 0.6415075875 -0.4996561800 0.361470816634 +1413394970455760384.0000000000 1.0802120994 1.8966831929 1.6886642927 0.4910939457 0.6155851216 -0.4979820846 0.363174252855 +1413394970555760384.0000000000 1.0887806974 1.9715354375 1.6842412653 0.5107498642 0.6009820054 -0.5030915551 0.353346986103 +1413394970655760384.0000000000 1.0886876508 2.0317604242 1.6711955260 0.5243392720 0.5903164364 -0.5130865419 0.336655659922 +1413394970755760384.0000000000 1.0838964604 2.0720105895 1.6536880840 0.5287217355 0.5855156900 -0.5113982863 0.340729358749 +1413394970855760384.0000000000 1.0719390311 2.0909437808 1.6317118969 0.5006647684 0.6064519360 -0.5013261968 0.360864078728 +1413394970955760384.0000000000 1.0525856293 2.0969608437 1.6169290641 0.4593512214 0.6355170913 -0.4977986972 0.370554907014 +1413394971055760384.0000000000 1.0308499273 2.1010762416 1.6205466771 0.4307670289 0.6528115291 -0.4962947555 0.376786929229 +1413394971155760384.0000000000 1.0092340643 2.1104448575 1.6391157133 0.4141380814 0.6610009857 -0.5039035890 0.37101013396 +1413394971255760384.0000000000 0.9914843704 2.1265557895 1.6592789692 0.3967641379 0.6699136969 -0.5174804537 0.354975826792 +1413394971355760384.0000000000 0.9826858608 2.1481760485 1.6701344315 0.3781613375 0.6791846473 -0.5306545862 0.337798649811 +1413394971455760384.0000000000 0.9899650014 2.1757044742 1.6734825048 0.3649150723 0.6853757843 -0.5402833466 0.324331512022 +1413394971555760384.0000000000 1.0197665716 2.2108086525 1.6784179399 0.3664627443 0.6814225964 -0.5516817041 0.311473272465 +1413394971655760384.0000000000 1.0747466193 2.2501044593 1.6921038507 0.3911486450 0.6642970506 -0.5557111686 0.311283252398 +1413394971755760384.0000000000 1.1480355787 2.2858374395 1.7094285091 0.4245301283 0.6383448611 -0.5534556792 0.325540810805 +1413394971855760384.0000000000 1.2318660497 2.3126288104 1.7266974594 0.4501766179 0.6116492173 -0.5506192019 0.346474735425 +1413394971955760384.0000000000 1.3187447401 2.3271317025 1.7440291582 0.4701566853 0.5824120770 -0.5513240586 0.368497823866 +1413394972055760384.0000000000 1.4012206997 2.3274952411 1.7542962413 0.4750848984 0.5566910443 -0.5554603956 0.394782433098 +1413394972155760384.0000000000 1.4743152948 2.3142149612 1.7549443402 0.4690547671 0.5301806419 -0.5685656441 0.419081401213 +1413394972255760384.0000000000 1.5340865157 2.2876551523 1.7461363536 0.4546412043 0.5018148641 -0.5884696231 0.441799411771 +1413394972355760384.0000000000 1.5791043339 2.2487899824 1.7309651371 0.4341955879 0.4707617419 -0.6120019046 0.464016424896 +1413394972455760384.0000000000 1.6080548855 2.1992106196 1.7094910754 0.4075878255 0.4380119120 -0.6416783748 0.479861014071 +1413394972555760384.0000000000 1.6209221352 2.1398792927 1.6808131032 0.3666682981 0.4112406068 -0.6785041734 0.485867892766 +1413394972655760384.0000000000 1.6192501114 2.0718363235 1.6543929973 0.3177722782 0.3859496131 -0.7116835143 0.493528368804 +1413394972755760384.0000000000 1.6127313167 1.9945383478 1.6332779425 0.2644255287 0.3611106135 -0.7319092494 0.513796764535 +1413394972855760384.0000000000 1.6038673027 1.9137113633 1.6198072362 0.2131064448 0.3338572593 -0.7438658124 0.538320189811 +1413394972955760384.0000000000 1.5963537094 1.8351191933 1.6113394412 0.1719440020 0.2989100016 -0.7544169107 0.558518751707 +1413394973005760512.0000000000 1.5937156397 1.7976869745 1.6080009680 0.1550191443 0.2790139606 -0.7608828236 0.564958054658 +1413394973055760384.0000000000 1.5917722118 1.7615089887 1.6051970805 0.1402764761 0.2575146446 -0.7678304596 0.569600828156 +1413394973105760512.0000000000 1.5907656763 1.7265550556 1.6023802701 0.1266346396 0.2352611184 -0.7745826085 0.573269270818 +1413394973155760384.0000000000 1.5907239545 1.6928518631 1.5990681429 0.1149464426 0.2120334387 -0.7821703257 0.574489963194 +1413394973205760512.0000000000 1.5912796208 1.6602597358 1.5956264918 0.1051630421 0.1873989689 -0.7902593279 0.573857609202 +1413394973255760384.0000000000 1.5921937933 1.6278964329 1.5921861607 0.0942746496 0.1636672482 -0.7970158429 0.573664595768 +1413394973305760512.0000000000 1.5932451087 1.5955168151 1.5892510301 0.0828742305 0.1401723900 -0.8027325654 0.573675859158 +1413394973355760384.0000000000 1.5941036029 1.5631218985 1.5866462622 0.0715397734 0.1167474744 -0.8075100651 0.573741738826 +1413394973405760512.0000000000 1.5947080713 1.5301441941 1.5845944079 0.0592772651 0.0933363729 -0.8103939730 0.575357398421 +1413394973455760384.0000000000 1.5947600989 1.4970325779 1.5824808414 0.0459678451 0.0711450376 -0.8129156556 0.57618875183 +1413394973505760512.0000000000 1.5942301295 1.4635059925 1.5813470398 0.0325679981 0.0485033535 -0.8143486254 0.57742797512 +1413394973555760384.0000000000 1.5932144208 1.4296387417 1.5801535873 0.0185908630 0.0257832796 -0.8159482701 0.577250398738 +1413394973605760512.0000000000 1.5913033735 1.3954062303 1.5795467975 0.0045745877 0.0032890651 -0.8172638061 0.576236172442 +1413394973655760384.0000000000 1.5883858524 1.3606584262 1.5792780995 0.0125481336 0.0172056665 0.8177651634 -0.575157932184 +1413394973705760512.0000000000 1.5848100842 1.3253388778 1.5803691597 0.0289400631 0.0385265855 0.8155766664 -0.576639294721 +1413394973755760384.0000000000 1.5805599055 1.2902666377 1.5815913150 0.0467644103 0.0584015378 0.8129817731 -0.577462541554 +1413394973805760512.0000000000 1.5760448354 1.2547645641 1.5834812761 0.0622619878 0.0803901075 0.8090369526 -0.578895573336 +1413394973855760384.0000000000 1.5711357884 1.2197176715 1.5852869091 0.0770832669 0.1018683634 0.8053486734 -0.578873492805 +1413394973905760512.0000000000 1.5658627950 1.1849616928 1.5872472787 0.0909219599 0.1241127808 0.8013453522 -0.57807857719 +1413394973955760384.0000000000 1.5602140693 1.1509825226 1.5895833283 0.1044038492 0.1458179026 0.7975637392 -0.575959249832 +1413394974005760512.0000000000 1.5540602776 1.1177192653 1.5923802585 0.1174947330 0.1671607987 0.7930441234 -0.573875660208 +1413394974055760384.0000000000 1.5471794414 1.0852074978 1.5957983157 0.1310139636 0.1884003573 0.7876749278 -0.571759437931 +1413394974105760512.0000000000 1.5401131092 1.0538636393 1.5989516412 0.1431142248 0.2100364325 0.7822084704 -0.56881712743 +1413394974155760384.0000000000 1.5323399702 1.0232634041 1.6028508759 0.1547533408 0.2310747660 0.7752482484 -0.567138439287 +1413394974205760512.0000000000 1.5236456559 0.9936583915 1.6070370271 0.1656597876 0.2529668776 0.7678634505 -0.564756863661 +1413394974255760384.0000000000 1.5142384838 0.9650007223 1.6114751356 0.1762073653 0.2744326616 0.7601474555 -0.561972885929 +1413394974305760512.0000000000 1.5037557771 0.9378391984 1.6162995957 0.1867020099 0.2955368420 0.7531393738 -0.557298320591 +1413394974355760384.0000000000 1.4922943249 0.9121230636 1.6216596914 0.1957862441 0.3173389021 0.7453718122 -0.552616168344 +1413394974405760512.0000000000 1.4793132564 0.8877176048 1.6274972707 0.2044782030 0.3388937930 0.7377702234 -0.546840707086 +1413394974455760384.0000000000 1.4650883697 0.8655931918 1.6337361387 0.2143913902 0.3583846238 0.7297825382 -0.541307897775 +1413394974505760512.0000000000 1.4491575827 0.8451492933 1.6397296801 0.2248722609 0.3779669653 0.7208668171 -0.535653312679 +1413394974555760384.0000000000 1.4315992369 0.8267642388 1.6466893237 0.2358242509 0.3956285986 0.7115924763 -0.5305667557 +1413394974605760512.0000000000 1.4120450934 0.8105383693 1.6541773211 0.2497646173 0.4104653737 0.7009080397 -0.52712781455 +1413394974655760384.0000000000 1.3908399006 0.7962084878 1.6615454146 0.2654327183 0.4232107346 0.6890932113 -0.524965420077 +1413394974705760512.0000000000 1.3687631678 0.7841249663 1.6686996329 0.2809720190 0.4347876853 0.6786105306 -0.521058673307 +1413394974755760384.0000000000 1.3467418288 0.7745844548 1.6747260134 0.2951563176 0.4464345572 0.6699589616 -0.514523006431 +1413394974805760512.0000000000 1.3244588702 0.7668155493 1.6798851739 0.3076005815 0.4579517752 0.6626502253 -0.506514296695 +1413394974855760384.0000000000 1.3022750697 0.7609590252 1.6838172504 0.3198760628 0.4683918757 0.6562439119 -0.497626650629 +1413394974905760512.0000000000 1.2799028572 0.7564598136 1.6851009045 0.3326237635 0.4777298335 0.6510481103 -0.487105734168 +1413394974955760384.0000000000 1.2575067843 0.7526727979 1.6833828228 0.3441107534 0.4868604338 0.6458721942 -0.476868761987 +1413394975005760512.0000000000 1.2356927243 0.7492468095 1.6778463948 0.3546580187 0.4952838654 0.6398206661 -0.468552129099 +1413394975055760384.0000000000 1.2137440148 0.7461504473 1.6695545919 0.3665823839 0.5011390849 0.6329812545 -0.462397777813 +1413394975105760512.0000000000 1.1925906353 0.7432051294 1.6589696473 0.3793299123 0.5052788202 0.6242375950 -0.459488363777 +1413394975155760384.0000000000 1.1721613219 0.7401377372 1.6456459454 0.3905500922 0.5093557322 0.6154121110 -0.4574880295 +1413394975205760512.0000000000 1.1528427078 0.7369767794 1.6302973967 0.3995979777 0.5141451138 0.6062633682 -0.456531473665 +1413394975255760384.0000000000 1.1348254230 0.7338484869 1.6126448074 0.4073302454 0.5191552105 0.5979286609 -0.455017862415 +1413394975305760512.0000000000 1.1183944169 0.7306153632 1.5933199646 0.4136053087 0.5247304040 0.5906086169 -0.452515318492 +1413394975355760384.0000000000 1.1038640630 0.7274077980 1.5740170736 0.4198502541 0.5299299744 0.5844742044 -0.44865341945 +1413394975405760512.0000000000 1.0913283374 0.7243498473 1.5543269449 0.4246637506 0.5354799585 0.5807035528 -0.442385913766 +1413394975455760384.0000000000 1.0803083233 0.7212443111 1.5351892255 0.4277426483 0.5420216199 0.5783393776 -0.434479406524 +1413394975505760512.0000000000 1.0710201005 0.7177866529 1.5170574148 0.4301208174 0.5484347302 0.5772240561 -0.425473639867 +1413394975555760384.0000000000 1.0633991903 0.7136612057 1.4996071816 0.4311169528 0.5545413726 0.5770869846 -0.416644514296 +1413394975605760512.0000000000 1.0567191660 0.7086655807 1.4836414419 0.4310070263 0.5600046563 0.5778637210 -0.408290641773 +1413394975655760384.0000000000 1.0505253450 0.7025975142 1.4691069855 0.4298988365 0.5648011033 0.5782970639 -0.402193000833 +1413394975755760384.0000000000 1.0378103713 0.6870491578 1.4448187455 0.4283291320 0.5713651881 0.5790973140 -0.393347527493 +1413394975805760512.0000000000 1.0308889167 0.6777081027 1.4350161636 0.4265571774 0.5739321161 0.5799588054 -0.390254640586 +1413394975855760384.0000000000 1.0234313588 0.6673935921 1.4269623626 0.4261399487 0.5748248471 0.5796806335 -0.389809571989 +1413394975955760384.0000000000 1.0057557169 0.6440290744 1.4177329054 0.4346683770 0.5687139424 0.5754131483 -0.395635643711 +1413394976055760384.0000000000 0.9882977612 0.6169828416 1.4125395060 0.4444438617 0.5601030357 0.5676678585 -0.408053238759 +1413394976155760384.0000000000 0.9751671719 0.5867733931 1.4065255044 0.4491584350 0.5547803933 0.5656123502 -0.412986785283 +1413394976255760384.0000000000 0.9679997505 0.5537064119 1.3994215891 0.4491839331 0.5533034399 0.5677135757 -0.412056299068 +1413394976355760384.0000000000 0.9662855887 0.5172089167 1.3930975768 0.4515098767 0.5497924075 0.5683399823 -0.413348284663 +1413394976455760384.0000000000 0.9705716587 0.4769847774 1.3892249297 0.4593067240 0.5424891601 0.5627385021 -0.421981306214 +1413394976505760512.0000000000 0.9760688922 0.4557782252 1.3883586636 0.4637235493 0.5383116430 0.5586229059 -0.427926972519 +1413394976605760512.0000000000 0.9953726157 0.4106616796 1.3880485585 0.4701324062 0.5320935096 0.5497934800 -0.439976302773 +1413394976705760512.0000000000 1.0289751089 0.3630565888 1.3892528198 0.4638779473 0.5354128402 0.5424795439 -0.451515542343 +1413394976755760384.0000000000 1.0520163248 0.3394829546 1.3891966529 0.4535738408 0.5427996239 0.5424037268 -0.453252177502 +1413394976805760512.0000000000 1.0780131760 0.3164870723 1.3891410556 0.4414686406 0.5525178896 0.5446593889 -0.450750009619 +1413394976855760384.0000000000 1.1070219627 0.2946635296 1.3894253394 0.4242589602 0.5650837239 0.5499798931 -0.445204264114 +1413394976905760512.0000000000 1.1376676739 0.2747219825 1.3894430859 0.4038110208 0.5807209863 0.5564961683 -0.435903441313 +1413394976955760384.0000000000 1.1684270267 0.2570448366 1.3893858534 0.3835993957 0.5966709560 0.5642778618 -0.422404744952 +1413394977005760512.0000000000 1.1978346429 0.2419877556 1.3906169242 0.3641488304 0.6113348867 0.5714557432 -0.408783095484 +1413394977105760512.0000000000 1.2452801063 0.2212181941 1.3980544002 0.3316141652 0.6382437565 0.5784770932 -0.384761231581 +1413394977155760384.0000000000 1.2617504303 0.2161773032 1.4037807642 0.3174103809 0.6498763335 0.5809916153 -0.373309716073 +1413394977205760512.0000000000 1.2709332592 0.2150889368 1.4110277809 0.3064874941 0.6596696622 0.5821511743 -0.363319918236 +1413394977305760512.0000000000 1.2639334933 0.2265030076 1.4313442772 0.3069928870 0.6634920833 0.5912911134 -0.340453288821 +1413394977405760512.0000000000 1.2267308006 0.2517205259 1.4609273338 0.3316241399 0.6490427580 0.6057825360 -0.319055554884 +1413394977505760512.0000000000 1.1558350730 0.2806998355 1.4997239625 0.3513857759 0.6363192841 0.6149475070 -0.305721063797 +1413394977605760512.0000000000 1.0539864318 0.3065567455 1.5465975075 0.3598208991 0.6316558493 0.6167619440 -0.301901495735 +1413394977705760512.0000000000 0.9237151132 0.3285080163 1.5978099006 0.3648165465 0.6295454060 0.6158607434 -0.302153957338 +1413394977805760512.0000000000 0.7652142198 0.3458588543 1.6545957814 0.3776474644 0.6218285638 0.6117110069 -0.310678731156 +1413394977905760512.0000000000 0.5838921954 0.3576416480 1.7153049256 0.4012047114 0.6075851988 0.6010719198 -0.329526255339 +1413394978005760512.0000000000 0.3892983006 0.3629871818 1.7755014567 0.4263931241 0.5916419793 0.5886244791 -0.348812119324 +1413394978105760512.0000000000 0.1901403880 0.3612885425 1.8328931580 0.4468341424 0.5776380070 0.5787858414 -0.36287812261 +1413394978155760384.0000000000 0.0905818978 0.3574231773 1.8593885660 0.4535450410 0.5727404432 0.5764133955 -0.366077694122 +1413394978205760512.0000000000 -0.0082972957 0.3515604083 1.8827299768 0.4577756010 0.5696200160 0.5749816996 -0.367927413533 +1413394978255760384.0000000000 -0.1066129630 0.3434171587 1.9027651870 0.4609858785 0.5672425750 0.5740367101 -0.36906603257 +1413394978305760512.0000000000 -0.2038788651 0.3331466074 1.9198306725 0.4623205638 0.5657862365 0.5742167927 -0.369351737335 +1413394978355760384.0000000000 -0.3004424204 0.3206762365 1.9342009844 0.4630963634 0.5650278402 0.5743361586 -0.369355215192 +1413394978405760512.0000000000 -0.3957761504 0.3056657474 1.9453296025 0.4635428677 0.5643986085 0.5743290641 -0.369767963329 +1413394978455760384.0000000000 -0.4898112632 0.2883255356 1.9531996461 0.4622270028 0.5641666291 0.5746980563 -0.37119315263 +1413394978505760512.0000000000 -0.5830107266 0.2687062661 1.9584742248 0.4605261140 0.5647222221 0.5743531600 -0.372991900374 +1413394978555760384.0000000000 -0.6755291273 0.2465318958 1.9631581617 0.4573136880 0.5661592399 0.5736367635 -0.375857379043 +1413394978605760512.0000000000 -0.7675252572 0.2222771523 1.9681498922 0.4539764353 0.5676649420 0.5721811554 -0.379829745062 +1413394978655760384.0000000000 -0.8583485864 0.1961796902 1.9734062557 0.4489287167 0.5706951563 0.5700882426 -0.384407910293 +1413394978705760512.0000000000 -0.9483825439 0.1686198417 1.9797684611 0.4431296088 0.5741967160 0.5668946398 -0.390595376988 +1413394978755760384.0000000000 -1.0375697819 0.1403604886 1.9870375074 0.4378937630 0.5773344071 0.5638523973 -0.396237944649 +1413394978805760512.0000000000 -1.1256126018 0.1117452890 1.9951320349 0.4334915455 0.5803401305 0.5606501063 -0.401200537459 +1413394978855760384.0000000000 -1.2129382807 0.0834011230 2.0036277127 0.4307503000 0.5823318384 0.5581866269 -0.404686914222 +1413394978905760512.0000000000 -1.2992621586 0.0554396412 2.0126429204 0.4288046677 0.5840333065 0.5557569810 -0.40763443411 +1413394978955760384.0000000000 -1.3847681200 0.0280809259 2.0210836342 0.4288673495 0.5847668079 0.5530642387 -0.410171335905 +1413394979005760512.0000000000 -1.4696990723 0.0015433239 2.0286240028 0.4315012247 0.5839341182 0.5487181194 -0.414410501947 +1413394979055760384.0000000000 -1.5536744322 -0.0239994745 2.0335962342 0.4364224817 0.5817683871 0.5433931728 -0.41929085489 +1413394979105760512.0000000000 -1.6356566789 -0.0488095426 2.0362575593 0.4421461471 0.5787197233 0.5374160613 -0.425175544339 +1413394979155760384.0000000000 -1.7149945909 -0.0730415507 2.0365477222 0.4474188007 0.5755126962 0.5295494138 -0.43379600228 +1413394979205760512.0000000000 -1.7912246854 -0.0964869243 2.0355818661 0.4524820490 0.5723062675 0.5197273628 -0.444532338475 +1413394979255760384.0000000000 -1.8635047602 -0.1189440848 2.0325416151 0.4559572956 0.5692361217 0.5112255983 -0.454666438273 +1413394979305760512.0000000000 -1.9316821434 -0.1397332611 2.0284745049 0.4588353702 0.5660030665 0.5020980123 -0.4658414084 +1413394979355760384.0000000000 -1.9953892643 -0.1587639309 2.0236991191 0.4608057759 0.5632802677 0.4927887372 -0.477003812833 +1413394979405760512.0000000000 -2.0530446246 -0.1755360298 2.0204519429 0.4631437449 0.5586744841 0.4836309654 -0.489368758445 +1413394979455760384.0000000000 -2.1036550158 -0.1892375581 2.0184379745 0.4667539604 0.5530232233 0.4748608819 -0.50081253753 +1413394979505760512.0000000000 -2.1461680113 -0.2000213421 2.0186977119 0.4717892036 0.5460168820 0.4658938588 -0.512077556879 +1413394979555760384.0000000000 -2.1795131229 -0.2073779158 2.0211037104 0.4783614549 0.5374859567 0.4599648402 -0.520299443117 +1413394979605760512.0000000000 -2.2036145989 -0.2113044523 2.0254883840 0.4853986883 0.5293128783 0.4559269216 -0.525686819746 +1413394979655760384.0000000000 -2.2197434114 -0.2123094373 2.0322905895 0.4902619584 0.5234142464 0.4557728314 -0.52721140439 +1413394979705760512.0000000000 -2.2261794832 -0.2104007410 2.0409042575 0.4938962434 0.5191913141 0.4600101343 -0.52430673887 +1413394979755760384.0000000000 -2.2211378283 -0.2056561195 2.0496820637 0.4950975990 0.5193318355 0.4705158015 -0.513602660284 +1413394979805760512.0000000000 -2.2059325123 -0.1985567625 2.0586499853 0.4940122060 0.5238267482 0.4885500637 -0.492824830432 +1413394979855760384.0000000000 -2.1826826453 -0.1899479230 2.0693982332 0.4909304871 0.5312254778 0.5100346833 -0.465458236978 +1413394979905760512.0000000000 -2.1531391201 -0.1813235322 2.0816965918 0.4868348363 0.5390266581 0.5304083628 -0.437160236891 +1413394979955760384.0000000000 -2.1195703526 -0.1737816966 2.0957297931 0.4825815166 0.5458542563 0.5462240883 -0.413276488624 +1413394980005760512.0000000000 -2.0836190827 -0.1683042227 2.1101884037 0.4783077234 0.5521322565 0.5566292898 -0.395645708691 +1413394980055760384.0000000000 -2.0463749706 -0.1652785939 2.1239410149 0.4759221386 0.5560872825 0.5624556544 -0.384588987101 +1413394980105760512.0000000000 -2.0089149142 -0.1649516273 2.1365095752 0.4764448720 0.5578095650 0.5638413585 -0.379383309568 +1413394980155760384.0000000000 -1.9714482014 -0.1673741171 2.1478569432 0.4798158480 0.5570632155 0.5616633402 -0.379462275087 +1413394980205760512.0000000000 -1.9330876850 -0.1722859938 2.1573635940 0.4833167146 0.5555422076 0.5579824955 -0.38266609941 +1413394980255760384.0000000000 -1.8935785622 -0.1798443893 2.1645032660 0.4861536745 0.5546402609 0.5524576932 -0.388354584077 +1413394980305760512.0000000000 -1.8531650099 -0.1900429250 2.1699604011 0.4879069994 0.5541407741 0.5467055385 -0.394952929683 +1413394980355760384.0000000000 -1.8114077309 -0.2022728172 2.1725100210 0.4878806602 0.5550414868 0.5424874720 -0.399510640729 +1413394980405760512.0000000000 -1.7674914053 -0.2163379687 2.1722001837 0.4863153201 0.5571293805 0.5410064109 -0.400520069729 +1413394980455760384.0000000000 -1.7214495412 -0.2322503511 2.1711640412 0.4824023684 0.5611596518 0.5412992674 -0.39922788394 +1413394980505760512.0000000000 -1.6737103568 -0.2501273671 2.1699101163 0.4749877276 0.5678300195 0.5417547887 -0.398067175886 +1413394980555760384.0000000000 -1.6240749512 -0.2695262740 2.1696065248 0.4655872044 0.5755581478 0.5420270498 -0.397703471094 +1413394980605760512.0000000000 -1.5733052458 -0.2898669338 2.1700545216 0.4571297434 0.5826676650 0.5422859681 -0.396808163601 +1413394980655760384.0000000000 -1.5220213422 -0.3104926678 2.1718192762 0.4492607515 0.5886936527 0.5424532786 -0.396672410274 +1413394980705760512.0000000000 -1.4708195253 -0.3312024200 2.1748934986 0.4439381217 0.5929497645 0.5419924448 -0.396955552517 +1413394980755760384.0000000000 -1.4199547594 -0.3515517995 2.1788337660 0.4400432729 0.5955518637 0.5427036328 -0.396424851146 +1413394980805760512.0000000000 -1.3690852411 -0.3715257343 2.1836896229 0.4367335560 0.5977260867 0.5428230971 -0.39664897782 +1413394980855760384.0000000000 -1.3186077756 -0.3910769974 2.1890290350 0.4346326878 0.5992223752 0.5427554602 -0.396791484506 +1413394980905760512.0000000000 -1.2683203483 -0.4098954670 2.1944928344 0.4326684277 0.6001018977 0.5430158774 -0.397252439777 +1413394980955760384.0000000000 -1.2187317626 -0.4278520134 2.1987451403 0.4319514500 0.6005779369 0.5433257003 -0.396889493435 +1413394981005760512.0000000000 -1.1700286982 -0.4453082767 2.2005184823 0.4293048431 0.6022394611 0.5431586973 -0.397471524391 +1413394981055760384.0000000000 -1.1221651783 -0.4620617508 2.2001632403 0.4269564633 0.6037209000 0.5424188114 -0.398761941955 +1413394981105760512.0000000000 -1.0752354139 -0.4779267140 2.1972776635 0.4237861228 0.6058538296 0.5410838870 -0.400717714265 +1413394981155760384.0000000000 -1.0290278637 -0.4927438953 2.1920237861 0.4207945036 0.6079671237 0.5399406492 -0.402208972475 +1413394981205760512.0000000000 -0.9831662374 -0.5064854577 2.1838958558 0.4174390933 0.6101785320 0.5390601361 -0.403535540066 +1413394981255760384.0000000000 -0.9382447066 -0.5183586841 2.1729002689 0.4151521525 0.6120838569 0.5383931777 -0.403899527812 +1413394981305760512.0000000000 -0.8942370025 -0.5286247565 2.1600506491 0.4143137190 0.6132903493 0.5378828158 -0.403610166065 +1413394981355760384.0000000000 -0.8513186370 -0.5370339053 2.1460706474 0.4159464797 0.6129281543 0.5389957545 -0.400987755885 +1413394981405760512.0000000000 -0.8091810332 -0.5432388401 2.1326081654 0.4206560848 0.6108526818 0.5414318310 -0.395928063985 +1413394981455760384.0000000000 -0.7682826405 -0.5483310701 2.1197151561 0.4251682802 0.6094037903 0.5434200707 -0.390581080779 +1413394981505760512.0000000000 -0.7286546210 -0.5526724794 2.1084706127 0.4296767779 0.6079443764 0.5448826318 -0.385855438382 +1413394981555760384.0000000000 -0.6901192842 -0.5568791831 2.0985151196 0.4320948941 0.6078739769 0.5452312501 -0.382761171865 +1413394981605760512.0000000000 -0.6527429157 -0.5610191752 2.0892094895 0.4319410884 0.6096069779 0.5453212933 -0.380040676359 +1413394981655760384.0000000000 -0.6164180176 -0.5648029577 2.0799235634 0.4300704003 0.6126611516 0.5460734072 -0.376151030867 +1413394981705760512.0000000000 -0.5816114756 -0.5681268096 2.0704973747 0.4287268801 0.6162341192 0.5462406428 -0.371577626939 +1413394981755760384.0000000000 -0.5486385589 -0.5710060998 2.0616019854 0.4270429440 0.6212428982 0.5444021862 -0.367855739491 +1413394981805760512.0000000000 -0.5174488853 -0.5736454920 2.0526231012 0.4245914821 0.6276550721 0.5408231855 -0.365077342361 +1413394981855760384.0000000000 -0.4883542837 -0.5755245827 2.0448798591 0.4231034684 0.6339808910 0.5356708845 -0.36346717663 +1413394981905760512.0000000000 -0.4612916614 -0.5762978047 2.0371359148 0.4225254107 0.6404408485 0.5295368124 -0.361799061898 +1413394981955760384.0000000000 -0.4367260428 -0.5755640279 2.0305261560 0.4224899437 0.6470857036 0.5219070668 -0.36110296763 +1413394982005760512.0000000000 -0.4138438842 -0.5733726853 2.0245180000 0.4231286077 0.6539814260 0.5136477856 -0.359772745221 +1413394982055760384.0000000000 -0.3932481174 -0.5693773740 2.0196599075 0.4238557099 0.6616391095 0.5032491826 -0.359611298803 +1413394982105760512.0000000000 -0.3746750934 -0.5630251303 2.0156858288 0.4263160331 0.6686300733 0.4916462915 -0.359822718987 +1413394982155760384.0000000000 -0.3577592951 -0.5542480607 2.0126815250 0.4289280682 0.6757502632 0.4785776324 -0.361034269781 +1413394982205760512.0000000000 -0.3421680907 -0.5425954322 2.0103841337 0.4319972259 0.6828637797 0.4649842014 -0.361752881906 +1413394982255760384.0000000000 -0.3276644548 -0.5277666124 2.0090523301 0.4346788674 0.6909946284 0.4501311169 -0.36188766677 +1413394982305760512.0000000000 -0.3134067780 -0.5094844782 2.0078416054 0.4382715263 0.6985371396 0.4365663532 -0.359685631006 +1413394982355760384.0000000000 -0.2992716173 -0.4872176229 2.0074088131 0.4418851598 0.7061897808 0.4235031266 -0.355919373975 +1413394982405760512.0000000000 -0.2852953875 -0.4607792004 2.0081514473 0.4469983668 0.7134920259 0.4101891709 -0.350523084992 +1413394982455760384.0000000000 -0.2709905432 -0.4304348845 2.0103225546 0.4521306134 0.7205439464 0.3963876241 -0.345356600107 +1413394982505760512.0000000000 -0.2558433225 -0.3959971319 2.0137186341 0.4570910973 0.7277356620 0.3819960787 -0.339922830677 +1413394982555760384.0000000000 -0.2396287169 -0.3575320333 2.0182724719 0.4622576205 0.7347177060 0.3689026202 -0.33229300572 +1413394982605760512.0000000000 -0.2223929476 -0.3154944979 2.0242826601 0.4669655243 0.7416395734 0.3539423169 -0.326555934845 +1413394982655760384.0000000000 -0.2036866134 -0.2696489863 2.0306335479 0.4733671322 0.7472683570 0.3411850826 -0.31797216891 +1413394982705760512.0000000000 -0.1836643334 -0.2201778473 2.0377287358 0.4794278555 0.7523386640 0.3291874704 -0.309469021576 +1413394982755760384.0000000000 -0.1623075656 -0.1671888327 2.0455354858 0.4855433960 0.7572654472 0.3174245239 -0.300063867562 +1413394982805760512.0000000000 -0.1396340893 -0.1107157528 2.0535269521 0.4925909035 0.7613747866 0.3062199998 -0.289641067308 +1413394982855760384.0000000000 -0.1154019661 -0.0512865677 2.0613710800 0.4993445564 0.7652827326 0.2953311131 -0.278885078176 +1413394982905760512.0000000000 -0.0899543101 0.0107942277 2.0697081982 0.5058082010 0.7688776569 0.2847973375 -0.268096417504 +1413394983005760512.0000000000 -0.0351069584 0.1415940146 2.0866706089 0.5188903055 0.7737468734 0.2682226706 -0.245204457161 +1413394983105760512.0000000000 0.0237043620 0.2778415990 2.1041416096 0.5301823792 0.7755850288 0.2591166141 -0.224127392724 +1413394983205760512.0000000000 0.0844170588 0.4168312961 2.1231721758 0.5393069550 0.7749262634 0.2548454883 -0.209024093724 +1413394983305760512.0000000000 0.1455781872 0.5566849287 2.1426943365 0.5454219976 0.7734340269 0.2527767447 -0.201043696659 +1413394983405760512.0000000000 0.2072134951 0.6962709188 2.1614646111 0.5505010944 0.7706216649 0.2571701198 -0.192235075016 +1413394983505760512.0000000000 0.2689391537 0.8340618116 2.1786990354 0.5554974626 0.7660667097 0.2713015085 -0.175954132893 +1413394983605760512.0000000000 0.3270324252 0.9668396267 2.1901455587 0.5587689329 0.7617909358 0.2830333511 -0.165360127823 +1413394983705760512.0000000000 0.3790360129 1.0942653674 2.1908456430 0.5625788816 0.7568176356 0.2924295592 -0.158798681748 +1413394983805760512.0000000000 0.4247067461 1.2146458111 2.1803278354 0.5661953668 0.7524334555 0.2993783404 -0.153750807755 +1413394983905760512.0000000000 0.4624432120 1.3271642479 2.1594213288 0.5670129919 0.7509194307 0.3016388649 -0.153721406517 +1413394984005760512.0000000000 0.4924314601 1.4310753264 2.1289538544 0.5664776192 0.7505896122 0.3022552363 -0.156077266511 +1413394984105760512.0000000000 0.5141651756 1.5253645147 2.0935026420 0.5650490959 0.7488370464 0.3067786598 -0.160777644459 +1413394984205760512.0000000000 0.5287187364 1.6096000371 2.0595052363 0.5624553823 0.7460520473 0.3150287516 -0.16675482406 +1413394984305760512.0000000000 0.5360231549 1.6860165800 2.0271905325 0.5567634112 0.7458673467 0.3233434160 -0.170720357407 +1413394984405760512.0000000000 0.5361150040 1.7549619844 1.9977842955 0.5488009209 0.7482286624 0.3305422151 -0.172375352179 +1413394984505760512.0000000000 0.5273146823 1.8176242974 1.9714076200 0.5413666076 0.7491466528 0.3394517997 -0.174567936775 +1413394984605760512.0000000000 0.5092082850 1.8735001650 1.9484102500 0.5349187628 0.7469799479 0.3511088441 -0.180569804132 +1413394984705760512.0000000000 0.4820115239 1.9226614153 1.9293637686 0.5288821015 0.7418007989 0.3659164922 -0.190053724657 +1413394984805760512.0000000000 0.4446662055 1.9666983763 1.9138366784 0.5219423984 0.7353667753 0.3827614741 -0.20076227845 +1413394984905760512.0000000000 0.3965418896 2.0061130608 1.9021600026 0.5148309679 0.7274772627 0.3976271063 -0.218216844034 +1413394985005760512.0000000000 0.3401131658 2.0412904584 1.8949108013 0.5115472137 0.7147143659 0.4143479924 -0.236259527936 +1413394985105760512.0000000000 0.2767122926 2.0728972105 1.8918096835 0.5088796493 0.7019338277 0.4318181396 -0.248723739121 +1413394985205760512.0000000000 0.2075840347 2.0999962855 1.8928014721 0.5050702782 0.6941838783 0.4441325856 -0.256435184196 +1413394985305760512.0000000000 0.1317656291 2.1216445702 1.9029298841 0.4983964492 0.6919761794 0.4498228224 -0.265385333077 +1413394985405760512.0000000000 0.0501334726 2.1371536967 1.9283035155 0.4808503148 0.7003948448 0.4422189181 -0.287528197791 +1413394985505760512.0000000000 -0.0367387981 2.1548345674 1.9673404118 0.4618564392 0.7104136705 0.4327116641 -0.307833822045 +1413394985605760512.0000000000 -0.1272637601 2.1830569367 2.0204764470 0.4631074031 0.7076450690 0.4339064409 -0.310636749318 +1413394985705760512.0000000000 -0.2194610090 2.2192845823 2.0741248933 0.4750788112 0.6978386978 0.4466561765 -0.296343609694 +1413394985805760512.0000000000 -0.3134793230 2.2569941103 2.1169278867 0.4873643606 0.6877695522 0.4586322758 -0.281256926454 +1413394985905760512.0000000000 -0.4121718303 2.2917184532 2.1449616434 0.4944865548 0.6820020831 0.4650137411 -0.272246995203 +1413394986005760512.0000000000 -0.5158260070 2.3214235876 2.1610361743 0.4977009844 0.6801345120 0.4662152360 -0.268987229155 +1413394986105760512.0000000000 -0.6248156411 2.3451141277 2.1732577850 0.5000390366 0.6796472221 0.4647705641 -0.268382074775 +1413394986205760512.0000000000 -0.7399371586 2.3615063967 2.1889120431 0.4938808709 0.6862992267 0.4550809913 -0.279242454158 +1413394986305760512.0000000000 -0.8598877795 2.3739849166 2.2106743001 0.4827524709 0.6962275795 0.4406968591 -0.296653818166 +1413394986405760512.0000000000 -0.9812900698 2.3889048931 2.2363494639 0.4751023255 0.7026660913 0.4314260972 -0.307261561353 +1413394986505760512.0000000000 -1.1023908804 2.4087424247 2.2655414093 0.4760292999 0.7029349076 0.4298961706 -0.307356314073 +1413394986605760512.0000000000 -1.2232791395 2.4335649009 2.2963843108 0.4847016491 0.6974997979 0.4375385926 -0.29515813266 +1413394986705760512.0000000000 -1.3458422043 2.4599172785 2.3269827139 0.4942548112 0.6902939292 0.4493163989 -0.278066982074 +1413394986805760512.0000000000 -1.4726220683 2.4831200428 2.3583713427 0.5030026910 0.6833894867 0.4563444270 -0.267800048973 +1413394986905760512.0000000000 -1.6055761490 2.4993708859 2.3924587651 0.5058241273 0.6823202521 0.4521328299 -0.272317700296 +1413394987005760512.0000000000 -1.7413030337 2.5096240486 2.4244616173 0.5038757105 0.6854295402 0.4400873892 -0.287434694742 +1413394987105760512.0000000000 -1.8751670633 2.5156692726 2.4445501404 0.4963987482 0.6918906631 0.4270871014 -0.304092421843 +1413394987205760512.0000000000 -2.0070525393 2.5226513455 2.4519393771 0.4921606400 0.6955381957 0.4179998489 -0.315088319421 +1413394987305760512.0000000000 -2.1351184859 2.5334673337 2.4510980103 0.5007565539 0.6904229168 0.4180824632 -0.312675748312 +1413394987405760512.0000000000 -2.2582868910 2.5454634767 2.4449037414 0.5196464971 0.6772012746 0.4282274417 -0.296626380989 +1413394987505760512.0000000000 -2.3774785439 2.5520685633 2.4417620779 0.5358309539 0.6650932645 0.4361000004 -0.28346592048 +1413394987605760512.0000000000 -2.4942304756 2.5482241626 2.4441585317 0.5461476485 0.6568966609 0.4387769034 -0.278719127195 +1413394987705760512.0000000000 -2.6073444187 2.5308219750 2.4521262538 0.5554697723 0.6494944019 0.4372445039 -0.280049277262 +1413394987805760512.0000000000 -2.7149057879 2.4986872748 2.4643303432 0.5631169475 0.6434205789 0.4331364468 -0.285135196901 +1413394987905760512.0000000000 -2.8145321236 2.4509848242 2.4813072904 0.5686701188 0.6397744557 0.4301236526 -0.286873814399 +1413394988005760512.0000000000 -2.9052424207 2.3874207777 2.5037006904 0.5737348694 0.6363373330 0.4258349816 -0.290805203978 +1413394988105760512.0000000000 -2.9854262360 2.3080990724 2.5299552863 0.5753595436 0.6357075473 0.4182077601 -0.299899281809 +1413394988205760512.0000000000 -3.0535042143 2.2142024532 2.5580989525 0.5674424285 0.6426138164 0.4087471030 -0.313021371681 +1413394988305760512.0000000000 -3.1084588235 2.1108879590 2.5878531032 0.5538972963 0.6562967363 0.3924174382 -0.329364438376 +1413394988405760512.0000000000 -3.1490811550 2.0056388891 2.6122809711 0.5392957954 0.6760068671 0.3689695738 -0.340640887503 +1413394988505760512.0000000000 -3.1742138410 1.9049198722 2.6270155812 0.5291133960 0.6985653080 0.3409725981 -0.340269322607 +1413394988605760512.0000000000 -3.1836917115 1.8131276964 2.6332983397 0.5288142762 0.7197370624 0.3113578481 -0.324638741728 +1413394988705760512.0000000000 -3.1770924356 1.7299008917 2.6313978228 0.5382729025 0.7355208025 0.2884413788 -0.293382007759 +1413394988805760512.0000000000 -3.1575609296 1.6518173138 2.6227779979 0.5524751848 0.7436739858 0.2714599888 -0.26082493641 +1413394988905760512.0000000000 -3.1288005687 1.5752902501 2.6078635153 0.5676171234 0.7451702182 0.2592014655 -0.235258894124 +1413394989005760512.0000000000 -3.0915276983 1.4947667646 2.5894645799 0.5781218668 0.7451932598 0.2543255739 -0.21396405088 +1413394989105760512.0000000000 -3.0478054116 1.4098557596 2.5718429123 0.5803031432 0.7481560465 0.2553343219 -0.19574262702 +1413394989205760512.0000000000 -3.0011846532 1.3197437278 2.5576235466 0.5773068443 0.7525939335 0.2572424473 -0.184785015961 +1413394989305760512.0000000000 -2.9547496978 1.2257507441 2.5484934048 0.5720934985 0.7568289307 0.2570911970 -0.18391061671 +1413394989405760512.0000000000 -2.9076309395 1.1282784550 2.5422637172 0.5657868366 0.7607031119 0.2556169643 -0.189409605605 +1413394989505760512.0000000000 -2.8594434150 1.0295909799 2.5356276346 0.5602005403 0.7634694070 0.2546441745 -0.196076932733 +1413394989605760512.0000000000 -2.8091620782 0.9311599609 2.5223118082 0.5542504795 0.7662220433 0.2539001274 -0.203088433165 +1413394989705760512.0000000000 -2.7569814003 0.8338132428 2.4991226691 0.5463311533 0.7681630842 0.2571409161 -0.212899732938 +1413394989805760512.0000000000 -2.7026907625 0.7381310330 2.4665457640 0.5340121588 0.7680892854 0.2682716783 -0.230000370842 +1413394989905760512.0000000000 -2.6459607124 0.6462212192 2.4245839731 0.5143508746 0.7674798222 0.2897769386 -0.24989443001 +1413394990005760512.0000000000 -2.5866914147 0.5622088488 2.3762337276 0.4996060192 0.7576717528 0.3251777041 -0.265681767168 +1413394990105760512.0000000000 -2.5260532456 0.4865851905 2.3210331652 0.4921272180 0.7373523212 0.3703751573 -0.277388894157 +1413394990155760384.0000000000 -2.4960657542 0.4508810321 2.2901979967 0.4883646296 0.7254492365 0.3936579231 -0.283296370293 +1413394990205760512.0000000000 -2.4667733991 0.4163794445 2.2577894120 0.4837265765 0.7130690813 0.4164632291 -0.289999074597 +1413394990255760384.0000000000 -2.4387866119 0.3831114154 2.2248919137 0.4790494008 0.6995266368 0.4395546101 -0.296590459726 +1413394990355760384.0000000000 -2.3869794751 0.3186056737 2.1610848418 0.4689355791 0.6718712967 0.4819216282 -0.310547786362 +1413394990405760512.0000000000 -2.3626715223 0.2868201988 2.1297538494 0.4621488769 0.6597444457 0.5007699602 -0.316836123081 +1413394990455760384.0000000000 -2.3404578461 0.2551892615 2.0998204578 0.4555044796 0.6495862613 0.5156496948 -0.323510046988 +1413394990505760512.0000000000 -2.3203166900 0.2237120187 2.0713028179 0.4483247516 0.6415913245 0.5274048332 -0.330468805402 +1413394990555760384.0000000000 -2.3025336878 0.1922108531 2.0443084507 0.4414429213 0.6357574987 0.5357708727 -0.337476105823 +1413394990605760512.0000000000 -2.2867482080 0.1607190619 2.0181973342 0.4351986795 0.6320133232 0.5417468186 -0.343033020563 +1413394990655760384.0000000000 -2.2731574733 0.1295189973 1.9931158808 0.4295048757 0.6290183809 0.5466829553 -0.347849370588 +1413394990705760512.0000000000 -2.2619080042 0.0990407179 1.9688957703 0.4264258948 0.6263777072 0.5504994649 -0.350374461691 +1413394990755760384.0000000000 -2.2534820386 0.0685750833 1.9457825063 0.4242447721 0.6249127407 0.5519882515 -0.353283752783 +1413394990805760512.0000000000 -2.2477716772 0.0385672173 1.9232544463 0.4228636723 0.6238730275 0.5532583223 -0.354787244791 +1413394990855760384.0000000000 -2.2447056646 0.0089089078 1.9021707369 0.4222303588 0.6237740710 0.5535232995 -0.355301828615 +1413394990905760512.0000000000 -2.2440008005 -0.0204371562 1.8820781151 0.4223898170 0.6237790368 0.5533852835 -0.355318566557 +1413394990955760384.0000000000 -2.2451205017 -0.0494469802 1.8630836552 0.4228254303 0.6245140217 0.5522679596 -0.355247790903 +1413394991005760512.0000000000 -2.2485794148 -0.0780663697 1.8450313567 0.4242394537 0.6249864838 0.5511067925 -0.354533615111 +1413394991055760384.0000000000 -2.2538907793 -0.1064972101 1.8279170439 0.4257713825 0.6257634130 0.5499649150 -0.353096974114 +1413394991105760512.0000000000 -2.2612377739 -0.1350977748 1.8122026787 0.4259903482 0.6279773250 0.5466435315 -0.354058684289 +1413394991155760384.0000000000 -2.2705345905 -0.1634977629 1.7976562629 0.4263464835 0.6301605887 0.5425547159 -0.356034673568 +1413394991205760512.0000000000 -2.2818094956 -0.1913314338 1.7838658041 0.4269925004 0.6322487666 0.5384857805 -0.357731695403 +1413394991255760384.0000000000 -2.2948158912 -0.2183204530 1.7705143386 0.4273743812 0.6359994927 0.5338406299 -0.357589101457 +1413394991305760512.0000000000 -2.3095544939 -0.2442514274 1.7578994105 0.4281871471 0.6405275663 0.5281323166 -0.357010448127 +1413394991355760384.0000000000 -2.3257355546 -0.2686843566 1.7452834669 0.4301307426 0.6461031762 0.5213611008 -0.354571336347 +1413394991405760512.0000000000 -2.3437357891 -0.2920272237 1.7336477614 0.4327288319 0.6525205446 0.5134635268 -0.35116648989 +1413394991455760384.0000000000 -2.3631633090 -0.3139138107 1.7228819122 0.4363069591 0.6589901785 0.5046910456 -0.347354473855 +1413394991505760512.0000000000 -2.3836768607 -0.3340930747 1.7127122778 0.4409593093 0.6657109795 0.4950311171 -0.342531710095 +1413394991555760384.0000000000 -2.4052032259 -0.3527860058 1.7027462123 0.4461247468 0.6727992203 0.4847075083 -0.336708406251 +1413394991605760512.0000000000 -2.4277047529 -0.3698694623 1.6929996296 0.4522646188 0.6789295952 0.4747370237 -0.33035749979 +1413394991655760384.0000000000 -2.4512643230 -0.3851587052 1.6844539865 0.4601388652 0.6836608813 0.4645942361 -0.32408674749 +1413394991705760512.0000000000 -2.4758232268 -0.3991703675 1.6766663222 0.4703938386 0.6865384153 0.4546328662 -0.317338301908 +1413394991755760384.0000000000 -2.5009164520 -0.4124744516 1.6701098715 0.4815631250 0.6876393217 0.4440071938 -0.313219941499 +1413394991805760512.0000000000 -2.5260536790 -0.4253626912 1.6638821088 0.4913166414 0.6880747753 0.4339026721 -0.31127083486 +1413394991855760384.0000000000 -2.5511234455 -0.4381981879 1.6584896087 0.4999942690 0.6883063896 0.4234350847 -0.31135634571 +1413394991905760512.0000000000 -2.5754972566 -0.4512847566 1.6535571134 0.5058813387 0.6889108656 0.4144777791 -0.312560491789 +1413394991955760384.0000000000 -2.5989048520 -0.4641417072 1.6488253932 0.5101570026 0.6898735060 0.4068216814 -0.313545049361 +1413394992005760512.0000000000 -2.6210246507 -0.4768476107 1.6440989407 0.5127450847 0.6924114743 0.3989525715 -0.313840204602 +1413394992055760384.0000000000 -2.6414316728 -0.4892563780 1.6390132887 0.5119812643 0.6970945921 0.3914255670 -0.31419793164 +1413394992105760512.0000000000 -2.6599455613 -0.5007930398 1.6343762134 0.5103810005 0.7027018764 0.3835486160 -0.314025104786 +1413394992155760384.0000000000 -2.6766488058 -0.5114249083 1.6303565148 0.5069288809 0.7100238460 0.3752164866 -0.313212126181 +1413394992205760512.0000000000 -2.6914320722 -0.5205965412 1.6264619436 0.5033435423 0.7175690013 0.3682527165 -0.31004829225 +1413394992255760384.0000000000 -2.7045457036 -0.5276338264 1.6232686539 0.5012024192 0.7243261078 0.3616490099 -0.305545116285 +1413394992305760512.0000000000 -2.7161612690 -0.5323137496 1.6211542300 0.5017228323 0.7297773592 0.3554032041 -0.298977872154 +1413394992355760384.0000000000 -2.7261982453 -0.5347102264 1.6193363183 0.5045571564 0.7338837978 0.3501875747 -0.290181511753 +1413394992405760512.0000000000 -2.7349622535 -0.5349874787 1.6184674789 0.5095488319 0.7366961476 0.3451899766 -0.280147557731 +1413394992455760384.0000000000 -2.7428099364 -0.5333910983 1.6181140210 0.5159923596 0.7384468550 0.3418224519 -0.267592112347 +1413394992505760512.0000000000 -2.7499238570 -0.5306926955 1.6176985267 0.5231821162 0.7389482281 0.3413324195 -0.252444387648 +1413394992555760384.0000000000 -2.7566982186 -0.5275601264 1.6177593471 0.5304022839 0.7384499041 0.3415332280 -0.238160052185 +1413394992605760512.0000000000 -2.7637243170 -0.5247694913 1.6185815192 0.5366579035 0.7376390713 0.3407097859 -0.227604342895 +1413394992655760384.0000000000 -2.7714473234 -0.5228232205 1.6208466215 0.5410256846 0.7373641775 0.3368807971 -0.223822712982 +1413394992705760512.0000000000 -2.7796039614 -0.5217324921 1.6233186845 0.5444965400 0.7371691822 0.3320822343 -0.223218512515 +1413394992755760384.0000000000 -2.7880677808 -0.5212263403 1.6260740207 0.5456813663 0.7387275933 0.3249049065 -0.225721489992 +1413394992805760512.0000000000 -2.7963006893 -0.5211702125 1.6287453284 0.5454588117 0.7413612867 0.3167684769 -0.229163390323 +1413394992855760384.0000000000 -2.8040313105 -0.5211404995 1.6312670743 0.5443618289 0.7449424103 0.3087009596 -0.231159516779 +1413394992905760512.0000000000 -2.8110838736 -0.5212310588 1.6335442662 0.5427671893 0.7486436075 0.3009274512 -0.233193474014 +1413394992955760384.0000000000 -2.8171057352 -0.5210700597 1.6345750727 0.5414966081 0.7516220045 0.2954905764 -0.233518960888 +1413394993005760512.0000000000 -2.8223609495 -0.5204291793 1.6335986153 0.5405002455 0.7541626807 0.2913200052 -0.232875052919 +1413394993055760384.0000000000 -2.8266164534 -0.5192987265 1.6294035655 0.5406046047 0.7556071638 0.2893636431 -0.230376121432 +1413394993105760512.0000000000 -2.8300905439 -0.5173534463 1.6222065841 0.5418047850 0.7559262580 0.2897182984 -0.22602295219 +1413394993155760384.0000000000 -2.8330400130 -0.5150833807 1.6120051823 0.5428914786 0.7561728889 0.2908401090 -0.221095987128 +1413394993205760512.0000000000 -2.8356961691 -0.5125728374 1.5994283898 0.5436807955 0.7560354771 0.2929796744 -0.21675899122 +1413394993255760384.0000000000 -2.8375753073 -0.5100259642 1.5843790277 0.5453327575 0.7552624124 0.2956599110 -0.211603612813 +1413394993305760512.0000000000 -2.8394984886 -0.5071429913 1.5675482477 0.5476679359 0.7537862902 0.2990596279 -0.205983978898 +1413394993355760384.0000000000 -2.8413940466 -0.5047373264 1.5499523078 0.5494523832 0.7522969611 0.3026088930 -0.201442842646 +1413394993405760512.0000000000 -2.8437727870 -0.5027113113 1.5323217721 0.5512113804 0.7507507981 0.3062766952 -0.196809144093 +1413394993455760384.0000000000 -2.8467761629 -0.5012688547 1.5152290678 0.5526910192 0.7494162656 0.3090800243 -0.19333245143 +1413394993505760512.0000000000 -2.8506943925 -0.5006682789 1.4988164286 0.5535980626 0.7482016256 0.3119823160 -0.190763065055 +1413394993555760384.0000000000 -2.8552587380 -0.5011210695 1.4830302169 0.5543507985 0.7470927845 0.3139877114 -0.18962932454 +1413394993605760512.0000000000 -2.8610098170 -0.5026326348 1.4676795711 0.5544109203 0.7468478826 0.3143716799 -0.189782029406 +1413394993655760384.0000000000 -2.8674984264 -0.5048188558 1.4524709574 0.5535834844 0.7476060249 0.3133233875 -0.190942431374 +1413394993705760512.0000000000 -2.8749284931 -0.5074703117 1.4373377991 0.5530691560 0.7492552397 0.3091592168 -0.192747692864 +1413394993755760384.0000000000 -2.8828458946 -0.5104510897 1.4213288667 0.5525723324 0.7517675392 0.3024862801 -0.194965214514 +1413394993805760512.0000000000 -2.8909105174 -0.5132871761 1.4033793643 0.5514415771 0.7557558149 0.2938225898 -0.195993930985 +1413394993855760384.0000000000 -2.8990395037 -0.5156830805 1.3835764270 0.5512659205 0.7601128393 0.2831390635 -0.195362808877 +1413394993905760512.0000000000 -2.9070742203 -0.5177123259 1.3614596412 0.5508184857 0.7652208783 0.2705857781 -0.194471951361 +1413394993955760384.0000000000 -2.9146852712 -0.5189077452 1.3382916537 0.5508917175 0.7704341728 0.2566974092 -0.192499197271 +1413394994005760512.0000000000 -2.9216161088 -0.5191539613 1.3147057205 0.5512265182 0.7756965425 0.2414864993 -0.190074906797 +1413394994055760384.0000000000 -2.9274880940 -0.5183491402 1.2924347014 0.5522789529 0.7806511874 0.2260340969 -0.18568863414 +1413394994105760512.0000000000 -2.9316714017 -0.5170549916 1.2711010027 0.5542195796 0.7848479253 0.2119217778 -0.17872759116 +1413394994155760384.0000000000 -2.9339758628 -0.5149550619 1.2530939517 0.5572365841 0.7881569260 0.1976074065 -0.171018602167 +1413394994205760512.0000000000 -2.9347702997 -0.5109852630 1.2390603787 0.5613809749 0.7907606729 0.1837763051 -0.160546656395 +1413394994305760512.0000000000 -2.9311448022 -0.5016906374 1.2168213118 0.5692806077 0.7951585298 0.1596858437 -0.134695707061 +1413394994405760512.0000000000 -2.9221027191 -0.4923326584 1.2018976044 0.5747374038 0.7995687182 0.1417732516 -0.101326831234 +1413394994505760512.0000000000 -2.9128888424 -0.4834536281 1.1965479949 0.5800368365 0.8010050731 0.1299878609 -0.0710724789617 +1413394994605760512.0000000000 -2.9079243345 -0.4767421124 1.2003687480 0.5836781074 0.8013434820 0.1208352406 -0.0506688791461 +1413394994705760512.0000000000 -2.9093453757 -0.4731645240 1.2133450704 0.5867163095 0.8007237786 0.1146409886 -0.038247173902 +1413394994805760512.0000000000 -2.9180790826 -0.4729582377 1.2340165587 0.5919480713 0.7978216170 0.1094975050 -0.0329915855082 +1413394994905760512.0000000000 -2.9336782503 -0.4772766645 1.2559786482 0.5954194153 0.7958184890 0.1042970383 -0.0356480043226 +1413394995005760512.0000000000 -2.9537507005 -0.4861337028 1.2676857190 0.5964395878 0.7952163327 0.1006973589 -0.0418430899709 +1413394995105760512.0000000000 -2.9765638756 -0.4996762106 1.2601830826 0.5953168539 0.7960919661 0.0928652579 -0.0566698233366 +1413394995205760512.0000000000 -2.9989221498 -0.5176415121 1.2324141556 0.5867811249 0.8019909996 0.0845017749 -0.0731969815987 +1413394995305760512.0000000000 -3.0173238354 -0.5366133869 1.1905940468 0.5704644557 0.8132654231 0.0851407174 -0.0769461806626 +1413394995405760512.0000000000 -3.0309525930 -0.5525487776 1.1468232744 0.5563712869 0.8227924044 0.0895705814 -0.0737615168015 +1413394995505760512.0000000000 -3.0412719808 -0.5619673417 1.1036377249 0.5497651298 0.8271376159 0.0944914123 -0.0683596330881 +1413394995605760512.0000000000 -3.0508356904 -0.5639418001 1.0621357314 0.5494162274 0.8273999606 0.0970567882 -0.0642735886216 +1413394995705760512.0000000000 -3.0614184645 -0.5576160571 1.0258186379 0.5591564418 0.8208321519 0.0972465834 -0.064200887166 +1413394995805760512.0000000000 -3.0721821852 -0.5476319606 0.9973598697 0.5718028099 0.8120979465 0.0950731246 -0.0670788551836 +1413394995905760512.0000000000 -3.0815844152 -0.5378631723 0.9726135082 0.5798451066 0.8064299331 0.0923975266 -0.0700935976447 +1413394996005760512.0000000000 -3.0880693126 -0.5291928367 0.9324195187 0.5828549190 0.8046953715 0.0937209715 -0.0629434825486 +1413394996105760512.0000000000 -3.0900969240 -0.5341508110 0.9481661635 0.5927029403 0.7975684729 0.0928983390 -0.0629098894794 +1413394996205760512.0000000000 -3.0876083396 -0.5418297830 0.9407332269 0.5787708141 0.8072655468 0.0887577462 -0.0739509578961 +1413394996305760512.0000000000 -3.0919597927 -0.5455830303 0.9375798534 0.5948631415 0.7950364334 0.1023816858 -0.0597737635613 +1413394996405760512.0000000000 -3.0894872651 -0.5446586174 0.9352394422 0.5925761484 0.7966920149 0.1012009582 -0.0623995817633 +1413394996505760512.0000000000 -3.0905534214 -0.5439866432 0.9356600232 0.5894808286 0.7989075944 0.1036277715 -0.0593320595056 +1413394996605760512.0000000000 -3.0900155446 -0.5445191068 0.9358524246 0.5925416616 0.7966667484 0.1023375343 -0.061184150745 +1413394996705760512.0000000000 -3.0901584401 -0.5441941842 0.9348702590 0.5906338892 0.7980700010 0.1026618036 -0.0607983270676 +1413394996805760512.0000000000 -3.0902424466 -0.5446793090 0.9349542695 0.5916870627 0.7973076450 0.1025088492 -0.0608183759095 +1413394996905760512.0000000000 -3.0901361813 -0.5447374725 0.9347789240 0.5913097967 0.7975761144 0.1025899639 -0.0608306287721 +1413394997005760512.0000000000 -3.0900340499 -0.5449309088 0.9347444111 0.5913153476 0.7975453183 0.1026911704 -0.0610094133951 +1413394997105760512.0000000000 -3.0900072015 -0.5451555866 0.9347591409 0.5913273499 0.7975387214 0.1026711983 -0.0610129340612 +1413394997205760512.0000000000 -3.0898809744 -0.5451847454 0.9346310881 0.5910227816 0.7977775110 0.1026076587 -0.0609490200684 +1413394997305760512.0000000000 -3.0897054376 -0.5452911230 0.9346090718 0.5911311486 0.7976639151 0.1027081298 -0.0612150614496 +1413394997405760512.0000000000 -3.0897855259 -0.5451238265 0.9345891339 0.5910920387 0.7977128296 0.1026272529 -0.0610908359033 +1413394997505760512.0000000000 -3.0903243183 -0.5446490399 0.9346981523 0.5911032503 0.7977071319 0.1026683130 -0.060987676578 +1413394997605760512.0000000000 -3.0914405346 -0.5436055880 0.9347371540 0.5910447184 0.7977423555 0.1026996318 -0.0610414674311 diff --git a/demo.py b/demo.py new file mode 100644 index 00000000..c4a7eb33 --- /dev/null +++ b/demo.py @@ -0,0 +1,103 @@ +import sys +sys.path.append('droid_slam') + +from tqdm import tqdm +import numpy as np +import torch +import lietorch +import cv2 +import os +import glob +import time +import argparse + +from torch.multiprocessing import Process +from droid import Droid + +import torch.nn.functional as F + + +def show_image(image): + image = image.permute(1, 2, 0).cpu().numpy() + cv2.imshow('image', image / 255.0) + cv2.waitKey(1) + +def image_stream(imagedir, calib, stride): + """ image generator """ + + calib = np.loadtxt(calib, delimiter=" ") + fx, fy, cx, cy = calib[:4] + + K = np.eye(3) + K[0,0] = fx + K[0,2] = cx + K[1,1] = fy + K[1,2] = cy + + image_list = sorted(os.listdir(imagedir))[::stride] + + for t, imfile in enumerate(image_list): + image = cv2.imread(os.path.join(imagedir, imfile)) + if len(calib) > 4: + image = cv2.undistort(image, K, calib[4:]) + + h0, w0, _ = image.shape + h1 = int(h0 * np.sqrt((384 * 512) / (h0 * w0))) + w1 = int(w0 * np.sqrt((384 * 512) / (h0 * w0))) + + image = cv2.resize(image, (w1, h1)) + image = image[:h1-h1%8, :w1-w1%8] + image = torch.as_tensor(image).permute(2, 0, 1) + + intrinsics = torch.as_tensor([fx, fy, cx, cy]) + intrinsics[0:2] *= (w1 / w0) + intrinsics[2:4] *= (h1 / h0) + + yield t, image, intrinsics + + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument("--imagedir", type=str, help="path to image directory") + parser.add_argument("--calib", type=str, help="path to calibration file") + parser.add_argument("--t0", default=0, type=int, help="starting frame") + parser.add_argument("--stride", default=3, type=int, help="frame stride") + + parser.add_argument("--weights", default="droid.pth") + parser.add_argument("--buffer", type=int, default=512) + parser.add_argument("--image_size", default=[240, 320]) + parser.add_argument("--disable_vis", action="store_true") + + parser.add_argument("--beta", type=float, default=0.3, help="weight for translation / rotation components of flow") + parser.add_argument("--filter_thresh", type=float, default=2.4, help="how much motion before considering new keyframe") + parser.add_argument("--warmup", type=int, default=8, help="number of warmup frames") + parser.add_argument("--keyframe_thresh", type=float, default=4.0, help="threshold to create a new keyframe") + parser.add_argument("--frontend_thresh", type=float, default=16.0, help="add edges between frames whithin this distance") + parser.add_argument("--frontend_window", type=int, default=25, help="frontend optimization window") + parser.add_argument("--frontend_radius", type=int, default=2, help="force edges between frames within radius") + parser.add_argument("--frontend_nms", type=int, default=1, help="non-maximal supression of edges") + + parser.add_argument("--backend_thresh", type=float, default=22.0) + parser.add_argument("--backend_radius", type=int, default=2) + parser.add_argument("--backend_nms", type=int, default=3) + args = parser.parse_args() + + torch.multiprocessing.set_start_method('spawn') + + droid = None + + tstamps = [] + for (t, image, intrinsics) in tqdm(image_stream(args.imagedir, args.calib, args.stride)): + if t < args.t0: + continue + + if not args.disable_vis: + show_image(image) + + if droid is None: + args.image_size = [image.shape[1], image.shape[2]] + droid = Droid(args) + + droid.track(t, image, intrinsics=intrinsics) + + traj_est = droid.terminate(image_stream(args.imagedir, args.calib, args.stride)) diff --git a/droid_slam/data_readers/__init__.py b/droid_slam/data_readers/__init__.py new file mode 100644 index 00000000..8b137891 --- /dev/null +++ b/droid_slam/data_readers/__init__.py @@ -0,0 +1 @@ + diff --git a/droid_slam/data_readers/augmentation.py b/droid_slam/data_readers/augmentation.py new file mode 100644 index 00000000..ba534145 --- /dev/null +++ b/droid_slam/data_readers/augmentation.py @@ -0,0 +1,58 @@ +import torch +import torchvision.transforms as transforms +import numpy as np +import torch.nn.functional as F + + +class RGBDAugmentor: + """ perform augmentation on RGB-D video """ + + def __init__(self, crop_size): + self.crop_size = crop_size + self.augcolor = transforms.Compose([ + transforms.ToPILImage(), + transforms.ColorJitter(brightness=0.25, contrast=0.25, saturation=0.25, hue=0.4/3.14), + transforms.RandomGrayscale(p=0.1), + transforms.ToTensor()]) + + self.max_scale = 0.25 + + def spatial_transform(self, images, depths, poses, intrinsics): + """ cropping and resizing """ + ht, wd = images.shape[2:] + + max_scale = self.max_scale + min_scale = np.log2(np.maximum( + (self.crop_size[0] + 1) / float(ht), + (self.crop_size[1] + 1) / float(wd))) + + scale = 2 ** np.random.uniform(min_scale, max_scale) + intrinsics = scale * intrinsics + depths = depths.unsqueeze(dim=1) + + images = F.interpolate(images, scale_factor=scale, mode='bilinear', + align_corners=False, recompute_scale_factor=True) + + depths = F.interpolate(depths, scale_factor=scale, recompute_scale_factor=True) + + # always perform center crop (TODO: try non-center crops) + y0 = (images.shape[2] - self.crop_size[0]) // 2 + x0 = (images.shape[3] - self.crop_size[1]) // 2 + + intrinsics = intrinsics - torch.tensor([0.0, 0.0, x0, y0]) + images = images[:, :, y0:y0+self.crop_size[0], x0:x0+self.crop_size[1]] + depths = depths[:, :, y0:y0+self.crop_size[0], x0:x0+self.crop_size[1]] + + depths = depths.squeeze(dim=1) + return images, poses, depths, intrinsics + + def color_transform(self, images): + """ color jittering """ + num, ch, ht, wd = images.shape + images = images.permute(1, 2, 3, 0).reshape(ch, ht, wd*num) + images = 255 * self.augcolor(images[[2,1,0]] / 255.0) + return images[[2,1,0]].reshape(ch, ht, wd, num).permute(3,0,1,2).contiguous() + + def __call__(self, images, poses, depths, intrinsics): + images = self.color_transform(images) + return self.spatial_transform(images, depths, poses, intrinsics) diff --git a/droid_slam/data_readers/base.py b/droid_slam/data_readers/base.py new file mode 100644 index 00000000..f676697b --- /dev/null +++ b/droid_slam/data_readers/base.py @@ -0,0 +1,157 @@ + +import numpy as np +import torch +import torch.utils.data as data +import torch.nn.functional as F + +import csv +import os +import cv2 +import math +import random +import json +import pickle +import os.path as osp + +from .augmentation import RGBDAugmentor +from .rgbd_utils import * + +class RGBDDataset(data.Dataset): + def __init__(self, name, datapath, n_frames=4, crop_size=[384,512], fmin=8.0, fmax=75.0, do_aug=True): + """ Base class for RGBD dataset """ + self.aug = None + self.root = datapath + self.name = name + + self.n_frames = n_frames + self.fmin = fmin # exclude very easy examples + self.fmax = fmax # exclude very hard examples + + if do_aug: + self.aug = RGBDAugmentor(crop_size=crop_size) + + # building dataset is expensive, cache so only needs to be performed once + cur_path = osp.dirname(osp.abspath(__file__)) + if not os.path.isdir(osp.join(cur_path, 'cache')): + os.mkdir(osp.join(cur_path, 'cache')) + + cache_path = osp.join(cur_path, 'cache', '{}.pickle'.format(self.name)) + + if osp.isfile(cache_path): + scene_info = pickle.load(open(cache_path, 'rb'))[0] + else: + scene_info = self._build_dataset() + with open(cache_path, 'wb') as cachefile: + pickle.dump((scene_info,), cachefile) + + self.scene_info = scene_info + self._build_dataset_index() + + def _build_dataset_index(self): + self.dataset_index = [] + for scene in self.scene_info: + if not self.__class__.is_test_scene(scene): + graph = self.scene_info[scene]['graph'] + for i in graph: + if len(graph[i][0]) > self.n_frames: + self.dataset_index.append((scene, i)) + else: + print("Reserving {} for validation".format(scene)) + + @staticmethod + def image_read(image_file): + return cv2.imread(image_file) + + @staticmethod + def depth_read(depth_file): + return np.load(depth_file) + + def build_frame_graph(self, poses, depths, intrinsics, f=16, max_flow=256): + """ compute optical flow distance between all pairs of frames """ + def read_disp(fn): + depth = self.__class__.depth_read(fn)[f//2::f, f//2::f] + depth[depth < 0.01] = np.mean(depth) + return 1.0 / depth + + poses = np.array(poses) + intrinsics = np.array(intrinsics) / f + + disps = np.stack(list(map(read_disp, depths)), 0) + d = f * compute_distance_matrix_flow(poses, disps, intrinsics) + + # uncomment for nice visualization + # import matplotlib.pyplot as plt + # plt.imshow(d) + # plt.show() + + graph = {} + for i in range(d.shape[0]): + j, = np.where(d[i] < max_flow) + graph[i] = (j, d[i,j]) + + return graph + + def __getitem__(self, index): + """ return training video """ + + index = index % len(self.dataset_index) + scene_id, ix = self.dataset_index[index] + + frame_graph = self.scene_info[scene_id]['graph'] + images_list = self.scene_info[scene_id]['images'] + depths_list = self.scene_info[scene_id]['depths'] + poses_list = self.scene_info[scene_id]['poses'] + intrinsics_list = self.scene_info[scene_id]['intrinsics'] + + inds = [ ix ] + while len(inds) < self.n_frames: + # get other frames within flow threshold + k = (frame_graph[ix][1] > self.fmin) & (frame_graph[ix][1] < self.fmax) + frames = frame_graph[ix][0][k] + + # prefer frames forward in time + if np.count_nonzero(frames[frames > ix]): + ix = np.random.choice(frames[frames > ix]) + + elif np.count_nonzero(frames): + ix = np.random.choice(frames) + + inds += [ ix ] + + images, depths, poses, intrinsics = [], [], [], [] + for i in inds: + images.append(self.__class__.image_read(images_list[i])) + depths.append(self.__class__.depth_read(depths_list[i])) + poses.append(poses_list[i]) + intrinsics.append(intrinsics_list[i]) + + images = np.stack(images).astype(np.float32) + depths = np.stack(depths).astype(np.float32) + poses = np.stack(poses).astype(np.float32) + intrinsics = np.stack(intrinsics).astype(np.float32) + + images = torch.from_numpy(images).float() + images = images.permute(0, 3, 1, 2) + + disps = torch.from_numpy(1.0 / depths) + poses = torch.from_numpy(poses) + intrinsics = torch.from_numpy(intrinsics) + + if self.aug is not None: + images, poses, disps, intrinsics = \ + self.aug(images, poses, disps, intrinsics) + + # scale scene + if len(disps[disps>0.01]) > 0: + s = disps[disps>0.01].mean() + disps = disps / s + poses[...,:3] *= s + + return images, poses, disps, intrinsics + + def __len__(self): + return len(self.dataset_index) + + def __imul__(self, x): + self.dataset_index *= x + return self diff --git a/droid_slam/data_readers/factory.py b/droid_slam/data_readers/factory.py new file mode 100644 index 00000000..830dca09 --- /dev/null +++ b/droid_slam/data_readers/factory.py @@ -0,0 +1,82 @@ + +import pickle +import os +import os.path as osp + +# RGBD-Dataset +from .tartan import TartanAir + +from .stream import ImageStream +from .stream import StereoStream +from .stream import RGBDStream + +# streaming datasets for inference +from .tartan import TartanAirStream +from .tartan import TartanAirTestStream + +def dataset_factory(dataset_list, **kwargs): + """ create a combined dataset """ + + from torch.utils.data import ConcatDataset + + dataset_map = { 'tartan': (TartanAir, ) } + db_list = [] + for key in dataset_list: + # cache datasets for faster future loading + db = dataset_map[key][0](**kwargs) + + print("Dataset {} has {} images".format(key, len(db))) + db_list.append(db) + + return ConcatDataset(db_list) + + +def create_datastream(dataset_path, **kwargs): + """ create data_loader to stream images 1 by 1 """ + + from torch.utils.data import DataLoader + + if osp.isfile(osp.join(dataset_path, 'calibration.txt')): + db = ETH3DStream(dataset_path, **kwargs) + + elif osp.isdir(osp.join(dataset_path, 'image_left')): + db = TartanAirStream(dataset_path, **kwargs) + + elif osp.isfile(osp.join(dataset_path, 'rgb.txt')): + db = TUMStream(dataset_path, **kwargs) + + elif osp.isdir(osp.join(dataset_path, 'mav0')): + db = EurocStream(dataset_path, **kwargs) + + elif osp.isfile(osp.join(dataset_path, 'calib.txt')): + db = KITTIStream(dataset_path, **kwargs) + + else: + # db = TartanAirStream(dataset_path, **kwargs) + db = TartanAirTestStream(dataset_path, **kwargs) + + stream = DataLoader(db, shuffle=False, batch_size=1, num_workers=4) + return stream + + +def create_imagestream(dataset_path, **kwargs): + """ create data_loader to stream images 1 by 1 """ + from torch.utils.data import DataLoader + + db = ImageStream(dataset_path, **kwargs) + return DataLoader(db, shuffle=False, batch_size=1, num_workers=4) + +def create_stereostream(dataset_path, **kwargs): + """ create data_loader to stream images 1 by 1 """ + from torch.utils.data import DataLoader + + db = StereoStream(dataset_path, **kwargs) + return DataLoader(db, shuffle=False, batch_size=1, num_workers=4) + +def create_rgbdstream(dataset_path, **kwargs): + """ create data_loader to stream images 1 by 1 """ + from torch.utils.data import DataLoader + + db = RGBDStream(dataset_path, **kwargs) + return DataLoader(db, shuffle=False, batch_size=1, num_workers=4) + diff --git a/droid_slam/data_readers/rgbd_utils.py b/droid_slam/data_readers/rgbd_utils.py new file mode 100644 index 00000000..1e674864 --- /dev/null +++ b/droid_slam/data_readers/rgbd_utils.py @@ -0,0 +1,190 @@ +import numpy as np +import os.path as osp + +import torch +from lietorch import SE3 + +import geom.projective_ops as pops +from scipy.spatial.transform import Rotation + + +def parse_list(filepath, skiprows=0): + """ read list data """ + data = np.loadtxt(filepath, delimiter=' ', dtype=np.unicode_, skiprows=skiprows) + return data + +def associate_frames(tstamp_image, tstamp_depth, tstamp_pose, max_dt=1.0): + """ pair images, depths, and poses """ + associations = [] + for i, t in enumerate(tstamp_image): + if tstamp_pose is None: + j = np.argmin(np.abs(tstamp_depth - t)) + if (np.abs(tstamp_depth[j] - t) < max_dt): + associations.append((i, j)) + + else: + j = np.argmin(np.abs(tstamp_depth - t)) + k = np.argmin(np.abs(tstamp_pose - t)) + + if (np.abs(tstamp_depth[j] - t) < max_dt) and \ + (np.abs(tstamp_pose[k] - t) < max_dt): + associations.append((i, j, k)) + + return associations + +def loadtum(datapath, frame_rate=-1): + """ read video data in tum-rgbd format """ + if osp.isfile(osp.join(datapath, 'groundtruth.txt')): + pose_list = osp.join(datapath, 'groundtruth.txt') + + elif osp.isfile(osp.join(datapath, 'pose.txt')): + pose_list = osp.join(datapath, 'pose.txt') + + else: + return None, None, None, None + + image_list = osp.join(datapath, 'rgb.txt') + depth_list = osp.join(datapath, 'depth.txt') + + calib_path = osp.join(datapath, 'calibration.txt') + intrinsic = None + if osp.isfile(calib_path): + intrinsic = np.loadtxt(calib_path, delimiter=' ') + intrinsic = intrinsic.astype(np.float64) + + image_data = parse_list(image_list) + depth_data = parse_list(depth_list) + pose_data = parse_list(pose_list, skiprows=1) + pose_vecs = pose_data[:,1:].astype(np.float64) + + tstamp_image = image_data[:,0].astype(np.float64) + tstamp_depth = depth_data[:,0].astype(np.float64) + tstamp_pose = pose_data[:,0].astype(np.float64) + associations = associate_frames(tstamp_image, tstamp_depth, tstamp_pose) + + # print(len(tstamp_image)) + # print(len(associations)) + + indicies = range(len(associations))[::5] + + # indicies = [ 0 ] + # for i in range(1, len(associations)): + # t0 = tstamp_image[associations[indicies[-1]][0]] + # t1 = tstamp_image[associations[i][0]] + # if t1 - t0 > 1.0 / frame_rate: + # indicies += [ i ] + + images, poses, depths, intrinsics, tstamps = [], [], [], [], [] + for ix in indicies: + (i, j, k) = associations[ix] + images += [ osp.join(datapath, image_data[i,1]) ] + depths += [ osp.join(datapath, depth_data[j,1]) ] + poses += [ pose_vecs[k] ] + tstamps += [ tstamp_image[i] ] + + if intrinsic is not None: + intrinsics += [ intrinsic ] + + return images, depths, poses, intrinsics, tstamps + + +def all_pairs_distance_matrix(poses, beta=2.5): + """ compute distance matrix between all pairs of poses """ + poses = np.array(poses, dtype=np.float32) + poses[:,:3] *= beta # scale to balence rot + trans + poses = SE3(torch.from_numpy(poses)) + + r = (poses[:,None].inv() * poses[None,:]).log() + return r.norm(dim=-1).cpu().numpy() + +def pose_matrix_to_quaternion(pose): + """ convert 4x4 pose matrix to (t, q) """ + q = Rotation.from_matrix(pose[:3, :3]).as_quat() + return np.concatenate([pose[:3, 3], q], axis=0) + +def compute_distance_matrix_flow(poses, disps, intrinsics): + """ compute flow magnitude between all pairs of frames """ + if not isinstance(poses, SE3): + poses = torch.from_numpy(poses).float().cuda()[None] + poses = SE3(poses).inv() + + disps = torch.from_numpy(disps).float().cuda()[None] + intrinsics = torch.from_numpy(intrinsics).float().cuda()[None] + + N = poses.shape[1] + + ii, jj = torch.meshgrid(torch.arange(N), torch.arange(N)) + ii = ii.reshape(-1).cuda() + jj = jj.reshape(-1).cuda() + + MAX_FLOW = 100.0 + matrix = np.zeros((N, N), dtype=np.float32) + + s = 2048 + for i in range(0, ii.shape[0], s): + flow1, val1 = pops.induced_flow(poses, disps, intrinsics, ii[i:i+s], jj[i:i+s]) + flow2, val2 = pops.induced_flow(poses, disps, intrinsics, jj[i:i+s], ii[i:i+s]) + + flow = torch.stack([flow1, flow2], dim=2) + val = torch.stack([val1, val2], dim=2) + + mag = flow.norm(dim=-1).clamp(max=MAX_FLOW) + mag = mag.view(mag.shape[1], -1) + val = val.view(val.shape[1], -1) + + mag = (mag * val).mean(-1) / val.mean(-1) + mag[val.mean(-1) < 0.7] = np.inf + + i1 = ii[i:i+s].cpu().numpy() + j1 = jj[i:i+s].cpu().numpy() + matrix[i1, j1] = mag.cpu().numpy() + + return matrix + + +def compute_distance_matrix_flow2(poses, disps, intrinsics, beta=0.4): + """ compute flow magnitude between all pairs of frames """ + # if not isinstance(poses, SE3): + # poses = torch.from_numpy(poses).float().cuda()[None] + # poses = SE3(poses).inv() + + # disps = torch.from_numpy(disps).float().cuda()[None] + # intrinsics = torch.from_numpy(intrinsics).float().cuda()[None] + + N = poses.shape[1] + + ii, jj = torch.meshgrid(torch.arange(N), torch.arange(N)) + ii = ii.reshape(-1) + jj = jj.reshape(-1) + + MAX_FLOW = 128.0 + matrix = np.zeros((N, N), dtype=np.float32) + + s = 2048 + for i in range(0, ii.shape[0], s): + flow1a, val1a = pops.induced_flow(poses, disps, intrinsics, ii[i:i+s], jj[i:i+s], tonly=True) + flow1b, val1b = pops.induced_flow(poses, disps, intrinsics, ii[i:i+s], jj[i:i+s]) + flow2a, val2a = pops.induced_flow(poses, disps, intrinsics, jj[i:i+s], ii[i:i+s], tonly=True) + flow2b, val2b = pops.induced_flow(poses, disps, intrinsics, ii[i:i+s], jj[i:i+s]) + + flow1 = flow1a + beta * flow1b + val1 = val1a * val2b + + flow2 = flow2a + beta * flow2b + val2 = val2a * val2b + + flow = torch.stack([flow1, flow2], dim=2) + val = torch.stack([val1, val2], dim=2) + + mag = flow.norm(dim=-1).clamp(max=MAX_FLOW) + mag = mag.view(mag.shape[1], -1) + val = val.view(val.shape[1], -1) + + mag = (mag * val).mean(-1) / val.mean(-1) + mag[val.mean(-1) < 0.8] = np.inf + + i1 = ii[i:i+s].cpu().numpy() + j1 = jj[i:i+s].cpu().numpy() + matrix[i1, j1] = mag.cpu().numpy() + + return matrix diff --git a/droid_slam/data_readers/stream.py b/droid_slam/data_readers/stream.py new file mode 100644 index 00000000..1b17d706 --- /dev/null +++ b/droid_slam/data_readers/stream.py @@ -0,0 +1,234 @@ + +import numpy as np +import torch +import torch.utils.data as data +import torch.nn.functional as F + +import csv +import os +import cv2 +import math +import random +import json +import pickle +import os.path as osp + +from .rgbd_utils import * + +class RGBDStream(data.Dataset): + def __init__(self, datapath, frame_rate=-1, image_size=[384,512], crop_size=[0,0]): + self.datapath = datapath + self.frame_rate = frame_rate + self.image_size = image_size + self.crop_size = crop_size + self._build_dataset_index() + + @staticmethod + def image_read(image_file): + return cv2.imread(image_file) + + @staticmethod + def depth_read(depth_file): + return np.load(depth_file) + + def __len__(self): + return len(self.images) + + def __getitem__(self, index): + """ return training video """ + image = self.__class__.image_read(self.images[index]) + image = torch.from_numpy(image).float() + image = image.permute(2, 0, 1) + + try: + tstamp = self.tstamps[index] + except: + tstamp = index + + pose = torch.from_numpy(self.poses[index]).float() + intrinsic = torch.from_numpy(self.intrinsics[index]).float() + + # resize image + sx = self.image_size[1] / image.shape[2] + sy = self.image_size[0] / image.shape[1] + + image = F.interpolate(image[None], self.image_size, mode='bilinear', align_corners=False)[0] + + fx, fy, cx, cy = intrinsic.unbind(dim=0) + fx, cx = sx * fx, sx * cx + fy, cy = sy * fy, sy * cy + + # crop image + if self.crop_size[0] > 0: + cy = cy - self.crop_size[0] + image = image[:,self.crop_size[0]:-self.crop_size[0],:] + + if self.crop_size[1] > 0: + cx = cx - self.crop_size[1] + image = image[:,:,self.crop_size[1]:-self.crop_size[1]] + + intrinsic = torch.stack([fx, fy, cx, cy]) + + return tstamp, image, pose, intrinsic + + +class ImageStream(data.Dataset): + def __init__(self, datapath, intrinsics, rate=1, image_size=[384,512]): + rgb_list = osp.join(datapath, 'rgb.txt') + if os.path.isfile(rgb_list): + rgb_list = np.loadtxt(rgb_list, delimiter=' ', dtype=np.unicode_) + self.timestamps = rgb_list[:,0].astype(np.float) + self.images = [os.path.join(datapath, x) for x in rgb_list[:,1]] + self.images = self.images[::rate] + self.timestamps = self.timestamps[::rate] + + else: + import glob + self.images = sorted(glob.glob(osp.join(datapath, '*.jpg'))) + sorted(glob.glob(osp.join(datapath, '*.png'))) + self.images = self.images[::rate] + + self.intrinsics = intrinsics + self.image_size = image_size + + def __len__(self): + return len(self.images) + + @staticmethod + def image_read(imfile): + return cv2.imread(imfile) + + def __getitem__(self, index): + """ return training video """ + image = self.__class__.image_read(self.images[index]) + + try: + tstamp = self.timestamps[index] + except: + tstamp = index + + ht0, wd0 = image.shape[:2] + ht1, wd1 = self.image_size + + intrinsics = torch.as_tensor(self.intrinsics) + intrinsics[0] *= wd1 / wd0 + intrinsics[1] *= ht1 / ht0 + intrinsics[2] *= wd1 / wd0 + intrinsics[3] *= ht1 / ht0 + + # resize image + ikwargs = {'mode': 'bilinear', 'align_corners': True} + image = torch.from_numpy(image).float().permute(2, 0, 1) + image = F.interpolate(image[None], self.image_size, **ikwargs)[0] + + return tstamp, image, intrinsics + + + +class StereoStream(data.Dataset): + def __init__(self, datapath, intrinsics, rate=1, image_size=[384,512], + map_left=None, map_right=None, left_root='image_left', right_root='image_right'): + import glob + self.intrinsics = intrinsics + self.image_size = image_size + + imgs = sorted(glob.glob(osp.join(datapath, left_root, '*.png')))[::rate] + self.images_l = [] + self.images_r = [] + self.tstamps = [] + + for img_l in imgs: + img_r = img_l.replace(left_root, right_root) + if os.path.isfile(img_r): + t = np.float(img_l.split('/')[-1].replace('.png', '')) + self.tstamps.append(t) + self.images_l += [ img_l ] + self.images_r += [ img_r ] + + self.map_left = map_left + self.map_right = map_right + + def __len__(self): + return len(self.images_l) + + @staticmethod + def image_read(imfile, imap=None): + image = cv2.imread(imfile) + if imap is not None: + image = cv2.remap(image, imap[0], imap[1], interpolation=cv2.INTER_LINEAR) + return image + + def __getitem__(self, index): + """ return training video """ + tstamp = self.tstamps[index] + image_l = self.__class__.image_read(self.images_l[index], self.map_left) + image_r = self.__class__.image_read(self.images_r[index], self.map_right) + + ht0, wd0 = image_l.shape[:2] + ht1, wd1 = self.image_size + + intrinsics = torch.as_tensor(self.intrinsics) + intrinsics[0] *= wd1 / wd0 + intrinsics[1] *= ht1 / ht0 + intrinsics[2] *= wd1 / wd0 + intrinsics[3] *= ht1 / ht0 + + image_l = torch.from_numpy(image_l).float().permute(2, 0, 1) + image_r = torch.from_numpy(image_r).float().permute(2, 0, 1) + + # resize image + ikwargs = {'mode': 'bilinear', 'align_corners': True} + image_l = F.interpolate(image_l[None], self.image_size, **ikwargs)[0] + image_r = F.interpolate(image_r[None], self.image_size, **ikwargs)[0] + + return tstamp, image_l, image_r, intrinsics + + + +# class RGBDStream(data.Dataset): +# def __init__(self, datapath, intrinsics=None, rate=1, image_size=[384,512]): +# assoc_file = osp.join(datapath, 'associated.txt') +# assoc_list = np.loadtxt(assoc_file, delimiter=' ', dtype=np.unicode_) + +# self.intrinsics = intrinsics +# self.image_size = image_size + +# self.timestamps = assoc_list[:,0].astype(np.float)[::rate] +# self.images = [os.path.join(datapath, x) for x in assoc_list[:,1]][::rate] +# self.depths = [os.path.join(datapath, x) for x in assoc_list[:,3]][::rate] + +# def __len__(self): +# return len(self.images) + +# @staticmethod +# def image_read(imfile): +# return cv2.imread(imfile) + +# @staticmethod +# def depth_read(depth_file): +# depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH) +# return depth.astype(np.float32) / 5000.0 + +# def __getitem__(self, index): +# """ return training video """ +# tstamp = self.timestamps[index] +# image = self.__class__.image_read(self.images[index]) +# depth = self.__class__.depth_read(self.depths[index]) + +# ht0, wd0 = image.shape[:2] +# ht1, wd1 = self.image_size + +# intrinsics = torch.as_tensor(self.intrinsics) +# intrinsics[0] *= wd1 / wd0 +# intrinsics[1] *= ht1 / ht0 +# intrinsics[2] *= wd1 / wd0 +# intrinsics[3] *= ht1 / ht0 + +# # resize image +# ikwargs = {'mode': 'bilinear', 'align_corners': True} +# image = torch.from_numpy(image).float().permute(2, 0, 1) +# image = F.interpolate(image[None], self.image_size, **ikwargs)[0] + +# depth = torch.from_numpy(depth).float()[None,None] +# depth = F.interpolate(depth, self.image_size, mode='nearest').squeeze() + +# return tstamp, image, depth, intrinsics diff --git a/droid_slam/data_readers/tartan.py b/droid_slam/data_readers/tartan.py new file mode 100644 index 00000000..49780ca9 --- /dev/null +++ b/droid_slam/data_readers/tartan.py @@ -0,0 +1,138 @@ + +import numpy as np +import torch +import glob +import cv2 +import os +import os.path as osp + +from lietorch import SE3 +from .base import RGBDDataset +from .stream import RGBDStream + +cur_path = osp.dirname(osp.abspath(__file__)) +test_split = osp.join(cur_path, 'tartan_test.txt') +test_split = open(test_split).read().split() + + +class TartanAir(RGBDDataset): + + # scale depths to balance rot & trans + DEPTH_SCALE = 5.0 + + def __init__(self, mode='training', **kwargs): + self.mode = mode + self.n_frames = 2 + super(TartanAir, self).__init__(name='TartanAir', **kwargs) + + @staticmethod + def is_test_scene(scene): + # print(scene, any(x in scene for x in test_split)) + return any(x in scene for x in test_split) + + def _build_dataset(self): + from tqdm import tqdm + print("Building TartanAir dataset") + + scene_info = {} + scenes = glob.glob(osp.join(self.root, '*/*/*/*')) + for scene in tqdm(sorted(scenes)): + images = sorted(glob.glob(osp.join(scene, 'image_left/*.png'))) + depths = sorted(glob.glob(osp.join(scene, 'depth_left/*.npy'))) + + poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ') + poses = poses[:, [1, 2, 0, 4, 5, 3, 6]] + poses[:,:3] /= TartanAir.DEPTH_SCALE + intrinsics = [TartanAir.calib_read()] * len(images) + + # graph of co-visible frames based on flow + graph = self.build_frame_graph(poses, depths, intrinsics) + + scene = '/'.join(scene.split('/')) + scene_info[scene] = {'images': images, 'depths': depths, + 'poses': poses, 'intrinsics': intrinsics, 'graph': graph} + + return scene_info + + @staticmethod + def calib_read(): + return np.array([320.0, 320.0, 320.0, 240.0]) + + @staticmethod + def image_read(image_file): + return cv2.imread(image_file) + + @staticmethod + def depth_read(depth_file): + depth = np.load(depth_file) / TartanAir.DEPTH_SCALE + depth[depth==np.nan] = 1.0 + depth[depth==np.inf] = 1.0 + return depth + + +class TartanAirStream(RGBDStream): + def __init__(self, datapath, **kwargs): + super(TartanAirStream, self).__init__(datapath=datapath, **kwargs) + + def _build_dataset_index(self): + """ build list of images, poses, depths, and intrinsics """ + self.root = 'datasets/TartanAir' + + scene = osp.join(self.root, self.datapath) + image_glob = osp.join(scene, 'image_left/*.png') + images = sorted(glob.glob(image_glob)) + + poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ') + poses = poses[:, [1, 2, 0, 4, 5, 3, 6]] + + poses = SE3(torch.as_tensor(poses)) + poses = poses[[0]].inv() * poses + poses = poses.data.cpu().numpy() + + intrinsic = self.calib_read(self.datapath) + intrinsics = np.tile(intrinsic[None], (len(images), 1)) + + self.images = images[::int(self.frame_rate)] + self.poses = poses[::int(self.frame_rate)] + self.intrinsics = intrinsics[::int(self.frame_rate)] + + @staticmethod + def calib_read(datapath): + return np.array([320.0, 320.0, 320.0, 240.0]) + + @staticmethod + def image_read(image_file): + return cv2.imread(image_file) + + +class TartanAirTestStream(RGBDStream): + def __init__(self, datapath, **kwargs): + super(TartanAirTestStream, self).__init__(datapath=datapath, **kwargs) + + def _build_dataset_index(self): + """ build list of images, poses, depths, and intrinsics """ + self.root = 'datasets/mono' + image_glob = osp.join(self.root, self.datapath, '*.png') + images = sorted(glob.glob(image_glob)) + + poses = np.loadtxt(osp.join(self.root, 'mono_gt', self.datapath + '.txt'), delimiter=' ') + poses = poses[:, [1, 2, 0, 4, 5, 3, 6]] + + poses = SE3(torch.as_tensor(poses)) + poses = poses[[0]].inv() * poses + poses = poses.data.cpu().numpy() + + intrinsic = self.calib_read(self.datapath) + intrinsics = np.tile(intrinsic[None], (len(images), 1)) + + self.images = images[::int(self.frame_rate)] + self.poses = poses[::int(self.frame_rate)] + self.intrinsics = intrinsics[::int(self.frame_rate)] + + @staticmethod + def calib_read(datapath): + return np.array([320.0, 320.0, 320.0, 240.0]) + + @staticmethod + def image_read(image_file): + return cv2.imread(image_file) \ No newline at end of file diff --git a/droid_slam/data_readers/tartan_test.txt b/droid_slam/data_readers/tartan_test.txt new file mode 100644 index 00000000..d52d88da --- /dev/null +++ b/droid_slam/data_readers/tartan_test.txt @@ -0,0 +1,32 @@ +abandonedfactory/abandonedfactory/Easy/P011 +abandonedfactory/abandonedfactory/Hard/P011 +abandonedfactory_night/abandonedfactory_night/Easy/P013 +abandonedfactory_night/abandonedfactory_night/Hard/P014 +amusement/amusement/Easy/P008 +amusement/amusement/Hard/P007 +carwelding/carwelding/Easy/P007 +endofworld/endofworld/Easy/P009 +gascola/gascola/Easy/P008 +gascola/gascola/Hard/P009 +hospital/hospital/Easy/P036 +hospital/hospital/Hard/P049 +japanesealley/japanesealley/Easy/P007 +japanesealley/japanesealley/Hard/P005 +neighborhood/neighborhood/Easy/P021 +neighborhood/neighborhood/Hard/P017 +ocean/ocean/Easy/P013 +ocean/ocean/Hard/P009 +office2/office2/Easy/P011 +office2/office2/Hard/P010 +office/office/Hard/P007 +oldtown/oldtown/Easy/P007 +oldtown/oldtown/Hard/P008 +seasidetown/seasidetown/Easy/P009 +seasonsforest/seasonsforest/Easy/P011 +seasonsforest/seasonsforest/Hard/P006 +seasonsforest_winter/seasonsforest_winter/Easy/P009 +seasonsforest_winter/seasonsforest_winter/Hard/P018 +soulcity/soulcity/Easy/P012 +soulcity/soulcity/Hard/P009 +westerndesert/westerndesert/Easy/P013 +westerndesert/westerndesert/Hard/P007 diff --git a/droid_slam/depth_video.py b/droid_slam/depth_video.py new file mode 100644 index 00000000..dbc35279 --- /dev/null +++ b/droid_slam/depth_video.py @@ -0,0 +1,189 @@ +import numpy as np +import torch +import lietorch +import droid_backends + +from torch.multiprocessing import Process, Queue, Lock, Value +from collections import OrderedDict + +from droid_net import cvx_upsample +import geom.projective_ops as pops + +class DepthVideo: + def __init__(self, image_size=[480, 640], buffer=1024, device="cuda:0"): + + # current keyframe count + self.counter = Value('i', 0) + self.ready = Value('i', 0) + self.ht = ht = image_size[0] + self.wd = wd = image_size[1] + + ### state attributes ### + self.tstamp = torch.zeros(buffer, device="cuda", dtype=torch.float).share_memory_() + self.images = torch.zeros(buffer, 3, ht, wd, device="cuda", dtype=torch.uint8) + self.dirty = torch.zeros(buffer, device="cuda", dtype=torch.bool).share_memory_() + self.red = torch.zeros(buffer, device="cuda", dtype=torch.bool).share_memory_() + self.poses = torch.zeros(buffer, 7, device="cuda", dtype=torch.float).share_memory_() + self.disps = torch.ones(buffer, ht//8, wd//8, device="cuda", dtype=torch.float).share_memory_() + self.disps_up = torch.zeros(buffer, ht, wd, device="cuda", dtype=torch.float).share_memory_() + self.intrinsics = torch.zeros(buffer, 4, device="cuda", dtype=torch.float).share_memory_() + + ### feature attributes ### + self.fmaps = torch.zeros(buffer, 128, ht//8, wd//8, dtype=torch.half, device="cuda").share_memory_() + self.nets = torch.zeros(buffer, 128, ht//8, wd//8, dtype=torch.half, device="cuda").share_memory_() + self.inps = torch.zeros(buffer, 128, ht//8, wd//8, dtype=torch.half, device="cuda").share_memory_() + + # initialize poses to identity transformation + self.poses[:] = torch.as_tensor([0, 0, 0, 0, 0, 0, 1], dtype=torch.float, device="cuda") + + def get_lock(self): + return self.counter.get_lock() + + def __item_setter(self, index, item): + if isinstance(index, int) and index >= self.counter.value: + self.counter.value = index + 1 + + elif isinstance(index, torch.Tensor) and index.max().item() > self.counter.value: + self.counter.value = index.max().item() + 1 + + # self.dirty[index] = True + self.tstamp[index] = item[0] + self.images[index] = item[1] + + if item[2] is not None: + self.poses[index] = item[2] + + if item[3] is not None: + self.disps[index] = item[3] + + if item[4] is not None: + self.intrinsics[index] = item[4] + + if len(item) > 5: + self.fmaps[index] = item[5] + + if len(item) > 6: + self.nets[index] = item[6] + + if len(item) > 7: + self.inps[index] = item[7] + + def __setitem__(self, index, item): + with self.get_lock(): + self.__item_setter(index, item) + + def __getitem__(self, index): + """ index the depth video """ + + with self.get_lock(): + # support negative indexing + if isinstance(index, int) and index < 0: + index = self.counter.value + index + + item = ( + self.poses[index], + self.disps[index], + self.intrinsics[index], + self.fmaps[index], + self.nets[index], + self.inps[index]) + + return item + + def append(self, *item): + with self.get_lock(): + self.__item_setter(self.counter.value, item) + + + ### geometric operations ### + + @staticmethod + def format_indicies(ii, jj): + """ to device, long, {-1} """ + + if not isinstance(ii, torch.Tensor): + ii = torch.as_tensor(ii) + + if not isinstance(jj, torch.Tensor): + jj = torch.as_tensor(jj) + + ii = ii.to(device="cuda", dtype=torch.long).reshape(-1) + jj = jj.to(device="cuda", dtype=torch.long).reshape(-1) + + return ii, jj + + def upsample(self, ix, mask): + """ upsample disparity """ + + disps_up = cvx_upsample(self.disps[ix].unsqueeze(-1), mask) + self.disps_up[ix] = disps_up.squeeze() + + def normalize(self): + """ normalize depth and poses """ + + with self.get_lock(): + s = self.disps[:self.counter.value].mean() + self.disps[:self.counter.value] /= s + self.poses[:self.counter.value,:3] *= s + self.dirty[:self.counter.value] = True + + + def reproject(self, ii, jj): + """ project points from ii -> jj """ + ii, jj = DepthVideo.format_indicies(ii, jj) + Gs = lietorch.SE3(self.poses[None]) + + coords, valid_mask = \ + pops.projective_transform(Gs, self.disps[None], self.intrinsics[None], ii, jj) + + return coords, valid_mask + + def distance(self, ii=None, jj=None, beta=0.3, bidirectional=True): + """ frame distance metric """ + + return_matrix = False + if ii is None: + return_matrix = True + N = self.counter.value + ii, jj = torch.meshgrid(torch.arange(N), torch.arange(N)) + + ii, jj = DepthVideo.format_indicies(ii, jj) + + if bidirectional: + + poses = self.poses[:self.counter.value].clone() + + d1 = droid_backends.frame_distance( + poses, self.disps, self.intrinsics[0], ii, jj, beta) + + d2 = droid_backends.frame_distance( + poses, self.disps, self.intrinsics[0], jj, ii, beta) + + d = .5 * (d1 + d2) + + else: + d = droid_backends.frame_distance( + self.poses, self.disps, self.intrinsics[0], ii, jj, beta) + + if return_matrix: + return d.reshape(N, N) + + return d + + def ba(self, target, weight, eta, ii, jj, t0=1, t1=None, itrs=2, lm=1e-4, ep=0.1, motion_only=False): + """ dense bundle adjustment (DBA) """ + + with self.get_lock(): + + # [t0, t1] window of bundle adjustment optimization + if t1 is None: + t1 = max(ii.max().item(), jj.max().item()) + 1 + + if eta is None: + k = torch.unique(torch.cat([ii, jj], 0)).shape[0] + eta = 1e-7 * torch.ones([k, self.ht//8, self.wd//8], device="cuda") + + droid_backends.ba(self.poses, self.disps, self.intrinsics[0], + target, weight, eta, ii, jj, t0, t1, itrs, lm, ep, motion_only) + + self.disps.clamp_(min=0.001) diff --git a/droid_slam/droid.py b/droid_slam/droid.py new file mode 100644 index 00000000..813afa6c --- /dev/null +++ b/droid_slam/droid.py @@ -0,0 +1,89 @@ +import torch +import lietorch +import numpy as np + +from droid_net import DroidNet +from depth_video import DepthVideo +from motion_filter import MotionFilter +from droid_frontend import DroidFrontend +from droid_backend import DroidBackend +from trajectory_filler import PoseTrajectoryFiller + +from collections import OrderedDict +from torch.multiprocessing import Process + + +class Droid: + def __init__(self, args): + super(Droid, self).__init__() + self.load_weights(args.weights) + self.args = args + self.disable_vis = args.disable_vis + + # store images, depth, poses, intrinsics (shared between processes) + self.video = DepthVideo(args.image_size, args.buffer) + + # filter incoming frames so that there is enough motion + self.filterx = MotionFilter(self.net, self.video, thresh=args.filter_thresh) + + # frontend process + self.frontend = DroidFrontend(self.net, self.video, self.args) + + # backend process + self.backend = DroidBackend(self.net, self.video, self.args) + + # visualizer + if not self.disable_vis: + from visualization import droid_visualization + self.visualizer = Process(target=droid_visualization, args=(self.video,)) + self.visualizer.start() + + # post processor - fill in poses for non-keyframes + self.traj_filler = PoseTrajectoryFiller(self.net, self.video) + + + def load_weights(self, weights): + """ load trained model weights """ + + print(weights) + self.net = DroidNet() + state_dict = OrderedDict([ + (k.replace("module.", ""), v) for (k, v) in torch.load(weights).items()]) + + state_dict["update.weight.2.weight"] = state_dict["update.weight.2.weight"][:2] + state_dict["update.weight.2.bias"] = state_dict["update.weight.2.bias"][:2] + state_dict["update.delta.2.weight"] = state_dict["update.delta.2.weight"][:2] + state_dict["update.delta.2.bias"] = state_dict["update.delta.2.bias"][:2] + + self.net.load_state_dict(state_dict) + self.net.to("cuda:0").eval() + + def track(self, tstamp, image, depth=None, intrinsics=None): + """ main thread - update map """ + + with torch.no_grad(): + # check there is enough motion + self.filterx.track(tstamp, image, depth, intrinsics) + + # local bundle adjustment + self.frontend() + + # global bundle adjustment + # self.backend() + + def terminate(self, stream=None): + """ terminate the visualization process, return poses [t, q] """ + + del self.frontend + + torch.cuda.empty_cache() + print("#" * 32) + self.backend(7) + + torch.cuda.empty_cache() + print("#" * 32) + self.backend(12) + + camera_trajectory = self.traj_filler(stream) + return camera_trajectory.inv().data.cpu().numpy() + diff --git a/droid_slam/droid_backend.py b/droid_slam/droid_backend.py new file mode 100644 index 00000000..9bdc2f12 --- /dev/null +++ b/droid_slam/droid_backend.py @@ -0,0 +1,40 @@ +import torch +import lietorch +import numpy as np + +from lietorch import SE3 +from factor_graph import FactorGraph + + +class DroidBackend: + def __init__(self, net, video, args): + self.video = video + self.update_op = net.update + + # global optimization window + self.t0 = 0 + self.t1 = 0 + + self.beta = args.beta + self.backend_thresh = args.backend_thresh + self.backend_radius = args.backend_radius + self.backend_nms = args.backend_nms + + @torch.no_grad() + def __call__(self, steps=12): + """ main update """ + + t = self.video.counter.value + self.video.normalize() + + graph = FactorGraph(self.video, self.update_op, corr_impl="alt", max_factors=100000) + + graph.add_proximity_factors(rad=self.backend_radius, + nms=self.backend_nms, + thresh=self.backend_thresh, + beta=self.beta) + + graph.update_lowmem(steps=steps) + graph.clear_edges() + self.video.dirty[:t] = True + diff --git a/droid_slam/droid_frontend.py b/droid_slam/droid_frontend.py new file mode 100644 index 00000000..d2fe0ec6 --- /dev/null +++ b/droid_slam/droid_frontend.py @@ -0,0 +1,113 @@ +import torch +import lietorch +import numpy as np + +from lietorch import SE3 +from factor_graph import FactorGraph + + +class DroidFrontend: + def __init__(self, net, video, args): + self.video = video + self.update_op = net.update + self.graph = FactorGraph(video, net.update, max_factors=48) + + # local optimization window + self.t0 = 0 + self.t1 = 0 + + # frontent variables + self.is_initialized = False + self.count = 0 + + self.max_age = 25 + self.iters1 = 4 + self.iters2 = 2 + + self.warmup = args.warmup + self.beta = args.beta + self.frontend_nms = args.frontend_nms + self.keyframe_thresh = args.keyframe_thresh + self.frontend_window = args.frontend_window + self.frontend_thresh = args.frontend_thresh + self.frontend_radius = args.frontend_radius + + def __update(self): + """ add edges, perform update """ + + self.count += 1 + self.t1 += 1 + + if self.graph.corr is not None: + self.graph.rm_factors(self.graph.age > self.max_age, store=True) + + self.graph.add_proximity_factors(self.t1-5, max(self.t1-self.frontend_window, 0), + rad=self.frontend_radius, nms=self.frontend_nms, thresh=self.frontend_thresh, beta=self.beta, remove=True) + + for itr in range(self.iters1): + self.graph.update(None, None, use_inactive=True) + + # set initial pose for next frame + poses = SE3(self.video.poses) + d = self.video.distance([self.t1-3], [self.t1-2], beta=self.beta, bidirectional=True) + + if d.item() < self.keyframe_thresh: + self.graph.rm_keyframe(self.t1 - 2) + + with self.video.get_lock(): + self.video.counter.value -= 1 + self.t1 -= 1 + + else: + for itr in range(self.iters2): + self.graph.update(None, None, use_inactive=True) + + # set pose for next itration + self.video.poses[self.t1] = self.video.poses[self.t1-1] + self.video.disps[self.t1] = self.video.disps[self.t1-1].mean() + + # update visualization + self.video.dirty[self.graph.ii.min():self.t1] = True + + def __initialize(self): + """ initialize the SLAM system """ + + self.t0 = 0 + self.t1 = self.video.counter.value + + self.graph.add_neighborhood_factors(self.t0, self.t1, r=3) + + for itr in range(8): + self.graph.update(1, use_inactive=True) + + self.graph.add_proximity_factors(0, 0, rad=2, nms=2, thresh=self.frontend_thresh) + + for itr in range(12): + self.graph.update(1, use_inactive=True) + + # self.video.normalize() + self.video.poses[self.t1] = self.video.poses[self.t1-1].clone() + self.video.disps[self.t1] = self.video.disps[self.t1-4:self.t1].mean() + + # initialization complete + self.is_initialized = True + self.last_pose = self.video.poses[self.t1-1].clone() + self.last_disp = self.video.disps[self.t1-1].clone() + self.last_time = self.video.tstamp[self.t1-1].clone() + + with self.video.get_lock(): + self.video.ready.value = 1 + self.video.dirty[:self.t1] = True + + def __call__(self): + """ main update """ + + # do initialization + if not self.is_initialized and self.video.counter.value == self.warmup: + self.__initialize() + + # do update + elif self.is_initialized and self.t1 < self.video.counter.value: + self.__update() + + diff --git a/droid_slam/droid_net.py b/droid_slam/droid_net.py new file mode 100644 index 00000000..0e360314 --- /dev/null +++ b/droid_slam/droid_net.py @@ -0,0 +1,222 @@ +import numpy as np +import torch +import torch.nn as nn +import torch.nn.functional as F +from collections import OrderedDict + +from modules.extractor import BasicEncoder +from modules.corr import CorrBlock +from modules.gru import ConvGRU +from modules.clipping import GradientClip + +from lietorch import SE3 +from geom.ba import BA + +import geom.projective_ops as pops +from geom.graph_utils import graph_to_edge_list, keyframe_indicies + +from torch_scatter import scatter_mean + + +def cvx_upsample(data, mask): + """ upsample pixel-wise transformation field """ + batch, ht, wd, dim = data.shape + data = data.permute(0, 3, 1, 2) + mask = mask.view(batch, 1, 9, 8, 8, ht, wd) + mask = torch.softmax(mask, dim=2) + + up_data = F.unfold(data, [3,3], padding=1) + up_data = up_data.view(batch, dim, 9, 1, 1, ht, wd) + + up_data = torch.sum(mask * up_data, dim=2) + up_data = up_data.permute(0, 4, 2, 5, 3, 1) + up_data = up_data.reshape(batch, 8*ht, 8*wd, dim) + + return up_data + +def upsample_disp(disp, mask): + batch, num, ht, wd = disp.shape + disp = disp.view(batch*num, ht, wd, 1) + mask = mask.view(batch*num, -1, ht, wd) + return cvx_upsample(disp, mask).view(batch, num, 8*ht, 8*wd) + + +class GraphAgg(nn.Module): + def __init__(self): + super(GraphAgg, self).__init__() + self.conv1 = nn.Conv2d(128, 128, 3, padding=1) + self.conv2 = nn.Conv2d(128, 128, 3, padding=1) + self.relu = nn.ReLU(inplace=True) + + self.eta = nn.Sequential( + nn.Conv2d(128, 1, 3, padding=1), + GradientClip(), + nn.Softplus()) + + self.upmask = nn.Sequential( + nn.Conv2d(128, 8*8*9, 1, padding=0)) + + def forward(self, net, ii): + batch, num, ch, ht, wd = net.shape + net = net.view(batch*num, ch, ht, wd) + + _, ix = torch.unique(ii, return_inverse=True) + net = self.relu(self.conv1(net)) + + net = net.view(batch, num, 128, ht, wd) + net = scatter_mean(net, ix, dim=1) + net = net.view(-1, 128, ht, wd) + + net = self.relu(self.conv2(net)) + + eta = self.eta(net).view(batch, -1, ht, wd) + upmask = self.upmask(net).view(batch, -1, 8*8*9, ht, wd) + + return .01 * eta, upmask + + +class UpdateModule(nn.Module): + def __init__(self): + super(UpdateModule, self).__init__() + cor_planes = 4 * (2*3 + 1)**2 + + self.corr_encoder = nn.Sequential( + nn.Conv2d(cor_planes, 128, 1, padding=0), + nn.ReLU(inplace=True), + nn.Conv2d(128, 128, 3, padding=1), + nn.ReLU(inplace=True)) + + self.flow_encoder = nn.Sequential( + nn.Conv2d(4, 128, 7, padding=3), + nn.ReLU(inplace=True), + nn.Conv2d(128, 64, 3, padding=1), + nn.ReLU(inplace=True)) + + self.weight = nn.Sequential( + nn.Conv2d(128, 128, 3, padding=1), + nn.ReLU(inplace=True), + nn.Conv2d(128, 2, 3, padding=1), + GradientClip(), + nn.Sigmoid()) + + self.delta = nn.Sequential( + nn.Conv2d(128, 128, 3, padding=1), + nn.ReLU(inplace=True), + nn.Conv2d(128, 2, 3, padding=1), + GradientClip()) + + self.gru = ConvGRU(128, 128+128+64) + self.agg = GraphAgg() + + def forward(self, net, inp, corr, flow=None, ii=None, jj=None): + """ RaftSLAM update operator """ + + batch, num, ch, ht, wd = net.shape + + if flow is None: + flow = torch.zeros(batch, num, 4, ht, wd, device=net.device) + + output_dim = (batch, num, -1, ht, wd) + net = net.view(batch*num, -1, ht, wd) + inp = inp.view(batch*num, -1, ht, wd) + corr = corr.view(batch*num, -1, ht, wd) + flow = flow.view(batch*num, -1, ht, wd) + + corr = self.corr_encoder(corr) + flow = self.flow_encoder(flow) + net = self.gru(net, inp, corr, flow) + + ### update variables ### + delta = self.delta(net).view(*output_dim) + weight = self.weight(net).view(*output_dim) + + delta = delta.permute(0,1,3,4,2)[...,:2].contiguous() + weight = weight.permute(0,1,3,4,2)[...,:2].contiguous() + + net = net.view(*output_dim) + + if ii is not None: + eta, upmask = self.agg(net, ii.to(net.device)) + return net, delta, weight, eta, upmask + + else: + return net, delta, weight + + +class DroidNet(nn.Module): + def __init__(self): + super(DroidNet, self).__init__() + self.fnet = BasicEncoder(output_dim=128, norm_fn='instance') + self.cnet = BasicEncoder(output_dim=256, norm_fn='none') + self.update = UpdateModule() + + + def extract_features(self, images): + """ run feeature extraction networks """ + + # normalize images + images = images[:, :, [2,1,0]] / 255.0 + mean = torch.as_tensor([0.485, 0.456, 0.406], device=images.device) + std = torch.as_tensor([0.229, 0.224, 0.225], device=images.device) + images = images.sub_(mean[:, None, None]).div_(std[:, None, None]) + + fmaps = self.fnet(images) + net = self.cnet(images) + + net, inp = net.split([128,128], dim=2) + net = torch.tanh(net) + inp = torch.relu(inp) + return fmaps, net, inp + + + def forward(self, Gs, images, disps, intrinsics, graph=None, num_steps=12, fixedp=2): + """ Estimates SE3 or Sim3 between pair of frames """ + + u = keyframe_indicies(graph) + ii, jj, kk = graph_to_edge_list(graph) + + ii = ii.to(device=images.device, dtype=torch.long) + jj = jj.to(device=images.device, dtype=torch.long) + + fmaps, net, inp = self.extract_features(images) + net, inp = net[:,ii], inp[:,ii] + corr_fn = CorrBlock(fmaps[:,ii], fmaps[:,jj], num_levels=4, radius=3) + + ht, wd = images.shape[-2:] + coords0 = pops.coords_grid(ht//8, wd//8, device=images.device) + + coords1, _ = pops.projective_transform(Gs, disps, intrinsics, ii, jj) + target = coords1.clone() + + Gs_list, disp_list, residual_list = [], [], [] + for step in range(num_steps): + Gs = Gs.detach() + disps = disps.detach() + coords1 = coords1.detach() + target = target.detach() + + # extract motion features + corr = corr_fn(coords1) + resd = target - coords1 + flow = coords1 - coords0 + + motion = torch.cat([flow, resd], dim=-1) + motion = motion.permute(0,1,4,2,3).clamp(-64.0, 64.0) + + net, delta, weight, eta, upmask = \ + self.update(net, inp, corr, motion, ii, jj) + + target = coords1 + delta + + for i in range(2): + Gs, disps = BA(target, weight, eta, Gs, disps, intrinsics, ii, jj, fixedp=2) + + coords1, valid_mask = pops.projective_transform(Gs, disps, intrinsics, ii, jj) + residual = (target - coords1) + + Gs_list.append(Gs) + disp_list.append(upsample_disp(disps, upmask)) + residual_list.append(valid_mask * residual) + + + return Gs_list, disp_list, residual_list diff --git a/droid_slam/factor_graph.py b/droid_slam/factor_graph.py new file mode 100644 index 00000000..9a8b09c7 --- /dev/null +++ b/droid_slam/factor_graph.py @@ -0,0 +1,349 @@ +import torch +import lietorch +import numpy as np + +import matplotlib.pyplot as plt +from lietorch import SE3 +from modules.corr import CorrBlock, AltCorrBlock +import geom.projective_ops as pops + + +class FactorGraph: + def __init__(self, video, update_op, device="cuda:0", corr_impl="volume", max_factors=-1): + self.video = video + self.update_op = update_op + self.device = device + self.max_factors = max_factors + self.corr_impl = corr_impl + + # operator at 1/8 resolution + self.ht = ht = video.ht // 8 + self.wd = wd = video.wd // 8 + + self.coords0 = pops.coords_grid(ht, wd, device=device) + self.ii = torch.as_tensor([], dtype=torch.long, device=device) + self.jj = torch.as_tensor([], dtype=torch.long, device=device) + self.age = torch.as_tensor([], dtype=torch.long, device=device) + + self.corr, self.net, self.inp = None, None, None + self.damping = 1e-6 * torch.ones_like(self.video.disps) + + self.target = torch.zeros([1, 0, ht, wd, 2], device=device, dtype=torch.float) + self.weight = torch.zeros([1, 0, ht, wd, 2], device=device, dtype=torch.float) + + # inactive factors + self.ii_inac = torch.as_tensor([], dtype=torch.long, device=device) + self.jj_inac = torch.as_tensor([], dtype=torch.long, device=device) + self.ii_bad = torch.as_tensor([], dtype=torch.long, device=device) + self.jj_bad = torch.as_tensor([], dtype=torch.long, device=device) + + self.target_inac = torch.zeros([1, 0, ht, wd, 2], device=device, dtype=torch.float) + self.weight_inac = torch.zeros([1, 0, ht, wd, 2], device=device, dtype=torch.float) + + def __filter_repeated_edges(self, ii, jj): + """ remove duplicate edges """ + + keep = torch.zeros(ii.shape[0], dtype=torch.bool, device=ii.device) + eset = set( + [(i.item(), j.item()) for i, j in zip(self.ii, self.jj)] + + [(i.item(), j.item()) for i, j in zip(self.ii_inac, self.jj_inac)]) + + for k, (i, j) in enumerate(zip(ii, jj)): + keep[k] = (i.item(), j.item()) not in eset + + return ii[keep], jj[keep] + + def print_edges(self): + ii = self.ii.cpu().numpy() + jj = self.jj.cpu().numpy() + + ix = np.argsort(ii) + ii = ii[ix] + jj = jj[ix] + + w = torch.mean(self.weight, dim=[0,2,3,4]).cpu().numpy() + w = w[ix] + for e in zip(ii, jj, w): + print(e) + print() + + def filter_edges(self): + """ remove bad edges """ + conf = torch.mean(self.weight, dim=[0,2,3,4]) + mask = (torch.abs(self.ii-self.jj) > 2) & (conf < 0.001) + + self.ii_bad = torch.cat([self.ii_bad, self.ii[mask]]) + self.jj_bad = torch.cat([self.jj_bad, self.jj[mask]]) + self.rm_factors(mask, store=False) + + def clear_edges(self): + self.rm_factors(self.ii >= 0) + self.net = None + self.inp = None + + @torch.cuda.amp.autocast(enabled=True) + def add_factors(self, ii, jj, remove=False): + """ add edges to factor graph """ + + if not isinstance(ii, torch.Tensor): + ii = torch.as_tensor(ii, dtype=torch.long, device=self.device) + + if not isinstance(jj, torch.Tensor): + jj = torch.as_tensor(jj, dtype=torch.long, device=self.device) + + # remove duplicate edges + ii, jj = self.__filter_repeated_edges(ii, jj) + + + if ii.shape[0] == 0: + return + + # place limit on number of factors + if self.max_factors > 0 and self.ii.shape[0] + ii.shape[0] > self.max_factors \ + and self.corr is not None and remove: + + ix = torch.arange(len(self.age))[torch.argsort(self.age).cpu()] + self.rm_factors(ix >= self.max_factors - ii.shape[0], store=True) + + net = self.video.nets[ii].to(self.device).unsqueeze(0) + + # correlation volume for new edges + if self.corr_impl == "volume": + fmap1 = self.video.fmaps[ii].to(self.device).unsqueeze(0) + fmap2 = self.video.fmaps[jj].to(self.device).unsqueeze(0) + corr = CorrBlock(fmap1, fmap2) + self.corr = corr if self.corr is None else self.corr.cat(corr) + + inp = self.video.inps[ii].to(self.device).unsqueeze(0) + self.inp = inp if self.inp is None else torch.cat([self.inp, inp], 1) + + with torch.cuda.amp.autocast(enabled=False): + target, _ = self.video.reproject(ii, jj) + weight = torch.zeros_like(target) + + self.ii = torch.cat([self.ii, ii], 0) + self.jj = torch.cat([self.jj, jj], 0) + self.age = torch.cat([self.age, torch.zeros_like(ii)], 0) + + # reprojection factors + self.net = net if self.net is None else torch.cat([self.net, net], 1) + + self.target = torch.cat([self.target, target], 1) + self.weight = torch.cat([self.weight, weight], 1) + + @torch.cuda.amp.autocast(enabled=True) + def rm_factors(self, mask, store=False): + """ drop edges from factor graph """ + + # store estimated factors + if store: + self.ii_inac = torch.cat([self.ii_inac, self.ii[mask]], 0) + self.jj_inac = torch.cat([self.jj_inac, self.jj[mask]], 0) + self.target_inac = torch.cat([self.target_inac, self.target[:,mask]], 1) + self.weight_inac = torch.cat([self.weight_inac, self.weight[:,mask]], 1) + + self.ii = self.ii[~mask] + self.jj = self.jj[~mask] + self.age = self.age[~mask] + + if self.corr_impl == "volume": + self.corr = self.corr[~mask] + + if self.net is not None: + self.net = self.net[:,~mask] + + if self.inp is not None: + self.inp = self.inp[:,~mask] + + self.target = self.target[:,~mask] + self.weight = self.weight[:,~mask] + + + @torch.cuda.amp.autocast(enabled=True) + def rm_keyframe(self, ix): + """ drop edges from factor graph """ + + + with self.video.get_lock(): + self.video.poses[ix] = self.video.poses[ix+1] + self.video.disps[ix] = self.video.disps[ix+1] + self.video.intrinsics[ix] = self.video.intrinsics[ix+1] + + self.video.nets[ix] = self.video.nets[ix+1] + self.video.inps[ix] = self.video.inps[ix+1] + self.video.fmaps[ix] = self.video.fmaps[ix+1] + + m = (self.ii == ix) | (self.jj == ix) + + self.ii[self.ii >= ix] -= 1 + self.jj[self.jj >= ix] -= 1 + + self.ii_inac[self.ii_inac >= ix] -= 1 + self.jj_inac[self.jj_inac >= ix] -= 1 + + self.rm_factors(m, store=False) + + + @torch.cuda.amp.autocast(enabled=True) + def update(self, t0=None, t1=None, itrs=2, use_inactive=False, EP=1e-7, motion_only=False): + """ run update operator on factor graph """ + + # motion features + with torch.cuda.amp.autocast(enabled=False): + coords1, mask = self.video.reproject(self.ii, self.jj) + motn = torch.cat([coords1 - self.coords0, self.target - coords1], dim=-1) + motn = motn.permute(0,1,4,2,3).clamp(-64.0, 64.0) + + # correlation features + corr = self.corr(coords1) + + self.net, delta, weight, damping, upmask = \ + self.update_op(self.net, self.inp, corr, motn, self.ii, self.jj) + + if t0 is None: + t0 = max(1, self.ii.min().item()+1) + + with torch.cuda.amp.autocast(enabled=False): + self.target = coords1 + delta.to(dtype=torch.float) + self.weight = weight.to(dtype=torch.float) + + ht, wd = self.coords0.shape[0:2] + self.damping[torch.unique(self.ii)] = damping + + if use_inactive: + m = (self.ii_inac >= t0 - 3) & (self.jj_inac >= t0 - 3) + ii = torch.cat([self.ii_inac[m], self.ii], 0) + jj = torch.cat([self.jj_inac[m], self.jj], 0) + target = torch.cat([self.target_inac[:,m], self.target], 1) + weight = torch.cat([self.weight_inac[:,m], self.weight], 1) + + else: + ii, jj, target, weight = self.ii, self.jj, self.target, self.weight + + + damping = .2 * self.damping[torch.unique(ii)].contiguous() + EP + + target = target.view(-1, ht, wd, 2).permute(0,3,1,2).contiguous() + weight = weight.view(-1, ht, wd, 2).permute(0,3,1,2).contiguous() + + # dense bundle adjustment + self.video.ba(target, weight, damping, ii, jj, t0, t1, + itrs=itrs, lm=1e-4, ep=0.1, motion_only=motion_only) + + self.age += 1 + + + @torch.cuda.amp.autocast(enabled=False) + def update_lowmem(self, t0=None, t1=None, itrs=2, use_inactive=False, EP=1e-7, steps=8): + """ run update operator on factor graph - reduced memory implementation """ + + # alternate corr implementation + t = self.video.counter.value + corr_op = AltCorrBlock(self.video.fmaps[None,:t]) + + for step in range(steps): + print("Global BA Iteration #{}".format(step+1)) + with torch.cuda.amp.autocast(enabled=False): + coords1, mask = self.video.reproject(self.ii, self.jj) + motn = torch.cat([coords1 - self.coords0, self.target - coords1], dim=-1) + motn = motn.permute(0,1,4,2,3).clamp(-64.0, 64.0) + + s = 8 + for i in range(0, self.jj.max()+1, s): + v = (self.ii >= i) & (self.ii < i + s) + iis = self.ii[v] + jjs = self.jj[v] + + ht, wd = self.coords0.shape[0:2] + corr1 = corr_op(coords1[:,v], iis, jjs) + + with torch.cuda.amp.autocast(enabled=True): + net, delta, weight, damping, _ = \ + self.update_op(self.net[:,v], self.video.inps[None,iis], corr1, motn[:,v], iis, jjs) + + + self.net[:,v] = net + self.target[:,v] = coords1[:,v] + delta.float() + self.weight[:,v] = weight.float() + self.damping[torch.unique(iis)] = damping + + damping = self.damping[torch.unique(self.ii)].contiguous() + EP + target = self.target.view(-1, ht, wd, 2).permute(0,3,1,2).contiguous() + weight = self.weight.view(-1, ht, wd, 2).permute(0,3,1,2).contiguous() + + # dense bundle adjustment + self.video.ba(target, weight, damping, self.ii, self.jj, 1, t, + itrs=itrs, lm=1e-5, ep=1e-2, motion_only=False) + + self.video.dirty[:t] = True + + + def add_neighborhood_factors(self, t0, t1, r=3): + """ add edges between neighboring frames within radius r """ + + ii, jj = torch.meshgrid(torch.arange(t0,t1), torch.arange(t0,t1)) + ii = ii.reshape(-1).to(dtype=torch.long, device=self.device) + jj = jj.reshape(-1).to(dtype=torch.long, device=self.device) + + keep = ((ii - jj).abs() > 0) & ((ii - jj).abs() <= r) + self.add_factors(ii[keep], jj[keep]) + + + def add_proximity_factors(self, t0=0, t1=0, rad=2, nms=2, beta=0.25, thresh=16.0, remove=False): + """ add edges to the factor graph based on distance """ + + t = self.video.counter.value + ix = torch.arange(t0, t) + jx = torch.arange(t1, t) + + ii, jj = torch.meshgrid(ix, jx) + ii = ii.reshape(-1) + jj = jj.reshape(-1) + + d = self.video.distance(ii, jj, beta=beta) + d[ii - rad < jj] = np.inf + d[d > 100] = np.inf + + ii1 = torch.cat([self.ii, self.ii_bad, self.ii_inac], 0) + jj1 = torch.cat([self.jj, self.jj_bad, self.jj_inac], 0) + for i, j in zip(ii1.cpu().numpy(), jj1.cpu().numpy()): + if abs(i - j) <= 2: + continue + for di in range(-nms, nms+1): + for dj in range(-nms, nms+1): + if abs(di) + abs(dj) <= max(min(abs(i-j)-2, nms), 0): + i1 = i + di + j1 = j + dj + + if (t0 <= i1 < t) and (t1 <= j1 < t): + d[(i1-t0)*(t-t1) + (j1-t1)] = np.inf + + es = [] + for i in range(t0, t): + for j in range(i+1, min(i+rad+1, t)): + es.append((i,j)) + es.append((j,i)) + + ix = torch.argsort(d) + for k in ix: + if d[k].item() > thresh: + continue + + i = ii[k] + j = jj[k] + + # bidirectional + es.append((i, j)) + es.append((j, i)) + + for di in range(-nms, nms+1): + for dj in range(-nms, nms+1): + if abs(di) + abs(dj) <= max(min(abs(i-j)-2, nms), 0): + i1 = i + di + j1 = j + dj + + if (t0 <= i1 < t) and (t1 <= j1 < t): + d[(i1-t0)*(t-t1) + (j1-t1)] = np.inf + + ii, jj = torch.as_tensor(es, device=self.device).unbind(dim=-1) + self.add_factors(ii, jj, remove) diff --git a/droid_slam/geom/__init__.py b/droid_slam/geom/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/droid_slam/geom/ba.py b/droid_slam/geom/ba.py new file mode 100644 index 00000000..34c95c8a --- /dev/null +++ b/droid_slam/geom/ba.py @@ -0,0 +1,158 @@ +import lietorch +import torch +import torch.nn.functional as F + +from .chol import block_solve, schur_solve +import geom.projective_ops as pops + +from torch_scatter import scatter_sum + + +# utility functions for scattering ops +def safe_scatter_add_mat(A, ii, jj, n, m): + v = (ii >= 0) & (jj >= 0) & (ii < n) & (jj < m) + return scatter_sum(A[:,v], ii[v]*m + jj[v], dim=1, dim_size=n*m) + +def safe_scatter_add_vec(b, ii, n): + v = (ii >= 0) & (ii < n) + return scatter_sum(b[:,v], ii[v], dim=1, dim_size=n) + +# apply retraction operator to inv-depth maps +def disp_retr(disps, dz, ii): + ii = ii.to(device=dz.device) + return disps + scatter_sum(dz, ii, dim=1, dim_size=disps.shape[1]) + +# apply retraction operator to poses +def pose_retr(poses, dx, ii): + ii = ii.to(device=dx.device) + return poses.retr(scatter_sum(dx, ii, dim=1, dim_size=poses.shape[1])) + + +def BA(target, weight, eta, poses, disps, intrinsics, ii, jj, fixedp=1, rig=1): + """ Full Bundle Adjustment """ + + B, P, ht, wd = disps.shape + N = ii.shape[0] + D = poses.manifold_dim + + ### 1: commpute jacobians and residuals ### + coords, valid, (Ji, Jj, Jz) = pops.projective_transform( + poses, disps, intrinsics, ii, jj, jacobian=True) + + r = (target - coords).view(B, N, -1, 1) + w = .001 * (valid * weight).view(B, N, -1, 1) + + ### 2: construct linear system ### + Ji = Ji.reshape(B, N, -1, D) + Jj = Jj.reshape(B, N, -1, D) + wJiT = (w * Ji).transpose(2,3) + wJjT = (w * Jj).transpose(2,3) + + Jz = Jz.reshape(B, N, ht*wd, -1) + + Hii = torch.matmul(wJiT, Ji) + Hij = torch.matmul(wJiT, Jj) + Hji = torch.matmul(wJjT, Ji) + Hjj = torch.matmul(wJjT, Jj) + + vi = torch.matmul(wJiT, r).squeeze(-1) + vj = torch.matmul(wJjT, r).squeeze(-1) + + Ei = (wJiT.view(B,N,D,ht*wd,-1) * Jz[:,:,None]).sum(dim=-1) + Ej = (wJjT.view(B,N,D,ht*wd,-1) * Jz[:,:,None]).sum(dim=-1) + + w = w.view(B, N, ht*wd, -1) + r = r.view(B, N, ht*wd, -1) + wk = torch.sum(w*r*Jz, dim=-1) + Ck = torch.sum(w*Jz*Jz, dim=-1) + + kx, kk = torch.unique(ii, return_inverse=True) + M = kx.shape[0] + + # only optimize keyframe poses + P = P // rig - fixedp + ii = ii // rig - fixedp + jj = jj // rig - fixedp + + H = safe_scatter_add_mat(Hii, ii, ii, P, P) + \ + safe_scatter_add_mat(Hij, ii, jj, P, P) + \ + safe_scatter_add_mat(Hji, jj, ii, P, P) + \ + safe_scatter_add_mat(Hjj, jj, jj, P, P) + + E = safe_scatter_add_mat(Ei, ii, kk, P, M) + \ + safe_scatter_add_mat(Ej, jj, kk, P, M) + + v = safe_scatter_add_vec(vi, ii, P) + \ + safe_scatter_add_vec(vj, jj, P) + + C = safe_scatter_add_vec(Ck, kk, M) + w = safe_scatter_add_vec(wk, kk, M) + + C = C + eta.view(*C.shape) + 1e-7 + + H = H.view(B, P, P, D, D) + E = E.view(B, P, M, D, ht*wd) + + ### 3: solve the system ### + dx, dz = schur_solve(H, E, C, v, w) + + ### 4: apply retraction ### + poses = pose_retr(poses, dx, torch.arange(P) + fixedp) + disps = disp_retr(disps, dz.view(B,-1,ht,wd), kx) + + disps = torch.where(disps > 10, torch.zeros_like(disps), disps) + disps = disps.clamp(min=0.0) + + return poses, disps + + +def MoBA(target, weight, eta, poses, disps, intrinsics, ii, jj, fixedp=1, rig=1): + """ Motion only bundle adjustment """ + + B, P, ht, wd = disps.shape + N = ii.shape[0] + D = poses.manifold_dim + + ### 1: commpute jacobians and residuals ### + coords, valid, (Ji, Jj, Jz) = pops.projective_transform( + poses, disps, intrinsics, ii, jj, jacobian=True) + + r = (target - coords).view(B, N, -1, 1) + w = .001 * (valid * weight).view(B, N, -1, 1) + + ### 2: construct linear system ### + Ji = Ji.reshape(B, N, -1, D) + Jj = Jj.reshape(B, N, -1, D) + wJiT = (w * Ji).transpose(2,3) + wJjT = (w * Jj).transpose(2,3) + + Hii = torch.matmul(wJiT, Ji) + Hij = torch.matmul(wJiT, Jj) + Hji = torch.matmul(wJjT, Ji) + Hjj = torch.matmul(wJjT, Jj) + + vi = torch.matmul(wJiT, r).squeeze(-1) + vj = torch.matmul(wJjT, r).squeeze(-1) + + # only optimize keyframe poses + P = P // rig - fixedp + ii = ii // rig - fixedp + jj = jj // rig - fixedp + + H = safe_scatter_add_mat(Hii, ii, ii, P, P) + \ + safe_scatter_add_mat(Hij, ii, jj, P, P) + \ + safe_scatter_add_mat(Hji, jj, ii, P, P) + \ + safe_scatter_add_mat(Hjj, jj, jj, P, P) + + v = safe_scatter_add_vec(vi, ii, P) + \ + safe_scatter_add_vec(vj, jj, P) + + H = H.view(B, P, P, D, D) + + ### 3: solve the system ### + dx = block_solve(H, v) + + ### 4: apply retraction ### + poses = pose_retr(poses, dx, torch.arange(P) + fixedp) + return poses + diff --git a/droid_slam/geom/chol.py b/droid_slam/geom/chol.py new file mode 100644 index 00000000..86bc8f9b --- /dev/null +++ b/droid_slam/geom/chol.py @@ -0,0 +1,73 @@ +import torch +import torch.nn.functional as F +import geom.projective_ops as pops + +class CholeskySolver(torch.autograd.Function): + @staticmethod + def forward(ctx, H, b): + # don't crash training if cholesky decomp fails + try: + U = torch.linalg.cholesky(H) + xs = torch.cholesky_solve(b, U) + ctx.save_for_backward(U, xs) + ctx.failed = False + except Exception as e: + print(e) + ctx.failed = True + xs = torch.zeros_like(b) + + return xs + + @staticmethod + def backward(ctx, grad_x): + if ctx.failed: + return None, None + + U, xs = ctx.saved_tensors + dz = torch.cholesky_solve(grad_x, U) + dH = -torch.matmul(xs, dz.transpose(-1,-2)) + + return dH, dz + +def block_solve(H, b, ep=0.1, lm=0.0001): + """ solve normal equations """ + B, N, _, D, _ = H.shape + I = torch.eye(D).to(H.device) + H = H + (ep + lm*H) * I + + H = H.permute(0,1,3,2,4) + H = H.reshape(B, N*D, N*D) + b = b.reshape(B, N*D, 1) + + x = CholeskySolver.apply(H,b) + return x.reshape(B, N, D) + + +def schur_solve(H, E, C, v, w, ep=0.1, lm=0.0001, sless=False): + """ solve using shur complement """ + + B, P, M, D, HW = E.shape + H = H.permute(0,1,3,2,4).reshape(B, P*D, P*D) + E = E.permute(0,1,3,2,4).reshape(B, P*D, M*HW) + Q = (1.0 / C).view(B, M*HW, 1) + + # damping + I = torch.eye(P*D).to(H.device) + H = H + (ep + lm*H) * I + + v = v.reshape(B, P*D, 1) + w = w.reshape(B, M*HW, 1) + + Et = E.transpose(1,2) + S = H - torch.matmul(E, Q*Et) + v = v - torch.matmul(E, Q*w) + + dx = CholeskySolver.apply(S, v) + if sless: + return dx.reshape(B, P, D) + + dz = Q * (w - Et @ dx) + dx = dx.reshape(B, P, D) + dz = dz.reshape(B, M, HW) + + return dx, dz \ No newline at end of file diff --git a/droid_slam/geom/graph_utils.py b/droid_slam/geom/graph_utils.py new file mode 100644 index 00000000..b06b7de9 --- /dev/null +++ b/droid_slam/geom/graph_utils.py @@ -0,0 +1,113 @@ + +import torch +import numpy as np +from collections import OrderedDict + +import lietorch +from data_readers.rgbd_utils import compute_distance_matrix_flow, compute_distance_matrix_flow2 + + +def graph_to_edge_list(graph): + ii, jj, kk = [], [], [] + for s, u in enumerate(graph): + for v in graph[u]: + ii.append(u) + jj.append(v) + kk.append(s) + + ii = torch.as_tensor(ii) + jj = torch.as_tensor(jj) + kk = torch.as_tensor(kk) + return ii, jj, kk + +def keyframe_indicies(graph): + return torch.as_tensor([u for u in graph]) + +def meshgrid(m, n, device='cuda'): + ii, jj = torch.meshgrid(torch.arange(m), torch.arange(n)) + return ii.reshape(-1).to(device), jj.reshape(-1).to(device) + +def neighbourhood_graph(n, r): + ii, jj = meshgrid(n, n) + d = (ii - jj).abs() + keep = (d >= 1) & (d <= r) + return ii[keep], jj[keep] + + +def build_frame_graph(poses, disps, intrinsics, num=16, thresh=24.0, r=2): + """ construct a frame graph between co-visible frames """ + N = poses.shape[1] + poses = poses[0].cpu().numpy() + disps = disps[0][:,3::8,3::8].cpu().numpy() + intrinsics = intrinsics[0].cpu().numpy() / 8.0 + d = compute_distance_matrix_flow(poses, disps, intrinsics) + + count = 0 + graph = OrderedDict() + + for i in range(N): + graph[i] = [] + d[i,i] = np.inf + for j in range(i-r, i+r+1): + if 0 <= j < N and i != j: + graph[i].append(j) + d[i,j] = np.inf + count += 1 + + while count < num: + ix = np.argmin(d) + i, j = ix // N, ix % N + + if d[i,j] < thresh: + graph[i].append(j) + d[i,j] = np.inf + count += 1 + else: + break + + return graph + + + +def build_frame_graph_v2(poses, disps, intrinsics, num=16, thresh=24.0, r=2): + """ construct a frame graph between co-visible frames """ + N = poses.shape[1] + # poses = poses[0].cpu().numpy() + # disps = disps[0].cpu().numpy() + # intrinsics = intrinsics[0].cpu().numpy() + d = compute_distance_matrix_flow2(poses, disps, intrinsics) + + # import matplotlib.pyplot as plt + # plt.imshow(d) + # plt.show() + + count = 0 + graph = OrderedDict() + + for i in range(N): + graph[i] = [] + d[i,i] = np.inf + for j in range(i-r, i+r+1): + if 0 <= j < N and i != j: + graph[i].append(j) + d[i,j] = np.inf + count += 1 + + while 1: + ix = np.argmin(d) + i, j = ix // N, ix % N + + if d[i,j] < thresh: + graph[i].append(j) + + for i1 in range(i-1, i+2): + for j1 in range(j-1, j+2): + if 0 <= i1 < N and 0 <= j1 < N: + d[i1, j1] = np.inf + + count += 1 + else: + break + + return graph + diff --git a/droid_slam/geom/losses.py b/droid_slam/geom/losses.py new file mode 100644 index 00000000..7fa91cf3 --- /dev/null +++ b/droid_slam/geom/losses.py @@ -0,0 +1,118 @@ +from collections import OrderedDict +import numpy as np +import torch +from lietorch import SO3, SE3, Sim3 +from .graph_utils import graph_to_edge_list +from .projective_ops import projective_transform + + +def pose_metrics(dE): + """ Translation/Rotation/Scaling metrics from Sim3 """ + t, q, s = dE.data.split([3, 4, 1], -1) + ang = SO3(q).log().norm(dim=-1) + + # convert radians to degrees + r_err = (180 / np.pi) * ang + t_err = t.norm(dim=-1) + s_err = (s - 1.0).abs() + return r_err, t_err, s_err + + +def fit_scale(Ps, Gs): + b = Ps.shape[0] + t1 = Ps.data[...,:3].detach().reshape(b, -1) + t2 = Gs.data[...,:3].detach().reshape(b, -1) + + s = (t1*t2).sum(-1) / ((t2*t2).sum(-1) + 1e-8) + return s + + +def geodesic_loss(Ps, Gs, graph, gamma=0.9, do_scale=True): + """ Loss function for training network """ + + # relative pose + ii, jj, kk = graph_to_edge_list(graph) + dP = Ps[:,jj] * Ps[:,ii].inv() + + n = len(Gs) + geodesic_loss = 0.0 + + for i in range(n): + w = gamma ** (n - i - 1) + dG = Gs[i][:,jj] * Gs[i][:,ii].inv() + + if do_scale: + s = fit_scale(dP, dG) + dG = dG.scale(s[:,None]) + + # pose error + d = (dG * dP.inv()).log() + + if isinstance(dG, SE3): + tau, phi = d.split([3,3], dim=-1) + geodesic_loss += w * ( + tau.norm(dim=-1).mean() + + phi.norm(dim=-1).mean()) + + elif isinstance(dG, Sim3): + tau, phi, sig = d.split([3,3,1], dim=-1) + geodesic_loss += w * ( + tau.norm(dim=-1).mean() + + phi.norm(dim=-1).mean() + + 0.05 * sig.norm(dim=-1).mean()) + + dE = Sim3(dG * dP.inv()).detach() + r_err, t_err, s_err = pose_metrics(dE) + + metrics = { + 'rot_error': r_err.mean().item(), + 'tr_error': t_err.mean().item(), + 'bad_rot': (r_err < .1).float().mean().item(), + 'bad_tr': (t_err < .01).float().mean().item(), + } + + return geodesic_loss, metrics + + +def residual_loss(residuals, gamma=0.9): + """ loss on system residuals """ + residual_loss = 0.0 + n = len(residuals) + + for i in range(n): + w = gamma ** (n - i - 1) + residual_loss += w * residuals[i].abs().mean() + + return residual_loss, {'residual': residual_loss.item()} + + +def flow_loss(Ps, disps, poses_est, disps_est, intrinsics, graph, gamma=0.9): + """ optical flow loss """ + + N = Ps.shape[1] + graph = OrderedDict() + for i in range(N): + graph[i] = [j for j in range(N) if abs(i-j)==1] + + ii, jj, kk = graph_to_edge_list(graph) + coords0, val0 = projective_transform(Ps, disps, intrinsics, ii, jj) + val0 = val0 * (disps[:,ii] > 0).float().unsqueeze(dim=-1) + + n = len(poses_est) + flow_loss = 0.0 + + for i in range(n): + w = gamma ** (n - i - 1) + coords1, val1 = projective_transform(poses_est[i], disps_est[i], intrinsics, ii, jj) + + v = (val0 * val1).squeeze(dim=-1) + epe = v * (coords1 - coords0).norm(dim=-1) + flow_loss += w * epe.mean() + + epe = epe.reshape(-1)[v.reshape(-1) > 0.5] + metrics = { + 'f_error': epe.mean().item(), + '1px': (epe<1.0).float().mean().item(), + } + + return flow_loss, metrics diff --git a/droid_slam/geom/projective_ops.py b/droid_slam/geom/projective_ops.py new file mode 100644 index 00000000..2303244f --- /dev/null +++ b/droid_slam/geom/projective_ops.py @@ -0,0 +1,137 @@ +import torch +import torch.nn.functional as F + +from lietorch import SE3, Sim3 + +MIN_DEPTH = 0.2 + +def extract_intrinsics(intrinsics): + return intrinsics[...,None,None,:].unbind(dim=-1) + +def coords_grid(ht, wd, **kwargs): + y, x = torch.meshgrid( + torch.arange(ht).to(**kwargs).float(), + torch.arange(wd).to(**kwargs).float()) + + return torch.stack([x, y], dim=-1) + +def iproj(disps, intrinsics, jacobian=False): + """ pinhole camera inverse projection """ + ht, wd = disps.shape[2:] + fx, fy, cx, cy = extract_intrinsics(intrinsics) + + y, x = torch.meshgrid( + torch.arange(ht).to(disps.device).float(), + torch.arange(wd).to(disps.device).float()) + + i = torch.ones_like(disps) + X = (x - cx) / fx + Y = (y - cy) / fy + pts = torch.stack([X, Y, i, disps], dim=-1) + + if jacobian: + J = torch.zeros_like(pts) + J[...,-1] = 1.0 + return pts, J + + return pts, None + +def proj(Xs, intrinsics, jacobian=False, return_depth=False): + """ pinhole camera projection """ + fx, fy, cx, cy = extract_intrinsics(intrinsics) + X, Y, Z, D = Xs.unbind(dim=-1) + + Z = torch.where(Z < 0.5*MIN_DEPTH, torch.ones_like(Z), Z) + d = 1.0 / Z + + x = fx * (X * d) + cx + y = fy * (Y * d) + cy + if return_depth: + coords = torch.stack([x, y, D*d], dim=-1) + else: + coords = torch.stack([x, y], dim=-1) + + if jacobian: + B, N, H, W = d.shape + o = torch.zeros_like(d) + proj_jac = torch.stack([ + fx*d, o, -fx*X*d*d, o, + o, fy*d, -fy*Y*d*d, o, + # o, o, -D*d*d, d, + ], dim=-1).view(B, N, H, W, 2, 4) + + return coords, proj_jac + + return coords, None + +def actp(Gij, X0, jacobian=False): + """ action on point cloud """ + X1 = Gij[:,:,None,None] * X0 + + if jacobian: + X, Y, Z, d = X1.unbind(dim=-1) + o = torch.zeros_like(d) + B, N, H, W = d.shape + + if isinstance(Gij, SE3): + Ja = torch.stack([ + d, o, o, o, Z, -Y, + o, d, o, -Z, o, X, + o, o, d, Y, -X, o, + o, o, o, o, o, o, + ], dim=-1).view(B, N, H, W, 4, 6) + + elif isinstance(Gij, Sim3): + Ja = torch.stack([ + d, o, o, o, Z, -Y, X, + o, d, o, -Z, o, X, Y, + o, o, d, Y, -X, o, Z, + o, o, o, o, o, o, o + ], dim=-1).view(B, N, H, W, 4, 7) + + return X1, Ja + + return X1, None + +def projective_transform(poses, depths, intrinsics, ii, jj, jacobian=False, return_depth=False): + """ map points from ii->jj """ + + # inverse project (pinhole) + X0, Jz = iproj(depths[:,ii], intrinsics[:,ii], jacobian=jacobian) + + # transform + Gij = poses[:,jj] * poses[:,ii].inv() + X1, Ja = actp(Gij, X0, jacobian=jacobian) + + # project (pinhole) + x1, Jp = proj(X1, intrinsics[:,jj], jacobian=jacobian, return_depth=return_depth) + + # exclude points too close to camera + valid = ((X1[...,2] > MIN_DEPTH) & (X0[...,2] > MIN_DEPTH)).float() + valid = valid.unsqueeze(-1) + + if jacobian: + # Ji transforms according to dual adjoint + Jj = torch.matmul(Jp, Ja) + Ji = -Gij[:,:,None,None,None].adjT(Jj) + + Jz = Gij[:,:,None,None] * Jz + Jz = torch.matmul(Jp, Jz.unsqueeze(-1)) + + return x1, valid, (Ji, Jj, Jz) + + return x1, valid + +def induced_flow(poses, disps, intrinsics, ii, jj): + """ optical flow induced by camera motion """ + + ht, wd = disps.shape[2:] + y, x = torch.meshgrid( + torch.arange(ht).to(disps.device).float(), + torch.arange(wd).to(disps.device).float()) + + coords0 = torch.stack([x, y], dim=-1) + coords1, valid = projective_transform(poses, disps, intrinsics, ii, jj, False) + + return coords1[...,:2] - coords0, valid + diff --git a/droid_slam/logger.py b/droid_slam/logger.py new file mode 100644 index 00000000..3af7a2cb --- /dev/null +++ b/droid_slam/logger.py @@ -0,0 +1,54 @@ + +import torch +from torch.utils.tensorboard import SummaryWriter + + +SUM_FREQ = 100 + +class Logger: + def __init__(self, name, scheduler): + self.total_steps = 0 + self.running_loss = {} + self.writer = None + self.name = name + self.scheduler = scheduler + + def _print_training_status(self): + if self.writer is None: + self.writer = SummaryWriter('runs/%s' % self.name) + print([k for k in self.running_loss]) + + lr = self.scheduler.get_lr().pop() + metrics_data = [self.running_loss[k]/SUM_FREQ for k in self.running_loss.keys()] + training_str = "[{:6d}, {:10.7f}] ".format(self.total_steps+1, lr) + metrics_str = ("{:10.4f}, "*len(metrics_data)).format(*metrics_data) + + # print the training status + print(training_str + metrics_str) + + for key in self.running_loss: + val = self.running_loss[key] / SUM_FREQ + self.writer.add_scalar(key, val, self.total_steps) + self.running_loss[key] = 0.0 + + def push(self, metrics): + + for key in metrics: + if key not in self.running_loss: + self.running_loss[key] = 0.0 + + self.running_loss[key] += metrics[key] + + if self.total_steps % SUM_FREQ == SUM_FREQ-1: + self._print_training_status() + self.running_loss = {} + + self.total_steps += 1 + + def write_dict(self, results): + for key in results: + self.writer.add_scalar(key, results[key], self.total_steps) + + def close(self): + self.writer.close() + diff --git a/droid_slam/modules/__init__.py b/droid_slam/modules/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/droid_slam/modules/clipping.py b/droid_slam/modules/clipping.py new file mode 100644 index 00000000..e59307f5 --- /dev/null +++ b/droid_slam/modules/clipping.py @@ -0,0 +1,24 @@ +import torch +import torch.nn as nn +import torch.nn.functional as F + +GRAD_CLIP = .01 + +class GradClip(torch.autograd.Function): + @staticmethod + def forward(ctx, x): + return x + + @staticmethod + def backward(ctx, grad_x): + o = torch.zeros_like(grad_x) + grad_x = torch.where(grad_x.abs()>GRAD_CLIP, o, grad_x) + grad_x = torch.where(torch.isnan(grad_x), o, grad_x) + return grad_x + +class GradientClip(nn.Module): + def __init__(self): + super(GradientClip, self).__init__() + + def forward(self, x): + return GradClip.apply(x) \ No newline at end of file diff --git a/droid_slam/modules/corr.py b/droid_slam/modules/corr.py new file mode 100644 index 00000000..6a1e32ad --- /dev/null +++ b/droid_slam/modules/corr.py @@ -0,0 +1,140 @@ +import torch +import torch.nn.functional as F + +import droid_backends + +class CorrSampler(torch.autograd.Function): + + @staticmethod + def forward(ctx, volume, coords, radius): + ctx.save_for_backward(volume,coords) + ctx.radius = radius + corr, = droid_backends.corr_index_forward(volume, coords, radius) + return corr + + @staticmethod + def backward(ctx, grad_output): + volume, coords = ctx.saved_tensors + grad_output = grad_output.contiguous() + grad_volume, = droid_backends.corr_index_backward(volume, coords, grad_output, ctx.radius) + return grad_volume, None, None + + +class CorrBlock: + def __init__(self, fmap1, fmap2, num_levels=4, radius=3): + self.num_levels = num_levels + self.radius = radius + self.corr_pyramid = [] + + # all pairs correlation + corr = CorrBlock.corr(fmap1, fmap2) + + batch, num, h1, w1, h2, w2 = corr.shape + corr = corr.reshape(batch*num*h1*w1, 1, h2, w2) + + for i in range(self.num_levels): + self.corr_pyramid.append( + corr.view(batch*num, h1, w1, h2//2**i, w2//2**i)) + corr = F.avg_pool2d(corr, 2, stride=2) + + def __call__(self, coords): + out_pyramid = [] + batch, num, ht, wd, _ = coords.shape + coords = coords.permute(0,1,4,2,3) + coords = coords.contiguous().view(batch*num, 2, ht, wd) + + for i in range(self.num_levels): + corr = CorrSampler.apply(self.corr_pyramid[i], coords/2**i, self.radius) + out_pyramid.append(corr.view(batch, num, -1, ht, wd)) + + return torch.cat(out_pyramid, dim=2) + + def cat(self, other): + for i in range(self.num_levels): + self.corr_pyramid[i] = torch.cat([self.corr_pyramid[i], other.corr_pyramid[i]], 0) + return self + + def __getitem__(self, index): + for i in range(self.num_levels): + self.corr_pyramid[i] = self.corr_pyramid[i][index] + return self + + + @staticmethod + def corr(fmap1, fmap2): + """ all-pairs correlation """ + batch, num, dim, ht, wd = fmap1.shape + fmap1 = fmap1.reshape(batch*num, dim, ht*wd) / 4.0 + fmap2 = fmap2.reshape(batch*num, dim, ht*wd) / 4.0 + + corr = torch.matmul(fmap1.transpose(1,2), fmap2) + return corr.view(batch, num, ht, wd, ht, wd) + + +class CorrLayer(torch.autograd.Function): + @staticmethod + def forward(ctx, fmap1, fmap2, coords, r): + ctx.r = r + ctx.save_for_backward(fmap1, fmap2, coords) + corr, = droid_backends.altcorr_forward(fmap1, fmap2, coords, ctx.r) + return corr + + @staticmethod + def backward(ctx, grad_corr): + fmap1, fmap2, coords = ctx.saved_tensors + grad_corr = grad_corr.contiguous() + fmap1_grad, fmap2_grad, coords_grad = \ + droid_backends.altcorr_backward(fmap1, fmap2, coords, grad_corr, ctx.r) + return fmap1_grad, fmap2_grad, coords_grad, None + + +class AltCorrBlock: + def __init__(self, fmaps, num_levels=4, radius=3): + self.num_levels = num_levels + self.radius = radius + + B, N, C, H, W = fmaps.shape + fmaps = fmaps.view(B*N, C, H, W) / 4.0 + + self.pyramid = [] + for i in range(self.num_levels): + sz = (B, N, H//2**i, W//2**i, C) + fmap_lvl = fmaps.permute(0, 2, 3, 1).contiguous() + self.pyramid.append(fmap_lvl.view(*sz)) + fmaps = F.avg_pool2d(fmaps, 2, stride=2) + + def corr_fn(self, coords, ii, jj): + B, N, H, W, S, _ = coords.shape + coords = coords.permute(0, 1, 4, 2, 3, 5) + + corr_list = [] + for i in range(self.num_levels): + r = self.radius + fmap1_i = self.pyramid[0][:, ii] + fmap2_i = self.pyramid[i][:, jj] + + coords_i = (coords / 2**i).reshape(B*N, S, H, W, 2).contiguous() + fmap1_i = fmap1_i.reshape((B*N,) + fmap1_i.shape[2:]) + fmap2_i = fmap2_i.reshape((B*N,) + fmap2_i.shape[2:]) + + corr = CorrLayer.apply(fmap1_i.float(), fmap2_i.float(), coords_i, self.radius) + corr = corr.view(B, N, S, -1, H, W).permute(0, 1, 3, 4, 5, 2) + corr_list.append(corr) + + corr = torch.cat(corr_list, dim=2) + return corr + + + def __call__(self, coords, ii, jj): + squeeze_output = False + if len(coords.shape) == 5: + coords = coords.unsqueeze(dim=-2) + squeeze_output = True + + corr = self.corr_fn(coords, ii, jj) + + if squeeze_output: + corr = corr.squeeze(dim=-1) + + return corr.contiguous() + diff --git a/droid_slam/modules/extractor.py b/droid_slam/modules/extractor.py new file mode 100644 index 00000000..5807d45f --- /dev/null +++ b/droid_slam/modules/extractor.py @@ -0,0 +1,198 @@ +import torch +import torch.nn as nn +import torch.nn.functional as F + + +class ResidualBlock(nn.Module): + def __init__(self, in_planes, planes, norm_fn='group', stride=1): + super(ResidualBlock, self).__init__() + + self.conv1 = nn.Conv2d(in_planes, planes, kernel_size=3, padding=1, stride=stride) + self.conv2 = nn.Conv2d(planes, planes, kernel_size=3, padding=1) + self.relu = nn.ReLU(inplace=True) + + num_groups = planes // 8 + + if norm_fn == 'group': + self.norm1 = nn.GroupNorm(num_groups=num_groups, num_channels=planes) + self.norm2 = nn.GroupNorm(num_groups=num_groups, num_channels=planes) + if not stride == 1: + self.norm3 = nn.GroupNorm(num_groups=num_groups, num_channels=planes) + + elif norm_fn == 'batch': + self.norm1 = nn.BatchNorm2d(planes) + self.norm2 = nn.BatchNorm2d(planes) + if not stride == 1: + self.norm3 = nn.BatchNorm2d(planes) + + elif norm_fn == 'instance': + self.norm1 = nn.InstanceNorm2d(planes) + self.norm2 = nn.InstanceNorm2d(planes) + if not stride == 1: + self.norm3 = nn.InstanceNorm2d(planes) + + elif norm_fn == 'none': + self.norm1 = nn.Sequential() + self.norm2 = nn.Sequential() + if not stride == 1: + self.norm3 = nn.Sequential() + + if stride == 1: + self.downsample = None + + else: + self.downsample = nn.Sequential( + nn.Conv2d(in_planes, planes, kernel_size=1, stride=stride), self.norm3) + + def forward(self, x): + y = x + y = self.relu(self.norm1(self.conv1(y))) + y = self.relu(self.norm2(self.conv2(y))) + + if self.downsample is not None: + x = self.downsample(x) + + return self.relu(x+y) + + +class BottleneckBlock(nn.Module): + def __init__(self, in_planes, planes, norm_fn='group', stride=1): + super(BottleneckBlock, self).__init__() + + self.conv1 = nn.Conv2d(in_planes, planes//4, kernel_size=1, padding=0) + self.conv2 = nn.Conv2d(planes//4, planes//4, kernel_size=3, padding=1, stride=stride) + self.conv3 = nn.Conv2d(planes//4, planes, kernel_size=1, padding=0) + self.relu = nn.ReLU(inplace=True) + + num_groups = planes // 8 + + if norm_fn == 'group': + self.norm1 = nn.GroupNorm(num_groups=num_groups, num_channels=planes//4) + self.norm2 = nn.GroupNorm(num_groups=num_groups, num_channels=planes//4) + self.norm3 = nn.GroupNorm(num_groups=num_groups, num_channels=planes) + if not stride == 1: + self.norm4 = nn.GroupNorm(num_groups=num_groups, num_channels=planes) + + elif norm_fn == 'batch': + self.norm1 = nn.BatchNorm2d(planes//4) + self.norm2 = nn.BatchNorm2d(planes//4) + self.norm3 = nn.BatchNorm2d(planes) + if not stride == 1: + self.norm4 = nn.BatchNorm2d(planes) + + elif norm_fn == 'instance': + self.norm1 = nn.InstanceNorm2d(planes//4) + self.norm2 = nn.InstanceNorm2d(planes//4) + self.norm3 = nn.InstanceNorm2d(planes) + if not stride == 1: + self.norm4 = nn.InstanceNorm2d(planes) + + elif norm_fn == 'none': + self.norm1 = nn.Sequential() + self.norm2 = nn.Sequential() + self.norm3 = nn.Sequential() + if not stride == 1: + self.norm4 = nn.Sequential() + + if stride == 1: + self.downsample = None + + else: + self.downsample = nn.Sequential( + nn.Conv2d(in_planes, planes, kernel_size=1, stride=stride), self.norm4) + + def forward(self, x): + y = x + y = self.relu(self.norm1(self.conv1(y))) + y = self.relu(self.norm2(self.conv2(y))) + y = self.relu(self.norm3(self.conv3(y))) + + if self.downsample is not None: + x = self.downsample(x) + + return self.relu(x+y) + + +DIM=32 + +class BasicEncoder(nn.Module): + def __init__(self, output_dim=128, norm_fn='batch', dropout=0.0, multidim=False): + super(BasicEncoder, self).__init__() + self.norm_fn = norm_fn + self.multidim = multidim + + if self.norm_fn == 'group': + self.norm1 = nn.GroupNorm(num_groups=8, num_channels=DIM) + + elif self.norm_fn == 'batch': + self.norm1 = nn.BatchNorm2d(DIM) + + elif self.norm_fn == 'instance': + self.norm1 = nn.InstanceNorm2d(DIM) + + elif self.norm_fn == 'none': + self.norm1 = nn.Sequential() + + self.conv1 = nn.Conv2d(3, DIM, kernel_size=7, stride=2, padding=3) + self.relu1 = nn.ReLU(inplace=True) + + self.in_planes = DIM + self.layer1 = self._make_layer(DIM, stride=1) + self.layer2 = self._make_layer(2*DIM, stride=2) + self.layer3 = self._make_layer(4*DIM, stride=2) + + # output convolution + self.conv2 = nn.Conv2d(4*DIM, output_dim, kernel_size=1) + + if self.multidim: + self.layer4 = self._make_layer(256, stride=2) + self.layer5 = self._make_layer(512, stride=2) + + self.in_planes = 256 + self.layer6 = self._make_layer(256, stride=1) + + self.in_planes = 128 + self.layer7 = self._make_layer(128, stride=1) + + self.up1 = nn.Conv2d(512, 256, 1) + self.up2 = nn.Conv2d(256, 128, 1) + self.conv3 = nn.Conv2d(128, output_dim, kernel_size=1) + + if dropout > 0: + self.dropout = nn.Dropout2d(p=dropout) + else: + self.dropout = None + + for m in self.modules(): + if isinstance(m, nn.Conv2d): + nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu') + elif isinstance(m, (nn.BatchNorm2d, nn.InstanceNorm2d, nn.GroupNorm)): + if m.weight is not None: + nn.init.constant_(m.weight, 1) + if m.bias is not None: + nn.init.constant_(m.bias, 0) + + def _make_layer(self, dim, stride=1): + layer1 = ResidualBlock(self.in_planes, dim, self.norm_fn, stride=stride) + layer2 = ResidualBlock(dim, dim, self.norm_fn, stride=1) + layers = (layer1, layer2) + + self.in_planes = dim + return nn.Sequential(*layers) + + def forward(self, x): + b, n, c1, h1, w1 = x.shape + x = x.view(b*n, c1, h1, w1) + + x = self.conv1(x) + x = self.norm1(x) + x = self.relu1(x) + + x = self.layer1(x) + x = self.layer2(x) + x = self.layer3(x) + + x = self.conv2(x) + + _, c2, h2, w2 = x.shape + return x.view(b, n, c2, h2, w2) diff --git a/droid_slam/modules/gru.py b/droid_slam/modules/gru.py new file mode 100644 index 00000000..84ea5038 --- /dev/null +++ b/droid_slam/modules/gru.py @@ -0,0 +1,34 @@ +import torch +import torch.nn as nn + + +class ConvGRU(nn.Module): + def __init__(self, h_planes=128, i_planes=128): + super(ConvGRU, self).__init__() + self.do_checkpoint = False + self.convz = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1) + self.convr = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1) + self.convq = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1) + + self.w = nn.Conv2d(h_planes, h_planes, 1, padding=0) + + self.convz_glo = nn.Conv2d(h_planes, h_planes, 1, padding=0) + self.convr_glo = nn.Conv2d(h_planes, h_planes, 1, padding=0) + self.convq_glo = nn.Conv2d(h_planes, h_planes, 1, padding=0) + + def forward(self, net, *inputs): + inp = torch.cat(inputs, dim=1) + net_inp = torch.cat([net, inp], dim=1) + + b, c, h, w = net.shape + glo = torch.sigmoid(self.w(net)) * net + glo = glo.view(b, c, h*w).mean(-1).view(b, c, 1, 1) + + z = torch.sigmoid(self.convz(net_inp) + self.convz_glo(glo)) + r = torch.sigmoid(self.convr(net_inp) + self.convr_glo(glo)) + q = torch.tanh(self.convq(torch.cat([r*net, inp], dim=1)) + self.convq_glo(glo)) + + net = (1-z) * net + z * q + return net + + diff --git a/droid_slam/motion_filter.py b/droid_slam/motion_filter.py new file mode 100644 index 00000000..09912e8f --- /dev/null +++ b/droid_slam/motion_filter.py @@ -0,0 +1,84 @@ +import cv2 +import torch +import lietorch + +from collections import OrderedDict +from droid_net import DroidNet + +import geom.projective_ops as pops +from modules.corr import CorrBlock + + +class MotionFilter: + """ This class is used to filter incoming frames and extract features """ + + def __init__(self, net, video, thresh=2.5, device="cuda:0"): + + # split net modules + self.cnet = net.cnet + self.fnet = net.fnet + self.update = net.update + + self.video = video + self.thresh = thresh + self.device = device + + self.count = 0 + + # mean, std for image normalization + self.MEAN = torch.as_tensor([0.485, 0.456, 0.406], device=self.device)[:, None, None] + self.STDV = torch.as_tensor([0.229, 0.224, 0.225], device=self.device)[:, None, None] + + @torch.cuda.amp.autocast(enabled=True) + def __context_encoder(self, image): + """ context features """ + x = self.cnet(image) + net, inp = self.cnet(image).split([128,128], dim=2) + return net.tanh().squeeze(0), inp.relu().squeeze(0) + + @torch.cuda.amp.autocast(enabled=True) + def __feature_encoder(self, image): + """ features for correlation volume """ + return self.fnet(image).squeeze(0) + + @torch.cuda.amp.autocast(enabled=True) + @torch.no_grad() + def track(self, tstamp, image, depth=None, intrinsics=None): + """ main update operation - run on every frame in video """ + + Id = lietorch.SE3.Identity(1,).data.squeeze() + ht = image.shape[-2] // 8 + wd = image.shape[-1] // 8 + + # normalize images + inputs = image[None, None, [2,1,0]].to(self.device) / 255.0 + inputs = inputs.sub_(self.MEAN).div_(self.STDV) + + # extract features + gmap = self.__feature_encoder(inputs) + + ### always add first frame to the depth video ### + if self.video.counter.value == 0: + net, inp = self.__context_encoder(inputs) + self.net, self.inp, self.fmap = net, inp, gmap + self.video.append(tstamp, image, Id, 1.0, intrinsics / 8.0, gmap[0], net[0], inp[0]) + + ### only add new frame if there is enough motion ### + else: + # index correlation volume + coords0 = pops.coords_grid(ht, wd, device=self.device)[None,None] + corr = CorrBlock(self.fmap[None], gmap[None])(coords0) + + # approximate flow magnitude using 1 update iteration + _, delta, weight = self.update(self.net[None], self.inp[None], corr) + + # check motion magnitue / add new frame to video + if delta.norm(dim=-1).mean().item() > self.thresh: + self.count = 0 + net, inp = self.__context_encoder(inputs) + self.net, self.inp, self.fmap = net, inp, gmap + self.video.append(tstamp, image, None, None, intrinsics / 8.0, gmap[0], net[0], inp[0]) + + else: + self.count += 1 + diff --git a/droid_slam/trajectory_filler.py b/droid_slam/trajectory_filler.py new file mode 100644 index 00000000..96438c29 --- /dev/null +++ b/droid_slam/trajectory_filler.py @@ -0,0 +1,104 @@ +import cv2 +import torch +import lietorch + +from lietorch import SE3 +from collections import OrderedDict +from factor_graph import FactorGraph +from droid_net import DroidNet +import geom.projective_ops as pops + + +class PoseTrajectoryFiller: + """ This class is used to fill in non-keyframe poses """ + + def __init__(self, net, video, device="cuda:0"): + + # split net modules + self.cnet = net.cnet + self.fnet = net.fnet + self.update = net.update + + self.count = 0 + self.video = video + self.device = device + + # mean, std for image normalization + self.MEAN = torch.as_tensor([0.485, 0.456, 0.406], device=self.device)[:, None, None] + self.STDV = torch.as_tensor([0.229, 0.224, 0.225], device=self.device)[:, None, None] + + @torch.cuda.amp.autocast(enabled=True) + def __feature_encoder(self, image): + """ features for correlation volume """ + return self.fnet(image).squeeze(0) + + def __fill(self, tstamps, images, intrinsics): + """ fill operator """ + + tt = torch.as_tensor(tstamps, device="cuda") + images = torch.stack(images, 0) + intrinsics = torch.stack(intrinsics, 0) + inputs = images[None,:,[2,1,0]].to(self.device) / 255.0 + + ### linear pose interpolation ### + N = self.video.counter.value + M = len(tstamps) + + ts = self.video.tstamp[:N] + Ps = SE3(self.video.poses[:N]) + + t0 = torch.as_tensor([ts[ts<=t].shape[0] - 1 for t in tstamps]) + t1 = torch.where(t0 0: + pose_list += self.__fill(tstamps, images, intrinsics) + + # stitch pose segments together + return lietorch.cat(pose_list, 0) + diff --git a/droid_slam/visualization.py b/droid_slam/visualization.py new file mode 100644 index 00000000..b28cc755 --- /dev/null +++ b/droid_slam/visualization.py @@ -0,0 +1,154 @@ +import torch +import cv2 +import lietorch +import droid_backends +import time +import argparse +import numpy as np +import open3d as o3d + +from lietorch import SE3 +import geom.projective_ops as pops + +CAM_POINTS = np.array([ + [ 0, 0, 0], + [-1, -1, 1.5], + [ 1, -1, 1.5], + [ 1, 1, 1.5], + [-1, 1, 1.5], + [-0.5, 1, 1.5], + [ 0.5, 1, 1.5], + [ 0, 1.2, 1.5]]) + +CAM_LINES = np.array([ + [1,2], [2,3], [3,4], [4,1], [1,0], [0,2], [3,0], [0,4], [5,7], [7,6]]) + +def white_balance(img): + # from https://stackoverflow.com/questions/46390779/automatic-white-balancing-with-grayworld-assumption + result = cv2.cvtColor(img, cv2.COLOR_BGR2LAB) + avg_a = np.average(result[:, :, 1]) + avg_b = np.average(result[:, :, 2]) + result[:, :, 1] = result[:, :, 1] - ((avg_a - 128) * (result[:, :, 0] / 255.0) * 1.1) + result[:, :, 2] = result[:, :, 2] - ((avg_b - 128) * (result[:, :, 0] / 255.0) * 1.1) + result = cv2.cvtColor(result, cv2.COLOR_LAB2BGR) + return result + +def create_camera_actor(g, scale=0.05): + """ build open3d camera polydata """ + camera_actor = o3d.geometry.LineSet( + points=o3d.utility.Vector3dVector(scale * CAM_POINTS), + lines=o3d.utility.Vector2iVector(CAM_LINES)) + + color = (g * 1.0, 0.5 * (1-g), 0.9 * (1-g)) + camera_actor.paint_uniform_color(color) + return camera_actor + +def create_point_actor(points, colors): + """ open3d point cloud from numpy array """ + point_cloud = o3d.geometry.PointCloud() + point_cloud.points = o3d.utility.Vector3dVector(points) + point_cloud.colors = o3d.utility.Vector3dVector(colors) + return point_cloud + +def droid_visualization(video, device="cuda:0"): + """ DROID visualization frontend """ + + torch.cuda.set_device(device) + droid_visualization.video = video + droid_visualization.cameras = {} + droid_visualization.points = {} + droid_visualization.warmup = 8 + droid_visualization.scale = 1.0 + droid_visualization.ix = 0 + + droid_visualization.filter_thresh = 0.005 + + def increase_filter(vis): + droid_visualization.filter_thresh *= 2 + with droid_visualization.video.get_lock(): + droid_visualization.video.dirty[:droid_visualization.video.counter.value] = True + + def decrease_filter(vis): + droid_visualization.filter_thresh *= 0.5 + with droid_visualization.video.get_lock(): + droid_visualization.video.dirty[:droid_visualization.video.counter.value] = True + + def animation_callback(vis): + cam = vis.get_view_control().convert_to_pinhole_camera_parameters() + + with torch.no_grad(): + + with video.get_lock(): + t = video.counter.value + dirty_index, = torch.where(video.dirty.clone()) + dirty_index = dirty_index + + if len(dirty_index) == 0: + return + + video.dirty[dirty_index] = False + + # convert poses to 4x4 matrix + poses = torch.index_select(video.poses, 0, dirty_index) + disps = torch.index_select(video.disps, 0, dirty_index) + Ps = SE3(poses).inv().matrix().cpu().numpy() + + images = torch.index_select(video.images, 0, dirty_index) + images = images.cpu()[:,[2,1,0],3::8,3::8].permute(0,2,3,1) / 255.0 + points = droid_backends.iproj(SE3(poses).inv().data, disps, video.intrinsics[0]).cpu() + + thresh = droid_visualization.filter_thresh * torch.ones_like(disps.mean(dim=[1,2])) + + count = droid_backends.depth_filter( + video.poses, video.disps, video.intrinsics[0], dirty_index, thresh) + + count = count.cpu() + disps = disps.cpu() + masks = ((count >= 2) & (disps > .5*disps.mean(dim=[1,2], keepdim=True))) + + for i in range(len(dirty_index)): + pose = Ps[i] + ix = dirty_index[i].item() + + if ix in droid_visualization.cameras: + vis.remove_geometry(droid_visualization.cameras[ix]) + del droid_visualization.cameras[ix] + + if ix in droid_visualization.points: + vis.remove_geometry(droid_visualization.points[ix]) + del droid_visualization.points[ix] + + ### add camera actor ### + cam_actor = create_camera_actor(True) + cam_actor.transform(pose) + vis.add_geometry(cam_actor) + droid_visualization.cameras[ix] = cam_actor + + mask = masks[i].reshape(-1) + pts = points[i].reshape(-1, 3)[mask].cpu().numpy() + clr = images[i].reshape(-1, 3)[mask].cpu().numpy() + + ## add point actor ### + point_actor = create_point_actor(pts, clr) + vis.add_geometry(point_actor) + droid_visualization.points[ix] = point_actor + + # hack to allow interacting with vizualization during inference + if len(droid_visualization.cameras) >= droid_visualization.warmup: + cam = vis.get_view_control().convert_from_pinhole_camera_parameters(cam) + + droid_visualization.ix += 1 + vis.poll_events() + vis.update_renderer() + + ### create Open3D visualization ### + vis = o3d.visualization.VisualizerWithKeyCallback() + vis.register_animation_callback(animation_callback) + vis.register_key_callback(ord("S"), increase_filter) + vis.register_key_callback(ord("A"), decrease_filter) + + vis.create_window(height=540, width=960) + vis.get_render_option().load_from_json("misc/renderoption.json") + + vis.run() + vis.destroy_window() diff --git a/environment.yaml b/environment.yaml new file mode 100644 index 00000000..caf588ad --- /dev/null +++ b/environment.yaml @@ -0,0 +1,22 @@ +name: droidenv +channels: + - rusty1s + - pytorch + - open3d-admin + - nvidia + - conda-forge + - defaults +dependencies: + - pytorch-scatter + - torchaudio + - torchvision + - open3d + - pytorch + - cudatoolkit=11.1 + - tensorboard + - scipy + - opencv + - tqdm + - suitesparse + - matplotlib + - pyyaml diff --git a/environment_novis.yaml b/environment_novis.yaml new file mode 100644 index 00000000..d6c8cbec --- /dev/null +++ b/environment_novis.yaml @@ -0,0 +1,20 @@ +name: droidenv +channels: + - rusty1s + - pytorch + - nvidia + - conda-forge + - defaults +dependencies: + - pytorch-scatter + - torchaudio + - torchvision + - pytorch + - cudatoolkit=11.1 + - tensorboard + - scipy + - opencv + - tqdm + - suitesparse + - matplotlib + - pyyaml diff --git a/evaluation_scripts/test_euroc.py b/evaluation_scripts/test_euroc.py new file mode 100644 index 00000000..4fc4b26f --- /dev/null +++ b/evaluation_scripts/test_euroc.py @@ -0,0 +1,135 @@ +import sys +sys.path.append('droid_slam') + +from tqdm import tqdm +import numpy as np +import torch +import lietorch +import cv2 +import os +import glob +import time +import argparse + +from torch.multiprocessing import Process +from droid import Droid + +import torch.nn.functional as F + + + +def show_image(image): + image = image.permute(1, 2, 0).cpu().numpy() + cv2.imshow('image', image / 255.0) + cv2.waitKey(1) + +def image_stream(datapath, image_size=[320, 512], stereo=False): + """ image generator """ + + K_l = np.array([458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]).reshape(3,3) + d_l = np.array([-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]) + R_l = np.array([0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176]).reshape(3,3) + P_l = np.array([435.2046959714599, 0, 367.4517211914062, 0, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]).reshape(3,4) + map_l = cv2.initUndistortRectifyMap(K_l, d_l, R_l, P_l[:3,:3], (752, 480), cv2.CV_32F) + + K_r = np.array([457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1]).reshape(3,3) + d_r = np.array([-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0]).reshape(5) + R_r = np.array([0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]).reshape(3,3) + P_r = np.array([435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0]).reshape(3,4) + map_r = cv2.initUndistortRectifyMap(K_r, d_r, R_r, P_r[:3,:3], (752, 480), cv2.CV_32F) + + intrinsics_vec = [435.2046959714599, 435.2046959714599, 367.4517211914062, 252.2008514404297] + ht0, wd0 = [480, 752] + + # read all png images in folder + images_left = sorted(glob.glob(os.path.join(datapath, 'mav0/cam0/data/*.png')))[::2] + images_right = [x.replace('cam0', 'cam1') for x in images_left] + + for t, (imgL, imgR) in enumerate(zip(images_left, images_right)): + tstamp = float(imgL.split('/')[-1][:-4]) + images = [cv2.remap(cv2.imread(imgL), map_l[0], map_l[1], interpolation=cv2.INTER_LINEAR)] + if stereo: + images += [cv2.remap(cv2.imread(imgR), map_r[0], map_r[1], interpolation=cv2.INTER_LINEAR)] + + images = torch.from_numpy(np.stack(images, 0)) + images = images.permute(0, 3, 1, 2).to("cuda:0", dtype=torch.float32) + images = F.interpolate(images, image_size, mode="bilinear", align_corners=False) + + intrinsics = torch.as_tensor(intrinsics_vec).cuda() + intrinsics[0] *= image_size[1] / wd0 + intrinsics[1] *= image_size[0] / ht0 + intrinsics[2] *= image_size[1] / wd0 + intrinsics[3] *= image_size[0] / ht0 + + yield t, images[0], intrinsics + + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument("--datapath", help="path to euroc sequence") + parser.add_argument("--gt", help="path to gt file") + parser.add_argument("--weights", default="droid.pth") + parser.add_argument("--buffer", type=int, default=512) + parser.add_argument("--image_size", default=[320,512]) + parser.add_argument("--disable_vis", action="store_true") + + parser.add_argument("--beta", type=float, default=0.3) + parser.add_argument("--filter_thresh", type=float, default=2.4) + parser.add_argument("--warmup", type=int, default=15) + parser.add_argument("--keyframe_thresh", type=float, default=3.4) + parser.add_argument("--frontend_thresh", type=float, default=15.0) + parser.add_argument("--frontend_window", type=int, default=20) + parser.add_argument("--frontend_radius", type=int, default=2) + parser.add_argument("--frontend_nms", type=int, default=1) + + parser.add_argument("--backend_thresh", type=float, default=22.0) + parser.add_argument("--backend_radius", type=int, default=2) + parser.add_argument("--backend_nms", type=int, default=2) + args = parser.parse_args() + + torch.multiprocessing.set_start_method('spawn') + + print("Running evaluation on {}".format(args.datapath)) + print(args) + + + droid = Droid(args) + time.sleep(5) + + tstamps = [] + for (t, image, intrinsics) in tqdm(image_stream(args.datapath)): + if not args.disable_vis: + show_image(image) + + droid.track(t, image, intrinsics=intrinsics) + + traj_est = droid.terminate(image_stream(args.datapath)) + + ### run evaluation ### + + import evo + from evo.core.trajectory import PoseTrajectory3D + from evo.tools import file_interface + from evo.core import sync + import evo.main_ape as main_ape + from evo.core.metrics import PoseRelation + + + images_list = sorted(glob.glob(os.path.join(args.datapath, 'mav0/cam0/data/*.png')))[::2] + tstamps = [float(x.split('/')[-1][:-4]) for x in images_list] + + traj_est = PoseTrajectory3D( + positions_xyz=traj_est[:,:3], + orientations_quat_wxyz=traj_est[:,3:], + timestamps=np.array(tstamps)) + + traj_ref = file_interface.read_tum_trajectory_file(args.gt) + + traj_ref, traj_est = sync.associate_trajectories(traj_ref, traj_est) + result = main_ape.ape(traj_ref, traj_est, est_name='traj', + pose_relation=PoseRelation.translation_part, align=True, correct_scale=True) + + + print(result) + + diff --git a/evaluation_scripts/test_tum.py b/evaluation_scripts/test_tum.py new file mode 100644 index 00000000..eac9767a --- /dev/null +++ b/evaluation_scripts/test_tum.py @@ -0,0 +1,125 @@ +import sys +sys.path.append('droid_slam') + +from tqdm import tqdm +import numpy as np +import torch +import lietorch +import cv2 +import os +import glob +import time +import argparse + +import torch.nn.functional as F +from droid import Droid + + +def show_image(image): + image = image.permute(1, 2, 0).cpu().numpy() + cv2.imshow('image', image / 255.0) + cv2.waitKey(1) + +def image_stream(datapath, image_size=[320, 512]): + """ image generator """ + + fx, fy, cx, cy = 517.3, 516.5, 318.6, 255.3 + + K_l = np.array([fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0]).reshape(3,3) + d_l = np.array([0.2624, -0.9531, -0.0054, 0.0026, 1.1633]) + + # read all png images in folder + images_list = sorted(glob.glob(os.path.join(datapath, 'rgb', '*.png')))[::2] + + for t, imfile in enumerate(images_list): + image = cv2.imread(imfile) + ht0, wd0, _ = image.shape + image = cv2.undistort(image, K_l, d_l) + image = cv2.resize(image, (320+32, 240+16)) + image = torch.from_numpy(image).permute(2,0,1) + + intrinsics = torch.as_tensor([fx, fy, cx, cy]).cuda() + intrinsics[0] *= image.shape[2] / 640.0 + intrinsics[1] *= image.shape[1] / 480.0 + intrinsics[2] *= image.shape[2] / 640.0 + intrinsics[3] *= image.shape[1] / 480.0 + + # crop image to remove distortion boundary + intrinsics[2] -= 16 + intrinsics[3] -= 8 + image = image[:, 8:-8, 16:-16] + + yield t, image, intrinsics + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument("--datapath") + parser.add_argument("--weights", default="droid.pth") + parser.add_argument("--buffer", type=int, default=512) + parser.add_argument("--image_size", default=[240, 320]) + parser.add_argument("--disable_vis", action="store_true") + + parser.add_argument("--beta", type=float, default=0.6) + parser.add_argument("--filter_thresh", type=float, default=1.75) + parser.add_argument("--warmup", type=int, default=12) + parser.add_argument("--keyframe_thresh", type=float, default=2.25) + parser.add_argument("--frontend_thresh", type=float, default=12.0) + parser.add_argument("--frontend_window", type=int, default=25) + parser.add_argument("--frontend_radius", type=int, default=2) + parser.add_argument("--frontend_nms", type=int, default=1) + + parser.add_argument("--backend_thresh", type=float, default=15.0) + parser.add_argument("--backend_radius", type=int, default=2) + parser.add_argument("--backend_nms", type=int, default=3) + args = parser.parse_args() + + torch.multiprocessing.set_start_method('spawn') + + print("Running evaluation on {}".format(args.datapath)) + print(args) + + droid = Droid(args) + time.sleep(5) + + tstamps = [] + for (t, image, intrinsics) in tqdm(image_stream(args.datapath)): + if not args.disable_vis: + show_image(image) + droid.track(t, image, intrinsics=intrinsics) + + + traj_est = droid.terminate(image_stream(args.datapath)) + + ### run evaluation ### + + print("#"*20 + " Results...") + + + import evo + from evo.core.trajectory import PoseTrajectory3D + from evo.tools import file_interface + from evo.core import sync + import evo.main_ape as main_ape + from evo.core.metrics import PoseRelation + + + image_path = os.path.join(args.datapath, 'rgb') + images_list = sorted(glob.glob(os.path.join(image_path, '*.png')))[::2] + tstamps = [float(x.split('/')[-1][:-4]) for x in images_list] + + + traj_est = PoseTrajectory3D( + positions_xyz=traj_est[:,:3], + orientations_quat_wxyz=traj_est[:,3:], + timestamps=np.array(tstamps)) + + gt_file = os.path.join(args.datapath, 'groundtruth.txt') + traj_ref = file_interface.read_tum_trajectory_file(gt_file) + + traj_ref, traj_est = sync.associate_trajectories(traj_ref, traj_est) + result = main_ape.ape(traj_ref, traj_est, est_name='traj', + pose_relation=PoseRelation.translation_part, align=True, correct_scale=True) + + + print(result) + diff --git a/evaluation_scripts/validate_tartanair.py b/evaluation_scripts/validate_tartanair.py new file mode 100644 index 00000000..95bdca14 --- /dev/null +++ b/evaluation_scripts/validate_tartanair.py @@ -0,0 +1,98 @@ +import sys +sys.path.append('droid_slam') +sys.path.append('thirdparty/tartanair_tools') + +from tqdm import tqdm +import numpy as np +import torch +import lietorch +import cv2 +import os +import glob +import time +import yaml +import argparse + +from droid import Droid + +def image_stream(datapath, image_size=[384, 512], intrinsics_vec=[320.0, 320.0, 320.0, 240.0], stereo=False): + """ image generator """ + + # read all png images in folder + ht0, wd0 = [480, 640] + images = sorted(glob.glob(os.path.join(datapath, 'image_left/*.png'))) + + for t in range(len(images)): + image = cv2.resize(cv2.imread(images[t]), (image_size[1], image_size[0])) + image = torch.from_numpy(image).permute(2, 0, 1) + + intrinsics = .8 * torch.as_tensor(intrinsics_vec) + yield t, image, intrinsics + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument("--datapath") + parser.add_argument("--weights", default="droid.pth") + parser.add_argument("--buffer", type=int, default=1024) + parser.add_argument("--config", default="config/TartanAir.yaml") + parser.add_argument("--image_size", default=[384,512]) + parser.add_argument("--disable_vis", action="store_true") + parser.add_argument("--plot_curve", action="store_true") + + parser.add_argument("--beta", type=float, default=0.3) + parser.add_argument("--filter_thresh", type=float, default=2.4) + parser.add_argument("--warmup", type=int, default=12) + parser.add_argument("--keyframe_thresh", type=float, default=3.5) + parser.add_argument("--frontend_thresh", type=float, default=16) + parser.add_argument("--frontend_window", type=int, default=20) + parser.add_argument("--frontend_radius", type=int, default=1) + parser.add_argument("--frontend_nms", type=int, default=1) + + parser.add_argument("--backend_thresh", type=float, default=20.0) + parser.add_argument("--backend_radius", type=int, default=2) + parser.add_argument("--backend_nms", type=int, default=3) + + args = parser.parse_args() + torch.multiprocessing.set_start_method('spawn') + + from data_readers.tartan import test_split + from evaluation.tartanair_evaluator import TartanAirEvaluator + + ate_list = [] + for scene in test_split: + print("Performing evaluation on {}".format(scene)) + torch.cuda.empty_cache() + droid = Droid(args) + + scenedir = os.path.join(args.datapath, scene) + for (tstamp, image, intrinsics) in tqdm(image_stream(scenedir)): + droid.track(tstamp, image, intrinsics=intrinsics) + + # fill in non-keyframe poses + global BA + traj_est = droid.terminate(image_stream(scenedir)) + + ### do evaluation ### + evaluator = TartanAirEvaluator() + gt_file = os.path.join(scenedir, "pose_left.txt") + traj_ref = np.loadtxt(gt_file, delimiter=' ')[:, [1, 2, 0, 4, 5, 3, 6]] # ned -> xyz + + results = evaluator.evaluate_one_trajectory( + traj_ref, traj_est, scale=True, title=scenedir[-20:].replace('/', '_')) + + print(results) + ate_list.append(results["ate_score"]) + + print("Results") + print(ate_list) + + if args.plot_curve: + import matplotlib.pyplot as plt + ate = np.array(ate_list) + xs = np.linspace(0.0, 1.0, 512) + ys = [np.count_nonzero(ate < t) / ate.shape[0] for t in xs] + + plt.plot(xs, ys) + plt.xlabel("ATE [m]") + plt.ylabel("% runs") + plt.show() + diff --git a/misc/renderoption.json b/misc/renderoption.json new file mode 100644 index 00000000..80d35c4b --- /dev/null +++ b/misc/renderoption.json @@ -0,0 +1,40 @@ +{ + "background_color" : [ 1, 1, 1 ], + "class_name" : "RenderOption", + "default_mesh_color" : [ 0.69999999999999996, 0.69999999999999996, 0.69999999999999996 ], + "image_max_depth" : 3000, + "image_stretch_option" : 0, + "interpolation_option" : 0, + "light0_color" : [ 1, 1, 1 ], + "light0_diffuse_power" : 20, + "light0_position" : [ 0, 0, 20 ], + "light0_specular_power" : 2.20000000000000001, + "light0_specular_shininess" : 100, + "light1_color" : [ 1, 1, 1 ], + "light1_diffuse_power" : 0.66000000000000003, + "light1_position" : [ 0, 0, 2 ], + "light1_specular_power" : 2.20000000000000001, + "light1_specular_shininess" : 100, + "light2_color" : [ 1, 1, 1 ], + "light2_diffuse_power" : 20, + "light2_position" : [ 0, 0, -20 ], + "light2_specular_power" : 2.20000000000000001, + "light2_specular_shininess" : 100, + "light3_color" : [ 1, 1, 1 ], + "light3_diffuse_power" : 20, + "light3_position" : [ 0, 0, -20 ], + "light3_specular_power" : 2.20000000000000001, + "light3_specular_shininess" : 100, + "light_ambient_color" : [ 0, 0, 0 ], + "light_on" : true, + "mesh_color_option" : 1, + "mesh_shade_option" : 0, + "mesh_show_back_face" : false, + "mesh_show_wireframe" : false, + "point_color_option" : 7, + "point_show_normal" : false, + "point_size" : 2, + "show_coordinate_frame" : false, + "version_major" : 1, + "version_minor" : 0 +} diff --git a/setup.py b/setup.py new file mode 100644 index 00000000..9af97d49 --- /dev/null +++ b/setup.py @@ -0,0 +1,61 @@ +from setuptools import setup +from torch.utils.cpp_extension import BuildExtension, CUDAExtension + +import os.path as osp +ROOT = osp.dirname(osp.abspath(__file__)) + +setup( + name='droid_backends', + ext_modules=[ + CUDAExtension('droid_backends', + include_dirs=[osp.join(ROOT, 'thirdparty/eigen')], + sources=[ + 'src/droid.cpp', + 'src/droid_kernels.cu', + 'src/correlation_kernels.cu', + 'src/altcorr_kernel.cu', + ], + extra_compile_args={ + 'cxx': ['-O3'], + 'nvcc': ['-O3', + '-gencode=arch=compute_60,code=sm_60', + '-gencode=arch=compute_61,code=sm_61', + '-gencode=arch=compute_70,code=sm_70', + '-gencode=arch=compute_75,code=sm_75', + '-gencode=arch=compute_80,code=sm_80', + '-gencode=arch=compute_86,code=sm_86', + ] + }), + ], + cmdclass={ 'build_ext' : BuildExtension } +) + +setup( + name='lietorch', + version='0.2', + description='Lie Groups for PyTorch', + packages=['lietorch'], + package_dir={'': 'thirdparty/lietorch'}, + ext_modules=[ + CUDAExtension('lietorch_backends', + include_dirs=[ + osp.join(ROOT, 'thirdparty/lietorch/lietorch/include'), + osp.join(ROOT, 'thirdparty/eigen')], + sources=[ + 'thirdparty/lietorch/lietorch/src/lietorch.cpp', + 'thirdparty/lietorch/lietorch/src/lietorch_gpu.cu', + 'thirdparty/lietorch/lietorch/src/lietorch_cpu.cpp'], + extra_compile_args={ + 'cxx': ['-O2'], + 'nvcc': ['-O2', + '-gencode=arch=compute_60,code=sm_60', + '-gencode=arch=compute_61,code=sm_61', + '-gencode=arch=compute_70,code=sm_70', + '-gencode=arch=compute_75,code=sm_75', + '-gencode=arch=compute_80,code=sm_80', + '-gencode=arch=compute_86,code=sm_86', + ] + }), + ], + cmdclass={ 'build_ext' : BuildExtension } +) diff --git a/src/altcorr_kernel.cu b/src/altcorr_kernel.cu new file mode 100644 index 00000000..f418f5cd --- /dev/null +++ b/src/altcorr_kernel.cu @@ -0,0 +1,356 @@ +#include +#include +#include +#include +#include +#include + + +#include +#include +#include +#include + + + +#define BLOCK_H 4 +#define BLOCK_W 8 +#define BLOCK_HW BLOCK_H * BLOCK_W +#define CHANNEL_STRIDE 32 + + +__forceinline__ __device__ +bool within_bounds(int h, int w, int H, int W) { + return h >= 0 && h < H && w >= 0 && w < W; +} + +template +__global__ void altcorr_forward_kernel( + const torch::PackedTensorAccessor32 fmap1, + const torch::PackedTensorAccessor32 fmap2, + const torch::PackedTensorAccessor32 coords, + torch::PackedTensorAccessor32 corr, + int r) +{ + const int b = blockIdx.x; + const int h0 = blockIdx.y * blockDim.x; + const int w0 = blockIdx.z * blockDim.y; + const int tid = threadIdx.x * blockDim.y + threadIdx.y; + + const int H1 = fmap1.size(1); + const int W1 = fmap1.size(2); + const int H2 = fmap2.size(1); + const int W2 = fmap2.size(2); + const int N = coords.size(1); + const int C = fmap1.size(3); + + __shared__ scalar_t f1[CHANNEL_STRIDE][BLOCK_HW]; + __shared__ scalar_t f2[CHANNEL_STRIDE][BLOCK_HW]; + + __shared__ float x2s[BLOCK_HW]; + __shared__ float y2s[BLOCK_HW]; + + for (int c=0; c(floor(y2s[k1])) - r + iy; + int w2 = static_cast(floor(x2s[k1])) - r + ix; + int c2 = tid % CHANNEL_STRIDE; + + if (within_bounds(h2, w2, H2, W2)) + f2[c2][k1] = fmap2[b][h2][w2][c+c2]; + + else + f2[c2][k1] = static_cast(0.0); + } + + __syncthreads(); + + scalar_t s = 0.0; + for (int k=0; k((dy) * (dx)); + scalar_t ne = s * static_cast((dy) * (1-dx)); + scalar_t sw = s * static_cast((1-dy) * (dx)); + scalar_t se = s * static_cast((1-dy) * (1-dx)); + + // if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1)) + // corr[b][n][ix_nw][h1][w1] += nw; + + // if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1)) + // corr[b][n][ix_ne][h1][w1] += ne; + + // if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1)) + // corr[b][n][ix_sw][h1][w1] += sw; + + // if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1)) + // corr[b][n][ix_se][h1][w1] += se; + + + scalar_t* corr_ptr = &corr[b][n][0][h1][w1]; + + if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1)) + *(corr_ptr + ix_nw) += nw; + + if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1)) + *(corr_ptr + ix_ne) += ne; + + if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1)) + *(corr_ptr + ix_sw) += sw; + + if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1)) + *(corr_ptr + ix_se) += se; + + + } + } + } + } +} + + +template +__global__ void altcorr_backward_kernel( + const torch::PackedTensorAccessor32 fmap1, + const torch::PackedTensorAccessor32 fmap2, + const torch::PackedTensorAccessor32 coords, + const torch::PackedTensorAccessor32 corr_grad, + torch::PackedTensorAccessor32 fmap1_grad, + torch::PackedTensorAccessor32 fmap2_grad, + torch::PackedTensorAccessor32 coords_grad, + int r) +{ + + const int b = blockIdx.x; + const int h0 = blockIdx.y * blockDim.x; + const int w0 = blockIdx.z * blockDim.y; + const int tid = threadIdx.x * blockDim.y + threadIdx.y; + + const int H1 = fmap1.size(1); + const int W1 = fmap1.size(2); + const int H2 = fmap2.size(1); + const int W2 = fmap2.size(2); + const int N = coords.size(1); + const int C = fmap1.size(3); + + __shared__ scalar_t f1[CHANNEL_STRIDE][BLOCK_HW+1]; + __shared__ scalar_t f2[CHANNEL_STRIDE][BLOCK_HW+1]; + + __shared__ scalar_t f1_grad[CHANNEL_STRIDE][BLOCK_HW+1]; + __shared__ scalar_t f2_grad[CHANNEL_STRIDE][BLOCK_HW+1]; + + __shared__ scalar_t x2s[BLOCK_HW]; + __shared__ scalar_t y2s[BLOCK_HW]; + + for (int c=0; c(floor(y2s[k1]))-r+iy; + int w2 = static_cast(floor(x2s[k1]))-r+ix; + int c2 = tid % CHANNEL_STRIDE; + + auto fptr = fmap2[b][h2][w2]; + if (within_bounds(h2, w2, H2, W2)) + f2[c2][k1] = fptr[c+c2]; + else + f2[c2][k1] = 0.0; + + f2_grad[c2][k1] = 0.0; + } + + __syncthreads(); + + const scalar_t* grad_ptr = &corr_grad[b][n][0][h1][w1]; + scalar_t g = 0.0; + + int ix_nw = H1*W1*((iy-1) + rd*(ix-1)); + int ix_ne = H1*W1*((iy-1) + rd*ix); + int ix_sw = H1*W1*(iy + rd*(ix-1)); + int ix_se = H1*W1*(iy + rd*ix); + + if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1)) + g += *(grad_ptr + ix_nw) * dy * dx; + + if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1)) + g += *(grad_ptr + ix_ne) * dy * (1-dx); + + if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1)) + g += *(grad_ptr + ix_sw) * (1-dy) * dx; + + if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1)) + g += *(grad_ptr + ix_se) * (1-dy) * (1-dx); + + for (int k=0; k(floor(y2s[k1]))-r+iy; + int w2 = static_cast(floor(x2s[k1]))-r+ix; + int c2 = tid % CHANNEL_STRIDE; + + scalar_t* fptr = &fmap2_grad[b][h2][w2][0]; + if (within_bounds(h2, w2, H2, W2)) + atomicAdd(fptr+c+c2, f2_grad[c2][k1]); + } + } + } + } + __syncthreads(); + + + for (int k=0; k altcorr_cuda_forward( + torch::Tensor fmap1, + torch::Tensor fmap2, + torch::Tensor coords, + int radius) +{ + const auto B = coords.size(0); + const auto N = coords.size(1); + const auto H = coords.size(2); + const auto W = coords.size(3); + + const auto rd = 2 * radius + 1; + auto opts = fmap1.options(); + auto corr = torch::zeros({B, N, rd*rd, H, W}, opts); + + const dim3 blocks(B, (H+BLOCK_H-1)/BLOCK_H, (W+BLOCK_W-1)/BLOCK_W); + const dim3 threads(BLOCK_H, BLOCK_W); + + + AT_DISPATCH_FLOATING_TYPES_AND_HALF(fmap1.type(), "altcorr_forward_kernel", ([&] { + altcorr_forward_kernel<<>>( + fmap1.packed_accessor32(), + fmap2.packed_accessor32(), + coords.packed_accessor32(), + corr.packed_accessor32(), + radius); + })); + + return {corr}; +} + +std::vector altcorr_cuda_backward( + torch::Tensor fmap1, + torch::Tensor fmap2, + torch::Tensor coords, + torch::Tensor corr_grad, + int radius) +{ + const auto B = coords.size(0); + const auto N = coords.size(1); + + const auto H1 = fmap1.size(1); + const auto W1 = fmap1.size(2); + const auto H2 = fmap2.size(1); + const auto W2 = fmap2.size(2); + const auto C = fmap1.size(3); + + auto opts = fmap1.options(); + auto fmap1_grad = torch::zeros({B, H1, W1, C}, opts); + auto fmap2_grad = torch::zeros({B, H2, W2, C}, opts); + auto coords_grad = torch::zeros({B, N, H1, W1, 2}, opts); + + const dim3 blocks(B, (H1+BLOCK_H-1)/BLOCK_H, (W1+BLOCK_W-1)/BLOCK_W); + const dim3 threads(BLOCK_H, BLOCK_W); + + altcorr_backward_kernel<<>>( + fmap1.packed_accessor32(), + fmap2.packed_accessor32(), + coords.packed_accessor32(), + corr_grad.packed_accessor32(), + fmap1_grad.packed_accessor32(), + fmap2_grad.packed_accessor32(), + coords_grad.packed_accessor32(), + radius); + + return {fmap1_grad, fmap2_grad, coords_grad}; +} \ No newline at end of file diff --git a/src/correlation_kernels.cu b/src/correlation_kernels.cu new file mode 100644 index 00000000..2812067b --- /dev/null +++ b/src/correlation_kernels.cu @@ -0,0 +1,185 @@ +#include +#include +#include +#include +#include +#include + + +#include +#include +#include + +#define BLOCK 16 + +__forceinline__ __device__ bool within_bounds(int h, int w, int H, int W) { + return h >= 0 && h < H && w >= 0 && w < W; +} + +template +__global__ void corr_index_forward_kernel( + const torch::PackedTensorAccessor32 volume, + const torch::PackedTensorAccessor32 coords, + torch::PackedTensorAccessor32 corr, + int r) +{ + // batch index + const int x = blockIdx.x * blockDim.x + threadIdx.x; + const int y = blockIdx.y * blockDim.y + threadIdx.y; + const int n = blockIdx.z; + + const int h1 = volume.size(1); + const int w1 = volume.size(2); + const int h2 = volume.size(3); + const int w2 = volume.size(4); + + if (!within_bounds(y, x, h1, w1)) { + return; + } + + float x0 = coords[n][0][y][x]; + float y0 = coords[n][1][y][x]; + + float dx = x0 - floor(x0); + float dy = y0 - floor(y0); + + int rd = 2*r + 1; + for (int i=0; i(floor(x0)) - r + i; + int y1 = static_cast(floor(y0)) - r + j; + + if (within_bounds(y1, x1, h2, w2)) { + scalar_t s = volume[n][y][x][y1][x1]; + + if (i > 0 && j > 0) + corr[n][i-1][j-1][y][x] += s * scalar_t(dx * dy); + + if (i > 0 && j < rd) + corr[n][i-1][j][y][x] += s * scalar_t(dx * (1.0f-dy)); + + if (i < rd && j > 0) + corr[n][i][j-1][y][x] += s * scalar_t((1.0f-dx) * dy); + + if (i < rd && j < rd) + corr[n][i][j][y][x] += s * scalar_t((1.0f-dx) * (1.0f-dy)); + + } + } + } +} + + +template +__global__ void corr_index_backward_kernel( + const torch::PackedTensorAccessor32 coords, + const torch::PackedTensorAccessor32 corr_grad, + torch::PackedTensorAccessor32 volume_grad, + int r) +{ + // batch index + const int x = blockIdx.x * blockDim.x + threadIdx.x; + const int y = blockIdx.y * blockDim.y + threadIdx.y; + const int n = blockIdx.z; + + const int h1 = volume_grad.size(1); + const int w1 = volume_grad.size(2); + const int h2 = volume_grad.size(3); + const int w2 = volume_grad.size(4); + + if (!within_bounds(y, x, h1, w1)) { + return; + } + + float x0 = coords[n][0][y][x]; + float y0 = coords[n][1][y][x]; + + float dx = x0 - floor(x0); + float dy = y0 - floor(y0); + + int rd = 2*r + 1; + for (int i=0; i(floor(x0)) - r + i; + int y1 = static_cast(floor(y0)) - r + j; + + if (within_bounds(y1, x1, h2, w2)) { + scalar_t g = 0.0; + if (i > 0 && j > 0) + g += corr_grad[n][i-1][j-1][y][x] * scalar_t(dx * dy); + + if (i > 0 && j < rd) + g += corr_grad[n][i-1][j][y][x] * scalar_t(dx * (1.0f-dy)); + + if (i < rd && j > 0) + g += corr_grad[n][i][j-1][y][x] * scalar_t((1.0f-dx) * dy); + + if (i < rd && j < rd) + g += corr_grad[n][i][j][y][x] * scalar_t((1.0f-dx) * (1.0f-dy)); + + volume_grad[n][y][x][y1][x1] += g; + } + } + } +} + +std::vector corr_index_cuda_forward( + torch::Tensor volume, + torch::Tensor coords, + int radius) +{ + const auto batch_size = volume.size(0); + const auto ht = volume.size(1); + const auto wd = volume.size(2); + + const dim3 blocks((wd + BLOCK - 1) / BLOCK, + (ht + BLOCK - 1) / BLOCK, + batch_size); + + const dim3 threads(BLOCK, BLOCK); + + auto opts = volume.options(); + torch::Tensor corr = torch::zeros( + {batch_size, 2*radius+1, 2*radius+1, ht, wd}, opts); + + AT_DISPATCH_FLOATING_TYPES_AND_HALF(volume.type(), "sampler_forward_kernel", ([&] { + corr_index_forward_kernel<<>>( + volume.packed_accessor32(), + coords.packed_accessor32(), + corr.packed_accessor32(), + radius); + })); + + return {corr}; + +} + +std::vector corr_index_cuda_backward( + torch::Tensor volume, + torch::Tensor coords, + torch::Tensor corr_grad, + int radius) +{ + const auto batch_size = volume.size(0); + const auto ht = volume.size(1); + const auto wd = volume.size(2); + + auto volume_grad = torch::zeros_like(volume); + + const dim3 blocks((wd + BLOCK - 1) / BLOCK, + (ht + BLOCK - 1) / BLOCK, + batch_size); + + const dim3 threads(BLOCK, BLOCK); + + + AT_DISPATCH_FLOATING_TYPES_AND_HALF(volume.type(), "sampler_backward_kernel", ([&] { + corr_index_backward_kernel<<>>( + coords.packed_accessor32(), + corr_grad.packed_accessor32(), + volume_grad.packed_accessor32(), + radius); + })); + + return {volume_grad}; +} \ No newline at end of file diff --git a/src/droid.cpp b/src/droid.cpp new file mode 100644 index 00000000..01f605e5 --- /dev/null +++ b/src/droid.cpp @@ -0,0 +1,247 @@ +#include +#include + +// CUDA forward declarations +std::vector projective_transform_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ii, + torch::Tensor jj); + + + +torch::Tensor depth_filter_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ix, + torch::Tensor thresh); + + +torch::Tensor frame_distance_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ii, + torch::Tensor jj, + const float beta); + +std::vector projmap_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ii, + torch::Tensor jj); + +torch::Tensor iproj_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics); + +std::vector ba_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor targets, + torch::Tensor weights, + torch::Tensor eta, + torch::Tensor ii, + torch::Tensor jj, + const int t0, + const int t1, + const int iterations, + const float lm, + const float ep, + const bool motion_only); + +std::vector corr_index_cuda_forward( + torch::Tensor volume, + torch::Tensor coords, + int radius); + +std::vector corr_index_cuda_backward( + torch::Tensor volume, + torch::Tensor coords, + torch::Tensor corr_grad, + int radius); + +std::vector altcorr_cuda_forward( + torch::Tensor fmap1, + torch::Tensor fmap2, + torch::Tensor coords, + int radius); + +std::vector altcorr_cuda_backward( + torch::Tensor fmap1, + torch::Tensor fmap2, + torch::Tensor coords, + torch::Tensor corr_grad, + int radius); + + +#define CHECK_CONTIGUOUS(x) TORCH_CHECK(x.is_contiguous(), #x " must be contiguous") +#define CHECK_INPUT(x) CHECK_CONTIGUOUS(x) + + +std::vector ba( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor targets, + torch::Tensor weights, + torch::Tensor eta, + torch::Tensor ii, + torch::Tensor jj, + const int t0, + const int t1, + const int iterations, + const float lm, + const float ep, + const bool motion_only) { + + CHECK_INPUT(targets); + CHECK_INPUT(weights); + CHECK_INPUT(poses); + CHECK_INPUT(disps); + CHECK_INPUT(intrinsics); + CHECK_INPUT(ii); + CHECK_INPUT(jj); + + return ba_cuda(poses, disps, intrinsics, targets, weights, + eta, ii, jj, t0, t1, iterations, lm, ep, motion_only); + +} + + +torch::Tensor frame_distance( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ii, + torch::Tensor jj, + const float beta) { + + CHECK_INPUT(poses); + CHECK_INPUT(disps); + CHECK_INPUT(intrinsics); + CHECK_INPUT(ii); + CHECK_INPUT(jj); + + return frame_distance_cuda(poses, disps, intrinsics, ii, jj, beta); + +} + + +std::vector projmap( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ii, + torch::Tensor jj) { + + CHECK_INPUT(poses); + CHECK_INPUT(disps); + CHECK_INPUT(intrinsics); + CHECK_INPUT(ii); + CHECK_INPUT(jj); + + return projmap_cuda(poses, disps, intrinsics, ii, jj); + +} + + +torch::Tensor iproj( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics) { + CHECK_INPUT(poses); + CHECK_INPUT(disps); + CHECK_INPUT(intrinsics); + + return iproj_cuda(poses, disps, intrinsics); +} + + +// c++ python binding +std::vector corr_index_forward( + torch::Tensor volume, + torch::Tensor coords, + int radius) { + CHECK_INPUT(volume); + CHECK_INPUT(coords); + + return corr_index_cuda_forward(volume, coords, radius); +} + +std::vector corr_index_backward( + torch::Tensor volume, + torch::Tensor coords, + torch::Tensor corr_grad, + int radius) { + CHECK_INPUT(volume); + CHECK_INPUT(coords); + CHECK_INPUT(corr_grad); + + auto volume_grad = corr_index_cuda_backward(volume, coords, corr_grad, radius); + return {volume_grad}; +} + +std::vector altcorr_forward( + torch::Tensor fmap1, + torch::Tensor fmap2, + torch::Tensor coords, + int radius) { + CHECK_INPUT(fmap1); + CHECK_INPUT(fmap2); + CHECK_INPUT(coords); + + return altcorr_cuda_forward(fmap1, fmap2, coords, radius); +} + +std::vector altcorr_backward( + torch::Tensor fmap1, + torch::Tensor fmap2, + torch::Tensor coords, + torch::Tensor corr_grad, + int radius) { + CHECK_INPUT(fmap1); + CHECK_INPUT(fmap2); + CHECK_INPUT(coords); + CHECK_INPUT(corr_grad); + + return altcorr_cuda_backward(fmap1, fmap2, coords, corr_grad, radius); +} + + +torch::Tensor depth_filter( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ix, + torch::Tensor thresh) { + + CHECK_INPUT(poses); + CHECK_INPUT(disps); + CHECK_INPUT(intrinsics); + CHECK_INPUT(ix); + CHECK_INPUT(thresh); + + return depth_filter_cuda(poses, disps, intrinsics, ix, thresh); +} + + +PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { + // bundle adjustment kernels + m.def("ba", &ba, "bundle adjustment"); + m.def("frame_distance", &frame_distance, "frame_distance"); + m.def("projmap", &projmap, "projmap"); + m.def("depth_filter", &depth_filter, "depth_filter"); + m.def("iproj", &iproj, "back projection"); + + // correlation volume kernels + m.def("altcorr_forward", &altcorr_forward, "ALTCORR forward"); + m.def("altcorr_backward", &altcorr_backward, "ALTCORR backward"); + m.def("corr_index_forward", &corr_index_forward, "INDEX forward"); + m.def("corr_index_backward", &corr_index_backward, "INDEX backward"); +} \ No newline at end of file diff --git a/src/droid_kernels.cu b/src/droid_kernels.cu new file mode 100644 index 00000000..8af86980 --- /dev/null +++ b/src/droid_kernels.cu @@ -0,0 +1,1518 @@ +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +// #include "utils.cuh" + +#include +#include +#include + +typedef Eigen::SparseMatrix SpMat; +typedef Eigen::Triplet T; +typedef std::vector> graph_t; +typedef std::vector tensor_list_t; + + + +#define MIN_DEPTH 0.25 + +#define THREADS 256 +#define NUM_BLOCKS(batch_size) ((batch_size + THREADS - 1) / THREADS) + + +#define GPU_1D_KERNEL_LOOP(k, n) \ + for (size_t k = threadIdx.x; k 1e-4) { + float a = (1 - cosf(theta)) / theta_sq; + crossInplace(phi, tau); + t[0] += a * tau[0]; + t[1] += a * tau[1]; + t[2] += a * tau[2]; + + float b = (theta - sinf(theta)) / (theta * theta_sq); + crossInplace(phi, tau); + t[0] += b * tau[0]; + t[1] += b * tau[1]; + t[2] += b * tau[2]; + } +} +__global__ void projective_transform_kernel( + const torch::PackedTensorAccessor32 target, + const torch::PackedTensorAccessor32 weight, + const torch::PackedTensorAccessor32 poses, + const torch::PackedTensorAccessor32 disps, + const torch::PackedTensorAccessor32 intrinsics, + const torch::PackedTensorAccessor32 ii, + const torch::PackedTensorAccessor32 jj, + torch::PackedTensorAccessor32 Hs, + torch::PackedTensorAccessor32 vs, + torch::PackedTensorAccessor32 Eii, + torch::PackedTensorAccessor32 Eij, + torch::PackedTensorAccessor32 Cii, + torch::PackedTensorAccessor32 bz) +{ + const int block_id = blockIdx.x; + const int thread_id = threadIdx.x; + + const int ht = disps.size(1); + const int wd = disps.size(2); + + __shared__ int ix; + __shared__ int jx; + + __shared__ float fx; + __shared__ float fy; + __shared__ float cx; + __shared__ float cy; + + __shared__ float ti[3], tj[3], tij[3]; + __shared__ float qi[4], qj[4], qij[4]; + + // load intrinsics from global memory + if (thread_id == 0) { + ix = static_cast(ii[block_id]); + jx = static_cast(jj[block_id]); + fx = intrinsics[0]; + fy = intrinsics[1]; + cx = intrinsics[2]; + cy = intrinsics[3]; + } + + __syncthreads(); + + // load poses from global memory + if (thread_id < 3) { + ti[thread_id] = poses[ix][thread_id]; + tj[thread_id] = poses[jx][thread_id]; + } + + if (thread_id < 4) { + qi[thread_id] = poses[ix][thread_id+3]; + qj[thread_id] = poses[jx][thread_id+3]; + } + + __syncthreads(); + + if (thread_id == 0) { + relSE3(ti, qi, tj, qj, tij, qij); + } + + //points + float Xi[4]; + float Xj[4]; + + // jacobians + float Jx[12]; + float Jz; + + float* Ji = &Jx[0]; + float* Jj = &Jx[6]; + + // hessians + float hij[12*(12+1)/2]; + + float vi[6], vj[6]; + + int l; + for (l=0; l<12*(12+1)/2; l++) { + hij[l] = 0; + } + + for (int n=0; n<6; n++) { + vi[n] = 0; + vj[n] = 0; + } + + __syncthreads(); + + GPU_1D_KERNEL_LOOP(k, ht*wd) { + + const int i = k / wd; + const int j = k % wd; + + const float u = static_cast(j); + const float v = static_cast(i); + + // homogenous coordinates + Xi[0] = (u - cx) / fx; + Xi[1] = (v - cy) / fy; + Xi[2] = 1; + Xi[3] = disps[ix][i][j]; + + // transform homogenous point + actSE3(tij, qij, Xi, Xj); + + const float x = Xj[0]; + const float y = Xj[1]; + const float h = Xj[3]; + + const float d = (Xj[2] < MIN_DEPTH) ? 0.0 : 1.0 / Xj[2]; + const float d2 = d * d; + + const float wu = (Xj[2] < MIN_DEPTH) ? 0.0 : .001 * weight[block_id][0][i][j]; + const float wv = (Xj[2] < MIN_DEPTH) ? 0.0 : .001 * weight[block_id][1][i][j]; + + const float ru = target[block_id][0][i][j] - (fx * d * x + cx); + const float rv = target[block_id][1][i][j] - (fy * d * y + cy); + + // x - coordinate + + Jj[0] = fx * (h*d); + Jj[1] = fx * 0; + Jj[2] = fx * (-x*h*d2); + Jj[3] = fx * (-x*y*d2); + Jj[4] = fx * (1 + x*x*d2); + Jj[5] = fx * (-y*d); + + Jz = fx * (tij[0] * d - tij[2] * (x * d2)); + adjSE3(tij, qij, Jj, Ji); + for (int n=0; n<6; n++) Ji[n] *= -1; + + l=0; + for (int n=0; n<12; n++) { + for (int m=0; m<=n; m++) { + hij[l] += wu * Jx[n] * Jx[m]; + l++; + } + } + + for (int n=0; n<6; n++) { + vi[n] += wu * ru * Ji[n]; + vj[n] += wu * ru * Jj[n]; + + Eii[block_id][n][k] = wu * Jz * Ji[n]; + Eij[block_id][n][k] = wu * Jz * Jj[n]; + } + + Cii[block_id][k] = wu * Jz * Jz; + bz[block_id][k] = wu * ru * Jz; + + Jj[0] = fy * 0; + Jj[1] = fy * (h*d); + Jj[2] = fy * (-y*h*d2); + Jj[3] = fy * (-1 - y*y*d2); + Jj[4] = fy * (x*y*d2); + Jj[5] = fy * (x*d); + + Jz = fy * (tij[1] * d - tij[2] * (y * d2)); + adjSE3(tij, qij, Jj, Ji); + for (int n=0; n<6; n++) Ji[n] *= -1; + + l=0; + for (int n=0; n<12; n++) { + for (int m=0; m<=n; m++) { + hij[l] += wv * Jx[n] * Jx[m]; + l++; + } + } + + for (int n=0; n<6; n++) { + vi[n] += wv * rv * Ji[n]; + vj[n] += wv * rv * Jj[n]; + + Eii[block_id][n][k] += wv * Jz * Ji[n]; + Eij[block_id][n][k] += wv * Jz * Jj[n]; + } + + Cii[block_id][k] += wv * Jz * Jz; + bz[block_id][k] += wv * rv * Jz; + } + + __syncthreads(); + + __shared__ float sdata[THREADS]; + for (int n=0; n<6; n++) { + sdata[threadIdx.x] = vi[n]; + blockReduce(sdata); + if (threadIdx.x == 0) { + vs[0][block_id][n] = sdata[0]; + } + + __syncthreads(); + + sdata[threadIdx.x] = vj[n]; + blockReduce(sdata); + if (threadIdx.x == 0) { + vs[1][block_id][n] = sdata[0]; + } + + } + + l=0; + for (int n=0; n<12; n++) { + for (int m=0; m<=n; m++) { + sdata[threadIdx.x] = hij[l]; + blockReduce(sdata); + + if (threadIdx.x == 0) { + if (n<6 && m<6) { + Hs[0][block_id][n][m] = sdata[0]; + Hs[0][block_id][m][n] = sdata[0]; + } + else if (n >=6 && m<6) { + Hs[1][block_id][m][n-6] = sdata[0]; + Hs[2][block_id][n-6][m] = sdata[0]; + } + else { + Hs[3][block_id][n-6][m-6] = sdata[0]; + Hs[3][block_id][m-6][n-6] = sdata[0]; + } + } + + l++; + } + } +} + + +__global__ void projmap_kernel( + const torch::PackedTensorAccessor32 poses, + const torch::PackedTensorAccessor32 disps, + const torch::PackedTensorAccessor32 intrinsics, + const torch::PackedTensorAccessor32 ii, + const torch::PackedTensorAccessor32 jj, + torch::PackedTensorAccessor32 coords, + torch::PackedTensorAccessor32 valid) +{ + + const int block_id = blockIdx.x; + const int thread_id = threadIdx.x; + + const int ht = disps.size(1); + const int wd = disps.size(2); + + __shared__ int ix; + __shared__ int jx; + + __shared__ float fx; + __shared__ float fy; + __shared__ float cx; + __shared__ float cy; + + __shared__ float ti[3], tj[3], tij[3]; + __shared__ float qi[4], qj[4], qij[4]; + + // load intrinsics from global memory + if (thread_id == 0) { + ix = static_cast(ii[block_id]); + jx = static_cast(jj[block_id]); + fx = intrinsics[0]; + fy = intrinsics[1]; + cx = intrinsics[2]; + cy = intrinsics[3]; + } + + __syncthreads(); + + // load poses from global memory + if (thread_id < 3) { + ti[thread_id] = poses[ix][thread_id]; + tj[thread_id] = poses[jx][thread_id]; + } + + if (thread_id < 4) { + qi[thread_id] = poses[ix][thread_id+3]; + qj[thread_id] = poses[jx][thread_id+3]; + } + + __syncthreads(); + + if (thread_id == 0) { + relSE3(ti, qi, tj, qj, tij, qij); + } + + //points + float Xi[4]; + float Xj[4]; + + __syncthreads(); + + GPU_1D_KERNEL_LOOP(k, ht*wd) { + const int i = k / wd; + const int j = k % wd; + + const float u = static_cast(j); + const float v = static_cast(i); + + // homogenous coordinates + Xi[0] = (u - cx) / fx; + Xi[1] = (v - cy) / fy; + Xi[2] = 1; + Xi[3] = disps[ix][i][j]; + + // transform homogenous point + actSE3(tij, qij, Xi, Xj); + + coords[block_id][i][j][0] = u; + coords[block_id][i][j][1] = v; + + if (Xj[2] > 0.01) { + coords[block_id][i][j][0] = fx * (Xj[0] / Xj[2]) + cx; + coords[block_id][i][j][1] = fy * (Xj[1] / Xj[2]) + cy; + } + + valid[block_id][i][j][0] = (Xj[2] > MIN_DEPTH) ? 1.0 : 0.0; + + } +} + +__global__ void frame_distance_kernel( + const torch::PackedTensorAccessor32 poses, + const torch::PackedTensorAccessor32 disps, + const torch::PackedTensorAccessor32 intrinsics, + const torch::PackedTensorAccessor32 ii, + const torch::PackedTensorAccessor32 jj, + torch::PackedTensorAccessor32 dist, + const float beta) { + + const int block_id = blockIdx.x; + const int thread_id = threadIdx.x; + + const int ht = disps.size(1); + const int wd = disps.size(2); + + __shared__ int ix; + __shared__ int jx; + + __shared__ float fx; + __shared__ float fy; + __shared__ float cx; + __shared__ float cy; + + __shared__ float ti[3], tj[3], tij[3]; + __shared__ float qi[4], qj[4], qij[4]; + + // load intrinsics from global memory + if (thread_id == 0) { + ix = static_cast(ii[block_id]); + jx = static_cast(jj[block_id]); + fx = intrinsics[0]; + fy = intrinsics[1]; + cx = intrinsics[2]; + cy = intrinsics[3]; + } + + __syncthreads(); + + + //points + float Xi[4]; + float Xj[4]; + + __shared__ float accum[THREADS]; accum[thread_id] = 0; + __shared__ float valid[THREADS]; valid[thread_id] = 0; + __shared__ float total[THREADS]; total[thread_id] = 0; + + __syncthreads(); + + for (int n=0; n<1; n++) { + + if (thread_id < 3) { + ti[thread_id] = poses[ix][thread_id]; + tj[thread_id] = poses[jx][thread_id]; + } + + if (thread_id < 4) { + qi[thread_id] = poses[ix][thread_id+3]; + qj[thread_id] = poses[jx][thread_id+3]; + } + + __syncthreads(); + + + relSE3(ti, qi, tj, qj, tij, qij); + + float d, du, dv; + + GPU_1D_KERNEL_LOOP(k, ht*wd) { + const int i = k / wd; + const int j = k % wd; + + const float u = static_cast(j); + const float v = static_cast(i); + + + // if (disps[ix][i][j] < 0.01) { + // continue; + // } + + // homogenous coordinates + Xi[0] = (u - cx) / fx; + Xi[1] = (v - cy) / fy; + Xi[2] = 1; + Xi[3] = disps[ix][i][j]; + + // transform homogenous point + actSE3(tij, qij, Xi, Xj); + + du = fx * (Xj[0] / Xj[2]) + cx - u; + dv = fy * (Xj[1] / Xj[2]) + cy - v; + d = sqrtf(du*du + dv*dv); + + total[threadIdx.x] += beta; + + if (Xj[2] > MIN_DEPTH) { + accum[threadIdx.x] += beta * d; + valid[threadIdx.x] += beta; + } + + Xi[0] = (u - cx) / fx; + Xi[1] = (v - cy) / fy; + Xi[2] = 1; + Xi[3] = disps[ix][i][j]; + + Xj[0] = Xi[0] + Xi[3] * tij[0]; + Xj[1] = Xi[1] + Xi[3] * tij[1]; + Xj[2] = Xi[2] + Xi[3] * tij[2]; + + du = fx * (Xj[0] / Xj[2]) + cx - u; + dv = fy * (Xj[1] / Xj[2]) + cy - v; + d = sqrtf(du*du + dv*dv); + + total[threadIdx.x] += (1 - beta); + + if (Xj[2] > MIN_DEPTH) { + accum[threadIdx.x] += (1 - beta) * d; + valid[threadIdx.x] += (1 - beta); + } + } + + if (threadIdx.x == 0) { + int tmp = ix; + ix = jx; + jx = tmp; + } + + __syncthreads(); + + } + __syncthreads(); blockReduce(accum); + __syncthreads(); blockReduce(total); + __syncthreads(); blockReduce(valid); + + __syncthreads(); + + if (thread_id == 0) { + dist[block_id] = (valid[0] / (total[0] + 1e-8) < 0.75) ? 1000.0 : accum[0] / valid[0]; + } +} + + + +__global__ void depth_filter_kernel( + const torch::PackedTensorAccessor32 poses, + const torch::PackedTensorAccessor32 disps, + const torch::PackedTensorAccessor32 intrinsics, + const torch::PackedTensorAccessor32 inds, + const torch::PackedTensorAccessor32 thresh, + torch::PackedTensorAccessor32 counter) +{ + + const int block_id = blockIdx.x; + const int neigh_id = blockIdx.y; + const int index = blockIdx.z * blockDim.x + threadIdx.x; + + // if (threadIdx.x == 0) { + // printf("%d %d %d %d\n", blockIdx.x, blockIdx.y, blockDim.x, threadIdx.x); + // } + + const int num = disps.size(0); + const int ht = disps.size(1); + const int wd = disps.size(2); + + __shared__ int ix; + __shared__ int jx; + + __shared__ float fx; + __shared__ float fy; + __shared__ float cx; + __shared__ float cy; + + __shared__ float ti[3], tj[3], tij[3]; + __shared__ float qi[4], qj[4], qij[4]; + + if (threadIdx.x == 0) { + ix = static_cast(inds[block_id]); + jx = (neigh_id < 3) ? ix - neigh_id - 1 : ix + neigh_id; + fx = intrinsics[0]; + fy = intrinsics[1]; + cx = intrinsics[2]; + cy = intrinsics[3]; + } + + __syncthreads(); + + if (jx < 0 || jx >= num) { + return; + } + + const float t = thresh[block_id]; + + // load poses from global memory + if (threadIdx.x < 3) { + ti[threadIdx.x] = poses[ix][threadIdx.x]; + tj[threadIdx.x] = poses[jx][threadIdx.x]; + } + + if (threadIdx.x < 4) { + qi[threadIdx.x] = poses[ix][threadIdx.x+3]; + qj[threadIdx.x] = poses[jx][threadIdx.x+3]; + } + + __syncthreads(); + + if (threadIdx.x == 0) { + relSE3(ti, qi, tj, qj, tij, qij); + } + + //points + float Xi[4]; + float Xj[4]; + + __syncthreads(); + + if (index < ht*wd) { + const int i = index / wd; + const int j = index % wd; + + const float ui = static_cast(j); + const float vi = static_cast(i); + const float di = disps[ix][i][j]; + + // homogenous coordinates + Xi[0] = (ui - cx) / fx; + Xi[1] = (vi - cy) / fy; + Xi[2] = 1; + Xi[3] = di; + + // transform homogenous point + actSE3(tij, qij, Xi, Xj); + + const float uj = fx * (Xj[0] / Xj[2]) + cx; + const float vj = fy * (Xj[1] / Xj[2]) + cy; + const float dj = Xj[3] / Xj[2]; + + const int u0 = static_cast(floor(uj)); + const int v0 = static_cast(floor(vj)); + + if (u0 >= 0 && v0 >= 0 && u0 < wd-1 && v0 < ht-1) { + const float wx = ceil(uj) - uj; + const float wy = ceil(vj) - vj; + + const float d00 = disps[jx][v0+0][u0+0]; + const float d01 = disps[jx][v0+0][u0+1]; + const float d10 = disps[jx][v0+1][u0+0]; + const float d11 = disps[jx][v0+1][u0+1]; + + const float dj_hat = wy*wx*d00 + wy*(1-wx)*d01 + (1-wy)*wx*d10 + (1-wy)*(1-wx)*d11; + + const float err = abs(1.0/dj - 1.0/dj_hat); + if (abs(1.0/dj - 1.0/d00) < t) atomicAdd(&counter[block_id][i][j], 1.0f); + else if (abs(1.0/dj - 1.0/d01) < t) atomicAdd(&counter[block_id][i][j], 1.0f); + else if (abs(1.0/dj - 1.0/d10) < t) atomicAdd(&counter[block_id][i][j], 1.0f); + else if (abs(1.0/dj - 1.0/d11) < t) atomicAdd(&counter[block_id][i][j], 1.0f); + } + } +} + + + +__global__ void iproj_kernel( + const torch::PackedTensorAccessor32 poses, + const torch::PackedTensorAccessor32 disps, + const torch::PackedTensorAccessor32 intrinsics, + torch::PackedTensorAccessor32 points) + +{ + + const int block_id = blockIdx.x; + const int index = blockIdx.y * blockDim.x + threadIdx.x; + + + const int num = disps.size(0); + const int ht = disps.size(1); + const int wd = disps.size(2); + + __shared__ float fx; + __shared__ float fy; + __shared__ float cx; + __shared__ float cy; + + __shared__ float t[3]; + __shared__ float q[4]; + + if (threadIdx.x == 0) { + fx = intrinsics[0]; + fy = intrinsics[1]; + cx = intrinsics[2]; + cy = intrinsics[3]; + } + + __syncthreads(); + + + // load poses from global memory + if (threadIdx.x < 3) { + t[threadIdx.x] = poses[block_id][threadIdx.x]; + } + + if (threadIdx.x < 4) { + q[threadIdx.x] = poses[block_id][threadIdx.x+3]; + } + + __syncthreads(); + + //points + float Xi[4]; + float Xj[4]; + + if (index < ht*wd) { + const int i = index / wd; + const int j = index % wd; + + const float ui = static_cast(j); + const float vi = static_cast(i); + const float di = disps[block_id][i][j]; + + // homogenous coordinates + Xi[0] = (ui - cx) / fx; + Xi[1] = (vi - cy) / fy; + Xi[2] = 1; + Xi[3] = di; + + // transform homogenous point + actSE3(t, q, Xi, Xj); + + points[block_id][i][j][0] = Xj[0] / Xj[3]; + points[block_id][i][j][1] = Xj[1] / Xj[3]; + points[block_id][i][j][2] = Xj[2] / Xj[3]; + + } +} + + + +__global__ void accum_kernel( + const torch::PackedTensorAccessor32 inps, + const torch::PackedTensorAccessor32 ptrs, + const torch::PackedTensorAccessor32 idxs, + torch::PackedTensorAccessor32 outs) +{ + + const int block_id = blockIdx.x; + const int D = inps.size(2); + + const int start = ptrs[block_id]; + const int end = ptrs[block_id+1]; + + for (int k=threadIdx.x; k poses, + const torch::PackedTensorAccessor32 dx, + const int t0, const int t1) +{ + + for (int k=t0+threadIdx.x; k disps, + const torch::PackedTensorAccessor32 dz, + const torch::PackedTensorAccessor32 inds) +{ + const int i = inds[blockIdx.x]; + const int ht = disps.size(1); + const int wd = disps.size(2); + + for (int k=threadIdx.x; k(); + long* jx_data = jx_cpu.data_ptr(); + long* kx_data = inds.data_ptr(); + + int count = jx.size(0); + std::vector cols; + + torch::Tensor ptrs_cpu = torch::zeros({count+1}, + torch::TensorOptions().dtype(torch::kInt64)); + + long* ptrs_data = ptrs_cpu.data_ptr(); + ptrs_data[0] = 0; + + int i = 0; + for (int j=0; j(); + + for (int i=0; i>>( + data.packed_accessor32(), + ptrs.packed_accessor32(), + idxs.packed_accessor32(), + out.packed_accessor32()); + + return out; +} + + +__global__ void EEt6x6_kernel( + const torch::PackedTensorAccessor32 E, + const torch::PackedTensorAccessor32 Q, + const torch::PackedTensorAccessor32 idx, + torch::PackedTensorAccessor32 S) +{ + + // indicices + const int ix = idx[blockIdx.x][0]; + const int jx = idx[blockIdx.x][1]; + const int kx = idx[blockIdx.x][2]; + + const int D = E.size(2); + + float dS[6][6]; + float ei[6]; + float ej[6]; + + for (int i=0; i<6; i++) { + for (int j=0; j<6; j++) { + dS[i][j] = 0; + } + } + + for (int k=threadIdx.x; k E, + const torch::PackedTensorAccessor32 Q, + const torch::PackedTensorAccessor32 w, + const torch::PackedTensorAccessor32 idx, + torch::PackedTensorAccessor32 v) +{ + const int D = E.size(2); + const int kx = idx[blockIdx.x][0]; + + float b[6]; + for (int n=0; n<6; n++) { + b[n] = 0.0; + } + + for (int k=threadIdx.x; k E, + const torch::PackedTensorAccessor32 x, + const torch::PackedTensorAccessor32 idx, + torch::PackedTensorAccessor32 w) +{ + + const int D = E.size(2); + const int ix = idx[blockIdx.x]; + + if (idx[blockIdx.x] <= 0 || idx[blockIdx.x] >= x.size(0)) + return; + + for (int k=threadIdx.x; k A; + Eigen::VectorX b; + + SparseBlock(int N, int M) : N(N), M(M) { + A = Eigen::SparseMatrix(N*M, N*M); + b = Eigen::VectorXd::Zero(N*M); + } + + SparseBlock(Eigen::SparseMatrix const& A, Eigen::VectorX const& b, + int N, int M) : A(A), b(b), N(N), M(M) {} + + void update_lhs(torch::Tensor As, torch::Tensor ii, torch::Tensor jj) { + + auto As_cpu = As.to(torch::kCPU).to(torch::kFloat64); + auto ii_cpu = ii.to(torch::kCPU).to(torch::kInt64); + auto jj_cpu = jj.to(torch::kCPU).to(torch::kInt64); + + auto As_acc = As_cpu.accessor(); + auto ii_acc = ii_cpu.accessor(); + auto jj_acc = jj_cpu.accessor(); + + std::vector tripletList; + for (int n=0; n= 0 && j >= 0) { + for (int k=0; k(); + auto ii_acc = ii_cpu.accessor(); + + for (int n=0; n= 0) { + for (int j=0; j get_dense() { + Eigen::MatrixXd Ad = Eigen::MatrixXd(A); + + torch::Tensor H = torch::from_blob(Ad.data(), {N*M, N*M}, torch::TensorOptions() + .dtype(torch::kFloat64)).to(torch::kCUDA).to(torch::kFloat32); + + torch::Tensor v = torch::from_blob(b.data(), {N*M, 1}, torch::TensorOptions() + .dtype(torch::kFloat64)).to(torch::kCUDA).to(torch::kFloat32); + + return std::make_tuple(H, v); + + } + + torch::Tensor solve(const float lm=0.0001, const float ep=0.1) { + + torch::Tensor dx; + + Eigen::SparseMatrix L(A); + L.diagonal().array() += ep + lm * L.diagonal().array(); + + Eigen::SimplicialLLT> solver; + solver.compute(L); + + if (solver.info() == Eigen::Success) { + Eigen::VectorXd x = solver.solve(b); + dx = torch::from_blob(x.data(), {N, M}, torch::TensorOptions() + .dtype(torch::kFloat64)).to(torch::kCUDA).to(torch::kFloat32); + } + else { + dx = torch::zeros({N, M}, torch::TensorOptions() + .device(torch::kCUDA).dtype(torch::kFloat32)); + } + + return dx; + } + + private: + const int N; + const int M; + +}; + + +SparseBlock schur_block(torch::Tensor E, + torch::Tensor Q, + torch::Tensor w, + torch::Tensor ii, + torch::Tensor jj, + torch::Tensor kk, + const int t0, + const int t1) +{ + + torch::Tensor ii_cpu = ii.to(torch::kCPU); + torch::Tensor jj_cpu = jj.to(torch::kCPU); + torch::Tensor kk_cpu = kk.to(torch::kCPU); + + const int P = t1 - t0; + const long* ii_data = ii_cpu.data_ptr(); + const long* jj_data = jj_cpu.data_ptr(); + const long* kk_data = kk_cpu.data_ptr(); + + std::vector> graph(P); + std::vector> index(P); + + for (int n=0; n= t0 && j <= t1) { + const int t = j - t0; + graph[t].push_back(k); + index[t].push_back(n); + } + } + + std::vector ii_list, jj_list, idx, jdx; + + for (int i=0; i>>( + E.packed_accessor32(), + Q.packed_accessor32(), + ix_cuda.packed_accessor32(), + S.packed_accessor32()); + + Ev6x1_kernel<<>>( + E.packed_accessor32(), + Q.packed_accessor32(), + w.packed_accessor32(), + jx_cuda.packed_accessor32(), + v.packed_accessor32()); + + // schur block + SparseBlock A(P, 6); + A.update_lhs(S, ii2_cpu, jj2_cpu); + A.update_rhs(v, jj_cpu - t0); + + return A; +} + + +std::vector ba_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor targets, + torch::Tensor weights, + torch::Tensor eta, + torch::Tensor ii, + torch::Tensor jj, + const int t0, + const int t1, + const int iterations, + const float lm, + const float ep, + const bool motion_only) +{ + auto opts = poses.options(); + const int num = ii.size(0); + const int ht = disps.size(1); + const int wd = disps.size(2); + + torch::Tensor ts = torch::arange(t0, t1).to(torch::kCUDA); + torch::Tensor ii_exp = torch::cat({ts, ii}, 0); + torch::Tensor jj_exp = torch::cat({ts, jj}, 0); + + std::tuple kuniq = + torch::_unique(ii_exp, true, true); + + torch::Tensor kx = std::get<0>(kuniq); + torch::Tensor kk_exp = std::get<1>(kuniq); + + torch::Tensor dx; + torch::Tensor dz; + + // initialize buffers + torch::Tensor Hs = torch::zeros({4, num, 6, 6}, opts); + torch::Tensor vs = torch::zeros({2, num, 6}, opts); + torch::Tensor Eii = torch::zeros({num, 6, ht*wd}, opts); + torch::Tensor Eij = torch::zeros({num, 6, ht*wd}, opts); + torch::Tensor Cii = torch::zeros({num, ht*wd}, opts); + torch::Tensor wi = torch::zeros({num, ht*wd}, opts); + + for (int itr=0; itr>>( + targets.packed_accessor32(), + weights.packed_accessor32(), + poses.packed_accessor32(), + disps.packed_accessor32(), + intrinsics.packed_accessor32(), + ii.packed_accessor32(), + jj.packed_accessor32(), + Hs.packed_accessor32(), + vs.packed_accessor32(), + Eii.packed_accessor32(), + Eij.packed_accessor32(), + Cii.packed_accessor32(), + wi.packed_accessor32()); + + + // pose x pose block + SparseBlock A(t1 - t0, 6); + + A.update_lhs(Hs.reshape({-1, 6, 6}), + torch::cat({ii, ii, jj, jj}) - t0, + torch::cat({ii, jj, ii, jj}) - t0); + + A.update_rhs(vs.reshape({-1, 6}), + torch::cat({ii, jj}) - t0); + + if (motion_only) { + dx = A.solve(lm, ep); + + // update poses + pose_retr_kernel<<<1, THREADS>>>( + poses.packed_accessor32(), + dx.packed_accessor32(), t0, t1); + } + + else { + + torch::Tensor C = accum_cuda(Cii, ii, kx); + torch::Tensor w = accum_cuda(wi, ii, kx); + torch::Tensor Q = 1.0 / (C + eta.view({-1, ht*wd})); + + torch::Tensor Ei = accum_cuda(Eii.view({num, 6*ht*wd}), ii, ts).view({t1-t0, 6, ht*wd}); + torch::Tensor E = torch::cat({Ei, Eij}, 0); + + SparseBlock S = schur_block(E, Q, w, ii_exp, jj_exp, kk_exp, t0, t1); + dx = (A - S).solve(lm, ep); + + torch::Tensor ix = jj_exp - t0; + torch::Tensor dw = torch::zeros({ix.size(0), ht*wd}, opts); + + EvT6x1_kernel<<>>( + E.packed_accessor32(), + dx.packed_accessor32(), + ix.packed_accessor32(), + dw.packed_accessor32()); + + dz = Q * (w - accum_cuda(dw, ii_exp, kx)); + + // update poses + pose_retr_kernel<<<1, THREADS>>>( + poses.packed_accessor32(), + dx.packed_accessor32(), t0, t1); + + // update disparity maps + disp_retr_kernel<<>>( + disps.packed_accessor32(), + dz.packed_accessor32(), + kx.packed_accessor32()); + } + + } + + return {dx, dz}; +} + + + +torch::Tensor frame_distance_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ii, + torch::Tensor jj, + const float beta) +{ + auto opts = poses.options(); + const int num = ii.size(0); + + torch::Tensor dist = torch::zeros({num}, opts); + + frame_distance_kernel<<>>( + poses.packed_accessor32(), + disps.packed_accessor32(), + intrinsics.packed_accessor32(), + ii.packed_accessor32(), + jj.packed_accessor32(), + dist.packed_accessor32(), beta); + + return dist; +} + + +std::vector projmap_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ii, + torch::Tensor jj) +{ + auto opts = poses.options(); + const int num = ii.size(0); + const int ht = disps.size(1); + const int wd = disps.size(2); + + torch::Tensor coords = torch::zeros({num, ht, wd, 3}, opts); + torch::Tensor valid = torch::zeros({num, ht, wd, 1}, opts); + + projmap_kernel<<>>( + poses.packed_accessor32(), + disps.packed_accessor32(), + intrinsics.packed_accessor32(), + ii.packed_accessor32(), + jj.packed_accessor32(), + coords.packed_accessor32(), + valid.packed_accessor32()); + + return {coords, valid}; +} + + +torch::Tensor depth_filter_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics, + torch::Tensor ix, + torch::Tensor thresh) +{ + const int num = ix.size(0); + const int ht = disps.size(1); + const int wd = disps.size(2); + + torch::Tensor counter = torch::zeros({num, ht, wd}, disps.options()); + + dim3 blocks(num, 6, NUM_BLOCKS(ht * wd)); + + depth_filter_kernel<<>>( + poses.packed_accessor32(), + disps.packed_accessor32(), + intrinsics.packed_accessor32(), + ix.packed_accessor32(), + thresh.packed_accessor32(), + counter.packed_accessor32()); + + return counter; +} + + +torch::Tensor iproj_cuda( + torch::Tensor poses, + torch::Tensor disps, + torch::Tensor intrinsics) +{ + + const int nm = disps.size(0); + const int ht = disps.size(1); + const int wd = disps.size(2); + + auto opts = disps.options(); + torch::Tensor points = torch::zeros({nm, ht, wd, 3}, opts); + + dim3 blocks(nm, NUM_BLOCKS(ht * wd)); + + iproj_kernel<<>>( + poses.packed_accessor32(), + disps.packed_accessor32(), + intrinsics.packed_accessor32(), + points.packed_accessor32()); + + return points; + +} + diff --git a/thirdparty/eigen b/thirdparty/eigen new file mode 160000 index 00000000..3d4ba855 --- /dev/null +++ b/thirdparty/eigen @@ -0,0 +1 @@ +Subproject commit 3d4ba855e014987cad86d62a8dff533492255695 diff --git a/thirdparty/lietorch b/thirdparty/lietorch new file mode 160000 index 00000000..0fa9ce8f --- /dev/null +++ b/thirdparty/lietorch @@ -0,0 +1 @@ +Subproject commit 0fa9ce8ffca86d985eca9e189a99690d6f3d4df6 diff --git a/thirdparty/tartanair_tools/LICENSE b/thirdparty/tartanair_tools/LICENSE new file mode 100644 index 00000000..0d8b27c7 --- /dev/null +++ b/thirdparty/tartanair_tools/LICENSE @@ -0,0 +1,12 @@ +Copyright (c) 2020, Carnegie Mellon University +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. \ No newline at end of file diff --git a/thirdparty/tartanair_tools/README.md b/thirdparty/tartanair_tools/README.md new file mode 100644 index 00000000..509e35b7 --- /dev/null +++ b/thirdparty/tartanair_tools/README.md @@ -0,0 +1,257 @@ +# TartanAir dataset: AirSim Simulation Dataset for Simultaneous Localization and Mapping +This repository provides sample code and scripts for accessing the training and testing data, as well as evaluation tools. Please refer to [TartanAir](http://theairlab.org/tartanair-dataset) for more information about the dataset. +You can also reach out to contributors on the associated [AirSim GitHub](https://github.com/microsoft/AirSim). + +This dataset was used to train the first generalizable learning-based visual odometry [TartanVO](http://theairlab.org/tartanvo/), which achieved better performance than geometry-based VO methods in challenging cases. Please check out the [paper](https://arxiv.org/pdf/2011.00359.pdf) and published [TartanVO code](https://github.com/castacks/tartanvo). + +## Download the training data + +The data is divided into two levels (Easy and Hard) in terms of the motion patterns. It is organized in trajectory folders. You can download data from different cameras (left or right), with different data types (RGB, depth, segmentation, camera pose, and flow). Please see [data type](data_type.md) page for the camera intrinsics, extrinsics and other information. + + +

!! NOTE: The size of all the data is up to 3TB! It could take days to download. We also added the option to use the dataset directly on Azure without requiring a download. Please select the data type you really need before download. You can also go to +TartanAir +to download the sample files for a better understanding of the data types.

+ +### Data directory structure + +``` +ROOT +| +--- ENV_NAME_0 # environment folder +| | +| ---- Easy # difficulty level +| | | +| | ---- P000 # trajectory folder +| | | | +| | | +--- depth_left # 000000_left_depth.npy - 000xxx_left_depth.npy +| | | +--- depth_right # 000000_right_depth.npy - 000xxx_right_depth.npy +| | | +--- flow # 000000_000001_flow/mask.npy - 000xxx_000xxx_flow/mask.npy +| | | +--- image_left # 000000_left.png - 000xxx_left.png +| | | +--- image_right # 000000_right.png - 000xxx_right.png +| | | +--- seg_left # 000000_left_seg.npy - 000xxx_left_seg.npy +| | | +--- seg_right # 000000_right_seg.npy - 000xxx_right_seg.npy +| | | ---- pose_left.txt +| | | ---- pose_right.txt +| | | +| | +--- P001 +| | . +| | . +| | | +| | +--- P00K +| | +| +--- Hard +| ++-- ENV_NAME_1 +. +. +| ++-- ENV_NAME_N +``` + +### Download data to your local machine + +We provide a python script `download_training.py` for the data downloading. You can also take look at the [URL list](download_training_zipfiles.txt) to download the spesific files you want. + +* Specify an output directory + + --output-dir OUTPUTDIR + +* Select file type: + + --rgb + + --depth + + --seg + + --flow + +* Select difficulty level: + + --only-hard + + --only-easy + + [NO TAG]: both 'hard' and 'easy' levels + +* Select camera: + + --only-left + + --only-right + + [NO TAG]: both 'left' and 'right' cameras + +* Select flow type when --flow is set: + + --only-flow + + --only-mask + + [NO TAG]: both 'flow' and 'mask' files + +For example, download all the RGB images from the left camera: + +``` +python download_training.py --output-dir OUTPUTDIR --rgb --only-left +``` + +Download all the depth data from both cameras in hard level: + +``` +python download_training.py --output-dir OUTPUTDIR --depth --only-hard +``` + +Download all optical flow data without flow-mask: + +``` +python download_training.py --output-dir OUTPUTDIR --flow --only-flow +``` + +Download all the files in the dataset (could be very slow due to the large size): + +``` +python download_training.py --output-dir OUTPUTDIR --rgb --depth --seg --flow +``` + +--- +**NOTE** + +We found that using AzCopy, which is a tool provided by MicroSoft, is much faster than directly downloading by the URLs. Please try the following steps if you want to accelerate the downloading process. + +1. Download the [AzCopy](https://docs.microsoft.com/en-us/azure/storage/common/storage-use-azcopy-v10) and put the executable to your system path. + +2. Run the above commands with a --azcopy tag. + +--- + +### Access the data using Azure virtual machine + +Yet another way to access the data is to use an Azure virtual machine. In this way, you don't have to download the data to your local machine. You can use [Azure SDKs](https://github.com/Azure/azure-sdk-for-python) to access the data on the cloud. [Here](TartanAir_Sample.ipynb) is a sample notebook for accessing and visualizing the data. **NOTE: This sample notebook can only be used on Azure. To download the data to your local machine, please refer to the download instructions [here](https://github.com/castacks/tartanair_tools#download-data-to-your-local-machine) or the [dataset website](http://theairlab.org/tartanair-dataset) for the sample data.** + +## Download the testing data for the CVPR Visual SLAM challenge + +You can click the download links below. In Linux system, you can also run the following command to download all the files: +``` +wget -r -i download_cvpr_slam_test.txt +``` + +* [Monocular track](https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-mono-release.tar.gz) (Size: 7.65 GB) + + MD5 hash: 009b52e7d7b224ffb8a203db294ac9fb + +``` +mono +| +--- ME000 # monocular easy trajectory 0 +| | +| ---- 000000.png # RGB image 000000 +| ---- 000001.png # RGB image 000001 +| . +| . +| ---- 000xxx.png # RGB image 000xxx +| ++-- ME001 # monocular easy trajectory 1 +. +. ++-- ME007 # monocular easy trajectory 7 +| ++-- MH000 # monocular hard trajectory 0 +. +. +| ++-- MH007 # monocular hard trajectory 7 +``` + +* [Stereo track](https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-stereo-release.tar.gz) (Size: 17.51 GB) + + MD5 hash: 8a3363ff2013f147c9495d5bb161c48e + +``` +stereo +| +--- SE000 # stereo easy trajectory 0 +| | +| ---- image_left # left image folder +| | | +| | ---- 000000_left.png # RGB left image 000000 +| | ---- 000001_left.png # RGB left image 000001 +| | . +| | . +| | ---- 000xxx_left.png # RGB left image 000xxx +| | +| ---- image_right # right image folder +| | +| ---- 000000_right.png # RGB right image 000000 +| ---- 000001_right.png # RGB right image 000001 +| . +| . +| ---- 000xxx_right.png # RGB right image 000xxx +| ++-- SE001 # stereo easy trajectory 1 +. +. ++-- SE007 # stereo easy trajectory 7 +| ++-- SH000 # stereo hard trajectory 0 +. +. +| ++-- SH007 # stereo hard trajectory 7 +``` + +* [Both monocular and stereo tracks](https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-release.tar.gz) (Size: 25.16 GB) + + MD5 hash: ea176ca274135622cbf897c8fa462012 + +More information about the [CVPR Visual SLAM challenge](https://sites.google.com/view/vislocslamcvpr2020/slam-challenge) + +* The [monocular track](https://www.aicrowd.com/challenges/tartanair-visual-slam-mono-track) + +* The [stereo track](https://www.aicrowd.com/challenges/tartanair-visual-slam-stereo-track) + +Now the CVPR challenge has completed, if you need the ground truth poses for the above testing trajectories, please send an email to [tartanair@hotmail.com](tartanair@hotmail.com). + +## Evaluation tools + +Following the [TUM dataset](https://vision.in.tum.de/data/datasets/rgbd-dataset) and the [KITTI dataset](http://www.cvlibs.net/datasets/kitti/eval_odometry.php), we adopt three metrics: absolute trajectory error (ATE), the relative pose error (RPE), a modified version of KITTI VO metric. + +[More details](https://vision.in.tum.de/data/datasets/rgbd-dataset/tools#evaluation) + +Check out the sample code: +``` +cd evaluation +python tartanair_evaluator.py +``` + +Note that our camera poses are defined in the NED frame. That is to say, the x-axis is pointing to the camera's forward, the y-axis is pointing to the camera's right, the z-axis is pointing to the camera's downward. You can use the `cam2ned` function in the `evaluation/trajectory_transform.py` to transform the trajectory from the camera frame to the NED frame. + +## Paper +More technical details are available in the [TartanAir paper](https://arxiv.org/abs/2003.14338). Please cite this as: +``` +@article{tartanair2020iros, + title = {TartanAir: A Dataset to Push the Limits of Visual SLAM}, + author = {Wang, Wenshan and Zhu, Delong and Wang, Xiangwei and Hu, Yaoyu and Qiu, Yuheng and Wang, Chen and Hu, Yafei and Kapoor, Ashish and Scherer, Sebastian}, + booktitle = {2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)}, + year = {2020} +} +``` + +## Contact +Email tartanair@hotmail.com if you have any questions about the data source. To post problems in the Github issue is also welcome. You can also reach out to contributors on the associated [GitHub](https://github.com/microsoft/AirSim). + +## License +[This software is BSD licensed.](https://opensource.org/licenses/BSD-3-Clause) + +Copyright (c) 2020, Carnegie Mellon University All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/thirdparty/tartanair_tools/TartanAir_Sample.ipynb b/thirdparty/tartanair_tools/TartanAir_Sample.ipynb new file mode 100644 index 00000000..1c1896f7 --- /dev/null +++ b/thirdparty/tartanair_tools/TartanAir_Sample.ipynb @@ -0,0 +1,618 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Demo notebook for accessing TartanAir data on Azure\n", + "\n", + "

!! NOTE: This sample file should only be used on Azure. To download the data to your local machine, please refer to the download instructions here or the dataset website for the sample data.

\n", + "\n", + "This notebook provides an example of accessing TartanAir data from blobl storage on Azure, including: \n", + "\n", + "1) navigate the directories of different environments and trajectories. \n", + "\n", + "2) load the data into memory, and \n", + "\n", + "3) visualize the data. \n", + "\n", + "## Data directory structure\n", + "```\n", + "ROOT\n", + "|\n", + "--- ENV_NAME_0 # environment folder\n", + "| |\n", + "| ---- Easy # difficulty level\n", + "| | |\n", + "| | ---- P000 # trajectory folder\n", + "| | | |\n", + "| | | +--- depth_left # 000000_left_depth.npy - 000xxx_left_depth.npy\n", + "| | | +--- depth_right # 000000_right_depth.npy - 000xxx_right_depth.npy\n", + "| | | +--- flow # 000000_000001_flow/mask.npy - 000xxx_000xxx_flow/mask.npy\n", + "| | | +--- image_left # 000000_left.png - 000xxx_left.png \n", + "| | | +--- image_right # 000000_right.png - 000xxx_right.png \n", + "| | | +--- seg_left # 000000_left_seg.npy - 000xxx_left_seg.npy\n", + "| | | +--- seg_right # 000000_right_seg.npy - 000xxx_right_seg.npy\n", + "| | | ---- pose_left.txt \n", + "| | | ---- pose_right.txt\n", + "| | | \n", + "| | +--- P001\n", + "| | .\n", + "| | .\n", + "| | |\n", + "| | +--- P00K\n", + "| |\n", + "| +--- Hard\n", + "|\n", + "+-- ENV_NAME_1\n", + ".\n", + ".\n", + "|\n", + "+-- ENV_NAME_N\n", + " ```" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Notebook dependencies\n", + "`pip install numpy`\n", + "\n", + "`pip install azure-storage-blob`\n", + "\n", + "`pip install opencv-python`" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Imports and contrainer_client" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from azure.storage.blob import ContainerClient\n", + "import numpy as np\n", + "import io\n", + "import cv2\n", + "import time\n", + "import matplotlib.pyplot as plt\n", + "%matplotlib inline\n", + "\n", + "# Dataset website: http://theairlab.org/tartanair-dataset/\n", + "account_url = 'https://tartanair.blob.core.windows.net/'\n", + "container_name = 'tartanair-release1'\n", + "\n", + "container_client = ContainerClient(account_url=account_url, \n", + " container_name=container_name,\n", + " credential=None)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## List the environments and trajectories" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "def get_environment_list():\n", + " '''\n", + " List all the environments shown in the root directory\n", + " '''\n", + " env_gen = container_client.walk_blobs()\n", + " envlist = []\n", + " for env in env_gen:\n", + " envlist.append(env.name)\n", + " return envlist\n", + "\n", + "def get_trajectory_list(envname, easy_hard = 'Easy'):\n", + " '''\n", + " List all the trajectory folders, which is named as 'P0XX'\n", + " '''\n", + " assert(easy_hard=='Easy' or easy_hard=='Hard')\n", + " traj_gen = container_client.walk_blobs(name_starts_with=envname + '/' + easy_hard+'/')\n", + " trajlist = []\n", + " for traj in traj_gen:\n", + " trajname = traj.name\n", + " trajname_split = trajname.split('/')\n", + " trajname_split = [tt for tt in trajname_split if len(tt)>0]\n", + " if trajname_split[-1][0] == 'P':\n", + " trajlist.append(trajname)\n", + " return trajlist\n", + "\n", + "def _list_blobs_in_folder(folder_name):\n", + " \"\"\"\n", + " List all blobs in a virtual folder in an Azure blob container\n", + " \"\"\"\n", + " \n", + " files = []\n", + " generator = container_client.list_blobs(name_starts_with=folder_name)\n", + " for blob in generator:\n", + " files.append(blob.name)\n", + " return files\n", + "\n", + "def get_image_list(trajdir, left_right = 'left'):\n", + " assert(left_right == 'left' or left_right == 'right')\n", + " files = _list_blobs_in_folder(trajdir + '/image_' + left_right + '/')\n", + " files = [fn for fn in files if fn.endswith('.png')]\n", + " return files\n", + "\n", + "def get_depth_list(trajdir, left_right = 'left'):\n", + " assert(left_right == 'left' or left_right == 'right')\n", + " files = _list_blobs_in_folder(trajdir + '/depth_' + left_right + '/')\n", + " files = [fn for fn in files if fn.endswith('.npy')]\n", + " return files\n", + "\n", + "def get_flow_list(trajdir, ):\n", + " files = _list_blobs_in_folder(trajdir + '/flow/')\n", + " files = [fn for fn in files if fn.endswith('flow.npy')]\n", + " return files\n", + "\n", + "def get_flow_mask_list(trajdir, ):\n", + " files = _list_blobs_in_folder(trajdir + '/flow/')\n", + " files = [fn for fn in files if fn.endswith('mask.npy')]\n", + " return files\n", + "\n", + "def get_posefile(trajdir, left_right = 'left'):\n", + " assert(left_right == 'left' or left_right == 'right')\n", + " return trajdir + '/pose_' + left_right + '.txt'\n", + "\n", + "def get_seg_list(trajdir, left_right = 'left'):\n", + " assert(left_right == 'left' or left_right == 'right')\n", + " files = _list_blobs_in_folder(trajdir + '/seg_' + left_right + '/')\n", + " files = [fn for fn in files if fn.endswith('.npy')]\n", + " return files" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### List all the environments " + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Find 18 environments..\n", + "['abandonedfactory/', 'abandonedfactory_night/', 'amusement/', 'carwelding/', 'endofworld/', 'gascola/', 'hospital/', 'japanesealley/', 'neighborhood/', 'ocean/', 'office/', 'office2/', 'oldtown/', 'seasidetown/', 'seasonsforest/', 'seasonsforest_winter/', 'soulcity/', 'westerndesert/']\n" + ] + } + ], + "source": [ + "envlist = get_environment_list()\n", + "print('Find {} environments..'.format(len(envlist)))\n", + "print(envlist)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### List all the 'Easy' trajectories in the first environment " + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Find 10 trajectories in abandonedfactory/Easy\n", + "['abandonedfactory/Easy/P000/', 'abandonedfactory/Easy/P001/', 'abandonedfactory/Easy/P002/', 'abandonedfactory/Easy/P004/', 'abandonedfactory/Easy/P005/', 'abandonedfactory/Easy/P006/', 'abandonedfactory/Easy/P008/', 'abandonedfactory/Easy/P009/', 'abandonedfactory/Easy/P010/', 'abandonedfactory/Easy/P011/']\n" + ] + } + ], + "source": [ + "diff_level = 'Easy'\n", + "env_ind = 0\n", + "trajlist = get_trajectory_list(envlist[env_ind], easy_hard = diff_level)\n", + "print('Find {} trajectories in {}'.format(len(trajlist), envlist[env_ind]+diff_level))\n", + "print(trajlist)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### List all the data files in one trajectory" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Find 434 left images in abandonedfactory/Easy/P001/\n", + "Find 434 right images in abandonedfactory/Easy/P001/\n", + "Find 434 left depth files in abandonedfactory/Easy/P001/\n", + "Find 434 right depth files in abandonedfactory/Easy/P001/\n", + "Find 434 left segmentation files in abandonedfactory/Easy/P001/\n", + "Find 434 right segmentation files in abandonedfactory/Easy/P001/\n", + "Find 433 flow files in abandonedfactory/Easy/P001/\n", + "Find 433 flow mask files in abandonedfactory/Easy/P001/\n", + "Left pose file: abandonedfactory/Easy/P001//pose_left.txt\n", + "Right pose file: abandonedfactory/Easy/P001//pose_right.txt\n" + ] + } + ], + "source": [ + "traj_ind = 1\n", + "traj_dir = trajlist[traj_ind]\n", + "\n", + "left_img_list = get_image_list(traj_dir, left_right = 'left')\n", + "print('Find {} left images in {}'.format(len(left_img_list), traj_dir)) \n", + "\n", + "right_img_list = get_image_list(traj_dir, left_right = 'right')\n", + "print('Find {} right images in {}'.format(len(right_img_list), traj_dir))\n", + "\n", + "left_depth_list = get_depth_list(traj_dir, left_right = 'left')\n", + "print('Find {} left depth files in {}'.format(len(left_depth_list), traj_dir))\n", + "\n", + "right_depth_list = get_depth_list(traj_dir, left_right = 'right')\n", + "print('Find {} right depth files in {}'.format(len(right_depth_list), traj_dir))\n", + "\n", + "left_seg_list = get_seg_list(traj_dir, left_right = 'left')\n", + "print('Find {} left segmentation files in {}'.format(len(left_seg_list), traj_dir))\n", + "\n", + "right_seg_list = get_seg_list(traj_dir, left_right = 'left')\n", + "print('Find {} right segmentation files in {}'.format(len(right_seg_list), traj_dir))\n", + "\n", + "flow_list = get_flow_list(traj_dir)\n", + "print('Find {} flow files in {}'.format(len(flow_list), traj_dir)) \n", + "\n", + "flow_mask_list = get_flow_mask_list(traj_dir)\n", + "print('Find {} flow mask files in {}'.format(len(flow_mask_list), traj_dir)) \n", + "\n", + "left_pose_file = get_posefile(traj_dir, left_right = 'left')\n", + "print('Left pose file: {}'.format(left_pose_file))\n", + "\n", + "right_pose_file = get_posefile(traj_dir, left_right = 'right')\n", + "print('Right pose file: {}'.format(right_pose_file))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Functions for data downloading" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "def read_numpy_file(numpy_file,):\n", + " '''\n", + " return a numpy array given the file path\n", + " '''\n", + " bc = container_client.get_blob_client(blob=numpy_file)\n", + " data = bc.download_blob()\n", + " ee = io.BytesIO(data.content_as_bytes())\n", + " ff = np.load(ee)\n", + " return ff\n", + "\n", + "\n", + "def read_image_file(image_file,):\n", + " '''\n", + " return a uint8 numpy array given the file path \n", + " '''\n", + " bc = container_client.get_blob_client(blob=image_file)\n", + " data = bc.download_blob()\n", + " ee = io.BytesIO(data.content_as_bytes())\n", + " img=cv2.imdecode(np.asarray(bytearray(ee.read()),dtype=np.uint8), cv2.IMREAD_COLOR)\n", + " im_rgb = img[:, :, [2, 1, 0]] # BGR2RGB\n", + " return im_rgb\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Functions for data visualization" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "def depth2vis(depth, maxthresh = 50):\n", + " depthvis = np.clip(depth,0,maxthresh)\n", + " depthvis = depthvis/maxthresh*255\n", + " depthvis = depthvis.astype(np.uint8)\n", + " depthvis = np.tile(depthvis.reshape(depthvis.shape+(1,)), (1,1,3))\n", + "\n", + " return depthvis\n", + "\n", + "def seg2vis(segnp):\n", + " colors = np.loadtxt('seg_rgbs.txt')\n", + " segvis = np.zeros(segnp.shape+(3,), dtype=np.uint8)\n", + "\n", + " for k in range(256):\n", + " mask = segnp==k\n", + " colorind = k % len(colors)\n", + " if np.sum(mask)>0:\n", + " segvis[mask,:] = colors[colorind]\n", + "\n", + " return segvis\n", + "\n", + "def _calculate_angle_distance_from_du_dv(du, dv, flagDegree=False):\n", + " a = np.arctan2( dv, du )\n", + "\n", + " angleShift = np.pi\n", + "\n", + " if ( True == flagDegree ):\n", + " a = a / np.pi * 180\n", + " angleShift = 180\n", + " # print(\"Convert angle from radian to degree as demanded by the input file.\")\n", + "\n", + " d = np.sqrt( du * du + dv * dv )\n", + "\n", + " return a, d, angleShift\n", + "\n", + "def flow2vis(flownp, maxF=500.0, n=8, mask=None, hueMax=179, angShift=0.0): \n", + " \"\"\"\n", + " Show a optical flow field as the KITTI dataset does.\n", + " Some parts of this function is the transform of the original MATLAB code flow_to_color.m.\n", + " \"\"\"\n", + "\n", + " ang, mag, _ = _calculate_angle_distance_from_du_dv( flownp[:, :, 0], flownp[:, :, 1], flagDegree=False )\n", + "\n", + " # Use Hue, Saturation, Value colour model \n", + " hsv = np.zeros( ( ang.shape[0], ang.shape[1], 3 ) , dtype=np.float32)\n", + "\n", + " am = ang < 0\n", + " ang[am] = ang[am] + np.pi * 2\n", + "\n", + " hsv[ :, :, 0 ] = np.remainder( ( ang + angShift ) / (2*np.pi), 1 )\n", + " hsv[ :, :, 1 ] = mag / maxF * n\n", + " hsv[ :, :, 2 ] = (n - hsv[:, :, 1])/n\n", + "\n", + " hsv[:, :, 0] = np.clip( hsv[:, :, 0], 0, 1 ) * hueMax\n", + " hsv[:, :, 1:3] = np.clip( hsv[:, :, 1:3], 0, 1 ) * 255\n", + " hsv = hsv.astype(np.uint8)\n", + "\n", + " rgb = cv2.cvtColor(hsv, cv2.COLOR_HSV2RGB)\n", + "\n", + " if ( mask is not None ):\n", + " mask = mask > 0\n", + " rgb[mask] = np.array([0, 0 ,0], dtype=np.uint8)\n", + "\n", + " return rgb\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Download and visualize the data" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "data_ind = 173 # randomly select one frame (data_ind < TRAJ_LEN)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Visualize the left and right RGB images" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "left_img = read_image_file(left_img_list[data_ind])\n", + "right_img = read_image_file(right_img_list[data_ind])\n", + "\n", + "plt.figure(figsize=(12, 5))\n", + "plt.subplot(121)\n", + "plt.imshow(left_img)\n", + "plt.title('Left Image')\n", + "plt.subplot(122)\n", + "plt.imshow(right_img)\n", + "plt.title('Right Image')\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Visualize the left and right depth files" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "left_depth = read_numpy_file(left_depth_list[data_ind])\n", + "left_depth_vis = depth2vis(left_depth)\n", + "\n", + "right_depth = read_numpy_file(right_depth_list[data_ind])\n", + "right_depth_vis = depth2vis(right_depth)\n", + "\n", + "plt.figure(figsize=(12, 5))\n", + "plt.subplot(121)\n", + "plt.imshow(left_depth_vis)\n", + "plt.title('Left Depth')\n", + "plt.subplot(122)\n", + "plt.imshow(right_depth_vis)\n", + "plt.title('Right Depth')\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Visualize the left and right segmentation files" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAskAAAETCAYAAADEeJs5AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDIuMi41LCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvSM8oowAAIABJREFUeJzt3Xu8VXWd//H3Rw3vgaQhiAoG4yUJTCu72M80M5zKnJ8aPXKkGQUnnVIrLUrNCjNnSkQnG68jRr8oLUdodExRRh3TEoVAzUShQDG8QV4yUz+/P9Z3HdZeZ+2zL2fvvdba+/V8PLZnr8ve67MPx/f5nu/6ru8ydxcAAACAjTbJuwAAAACgaGgkAwAAACk0kgEAAIAUGskAAABACo1kAAAAIIVGMgAAAJBCIxmDZma7m9kSM3vezD6Xdz1lYmY3mtnUvOsAUG5m9u9mdmad+15lZjPbXVO3M7NdzOwFM9s071rQHjSS0cfMVpnZB5t46emSbnP3bd39wnoC2MwODw3rP5nZ02Z2q5mNba7yfJjZIjM7voH9zzazucl17j7Z3ee0vjoA3STk859Do+zJkLPbxNvd/Z/c/ZstOpab2bgBtg8xs++a2ZpQzyozu6AVx+4UMxsTPudmDbym4neku//B3bdx99faUyXyRiMZrbCrpAfq3TmE79WSviBpqKSxkr4niaABgOo+6u7bSJokaR9JM3KqY4ak/SS9U9K2kg6UdF9OtQBtQyMZdTGzj4Se3/VmdpeZvS2sv1XSByT9W+hRmC7pU5JOD8sLMt5ukqSV7r7QI8+7+0/d/Q/hPTcxsy+b2aNm9oyZ/cTMhidqOdbMfh+2nZn86z701l5jZnPD8I9lZvY3ZjbDzNaZ2Woz+1DivYaa2RVmttbMHjezmfGpMzP7tJndaWbfMbPnzGylmU0O286RdEDic/9bWD87HONPZrbYzA4I6z8s6SuSPhH2XxrW9/VGh899Rvhs68zsajMbGrbFvR5TzewPoff9q6369wVQHu7+pKSbFGWppP5DKMzs9JBrT5jZ8Rm9w9uZ2X+FnLzHzN4SXnd72L40ZNUnMkp4h6Tr3P2JkOGr3P3qxLFHmdlPzeypkJufS2zb0szmhEx9KNS5JrF9lZmdZma/MbMXQz6PsGho2vNmdouZbZfYf//wO2m9mS01swMT2xaZ2TfN7H/Da39hZtuHzfHnXB8+57vN7C0WndV8JmTsD81sWHivH0jaRdKCsP/pluqNDp97vpk9a2YrzGxaopazw++yq0MtD5jZfgP+QyN/7s6Dh9xdklZJ+mDG+n0krZP0LkmbSpoa9t08bF8k6fjE/ldJmjnAcXaT9LKkWYoa2Nuktp8s6W5JoyVtLukSST8K2/aS9IKk90kaIuk7kv4a1y3p7PDeh0raTFGP9UpJX5X0BknTFDXQ42NdF95/a0lvlvQrSSeEbZ8O7z0tfO7PSHpCkmV97rDuGElvCsf+gqQnJW2RqG1uav++95D0j5JWhO/PNpJ+JukHYdsYSS7pMklbSpoo6S+S9sz754YHDx7tfyTzOWTjMkmzE9v7clfSh0P2vFXSVpLmhvwYl9j3GUU9wZtJ+qGkeYn36tu3Si1nSPqDpBMlTYgzMWzbRNJiSWeFjN5N0mOSDg3bvy3pfyRtFz7HbyStSX3OuyWNkLSTot899yn6PbSFpFslfS3su1P4HIeF4x4SlncI2xdJelTS34TcXCTp22FbnKmbJY49LrzH5pJ2UNSQviDr3yDrPcL+F4c6J0l6StJBYdvZin43Habo98m5ku7O++eKx8APepJRj+mSLnH3e9z9NY/G0P5F0v7NvJm7P6bo9NxOkn4i6WmrHF/3T5K+6u5r3P0visLlyPDX+pGSFrj7ne7+iqIg9tQh7nD3m9z9VUnXKAq7b7v7XyXNkzTGzIaZ2QhFgXWKu7/o7usUNdynJN7r9+5+mUdjzuZIGqkovKt9trnu/oy7v+ru31UUtrvX+a35lKTz3f0xd39B0SnNKVY5Zu7r7v5nd18qaamixjKA3vCfZva8pNWKGo9fq7Lf0ZL+w90fcPeXFGVo2nXu/quQkz9Uole6DudKOk9RZt0r6XHbeAHyOxQ1Ur/h7q+EvL9MG3P1aEnfcvfn3H2NpAsz3v8id/+juz8u6Q5J97j7/e7+sqKOjX3CfsdIusHdb3D319395lDPYYn3+g93/527/1nR75uqn9PdV7j7ze7+F3d/StL5kv5PPd8QM9tZ0nslfcndX3b3JZIul3RsYrc7Q62vSfqByO/Co5GMeuwq6QvhdNZ6M1svaWdJo5p9Q3e/292PdvcdFA1beL+i3t74eNcljvWQovHKI8IxVyfe5yVFPQdJf0w8/7Okp33jhRV/Dl+3Ccd5g6S1iWNdoqhHOfZk6ljxazOZ2RfDKcQN4f2GStq+2v4poyT9PrH8e0W9PMlG+ZOJ5y8NVAuArvNxd4/HAO+h6tlSkZOp57GmsyR0lnzP3d8raZikcyRdaWZ7KsrVUanfF1/Rxhyrp7Z0hqeX41p3lXRU6ljvU9SZ0fDnDMM65lk09O5PinrgG8nvZ939+cS63yvqDKpWyxbWwIWD6DwayajHaknnuPuwxGMrd/9Rlf3TPbsDcvdfKxpasHfieJNTx9si9CqsVXSKTlI0vk3R8IZmrFbUI7594jhvdPe31lt6ciGMPz5dUU/Jdu4+TNIGSZa1f4YnFIV+bBdJr6ryFwSAHufu/6NoyMR3quxSkZOKOjXaVcuf3f17kp5TNBxutaIhbcn83tbd497dVta2WtGQtOSxtnb3b9dTesa6b4X1E9z9jYp6qq3Ga2JPSBpuZtsm1u0i6fE6akFB0UhG2hvMbIvEYzNFp8r+yczeZZGtzexvU2GQ9EdF49Aymdn7zGyamb05LO8h6WOKxqFJ0r9LOsfMdg3bdzCzw8O2ayV91MzeY2ZDFJ1GNDXB3ddK+oWk75rZGy26cO4tZlbX6TX1/5zbKmrUPiVpMzM7S9IbU/uPMbNq/9/9SNKpZjY2DD35lqQfh9OhAJB0gaRDzCzrlP1PJP2Dme1pZltJqmv+5IRaGX6KmR0YLsLbLAy12FbS/Yqu63jezL4Utm9qZnub2TsStc0ws+3MbCdJ/9xgbUlzFf0+ODQcZ4tQ1+iar4xy+nX1z/AXJG0ItZ2Wek3V74u7r5Z0l6RzQx1vk3RcqBElRSMZaTcoOp0VP85293sVXbz2b4p6C1Youqitmisk7RVOf/1nxvb1ihrFy8zsBUn/rWic2b+E7bMlzZf0izD+7m5FFw3K3R+Q9FlFY4vXKgq0dYp6hJtxrKKLSx4Mn+1aVZ6qG8hsRWOlnzOzCxVdbf7fkn6n6DTby6o8lXhN+PqMmWVNl3SlonFqtyu62PBlRZ8VACqEMbNXK7ouI73tRkVjfW9TlNdxB0S9OXm2pDkhw4/O2P6SpO8qGj7wtKSTJP3fcD3Fa5I+ojCLUdh+uaKhZ5L0DUlrwrZbFGVuU/kdGqaHKxrO8ZSivD1NdbRtwvC5cyT9b/ic+0v6uqS3KzoD+F+KznAmnSvpjLD/FzPe9pOKLuZ7QtHvtK+5+y1NfDQURHyVPlBKocd1vaTx7r4y73oAoGjCWOHlimYkKtSZKTP7jKQp7l7vGTygY+hJRumY2UfNbCsz21rRmLxliqbmAQBIMrMjzGxzi+YUPk/RrEC5N5DNbKSZvTcMb9td0VSZ1+VdF5ClLY1kM/uwmT0cJtP+cjuOgZ52uKLTWU9IGq+oF4JTIsAgkNtd5wRFQ9EeVTQ70GfyLafPEEWzCD2vaM7j6xXNLQwUTsuHW1h0t7LfKZqQe42kX0v6pLs/2NIDAQBagtwGgP7a0ZP8TkkrwgD+VxRdYHV4jdcAAPJDbgNASjsayTup8or+NaqcTBsAUCzkNgCk5HanFzObruh2x9p0y8333XZM1Tv9okHbbr5l3/PXXxuSYyWd9+cHfl97J/Sz5Vt3rb0TMj23Zo1efPbZpubqLhMyu33IbDSKzB6cx5ctezrc8XdA7WgkP67KO+iMVsYdZ9z9UkmXStJ2e+3qB879ShtK6U0Hjt2r7/krG8bkV0gOlk2clncJpTRh/mV5l1Basz/2t3mX0Ao1c5vMbh8yG40iswfn9LG71PXXWTuGW/xa0vhw17AhkqYoujEEgILiF1XPI7eBEiGzO6PlPcnu/qqZ/bOiu49tKunKcJc0AEABkdsA0F9bxiS7+w2Kbm8MACgBchsAKnHHvS7Wa2PbAKDMyGygWGgkAwAAACm5TQEHAGU3ZOgqbbLpK3mXAQCow5Chqxran57kLtboD0M3mLCUaXHQfkOGrurJ/7/QXr34M0VmoxOazWwayV1o0coH8y4B6Eo0jtEOZDbQHoPNbBrJXSoOXX6ho17Mu1kdjWO0G5mNRpHZ1bUqs2kkdzF6J4DBoXGMTiKzgcFpdWbTSO5yi1Y+yC95oAn8f4M8kNlAc9rx/w2N5B5A7wRQP3qPkTcyG6hfOzObRnKPuOvZ/jfSoiEAbETjGEVCZgMD60RmM09yD+PuTgAND5QHmQ10NrNpJAPoSTSOAaA88shshlv0kKzTd92IyelRCw1klAGZDUTyymwayQD6dPu8m4w7BtBNyOz2YrgFgK5HwxgAyqMomU0jGUBXKkrIAgBqK2Jm00gG0FWKGLQAgGxFzmwayQC6QpGDFgBQqQyZzYV7AEqvDGELAIiUJbPpSQZQWmUJWgBA+TKbRjKA0ilb0AJALytrZjPcAl2JyembV+R5N/OeMxNAe5DZzSOz24eeZACFV+aQBYBe0y2ZTSMZQGF1S9ACQC/otsymkQygcLotaAGgm3VrZjMmucfc9ewNeZcAZIrHrnVr2ALNILNRVL2Q2fQkA8hVNwcsAHSbXspsGskActFLQQsAZdeLmc1wCwAd101h+9xTT+ddAgC0VTdl9rWXX1n3vvQkA+hn2cRpbZm3tFuCtpGQBYB2I7MH1mxm00gG0Ha9HrQAUCZkdoRGMrrWhKWXFfpORL2gG4KWhjHQGWR2/sjsSjSSAbQcQQsA5UFmZ6OR3IPuevYGvWf4YXmXgS5V5rClYYwiIrPRTmR2dTSSAbQEQQsA5UFm10YjGcCglDVoaRgD6EVkdv1oJANoGCELAOVBZjeHm4kAyJR1lfmQoasIWwAoIDK79ehJBlBT2UI2Ga5HHv+POVYCAJ1HZrdGzZ5kM7vSzNaZ2fLEuuFmdrOZPRK+bhfWm5ldaGYrzOw3Zvb2dhYPoL3K1gtx7eVX9ut9KEJvRKeR20BvIrNbq57hFldJ+nBq3ZclLXT38ZIWhmVJmixpfHhMl/T91pQJNKcdt+nsBfuu+qr2XfXVvMuoW1bQ9rirRG6jhMjs5pDZ7VFzuIW7325mY1KrD5d0YHg+R9IiSV8K6692d5d0t5kNM7OR7r62VQWjNZh3E1nKFrLIRm53HzIbWcjs9mp2TPKIRIA+KWlEeL6TpNWJ/daEdf3C1symK+q10JY7Dm+yDACtUJagLWPIFsigcpvMBoqDzO6MQV+45+5uZt7E6y6VdKkkbbfXrg2/HsDgEbS9qZncJrOB/JHZndVsI/mP8ek4MxspaV1Y/7iknRP7jQ7rABQIQduTyG2gpMjsfDTbSJ4vaaqkb4ev1yfW/7OZzZP0LkkbGNcGFEcZgrbbQrZAyG2gZMjsfNVsJJvZjxRd7LG9ma2R9DVFIfsTMztO0u8lHR12v0HSYZJWSHpJ0j+0oWYADSh6yHYiYLs5xLOQ20B5kdnFyex6Zrf4ZJVNB2fs65JOGmxRAAaPoO1d5DZQPmR28XDHPaALFTVsezFkAaAWMruYaCQDaKteD1kAKBMyeyMayQDagqAFgPIgs/ujkQygpQhaACgPMrs6Gsk9jNucopUIWqC9yGy0EpldG41kAE0jZAGgPMjsxtBIRtebsPQyLZs4Le8yugpBC6BdyOzWI7ObQyMZQF0IWQAoDzJ78GgkA6iKkAWA8iCzW4tGMoB+CFoAKA8yuz02ybsAAMUQhyxhCwDFR2a3Hz3JQBdaPOacum5zunjMOVp5xsi+ZcIWADqPzC4mGslAj1k85hxJioI2EbYAgOIhs/NDIxnoUumeiYqgBQAUCpldPDSSgS4WhywAoPjI7GLhwj30hAlLL8u7BABAnchsFAGN5B5317M35F0COojTdkC5kdm9hczOF41kAAAAIIVGMtBDxs5cm3cJAIA6kdn5opEMAAAApNBIBgAAAFJoJAMAAAApNJIBAACAlK5tJL9n+GF6z/DD8i4DAFAHMhtA0XRtI7nTc0kS8MXH5PRAcZHZSCOzkbeubSQDAAAAzaKRDPQY5t0EgPIgs/NDIxnc5hQASoTMBjqDRjIAAACQ0vWNZC7MAIDyILMBFEXXN5IBAACARtFIhg4cu1feJQAA6kRmA52xWd4FoD2Spyy/d/bnq+536qzP6ZUNYzpQEQCgGjIbKJ6uaCS/Z/hhPX+17/0X3tL3/KSzz6/Yll5OWvqrUyVJe+4+qz2FAUAKmU1mA2XQFY3kXhQHbBym7zm7sYtdHnr41JbXVAYTll6mZROn5V1G7sbOXKuVZ4zMuwygZ5DZzSGzI2R2Pmgkl9hAvQ21xL0QyyZO49afANABZDZQLly4V1KDCVtJGjJ0VWsKAQDURGYD5VOIRvJL657X/Rfe0vdoRifm1uyW+TuHDF3Vd+EHp7IANIrM7iwyG8hHIYZb7DBqdMVf2dWu7N3ncx/sVEkAgCrIbAC9oGYj2cx2lnS1pBGSXNKl7j7bzIZL+rGkMZJWSTra3Z8zM5M0W9Jhkl6S9Gl3v6+RomqdlkoHcqMXQJTd/Rfe0vRnTvZISKJHAugyZHbxkNlAOdUz3OJVSV9w970k7S/pJDPbS9KXJS109/GSFoZlSZosaXx4TJf0/VYXfdLZ51c8pIHnlWzlKbda71Xk03vpsE0ieHvP2Jlr8y4B7UFmN/BeZDbKgszuvJqNZHdfG/cquPvzkh6StJOkwyXNCbvNkfTx8PxwSVd75G5Jw8ys7fOWnHT2+YMaHwcA3YDMBoDWaGhMspmNkbSPpHskjXD3+M+aJxWd2pOiMF6deNmasK7iTyAzm66o10LDRu3UYNnZkj0U1U7/xb0G9U5kX8RJ75u5SnrI0FVa+qvZfctMRA90PzK7GMhsoJzqbiSb2TaSfirpFHf/UzSMLeLubmbeyIHd/VJJl0rS6Le9raHX1nLS2ef3ncrrm7g9dUqt2im2ooXrYGVNQJ8M2168UroXPzN6D5ldTmR2f734mVEMdU0BZ2ZvUBS2P3T3n4XVf4xPyYWv68L6xyXtnHj56LCuo+KxbwONe2ulTgV1o6cm99x9lia+8+S+kN1z91l66OFTe/buTUAvILNrI7MB1FKzkRyufL5C0kPunjxnNF/S1PB8qqTrE+uPtcj+kjYkTvF1XBy69QZvuy/ieM/wwwZ1jEanVEpe+JEM3XTPBIDuQGa3FpkN9K56epLfK+nvJR1kZkvC4zBJ35Z0iJk9IumDYVmSbpD0mKQVki6TdGLry25Moz0URb7aWWqsB6TaldGAxNXSXYrMLhgyG61CZndWzTHJ7n6nJKuy+eCM/V3SSYOsqy1OOvt8nXjxEXrrurFNXUhx17M3FD6MkwaaPghAdyKzNyKzAQxGIW5L3SknXnyEJOmBN6/se15NvVdUD3QqLt4Wb+/0VdeELYAyI7MB5KkQt6Vut2rhGq+/+MTrBnx9PVdZJ9cNtD39tUhXZi+bOI2xbgByR2bXh8wG2qurG8m1eh6q7RcHcCdO0xVxTk8AyAOZDaBIurKRXG/Q1np9rd6KVkmGbq3eiu2eulmS9FD4Wo94CqHkVwAoCjK7EpkNFINF12zka/Tb3uYnz/+vlrzXYMM2S6PBm57P8qKFqyRJnz14TF2v33P3Wbrr2Ru03VM367kdDpG0MWgvWriq733i983y2YPHDLg9+Zn+8L3XJUkbLj2hp07dMTl9ZOUZbb8DcVdbMnuBnl/zdLUL5boSmV2JzO4MMjtCZg/enadftdjd96u1X9f0JLcjaNPvnQ7edLDGf/VXC7pq6/uF48IjdGJYv91TN/d7XTrAs943DubktqwQjsMWADqJzO5/LDIbKJZCNJLfvO7Rpl/bzqCt51hxiH324DFN15IVjsltyeNkbRtoe3L9QMcBgHqR2WQ20AsK0UiWmhtT1smwraXeEEv3JMQBOFCwxvtXO/UXvz7eHveOxM8/q1Mr9k3a5aSNswAuu7SujwAAZDaZDXS9wjSSY/UEb9GDtp6//JPhmQ7SrOV0qA60f3z6MO4p+ezBY/ou/Lh492J9/wCUG5lNZgPdqhCN5KdH7txvXbXgLXpYDHShRz0XgWRdMJIM72qn6wYK+YsWrtLFu29c7tQV4CiHsTPXciEIGkJmb0Rmo9PI7M4pRCNZki6f0X+Km+PPPbXwAZs2UG9EtXDMCs6BTtVlvZ9UGaTxqTvGswFoBzK7chuZDXSfwjSSs1w+Y5aOP/fU2juWVNaVznHQ7rn7LCl1JXZWAGeFaXJezfTV3ADQLmQ2mQ10k0LMk7zLPnv4F26tnOuxG4O2nrkyk+JehqzTmFkTzA920vl4DspemXeTOTc34tRd83pxnmQyOxuZ3V5k9kZk9uDUO0/yJrV2yEM3hm2smdNoF594Xb8xaRctXNXvtCZ3ZWpMr/xiAdqNzK5EZrcHmY1OK9Rwi24OWqm5sM3C6TgARUBm14fMBsqpED3J269d3fVh20px70O9t0wFgFYisxtDZgPlVIhGci9p1VQ+XAENAO1HZgO9i0ZyDloRuoQtWmnszLV5lwAUFpmNoiGzO4NGck4GE7rJ+TQBAO1HZgO9h0ZyybXyghCuHAaA9iKzgfKgkVwyJ158RN9pO07fAUCxkdlAedFILpmLT7yOU3YAUBJkNlBeNJJzUO9dg9ITzz911gw9ddYM7bn7rJZdcQ0AGBiZDfSmQt1MpJekw7Sa4WvfsfH5Z8KTtbeEJ6N10cJVunj31ta2bOK0nhnrNmHpZdzqFEBNZHYxkNnoJHqSc0KvAgCUB5kN9B56knNSrVfitK3OrFjeVydo8U2X9C2//O4f9D3/34Ojr3u2vjz0oLEz12rlGSPzLgMoJDIbRUNmtx+N5A478eIj9Bltr4tPvE4rr7qv5v7JsJWkLX75933P//Wlb0pSy0/dAQAiZDbQu2gkd6HkmLi0Z0f+uoOVAABqIbOBYmJMckklT+EBAIqNzAbKh0ZyFxjMHZwWvHikFrx4ZAurAQAMhMwGyoHhFiV10cJV+uzBY6rewenZkb/WhiMmZWyJ1t0+d1z7igMAVCCzgfKhkVwwj/7dfpnr3/KzeyuWT9vqTF208JuZ+6488a+SJjUUqnHPxEeXXssclABQJzIb6F40knNULVxboZ6wff8xK/qt26BJkqpfRNKNmJweQD3I7GIgs9EpNJJzUO3OSBO/86W+50u/eF7N94nn59zil9KC0YkxagOEbVbIpu2yG1dT9yrm3QT6I7NRVGR2e3HhXkE0Grbtlj02DgAgkdlAL6AnOSfLJk6T7riirn3TY9uSlh/1rVaVBACogswGeg89yQUU91C85Wf3Dhi2I286V4ccbw29N1dIA0BrkdlAd6InOQfxbU4/+MbXtfKq+3TBkkv67XNKRtCOvOnciuWbL/emjn/73HE1x7mdteu7NLupdweA7kJmA72pZiPZzLaQdLukzcP+17r718xsrKR5kt4kabGkv3f3V8xsc0lXS9pX0jOSPuHuq9pUf2ld/oFNpFNO6Ld+x23m6skXjpFUeVrukOOt6YDNEvdO7H/e+Owd/vRsy44FoHPI7PYgs4HeU09P8l8kHeTuL5jZGyTdaWY3Svq8pFnuPs/M/l3ScZK+H74+5+7jzGyKpPMkfaJN9ZfeB895pmJ5b03WByVJlePWkmG7/NwbtfeMyQO+b9UgBdDtyOw2IrOB3lFzTLJHXgiLbwgPl3SQpGvD+jmSPh6eHx6WFbYfbGaNDcIqoJ2f+EXF1/TzekyeumnfY8dt5vYL27Tl596YuT4dtvufN77fYzCGLMs+LnrD2Jlr8y4Bg0BmR8hs9Aoyu33qGpNsZpsqOj03TtL3JD0qab27vxp2WSNpp/B8J0mrJcndXzWzDYpO7z2des/pkqZL0s5vHDK4T9ECOz/xC60e9aEBt6UDNr3/5KmbtqyedNjGy3vPmFzxvFW9D4Qs0D3IbDIbwODVNbuFu7/m7pMkjZb0Tkl7DPbA7n6pu+/n7vttv2W+1w9m9TgkxcG6etSHMoNXajxsa51623vG5IpwzbL83Bt1+esX6u4vPdL3QHOq3SwAKCMym8zudmQ2OqGhpHP39WZ2m6R3SxpmZpuFnonRkh4Puz0uaWdJa8xsM0lDFV0M0nHp3oRaPQtZvRLJ3opqp+2q9WbUKz1eLStk4/BN77v3NV/R8sRz6ZpB1QKge5DZZDaA5tUzu8UOkv4awnZLSYcourDjNklHKrpaeqqk68NL5oflX4btt7p7w5f4/t0x1+tncw+XNPBptYHEAZsMzPS65H5pyf2njLtDU8bdIUmat+IASepbPk1nau9rNl7ZXOsijSgYE8vj7pAS6/Yed0flMcK25WF53rk3asq4O7T8qG9p+VHf6nu/5Ud9q+qpvLu/9IiWn3ujjt/kc5nbX5kwmdN3QBcgs8lsAK1RT0/ySElzwhi3TST9xN1/bmYPSppnZjMl3S8pvhXRFZJ+YGYrJD0raUqtAzz6pnH6u2Ou77d+oBCsV3rfrNCNj3PaVmdKigI1DtjTdGa/95ySCMSkva/5SsX6dLDWEh83KZ5nc9ZbbujbZ+8Zk7VcUbDH+8dh/8JuR2mbx/r3TLz/mBVa/tbaNbwyIfyiYDohoKzI7BQyG0AzrIkOg5Yb+taJvv+Pbui3/mdzD6/7FFk9QZx8r2SwZQVdOlCr9UjEjhv2kCTpkHunV7wm671rSU9AL0lrD51R12uzwrZRj734sP7fazto9gX9J8zvZssmTsu7hMJYecbIvEsojSWzF+j5NU+XfjaIRpDZlcjsfJDZG5HZjbnz9KsWu/t+tfYr9B33GgngoiVfAAARaUlEQVTb+OvqUR/q612QKsO0WvBlrU+G5bwVB1T0VGT1SEjSFev37Bey1Y5ZLVSz1tdSb8he/vqFfafuHnvx4YaPg94xduZaQhcNI7PrQ2aj1cjs9ih0I1lS5ti0dIgll9On2hrpEYh7Fq5Yv2fFa9M9GPHXm/e7tG99/Jp0GKd7JaoFarVeh3h98n2zPtPlr18oSX2BevnrF/bb76Blh+qxzKP0d8Ybh2uHOvcFgBiZTWYD3aKwjeRf/8uWklRxAcZpOlNTxt2hfQ+Nbg26+KbWnVpKh22WOPTioD3k3ukDhn/Wci3p4K12qjDphd2OklZEz+OgnaLK/bd57Bqta6COF3Y7isAFUDcyu/KYZDZQfoVqJB/94r76ydaL+8JWkv71pL2q7t+K4K0naOP9jtsvu9eiXs2clovVE7zVtjcz5m3dspkafsRjGnrdkoZfC6A3kNnVkdlA+RWikbzd6w/q6Bf3lRSF7tEntf+YAwVtuveh2n7NiK94To+DS46la0aj4V/LHo/Ve5Kve0xYehkXggB1ILPJ7CIgs9FuhWgkd0IcsFIUntUCNKv3oVXWHjqj4pRaMiRrXTQyGC/sdlT0ZNnMuvbvxbAFUCxktshsIGdd0Uje99ATMk/fpUM2S3KfgfZrpWamGGrU5GOzJqifE/33tKlVXzf1X+dULP+2lUUBgMjsLGQ2UDxd0UiWouBMh2V6Oet0XScCNtbsabm07DCtXzpUqxk1f75++/FPDepYKC+mFEI7kdn1I7NRDzK79bqikbz4pku0OGN9OmA7Ga5JgwnawYZrvUbNn9+R4wAAmT14ZDbQfqVsJA90ZXSydyLvgE2OWav3dF1WwN549SNVtzWjWrg+8bGPteT9ASCJzB4cMhvIRykaybUCVsq/5yGp2t2gqhkoSKeetaPmfGNw9WQFLOEKoF3I7MHVQ2YDxVC4RnKt+TOLGLD1aLZHYc43nmxof8IVQCeR2ZXIbKB7FKKR/NKGXbX4pu9mbitrwKa1+vRbrJUBe+jnv9j3/Kbzv9N0TQC6G5ndPDIbKI9CNJKTuiVgk1oZsumArTdck2Fay7ID3993HK6U7m1cLY1ayOyBkdnoJDK7tQrXSO6GgJVaE7KN9DjEgXrT+d9pKFyriY+zx+vP67ebbDvo9wPQncjsjchsoLsUrpFcZoMJ2azehnp6HNLh2oqwnbDo9opffGM//fZBvycAFA2ZDWAghWgkb7/py33TAKXvptQK7ezpaDZkmz0Fl9SKcM1yyqQT2vK+ALoDmU1mA72gEI3kp1/bouXj2ZLBnXXXpmY1E7BZp+DiWpp5v3YFLQDUg8xuDJkNlFMhGsnt0OqeiHqCMRmsyV6G5PP4iunkcvq9s9YRsp0xYellWjZxWt5lAD2HzEYzyGy0U9c2klthoJBtdjxa/J7J4E0HLGELAI0jswG0Eo3kKpKh12y41vv+acnjTVh0+6CO04wLllyiUyadoAuWRDcJmK2BbxaA7saUQigDMpvMRoTMbh0aySl94+LmR19bEa4DyRr7JuUTtElx2O64zVzN0Iu51gIA1ZDZETIbaD0ayaq8YKRV4Tr1rB0zb0860BXSN179SF/QFcWTLxxDrwSAQiGzqyOzgdbp+Uby5GPH6wk1drVyPDZt3ooDMkNVUt/6agHbN74tMc6taGELAEVDZgPolJ5uJNc7lU/WlcuTjx2veWdV9j7cePUjFT0ch9w7XXO+UT1gkwhbABgYmQ2gk3q2kZw1hc9AsqYBmjLuEc1bcYBGzZ+vQ+6dLmlHzdMBmjLuDk0+drzmfCy7xyJL8qILAEAlMhtAp/VUI3nyseP7grNWwDYiCtuN5q04QLr6jpa9f95OPuUEzb6AXwYAOovMbg6ZDbTGJnkX0EmtDNnYlHH9gzVrnRSCeADcWhQANiKzAeSpaxrJk48d39TtQgcrK0ST62qFbBqhm78JSy/Lu4TCGTtzbd4loMuQ2WgVMrs/Mrs1uqKRnHVHpE5K9kJMGXdHv+Ws5wDQq8hsAGXQFWOSp561Y+5hlnX8eSuiC0Lir9Wkey4uYI5LAF2MzAZQBqXvSa7n1Ni8FQdU7HfbogUtO/5AY9nibXHo1qpLiiaCB4BuRWYDKIvS9SQngyz5V39SOlBHKFq+bU3nako/T+8fS2/fccVcQhdA1yCzAZSVuXveNWjLbXfwMfsensuxP3DgRwf9Hlk9DtV6IrLWJ0O3qPNu9tp0QssmTsu7hMJZecbIvEsopCWzF+j5NU9b3nV0EplNZhcNmd0fmV3dnadftdjd96u1X+l6klst2YNRb/hm9TYkl6v1OsTr06FbEcCTihu6AJA3MhtAp5R+THIr3bZoQd9jMOq58KNaYDc6/RAA9CoyG0A70Uiuolb4pnse4uVkz0N632o9F/Fyeiqi2I7bzG3yUwBAbyCzAbQajeQ6DKa3Iqt3IhnAyaupqynCRSEnn8KE+QDKgcwms4FW6PkL9war2pi4RubZzNqviGPcuBCkt3ERSDYu3CsXMrt7kdmVyOzq6r1wr+6eZDPb1MzuN7Ofh+WxZnaPma0wsx+b2ZCwfvOwvCJsH9PshyiDaj0W6fFq8fya8aNaT0X6OQA0g8zORmYDqFcjwy1OlvRQYvk8SbPcfZyk5yQdF9YfJ+m5sH5W2K8n1Dq9N9CFH8nnRThVB6SNnbk27xLQGDK7BjIb3YzMHry6GslmNlrS30q6PCybpIMkXRt2mSPp4+H54WFZYfvBYf+eke6pSF8gkgzUrBAuwkUfp0w6oe8BoFzI7MaQ2QCy1DtP8gWSTpe0bVh+k6T17v5qWF4jaafwfCdJqyXJ3V81sw1h/6eTb2hm0yVNl6TNNt+62foLb8Sa0yVJfxz9L5KiQD1FUYjFPRDztjmg/4UhS/KpN0scumNzrgNA3cjsJpHZAGI1G8lm9hFJ69x9sZkd2KoDu/ulki6VootAWvW+RRUHb/I2qyO0QBq2cTnZQ3HKpBMqQrjTF4VcsOQSeiSAEiKzW4PMBlDPcIv3SvqYma2SNE/RKbvZkoaZWdzIHi3p8fD8cUk7S1LYPlTSMy2suatMXD+qYlqhZLDG67koBEADyOw2IrOB3lGzJ9ndZ0iaIUmhV+KL7v4pM7tG0pGKQniqpOvDS+aH5V+G7bd6EeaZK7DbFi3Q0mFPSAqT0K/YuC0O4lMmnVDIKYYAFAuZ3X5kNtAbBnMzkS9J+ryZrVA0fu2KsP4KSW8K6z8v6cuDK7E3TFw/ShPXj+o7xScNfLcnAGgQmd1CZDbQ/eq9cE+S5O6LJC0Kzx+T9M6MfV6WdFQLautZybFw8cUjncbYNqD8yOzOILOB7sRtqQtuxJrT+wI47xBcedV9uR6/0yYsvSzvEgCUDJmdHzIbrUYjuSRGrDldty1a0HeKb+L6UW09HmPpAKB5ZDZQfjSSS6xT4QvEuIMT0DwyG51GZg8OjeQuQfACQHmQ2UDx0UjuMu3uqei1MW4A0E5kNlBcDc1ugXJJhm48pycAoJjIbKBYaCT3iKxeimZDeOVV92nsp98+2JIAAFWQ2UD+GG7RwxgPBwDlQWYDnUUjucdVGwtXa35PxrkBQOeR2UDnMNwCkip7KD5w4EdzrAQAUAuZDbQfPcno57ZFC/oeA+mFngnu4ASg6MjsjchstBI9yRhQVuimey2ygpeLRACg88hsoHVoJKNhtXor0N3GzlyrlWeMzLsMAHUis3sbmd08GskYlGT4JnsrmHIIAIqHzAbqRyMZLVMtfAEAxUNmAwOjkYy2qHYRyT9e9bUcqgEADITMBvqjkYyOuvLTX6+6jTAGgGIhs9HLaCSjMNJhTAADQHGR2eh2zJMMAAAApNBIRmENdJqvk5icHgBqI7PRbWgkAwAAACk0kgE0bOzMtXmXAACoE5ndHBrJAAAAQAqNZAAAACCFRjIAAACQQiMZAAAASKGRDAAAAKTQSAbQFK6WBoDyILMbRyMZAAAASKGRDNSBOzgBQHmQ2WgFGskAAABACo1kFNqVn/563iUAAOpEZqObmLvnXYPM7HlJD+ddxyBsL+npvItoUplrl6g/T2WuXWpd/bu6+w4teJ/SMLOnJL2o8v7787ObnzLXLpW7/jLXLrW2/rpyuyiN5Hvdfb+862hWmesvc+0S9eepzLVL5a8/b2X+/pW5dqnc9Ze5dqnc9Ze5dimf+hluAQAAAKTQSAYAAABSitJIvjTvAgapzPWXuXaJ+vNU5tql8teftzJ//8pcu1Tu+stcu1Tu+stcu5RD/YUYkwwAAAAUSVF6kgEAAIDCyL2RbGYfNrOHzWyFmX0573qymNmVZrbOzJYn1g03s5vN7JHwdbuw3szswvB5fmNmb8+vcsnMdjaz28zsQTN7wMxOLkv9ZraFmf3KzJaG2r8e1o81s3tCjT82syFh/eZheUXYPiav2pPMbFMzu9/Mfh6WS1G/ma0ys2VmtsTM7g3rCv9zEzOzYWZ2rZn91sweMrN3l6n+oiKz26vMmR3qKX1ulzWzQ02lze0iZnaujWQz21TS9yRNlrSXpE+a2V551lTFVZI+nFr3ZUkL3X28pIVhWYo+y/jwmC7p+x2qsZpXJX3B3feStL+kk8L3uAz1/0XSQe4+UdIkSR82s/0lnSdplruPk/ScpOPC/sdJei6snxX2K4KTJT2UWC5T/R9w90mJaXfK8HMTmy3pv919D0kTFf0blKn+wiGzO6LMmS11R26XObOl8uZ28TLb3XN7SHq3pJsSyzMkzcizpgFqHSNpeWL5YUkjw/ORkh4Ozy+R9Mms/YrwkHS9pEPKVr+krSTdJ+ldiiYT3yz9MyTpJknvDs83C/tZznWPVvQ/9kGSfi7JylK/pFWStk+tK8XPjaShklamv39lqb+oDzI7l89RyswOtZQut8uc2aGOUuZ2UTM77+EWO0lanVheE9aVwQh3XxuePylpRHhe2M8UTgXtI+kelaT+cNpriaR1km6W9Kik9e7+akZ9fbWH7RskvamzFfdzgaTTJb0elt+k8tTvkn5hZovNbHpYV4qfG0ljJT0l6T/CadPLzWxrlaf+oirz96l0//ZlzGyp9Lld5syWypvbhczsvBvJXcGjP2MKPU2ImW0j6aeSTnH3PyW3Fbl+d3/N3Scp+uv+nZL2yLmkupnZRyStc/fFedfSpPe5+9sVndY6yczen9xY5J8bRb06b5f0fXffR9EtlCvGzxa8frRRGf7ty5rZUnlzuwsyWypvbhcys/NuJD8uaefE8uiwrgz+aGYjJSl8XRfWF+4zmdkbFIXtD939Z2F1aeqXJHdfL+k2Rae6hpnZZmFTsr6+2sP2oZKe6XCpSe+V9DEzWyVpnqLTd7NVkvrd/fHwdZ2k6xT9sivLz80aSWvc/Z6wfK2iAC5L/UVV5u9Taf7tuyGzpVLmdqkzWyp1bhcys/NuJP9a0vhw5egQSVMkzc+5pnrNlzQ1PJ+qaNxYvP7YcOXl/pI2JE4VdJyZmaQrJD3k7ucnNhW+fjPbwcyGhedbKhqX95Ci0D0y7JauPf5MR0q6NfzlmQt3n+Huo919jKKf7Vvd/VMqQf1mtrWZbRs/l/QhSctVgp8bSXL3JyWtNrPdw6qDJT2oktRfYGR2m5U5s6Vy53aZM1sqd24XNrNbPci50YekwyT9TtGYpa/mXU+VGn8kaa2kvyr6a+c4ReOOFkp6RNItkoaHfU3R1d+PSlomab+ca3+fotMTv5G0JDwOK0P9kt4m6f5Q+3JJZ4X1u0n6laQVkq6RtHlYv0VYXhG275b3z07isxwo6edlqT/UuDQ8Hoj/3yzDz03iM0ySdG/4+flPSduVqf6iPsjsttde2swO9XRFbpctsxN1lja3i5jZ3HEPAAAASMl7uAUAAABQODSSAQAAgBQayQAAAEAKjWQAAAAghUYyAAAAkEIjGQAAAEihkQwAAACk0EgGAAAAUv4/bAXvr4+3OTsAAAAASUVORK5CYII=\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "left_seg = read_numpy_file(left_seg_list[data_ind])\n", + "left_seg_vis = seg2vis(left_seg)\n", + "\n", + "right_seg = read_numpy_file(right_seg_list[data_ind])\n", + "right_seg_vis = seg2vis(right_seg)\n", + "\n", + "plt.figure(figsize=(12, 5))\n", + "plt.subplot(121)\n", + "plt.imshow(left_seg_vis)\n", + "plt.title('Left Segmentation')\n", + "plt.subplot(122)\n", + "plt.imshow(right_seg_vis)\n", + "plt.title('Right Segmentation')\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Visualize the flow and mask files" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": { + "scrolled": true + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAskAAAETCAYAAADEeJs5AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDIuMi41LCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvSM8oowAAIABJREFUeJzsvXmwNclVH/g7de/7ultbt4SE0IoEbkCSPWMLMQiDRoAQBiIcIgiHwMMeOBSOwMQwAxixSxZgzEwAwUyAhwmzyGIdY9bRYBqBWgjTmGUYQJKRxCIkISFa6m4J1N/y3s35ozKzTp48Jyvr3nrfd/t95xfx3q3KPOfkUlW/yjq5UQgBDofD4XA4HA6HY8JwozPgcDgcDofD4XAcG7yR7HA4HA6Hw+FwCHgj2eFwOBwOh8PhEPBGssPhcDgcDofDIeCNZIfD4XA4HA6HQ8AbyQ6Hw+FwOBwOh4A3kh0PCRDRU4nob4hoc6Cd1xLRP7teeg6Hw3FMcC49DhDRy4joVTc6H442vJHsOBcQ0ZcQ0R8S0QeJ6N1E9P1EdMcC/T8nok9L5yGEvwghPCKEcHY+Oc6kdS2+QNLfvzyv9BwOh2MOzqXnCyL6T0T06Ur4DxNRIKIXifDvjuFfct0y6bhh8EayY3UQ0VcB+DcAvgbA7QCeC+DDAdxFRJduZN468JPxBZL+vvNGZ8jhcNyccC49XxDRwwE8B8DdhsibAXwRk98CeDGAPzn/3DmOAd5IdqwKInoUgJcD+IoQwi+FEK6FEP4cI7E8DcAXRLmXEdF/IKKfJKIPENHvEdF/G+P+PYCnAviF5IEgoqfFr/dtlHkMEf0QEf0lEd1HRD8bwx9NRL9IRH8dw3+RiJ68chkHIvpGInobEb2HiF5JRLfHuB+JLzYQ0ZNinr88nn8kEb2PiPy5czgcTTiX7sel0dbHxuPPj3rPiudflsoX8QIAvxFCuGJk8RcAfBIRPTqefwaAPwDwbpbeRxLRrxLRe4noXiL6Ue7pJ6KvJaJ3xmvzx0T0AiXPJ0T040T00w+Bj5+bCv6ydqyNfwjgVgD/kQeGEP4GwKsBvJAFvwjA/wXgMQB+DMDPEtFJCOELAfwFgH/c8ED8ewAPA/AsAB8K4Ltj+ADghzB6W54K4EEA//s6Rcv4kvj3KQA+AsAjWBp3A/jkePx8AH8K4L9n578eQtitnB+Hw3Hx4Fy6H5fO6XGv8WcB+L8b+bsM4OcAfF48/yIArxQyBOBfA3gigGcAeAqAlwEAEX00gH8B4ONCCI8E8I8A/HmhTHQbgJ8FcAXAi0MIVxv5cVxneCPZsTYeC+DeEMKpEveuGJ/wuyGE/xBCuAbguzC+EJ47lwARPQHAZwL45yGE+6KH5W4ACCG8N4Tw0yGED4YQPgDg2zASYy9eTET3s78nKjKfD+C7Qgh/Gl9YXwfg86Jn5m6MnocBIzF/J4BPjHqSoB0Oh8OCc+l+XHo3y+fzMDZg07nWSH71TDleCeCLonf4+RgbtBkhhLeGEO4KIVwJIfw1xvpP6Z0BuAXAM+NHy5+HEPhQjUcB+CWMwze+9DzHiTv2gzeSHWvjXgCPTV15Ak+I8QlvTwfRI/AOjF/jc3gKgPeFEO6TEUT0MCL6P2KX2/sBvA7AHdQ/k/unQgh3sL+/VGSeCOBt7PxtALYAHh8J8G8B/H2MBP2LAP4yehS8kexwOHrhXLofl94N4HnxA2AD4KcAfCIRPQ3juO7fj+X7ewAeCCG83bADAAghvB7A4wB8A4BfDCE8yOOJ6PFE9BNxSMX7AbwK8QMmhPBWAF+J0bP8nijHr8tzAfw3AL4jhBBa+XDcGHgj2bE2fhNjt9Hn8EAiegRGj8VrWPBTWPwA4MkAEpG2COPtAB5D+gzvrwLw0QA+PoTwKEzdbLSgDHP4S4xdkAlPBXAK4K/i+d0A/gmASyGEd8bzLwbwaESCdjgcjhk4l+7BpbFh+kEAXwHgdSGE92McQ/wSAK9nQzR6vMgJr8JYH3KoBQB8O8Y6/nuxnr4ArI5CCD8WQvikWM6AcSJmwi9j9HS/hoge35kXx3WEN5IdqyKE8ADGySb/GxF9RpyQ8DSMX/PvwDj+LeFjiehzoqfkKzG+EO6JcX+FcYyalsa7APw/AL4vTi45IaJE4I/EOHbufiJ6DIBvWbWAI34cwP9ERE+PL6xvxziTO3WL3o1xHNrr4vlr4/nrvTvN4XD0wLkUwP5cmvSSt/m14hyYH4/M8b0Yx4C/Tol7JIC/AfAAET0J40okAMYxyUT0qUR0C8bxzQ8CKMZRx3HiP4axocyH0DiOAN5IdqyO+NB/PYD/FcD7AfwWRo/FC8Qs4p8D8LkA7gPwhQA+J46pA8av62+MY9m+WknmCwFcA/BfAbwH44sBAL4HwG0YuyLvwTjea238IMYX1OsA/BlG8vsKFn83RuJMhPp6jBNjNIJ1OBwOFc6le3Op1CvOo+f8mQD+c08mQwjvCyG8xhgS8XIAzwbwAMZGN59oeQuA78BYh+/GODHy6xT7r8A41vlX4geJ40hAPgzGcSNARC8D8HdCCF9wo/PicDgcD1U4ly4HEb0YwD8JIbz4RufFcdxwT7LD4XA4HI6bCfdjWurO4TBxLo3kOH7qj4norUT00vNIw+FwOBzrwXnbcbMghPDLIYTfvNH5cBw/Vh9uEZeHeTPGQe7vAPDbAP5pCOGNqybkcDgcjlXgvO1wOBw1zsOT/N8BeGtcHPwqgJ/AuBuQw+FwOI4TztsOh8MhcB6N5CeBLWyO0SvxpHNIx+FwOBzrwHnb4XA4BLSdfK4LiOglGBf3xubWh33so558p7nkebVyOQ8I8yub96x8bsqIPFHTGBXyqqjIe1ceZiD1dtomphLWKBurPpO8jJR2lo7e0eRlvSywmWRJmCFhtFlGQ6aw2XHfqel0KJFxvA+602/f2MeFlbPKL3votM113nv/X+ADH3zvQ6gC9wPnbAAfeyPz4nA4HAfi3hDC4+aEzqOR/E6w3X8w7vzzTikUQvgBAD8AAI+58++HF37PXQAAiis7ElF+b6e3DwFFWD5mOojhWYfLp7BTEZf0FB1VXspx/dOyvWHZBAA6U8IGqsNotKuGK+k8+L7pFU5iufWsYjWkT6c8yHCJlK9iWPupImPkJQQjHyJse6q3krWbN6VxgjJfG3YcQsi6XGYbyrBtoVPanM7tFvyJ0vA026I05duKU6Ma9lRbhs1wUgbMtpln4rva3Cs0KweWUL5thN25vPDb7VoHI8pb9hX/56fMKx0/ZnmbczbRkk9Xh8PhODq8bV7kfBrJvw3gTiJ6OkaS/TwA/0OPIgGgSwRcEw3d9EvGMdPJdpQGdtLDydjwnW0cp/MTjI1HGc7evjnOkuXlTGFbTI1fq3GcwqKs1jDmstUxSyOHDQRcqsMB5PCqYdHbUFPkrEYK8S8XK63TgDMyGsTiPIRG/QjN6TwYMvNZk5Yq2ZkGcbf8TJxm76QRp9ml01A1lFv2u/PWoQ+Ujd2DkJ/N/XWr44bYBcLevO1wOBwXFas3kkMIp0T0LwD8JwAbAD8YQnjDnN7YsI3e40uYvMOYafxSbKaclB5ftXHMz09o3kNc5W9Kk4dXOtvSayplirBLVDSqTbnYuG/KKvkGoHqGmy96UuK3QFC82T2GqRGXymTaWNAi4dcIgemKxnNplkcEM8nUng/GeTNTWrASvjXCe+xZNvvixsi5oQZreIe7GsP1JVmcTnLw09JZFxe0BTyHfXnb4XA4LjLOZUxyCOHVAF69REcOr6AT1B7l4rj0vBKh9uJCb1SDh880kCtvcqf3eTas4Tme063Ci+Ox6VY0jHfz7/6i7SIa+U1ZaVjxXFc6VaRxfjopam0dGbZDUD8UZDuLoNfHEEN3SmNZDskOaNdperCWeJObHxNz9piuNcyCulq5N6gxfIgMgDPtw64hu1Ea31qWtXLsOtN5qGEf3nY4HI6LjBs2cY8jNWarxi33KIsGstlI5ceNBjIBlfcZc7oN+SrM8iZrjeM5D7EiW8mwxjsNYhCA1eg1Gtraebgm04sHc55gLt/bitkCOBP5U8TOgGJs8UCENFTSancD8w3c1FjWJvvJxvJsG7izwSsfxH09yifoaAwb0apaxzVbq0FsmeG3VzdhiY/gVlpcZK4sPXNiHQ6Hw3ExcBSNZKBu3OZj1oBUvcfsOMmTGBZQeY+5ftcYYirsy0l0pjd5y/LCPLuqXmPMcRWWGwC1TUtPO5cNXOlNTvmRY30r2VaLlAdrDWpLvqORrIYr14+fW+OWefjUEC6b1lpDu2f2Us8wCFVkpmEpG3TVwzzXVpYfQgvT043Oi2hp99o6uJGaOKPTk6yamHuuHA6Hw3EhcFyNZNnYTGEnAJ02vMckdPJQDbtxXJyLBups49qwo8rONY55WIc9AKATaq52IX8BFF7wAq2GKLcjGwbmiVh6jcSx1qDoCGu2Q1gDd2rIlRPytEZzYC5lKbOFKEduMs8vJadOMmwV4NDGKbUf5CVe6e4JdD3t5d7G44ENa77ASCXT8XVVPCZnAde2doZkzD/8mb/Fw++7qAMwzg//7NX31jy/hLOBZZzd2wMIgHYLODva/dbPebRRUofD8VDG8TSSlcbK1Ngjw0MsznnYnitepPRU++m8y5scjzaYlnpTXsxF2NwKFkqDW7Pb8k72eDVVaKtksIpsNVS0YSEFBiDsJgNnVwHZTjnDOJuoyjPKZuuwAXZnZWNvp6xgIXNRNoj1eCo0g+lJNqvRiNiiryHcjO5paC5tjB/YeF2avmVvto3fmz6XXXThanzcz38Ql9C/rrJjgtpAxkObs7/5Z+6r5ADB2UavHQH4ps+5Aw6H4/hwHI1kqhvH1dAKQJ/Mx3TGX+ZxvoSKdKVOQZB5cp5hm+uzcb5lg1Uh6zjGdtYrAVQeX20MM6CTfrJz26MJV+4XHk+CvuybKHOpZJ9XEwO5rLG8HBH0WU9bgM5Yo9ZYgjW9NIsGOaa0Q9zgg4aY1Si3IcLABhPvogHeYCLCtGkJTWHJBokwIgKFlJ8pQ/XY4nYrylp1bdJvx29TfmfQ05CUDb61G7+LbC60uzQ9a1nBls4pgI/7xQ8CAbhkfSE5ZpEm3DpnT3a+9Wfu1zkb0McYWZx9Crz8y92r7XCshaNoJKcGskqa6TeRo2ggc50qDCi9DcxWec5IkhpyIrwYc2x4MnLYgmXhAJ1oK1m+zjKVcrdqDWVpkEWojTkZdILRpSujhVzTqzwzLvn0cihehBxpop5WZ2lMcbr+sg3D7Q2g/KLepZa1kGHtZzOMqhijeg9sCJuGV7ZDp6Hdau9stJ5nQ3iRbUOHP8/aeHsNz3712DiuVkrRNt5xNOGcrcStyNkv+777yzCNsxsbO6k9gafAN3+te7sdNx+OopEMwPYeMwJLJNPaMc/0IChj0iwPguptAFRynCVaxQ6Pq3VofElwYjNlpwCtIXDrHZpHWSFWw5scFLulrUmuCqdartJrTJ6ykpXhsqGTr1Oj8SMbzBNC/qnqQoxf5mOWtetbpalEFA/fHg1Q8+E9oDG7C/X169VtKywQNRq1S3T2TUuGPfuXHhwbx+zaF0vsdTayHSWcsx96nP2K77y/5OxY3rMrY2AaDvfNL3dPtuPi4IgayYw0cxjUsJ41i6swScRUb3ud5ThBK7aL/HaMdeN2W5NNuG51LG2l47RcmpBJcrc+mnDlARYoh0aIBIq4RphMx7LXkpFhZ1enurD2gNAayZzyzwAMVMpJb6HYZwRAehDGUG0MM6SOshqGlr9m5jWRrhZh34Pb3XjT7rl9NuM4oCHcwhbj8Ih9oDUwUsgZgE0eelPLPfuXH5yeARCCj69YBdYSns7ZF4Ozv/VlpSdbziXZohyiBgDDDvjqV3jj2rE/XvWK+/EF37R+b8dxNJJZo4agEFL65XKtHfO0sEx2pOuY8lKuJkdLVrNbeD0soo1yfEycKqMdV0RHuPUOTN4JRtAyXzK9bnLVNhBp6RoEbZWvaTbUDRyiUL98Os4TbRfDMWKo3KDDqoYeUE8jt9Eo5Lr7NISXyBVDZxbuXnee3uYynX7F6jalemPxZ//Kg1N+WHcBgbD1hvLBsDjeOXtK42bk7O/5pmnyYwglz/HzwKolHf/zf+0N7ISf/gY2ifQGcnZjP7KDOFu7dT/3ZXecSwM5pXcU4JPyANgeZU6YYuyaSZ7pd8HsaStdzb6aZkMGshxW2saYuMqelKsISB/vNpwAO7FJiGq/J27unAcpcWciH3yjEMtsczypqNd0yscum3bZ8TQcwxiKEfRrPYtOYdWbc4A9oL2SxpmRJgDVZX49GsID0f673MkGiIg+ZWV6xusuY7sTjWBx+Ynco3wo5ji++HXOLsK/+UvvwL/6ofuds4Xdf/t1901pxyobQijO8y6brEqXNIAaK0OW+VLk1HTW4uzNzcvZn/uy8x8nfzyNZMCcsDEd191t2SOgyadfPqGitcseRPiMJ0OXFWUCaqKV49cUe1q+ZHwdV78UuJz0CoSYX9NboH2yJe/FHMG2tqfWyLiXgGbONUI1h0NwwlY2GeHjkK0tq6vmkjZQWeAQT3DPA9u91jGzO5sf0tNWvQV7kupe2FMtqxPwMb9+mQ0voXE5Qj4mp0rOG8qHwDlb2G7ISW5+xQ/fX8o6Zxdyztml3EXl7Bd/y/WbRHoUjeSCLBWP8hhXNpALMrM8ymK2cf6Vu+xxWyJNPkFCJVoeZuzel21J+Tl7ZByjBA2Ul1ZrylkRKYh16+Uvfu2GVvLKT+SEvIr8Rffh2ZU6DBiLJMezZSKEQqyJbKlcvYLLiVXeahheiwTpWZbXM9sn3Wty6GS7xcS0lJA685uyweNPG2ndKEIF7JfIM37jcvFSvYR4zYyG8iWAvZhZQ3mFPN5McM52zubpOmfvZ9eSv8ic/eJvvv4rrBxFIxkob/Ji4xDmEWgRZOWdsMiW6yhhU36mdFueDC1slmhJkVPikcqlzdwWS0/NTQYBgFvuIFx9ILQ9BixDpBnrgOblaD1vpldEC1K8B0BJbsMG+QWUCHIk6qBev8KOFqZM0pNeCjVvjXJZaBHT0m2nK/EF8nPrN2vYxkbl7gCvyFLsy+PP+M+X1bykF3rTo6w1lB2L4JztnO2cPQ/n7Ak3ooEMHFMjGYKw0lbUHQSZf5MXetDXWS7Ol25F3UG0OQ/KyhtcPqe/zySPjl331HPU0G7WHBYactpax4pXQSYqNyABgN3V0E24IdibQMj6kgRZXQ1Gvpr3gISu9Vwn4t1CkK+CSwcQ0dyDuhfxaGns4gurQ97CwNxSuwPWEW552JYbG3+eec+VvE5WYLsmJi+x1VC+ZN6bB+fspkPB5c7Z9jlqOGdPdp2zby7O/qPP/KtxVZQwXv9LAdMFD1NvxTN+9cMOTbnAcTWSE4ElsmJdYZz4TDIlAobOBjWhua1pJWus2wmIsJjBOSJNNpvbUKeTLUC7eaKV3V/yJiWCSm7FwyrzJG2mCLGxCIB6Nz0xs5aUE5427/aSOnItZB7Pu8xTGJEg0sqbUVB50/uheSqq91JY0D21kD328RAsTWMbdbYAdgt1WzOV02QZuYTb0heE4UjrLufTf/sKTvh9EsZ8B3ntGw1lccuMyR/8Jrj5UHG9c7Yql2Sds5OMczaHc/YUzjl7bRxPI5kY6YHd2HHtLWqNR+MegEiMTaIt7NOibU21rUrVPPTu1NQiZ/4S2Bkyhq56LtLlaXCdIInSuPHoBAjXRAINFElRXFmDe1mU5WoGJg/E8WosfgdgQ+XDkQiXWHhKhp9P4+Qol3HUiR4LPo4uHsuqkNfWekj3Jc19HtAlZMYdEPJ5WjNNkzCBxS+H3rw8/Xevjg1cxCX8eDoDRtIFW9YtXXN+GoBbZEOZy/loi8WQXO+c3TgX6fI0uI5ztnP22mk+VDl7bRxFIzmRpkaO+VjzCnCS478rbGuq2iVFRuYhHSj55XI5XJAzt1mk2fA4SK9CcwmixDwD7G1IoUOVIxnAoHTxJRt5Z7c5+fg7EWW9ri3vhks6KgEYY+NkOmkSidYVJ++JQkIrE/bbWU/qHeSxnMuTQPIgrEIOLG2td7fbDPVX3Uf8/tWpQTsQTnZh3DFPG1+MkXQD9PHHhFGv8CgD7fveYeIrX/s+AM7ZztnO2U04Z+/N2WvjKBrJAIovZs0jIMnOalTn80ZXWzWGzRrrxvNHk91xOR1SZbT8zMnxPDX1UMKSa8mSIWSF83PtXpSehlpA1+F6xX2+kCiD1mUWAtIXJi+3JMeCNZUy5okefCyclc09HtY5Em1GH0AMqZvONB3jEjlaw932wQaCdIvGy2G2P+L/u1q5jYhiI0OSbtXdOzMJb66h7OiCc3YjzpB1zlYSdc4u8KJvuQM//6/ud84+BxxVIxlgxCbCAIzehrOS6DSy5fLl8j5UyeZzxZOhy5KyELyQSREbXa6QHSh7COYIWvVgGHLSXso7Wf1wUZ8v1ZPB+l2qh0JyXcN2wu6aiOMy8YWW8nGGsWtOk9cmb2zCaKh6fFqkzW0qgQO4J6QsofZy5uh+wISB8+iymyNOMgqTiXcBH+1DnkX3q3KftUx+xB9cHa+MINM0ps0i3ZPinqBpu1yhP2YQdUMZ7Xw5ajhn63LO2c7ZEt2cLfJzM3P22jieRrJCWhrZaQvRlzLiIWgsLl99qS/wZGgyMh9SroiXM54XzJyu0tTkUt6MO59IMSrCi2ijPMUzyOqvpWc1xviX/1zZtUkhKUy+NCQxWzOjrfP8fAZ2H8SSB8TtUbEe9hoLZyHa2vdB5/WUiPdQ0tiinhTSzsT4U3k0ADz1j67hJLVZBZlKr1NBumZSohtPysqG8jkR80WFzuvO2fzAOds5G3DO3puzV8bxNJLlr0J4+VjbwlrKMz2QTsw96WYbMk5OCBH6ppy1HFCRXiPc8BBUhBEnt0ibmrdh7guSewuqdE+AwEm2xVxA3uVPlRV51UxoXpNCPJLpwEJ32kxoIS+PJYnLPBBRnixStaN4Ho0xbxaaD+QeBGAvLG8bs6JSOCe9fbv1NPLUE63TB4CnvuGa6HIdKzsAZvccUJLuCQwZiI1CZH8tayifnH9v34WCc7YuBzhnO2e37c1NztOij4WzP/vr78Dvff5fXx/OXhnH0UhWyLAgTCikOrNV6dzC8lkOIrzwTChEK+S7wlrLAfFjY3H5ilwsQpaL1SvEVT1HGhFbkzdmlitSA1vPtRWn5NvasUmLB8YlcYYYxrveJEny9o/WbWdeKx5irN9pjiPbgzgttIhz34f75Ay41qksSZOrWbPGl7yAOEIAPvyPx8Zx8iycsAsoSfeEky6/ppF0iVASNM8jYjeeldcw2XH0Q/Ktc7ZztnP2hH05+5defj8+4xvvwC982/2zsjeCs//fL/zrbPvcOXtlHEUjmQBjdjPzHrMHoEW0Sa+KZ2PDanlxzr7om94MY/JIIcfuLvPhtQjUChdrs1iejjmbMrK4LxVDcx5GaU+OVwrXhKw1dVaxYT6kIg2ZlbQep6yhAeXkDu494F/auWtOIeHpl4TGMqRJLGtOttiuSOoarOtxhumarZGHlM6T33xaE6C0n7tWDe/EHOkKm5cgvBOGR9nRD+fseO6cnWWcs0c4Z2MVzl4bR9FIBmLjV45FS3HsRi/CuAchh5NNxDPjmZO+FmeSajXRpLSTdWJfxSyhbgDaKeFCHmgTbfYiWEsGWeQ5I0MnVJFkONNJhvgFWxJP814IYJTZkj5ebRQor5uU4917ebwak7HG0KU07Qd++YMlyXbfL3fNloY5+4ekn3S1dynvsutJ4sPeejpunZqNTz9FHSvdeNDi4+9JABCHTGTSFXaSrblVL86Bly8unLNVuSzrnO2cbaDH/r55uEicvTaOqpEMjA90exiFCGtM8ih+ZwjUWmKopavas7wQVB+rJDmrG0/i7klNQlYSUUnUIL0iPS4r5ZWtSzPyzOegp80IPLCua6su0nkmw6DLViSsnE/CvJwsDzw9JUymc0hHz6JnvCF8Lg/0igRUkHCjwj7sT8eH74R43YshEMZLDwScQJnMoXgpSCNdjNtUF+kqmb3UKqhDBcE52znbOZvDORurc/aaOJJGMqGamAcUHgebSGkcv8a65UxSBYpJGc1tTaNstmvJJLk4fs0kSpG2ZRNA7ZkwSLxpI8WJ7rFbHkW4+n52K4mxd2V4HTz7pap1xyXmH9o2kpcliHTlpk5DNLcLodiFKScV0yCx4xWXK/QIbPcmyuPiUhpFdpMslaTP05bHc+jtsmvV/ZrdfmNibXJIPcfd27oaaQBjHQPAE992NhJqQLHsT/HCi8y4RcgRGjGmp7Fq3HICniHd8kVL8ZpPJH41eEN5KTLvOmfbcc7Z+dw5exlawyVuFs5eG0fSSBYPSjpWxo9NciVZzi4Nx8O3mNZbNuRKWSUu/bLdkHp3a5obEzed60Sbg5UliFQ7Ml6Oo9w1SFALl2t/VgmUpwGoyJ9EZTbXW5QQz1CPN0fzSqjpiK/YabeosmtP7daLv0seqjUeQI1sD+FBADiZMXDCjvfdkSnhiW8/q5gu3S4A8rUK8XiMnzwUnJB53ngTiBNvXvuYd/cx0uVly7YTOfPGMo0N5XDegwkvEIqhFc7Zth0Z75ztnN2B1qTAm4Wz18bxNJIV4kvdRDVpTmRZxPVM9EgHUVYlUY0M5a8ytqyr6w1lmap4lr+urrmOOClTxVEtw8Pnnt3quWyd9xC7URY+5i0UZGioskX4C66VXT6i+00SqNa1l8420kMR41qTbJPcGp6E1R9g5frMkbeYk9SNx719HLuWq0oQKYCSFNFJulInXr9qEp5BulkR5WHRWCbC2cNXeKvdZHDO7ouTMs7ZMsA5O8M5e1I8BxxFI5nQIEjmbegawxYnhmhkVE0ItNIUeeO7MDXXzDR2a6ryoqx1qY4j044BU86MF8sUzRFki6w1oQa36LqVQMO25q1QPAKaqUyiigeiIHH5AkRNoDx2wLiOp1kEy+OxAD3659FdtyR9jkQkvcT7uHdMki2PQ4bSjQesRLrc3hCnkOzCREyJgwNw+eFTR3KeuT33ADgynLOds52zzw//6KW345f/zQMBeFT0AAAgAElEQVRdsheWs1fGUTSSEzjxFWQYu9qajeNWuCTaFK4Rn/jN+ZlZUF4jSO3hz+Eib1JG1dHkBMlrdqR+FWd8VvI1QCvbWiVo59KuOf5tQvFACTLciIekeCbDuNbmBpPXolgyKBqXNpMda2b0dDLFDyhtaw96C4c+eGuMiWviLOw1jMBaISrhse+cJhrwOpBEehIrUSNIuaA8Xx/zRFxrSbqXNNIFqms2jbUcifdKbBwnsc3V0Z1ycj68fGHhnA3nbK7nnF1hX86+69vvxwu//o7FhHTROHttHE0jmdAiThon851qcbVOluVkZsnLiRk8T5wUpcdByOQwMfbLJk2daIvLbHg5dHuoUJFKvImIQi1r3F89D2xLRKZEpGWsPb5NJT8Wp63LSfEJTpMU0hqb9ZfqlNGid47J8WAenxa857PAe4jwUG/C0Ty0BrSdmT70XWNIoBmPgzhuehIk6SLULzxxLaHZ5HIEXAvTovZXHllOQdpcmfoaz3Mc3EXEN9xzHwDnbCuusgXnbOfs64OLxNn/9Qv+GgDwMa963LJKMHA0167yHmMiJVJu/llPRFxcvldetaERdkOv1LXipyfTWluz0rcIOcW14tkkFW1nKImlHg090fHHXAtzLt3Wi4UdW4vW5+eR13EQs3oFSXIyJZb/8uEX9vMxRXmdSPizvVHyuwTn3V3HcUg+k6PrMe8+m3axyteL7YwkKlMj3UJOQpAuZkg3wVz/OMpeZuONt1dQLHUlDDk64ZzN4pyzVXnn7MOxb14vGmevheNpJMtfUoZXGLOMNaJsEqqUb4w3K2R7dmsCjAkcVMlaNoo4Ja1KVuu+k9ud8hNB9mB5ruTZJ2aRJpM3mg+6B6LKTJ02j5feCv4Qmp4UkQdJ/OlrlwfwLrhWlgdGovV9QHnpI+4Bab0Ql+C8yVYuDaSsJtWN29+TvBAousd4XRFC1TUKKrvm0lOYXmYnULxT8XybZDXSnbLAVMYE8koVDyu9xrdeCSXhs+NitrWjG87ZEc7Zpnnn7H4ctJybwEORs+/8yQ/FG7703iybOPvv/MQ6XmTgGBvJivc4/SYyq2ZDk9BN4Ua3nNrITrLCRiVPelxlT5THkm2FAwBZhKfJtkiWpXXp4YRrHwhVuCZrGuLpya5ATqAd49lkGLfGexg0ot3BIKIGKfP3QEW+STESahorJ198shtPdv1p5HUIYd6QB3VP/r39PWe5TrJHgiOk6zoKaaTLjyXp5peuctlAmcrnixZfxlcfMWT9zbUA7GIjWFUSceu9oy48+HPnnB3PnbMrI87ZB2IhJ73wq2/Hf/mX73tIcvYbvuzeNmevgKNoJFeEyR4ylSzjbGhVtyFbyEu7A41rT2r5EvasiSOFbOw65HYqWTGDmcMiZFV2oIKlqvgUYK15aaSTbbNuvwLK7PGMxFuxm7qQEXGtfAyhDJ/h6sk+e2glaaf5aEGJo+zGKPW5vJZ2RcAChzxo17u7bl88+r07hIB6UXnudY11k7YtHZ/bUBMoR6736dpopFvyNMVjcY/FfFx+WNlTNaSxxoGNNSaebaO70dGNgkfhnO2cLdJ2zr7uePR7d/jtl94HvknSsXL2R/7o4/DGl9ybg1qcvSaOopEMjARlrpeZflkFkOFFqIgYaC4uX8yAbs2cFvaqrrn0y+1ZRDtD1nNyMp053Z60Wrbn5IM26p/bkrwa5Yt0eFdiUe5SWfNCcMIERL2x6yYJk98zKW4jM8DSJxZEVHfjacQYZNkX4kaSbW9P3iPeuytnPVPZfVa8lBRizePSMD5alpfiJErPeSeI3XKye+7yJcpl255G/TDJn0CkLcq15cLiJeJowznbOVuKO2evjx7efihy9htfcu9izl4Dx9FIprGSKOaGuiZvkDn0QiVCubtTmjUs5Lq3NZXHwh4As9utkGFL+Zjehw1AYYZgtaV/UCPXp+ZJiN6Hlp6WwPS4GGgQsrTFj+tutSmb6jnpW5Ia5qsuQoS6LAPT3CHaptJxwc9lPcTbdDHx3kiiTaRwrUG2j7wvviEDsJEvuAAAhI2ojdZ9QuyqzPFd2uY0IOT0smy63ikgANc2MQWKXXIB1YDr3ABOCYvnNYARviHnaMM5W8g6ZztnrwTekPu0r7odv/Jd9VrJNxNnr4njaCRjLF/dEBbnmB7AHNc7mY+nZZCt9TVb6ROmLjyNaKXsXLhFtCyvZhdfQ9eUIZSTOxSdSk+QJvELpmbsgPMtEOI1NcevScRnZSAqCZmmh8jyUKRz/gWt2U+7RfHlgzTbOThMD1ivVxa4vmTbSuvkLJHVhEc9sCu74sCOWdjY8BkLLT0Uxbqp4ph7NLh3YavocPvpRZgUrj6M8kvuliv22y6nwdPm+eL3RfGGZnlxdME5e17XlHHOds7uSOvu/+UBPP9rbs/nn/Y/347/8i333XycvSKOs5FsrokcyU2SoUKOqkfhhJqTQnKYXDdTkyMChg6ibaybmQ9nZjpTlGmOTZPnloxCDIWORs5WIq309jwPAbFLdl61+NKXQuzBt7p31HN2zEk5FLJUkC6Pg2JnCfYi23P0eKQyPOz9IW9HKus085JS/mLdTPFSk/W2zXo66Zp5jEZPQ0CIK1SkzT6ql0I6ZmmTljYvT3px5vKy8cmORXDO1tNuyjhnO2cvNE80cvZvv+z+XO6birNXhOwFqUBEP0hE7yGiP2JhjyGiu4joLfH30TGciOh7ieitRPQHRPTs3oxU5LmV4aPrneIFK/624pzdCJR1x0DaGOnxMChhSc6wxeVUm1Y4OwZGouWeDknikogKW9sOmVwn9Z9Mp7Ijdba6HU2/Fz36Z4Zs9XKI51sZLyql0FfC9bTYfaDlIdpZUjd7eyOqB0L/21JZFz1/D/+bgIenWfWx3KnMOe10LtLicpQeXKZT5F0cZ/nWtUt/w+iFuPbwAcNpwHAtFLJneUZ/X9pFPGJZRBzP3zHievH2ojzxP+fs8dw5uy44nLP35eznf83tuOcV99/0nL0mZhvJAH4YwGeIsJcCeE0I4U4Ar4nnAPCZAO6Mfy8B8P09mSgeZrC/7XRjc7IqflP4djov6jHdIDwdJb1KhtuTD5iwxeV4PKQtJS0AmWQ1opUPKIl4mfasjHiqNRJt2dHiWvdl78NtkdBSvSp8Q2N3nkKOWiGrcKazYeHafSHl53Z15nlZ2njt/duyvyW4dDng0mVOtGDH0zNZeFiLG66sqzGe1HD9IcRUrywPRAAN4/nVh1H+25wG3CKIttQ1HiBZN8Tyycqm6ioiR4Qfxjnz9lLkKk2Xwjm7qBtTxjnbObsDly4H3POt9+dyHSNnP+P7PuT6cvYKmB1uEUJ4HRE9TQS/CMAnx+MfAfBaAF8bw18Zxr7Ie4joDiJ6QgjhXT2ZkWXUJnpMcYpOMYGDhC2WzsxanNyeOhtbscXjVVvaMe+e08aPSb0F629qMlmOgJPbgNO/nbdh2ZmV2eM8d5X1lC3+qrOjRRwIeXwaMG13yu+hnvFtSZ6P76KY75MYueMdTefQ9dPbTad6ODrysrkS8lgyXs4tie65kJ6LsrykyKV6TfXEd7nidV+VkwDeLbeN9q7eOgpvr0bREIpxhMV1R7l0kbrDFq8b0R2cNg0JSlzP2p43CteTt3vhnK3ECzhnswDn7AvH2W/4yvcBp9eBs1fEvmOSH88I9N0AHh+PnwTg7UzuHTGsIlsieglGrwVuf8KTRQNYEJyc5ayRbUtfkzfGnZWkSdVDqMop8U0ZOXbN0Fdtz5CRSbIC44QG/W6yvANN5jOQnyX+IBgovlLnkmBEW8VLElbGt1nbnfaNb2NLCXHTzC4n9DkMSx7qDptLH+oQgJNrI3GFlAZ7mWTiZHGcdCWJqdcjXSeuAxaeTBovqXDrgGsAhmsBm1OuEEmcjUmTpF9mvxxPvOX3CCtAlpNlRyl/gocUDuJtztn7wjnbOds5u4Zz9sqcvSIOnrgXQghEcvueLr0fAPADAPDEZ/2DvFiORpYUczq7jnJcRL3aaISlW5GwRbTpuLWtaToQW4aqBLwFaKcTLZfRlvOZ80AU8Wk9S9QYEtGHSbba6rSRrhovCUnK5MRFWlUhpkNpa0dsFyUlb/mZUTwU8lybEMJJcjKmL2BffcQqD3UigTG+/Wjk7sAVsNnjC3p7TZxXhFp7bFIyaZmkgnTD1J1nrZ05Rpde2K1II+lfix6IS9cC0jwS7QUgJ28k0tW2j64merA0edglVq78MhCytNbFu87Yh7c5Zy/V/bbfH7uBnbOVeOds5+wFcM5mhbc4e0Xs20j+q9QdR0RPAPCeGP5OAE9hck+OYbPo8SSoxJl+5RJBij4PV2U40fI4w1Zlzwrndg0ZGdey3asPMJJV9ExissKVdT0zGclk5rY25SR4KsQMAjLrQxCtRcCcONN5Xi8yTEsRSeLVPBZVFuVXfA6z2bR30kcXaauZsjGcTsv6TIQayy9eebKuNRKG/IpX6kN2CfIv/1OwsXIBuHrLqDRcC7nrrWisyrJWb0J2zq5bYHFpEXr+oqxsCLLmcScrvSivI1bn7SVwznbOngyU8c7Z83DOXsDZK6Jn4p6GnwfwxfH4iwH8HAv/ojhb+rkAHlgyrk0jS/6HTR2WJ1DwMDlz2rKb7JEy65XrbXRbhb2NEk5i4ogmY9iV8bmOtm19YCTZ9MfrNssNLEykl8urhKfJFPyviGfpakRvgafV+9fSl+GaXBXPKpFPGuHhlTxqfdWm8reluhx2/ZD5t23EaRjOxj+zDEBZdtSTJDSdsdx6ncm6yHVErGwD4dqt49/ZlrA5w9RFx9IB1WmD2eLyJ1KOxxnhKexECdfuFdX+8eJceLsHxe3vnO2cbcQ5Z9dwzo5xRrjK2Sti1pNMRD+OcbLHY4noHQC+BcB3APgpIvoyAG8D8OIo/moAnwXgrQA+COBLezJBBPAVP9TfFG8sCF/9trYrncoWu9RsmSJtxVYRLi66JWPGAX2TQQQqcuvcgcl64AdtW9Ikz3TCKXs4lc+tKl+aR07TVdKWIrSbhOZ4i4bSpuQPotKDkY4HIvF1GyYdZpIIfP37qTvOcCZkL0Kwr0ELLW9G2b05Gh9CqL64kw0ezO2mXauSh6JRnCm9+H+UnbryqiKmcAKuXSLQtXESx+YM2RPAPRdaysnmBii8B6lLUFvIPictuhtzCtILQcjd7amrj6LwlskcI64Hby/KD5yzOZyz23DOds4+lLPXQs/qFv/UiHqBIhsAfPleOWGTMmpinM6JqFgQXj48hbwxIxrJjrBt2dFsVfGRvJsysZxy4XWZvtTT4iWZFWc9i9gnnpzxHrQIYZYsqkIZx3IL1A2qLSgBlKSpTKQJO9aQkXpUnpN1Lo75QzsQFd16KSpPCGFdg9o4ulS0KuMLMDeGjZerGkMb6t/8gjHihyQgyqXNpk4yEISWcIap/NduIQzXAobTMHafivoqL4E+iS5tbiI5Oc/gNrrzTvL1m8av5XdrYN6Mop7KxfWnSsZR4rrxdieS5xhwzlbjnbNrPeds5+x9OXtFHM+OezSVrSLOfB5JUkx0MOXFb2GDy0p7yoVvEu2cDEqY3g0lkMdnD8AWmZC0+0F6Dyy5YaBqDJqWBy2cj0kjwvx4NnHe4g3uDLD08zOhkHDyYOwEActlZrQHksvy4zQObgAXEDrQ7aQ0eh621lC2RRNGYh7GMWzsRSFJNZ02yFd+wcs0Kh0kuxTFxkKFWwi701FuOC1fXIVXgP2mMW/VzGVG8PLFUhBxkjXO82SUVBaej6qsrKEMRcZhwjkbztnJjnO2Ycg5e1XOXgnH00gGxm40Y5YzEfNEUCmryqff3IVHs7JaXJkHLreMaBvcU8eJr/Ri6RuRRjOsDipk+cumVzfHHXhDVvmVBD/3wgiTnBWXPC60C5lQcpcV/4pm50mfexc0T4Ps2qrIh4WpMIjVkpfddbMTeAVxSY+KzEf6kJcEusnhwjOgvfxQEkrK4m5DoxfjbCJC6WmoXrIKofJliPKMbghdRZZnsBirx2UZ6fL0pWeKiLBh19wbyn1wzkYF5+w6zjl7+nXOxv6cvSKOq5EM1N1tyYuQz5l8a1k4fkOckLokUEF6WrcbPybE5XdmiFau5SnLGe30LBvEiXYtkrXQiu9Ne5aEe99A2rm48bUXm5wZrclzEpXneckijTDZMSck3rWV7ElyVrvbOl9YVlfd3PXUvAt5Yf6Y3yKPStYk51RdaOKXaOqeu3ZCo+cBtYw2U7qIi5nY8rKzjGzLTBX3Bp9trQ6R0Bq2TFYdF6c0lNXliBxNOGc7Z0tR5+wJztkrcvaKOJpGMsCIMI8BozKcDLKUv+nm5/oG2WoPrkakh3ghWl/YJsmSHk/VgX5PWA9kDt8CdFU3QFSHpfAmd3SQaOtruiA0I06aLic96HF8LBx2YsF4g1QH68FLMiwseyhCYF/xLA89D61S5u6uOqO+1LSZh0F6IDQClURIvLIUXDsh4DRg2IXKjkasxW5OGokSe4Gl9Lm3gb1kc46KtAzSzRVV1gukrLTJ9Vcm44sMSSnO2TWcs52znbNX5OyVcBSNZGJ/AGYXmC9++YS/BjnKMXGqXWPyREHcyiSOVYm2Q1c713Tmwje3ALsrhjFj0fq5r+E5kLyICXyrWIXwC44UJFtliT2Eccv4inzlhBE5nk0SJrFj/gXf8lAgiK4iJf9qAaE/mObLSrsmYaqb1pi1nOUO8uWElhfzj6GnlwjDKXByFkpdDdweywsw5UPuqpTkR6+BTqLFGpoK6W61PFUvU2FbxKd8FR6VcyLniwTnbOdsbs85WxN2zl6Ns1fEUTSSAUZ6jQXmtWeVCGUXHgl9LQ1qxBUPvkLcLCMm0XIbKMEJq0myoguwkpmbDW3NNm6gxaUEIIjZzBUh97wVWnFKhVoeCikqJwIUh6G85iGU91nY6Vucto7Tw7jlRIXSQ6F+BaP90srL4yho6VX1RJMti0wLD4MlV5rMxTkFsNsCmzNCCOM6niNJNiacBGYolN1sRbgMQy3TWm2Ck7lmX2v8gmJ+OhrK0/O//u5OFxXO2XDOlnlzzhbCztmrcfaKOJ5GsraGZsf4telcIUcpqxChlDFt8XhOdrwM8kE34gbBGLMeCI1QheA+9wWR/RCraS5NhMufmlJtE8rLLZ1r3XZcNsWHIXbFASVxpvPUtZe6m2I4P5YeC06yRXrxYR4KhUYBWRm6dmFaQsYFuU5f+3IMH18jNGdbsZF0Tk+AkzNgsxvDSMgOgnRzmqhtTV6H+S68LUtDJVGWD0m6BJquxUzjtyBdWQ+8cpJdRxecs0tB5+w6WefsKT/O2Qdy9krYd8e9c0FFgkDeZa8I18hW242PFNmWPRK7LSnpcV0er8nIOL4rEN8hietZuqaMOLcDJ3tFuqT/VbZ2IgPaXwtzujO2tOCcV0NPKw8/34hzvutUIcdsq/Uk4nhe5G5XVsE2shxWfS6oNy1/smwgdt9TQ5aA3QY4G4BLu9Ju9YvphaPt/JTJU4QTUb1Jh8yTlW/0yRcyShqlfim/tXQds3DOrsMKGM+8c3Z57pw9xjlnW+mNB29/yb1YC8fjSYZ9/fhOTEXdMnIEwCb8lfqazVFftyO7pVRdo3uO28BOzHZGicXnrYdQC1LCi4eegDM0vpqVgpEVP3cu47SuxYY8ofzAt0TlOvtZTwm3zoeBinU7U1xQ5HncRoRVX6Ch7q4FyvFyQOz20zJpQcuYkj+pUz8nU0CILoxdvEYhBFUnfflXi8uHcrxfug5gcumwzO8UauU5VGG2ByFZO8nJUlQr5VUiPIeuu5sV+XlxztYFU5BztnO2IpICnLMnXC/OPu5GMr+4vWPYmFxLRls9ozgeDNIlRVY559uEtoizSarGTk+WsiWmfg0XAijIj6qDtp61zeluF5pboFbPyDDpadDqTY7r0rIs9fjEDohz2a01xJ3C5Bg4ThyJCCSpJPmi24qBb3XK0bpeO1lgxS7AliFiebFmTnOZM3bxNzEuMFIzl0ZSutTSovjqBI/cZacRsZjJzcuolSXEGdcIancccb0UjlquOsaUF/X+4LYcJr77TQ84ZxvKztnO2dm2c/a6nL0SjqqRXPxSHd41hk2EazJgtlR55cFeRLQpvDFRo0m0PH6G9LTonAft2RQV0+LitJj5QFTsGFWgcS8WxCFIvQX+suLqCcQIWeu5sSaOBPaQAyge+nROZKy9mXaGimPgCpJGqV/pijoOoXOrU6UcFhknIpZdX/IFIF8KoPEW3W3HiRxF2pKsUerl+mLEnNLdFDJi4XelfpqkC1RrYWr1XOSPHW+lHhiRWqTL6pBA2LYayo4mLK51zlby4JxdyDlnO2fvy9lr4SgayYR54sxj2OQkDo0cK10mk4hWmchhkWrdxYHKRkG0iq4ap2wL2nNps00jfVW2E4WdM/0Bl6StHp9BqbAF55wwpJgo64DSk6F6IVCSs+zOk2tsco9CccwmjAxMVpsUoj7E2H+JIWknYQNgo1ynal1NWTYAYQMMu/GPyxRdcflF1F6Yvsi6ING5FSM4cUvSzXUxQ7omiWp6TP5E3msK8aoe5SS7Hh9fSDT5uEfGObsJ52w4Zztnl3W9IicfRSM5V5i4YSciJCPckFe8AT1eaB6W7eyUcHZsEi1KVOdGmlagRpwDkdolRtWBYZbsbjfSXv5Lbjxj69Sl0F52nDQT8uSNFCc9F9ETEFjYKCiNlsfSY5EInAaaZlYrX/zFlzqzb3XXWS/GioiZXOHZ0F5MNH3ZJ1tnVL5AuGemp4dKzmjmxFxUqeJt6FpaTSFd9BI1ZkgX9TGxi5SIuEiDnfMXQCHrmIVzdkzbOTvDObvWdc4W9lAfd3P2SjiORjJQjEubiJDEOYqxyUWc/G0QrSqnxLWOp+ViGvIzpFk9YxpBijCr68biwhZHFnXQQaY9L4buuH10FZKSEygygaSuthR+FnSz7Ppr49ysbU9DGEl+J5YgMj0UYEsaWeUzyigxaARg1Fdx/zMZbfemdL4V4fIFUi39I39R20znJ0TjYvYLSHeLeY8Gf7HNdsvxa4zyRaCR7kmhp8g6mpgbc+yc3RfO45yznbOds2c4eyUcTyMZEDsx0RQOQYzKsItKdgPQjtoyaTKIiOPpyQXiB3kDN3aFyvpiXBeZJ3qQSbIdBD0Xr9po5G3OtvyyJa3yG+fNL2OFxGYJKijhKUyY4PmX3gigJieAeUMaHgoEe7vSltdB5re1JufSrr9EmpJcySBKSaCtbVLl2phSZlBIdyuJThB4T9cf10+kW+wCJS44sbyapAtNT4zXczThnG2k0whrxTtnO2c7Z3dy9go4rkYyUDWOx7BJRiVPKZcOLGIWD65Fljy8ItoZ3SoObWjxcjKERaYtkp2L63nJNwm4ReB73KikXRR2OkdQJGSmFydlzwRoIq/08crLyG1UJKx84SL0eSiyjlZeq3wx66VQLaNdxyYJR5KBIM1y8kabdE8s0oWt0yLdyiNQkepM1x9PF1P5qusF5dwiXWlby4ujCedsRdc5uzh1zrZtOWeLelzC2SvgaBrJQKygwpscf6H8Cm+BJNsWmRZhypI9FdFm27qMFS7jNJAYB6ZN5ljiOSDzxCD1S8DuajutFlrpHXLO7/FiljSJuk/yCslmvRhX1G0c/8a9D9ye5pXgE0XSMSdUy0ORJovIMmqFlfU/iPgeG5YtgNVTJlfbuzBHupmkpD5QkyLTaRHzXJgk3S2Lzy9KSaL5jcns8nqzSB2x204jbC7rmIVztnO2VHHOroOcs1fm7BVwFI1kwrgLS75BjO2oK5JT1k6WOl2LzCtEXHghrEXo08lc950CHq+SbHVgX/el4TKeDOGqDCveeBXkjPHWSwz1F7e8hkU8xZ2aWDifbR2YN6EaO2Y0kAoSkWEDTTY1op0j0CDm5PQQrGJDA/eyFCSWJov0EGUVb6yRKWTlTGi5FWpFmlaYtA9DFix/0psBtoOetInJFretHjtmUTRinLP3CpfxztnO2c7Z9XHB2SvhKBrJQP3AkCAxMuTGMCplhGwlL+OZh2NpF11FBtrDYSwwzyeSaLaWhJlpd8Z3eSPiupmFqFaxZiKN81Zc44u7EAtlvEa+XC+FbyP57nblrOIsFw80Mkj5k1/vidBD3P1JvgAqxPi9x8HNxTMZ9SXR8E5Ua2rOkK5aT9ovxmdgmCNdlPVbTPJQGq1JtlxrU1m4Hoq+tG/JYZJ1tOGc7ZwNOGc7Z19nzl4Jx9FIZg9H8dsaepEC1FUxynOzm49lIZHfXiSrBUpZKtORNi3bDdOjfstGZ57yV6dUWXDDqXlZci7iCn4ScVKNjz+zTFZFCajIV+7UpC39o3k/NiKMxyUyx46XiGUjEa1V15IkDX3zWhlEr5HolnsnhGpST/JbNX5iLsGBTRTbjjLSBcqZ8Dx9AsU8KCSaTi3vxII8FSVQ0gHsa+MY4Zwt8uSc7ZzNEzX0pYxzdl+e+krQj+NoJKO+WYsweUNLL4S2xqZmTyHNTIBGF59lqzpXFrpPmJvMoZLswpdxixvneNOyq4bzsB3mje+JJV13Sbbo7pohyaJs/Jx5FPgYOK2rMNnhRMAf8vQOCtwmUK0HykllqfdBXqNu/ZjXyptC9ZakuVwQ9STjaSTyoNjXlijK+WH2i3jVY6DkN5Gu1Ed9XIx34/LK8ZaZteyd1/1/0eCcrcTZUc7Zztm1vnN2Ka8cF5y9Eo6mkQzUxEYEdQybSobKA1r8xkXmK6I17FXHFqE2yFOOW5sjWpVk2eL4Ld05O634YOl03G3NtJpvqEYcI/KKQES6nESlPSuu6LoqjExxnCTDLmSvgUb0nFgKOUlqSS/azbO1jZ2nrHJNkajA9dW6U4hOI91RX4x542kaumO9l11rZMmirWfLGaTLyrVpEDARYSPkrWO+LrImlyehOEwQlYNSnLOVOOds52xNl0zGscUAACAASURBVOs7Z5f1YBxnzl4JR9NIrkiSP1DK+pkV0WpbVnP77CR30xnxWnjFFYY8YOzo1JDXSFXjJouvlhJst925wBm7a0B2xxUItpw21q0iYIVE0sPMvQ0kuvRk2gWxACq5yGvAJ5tYHouU96LIMt0isjyd1ZX5EyRHNI09C5LAUOrW3gudPAtZiIkhQo/vylTnrQ6TL84g9RovWvM45UnzfHAbDhX/9k8/4JythTtnO2fLPPXoOmeXtrXjmKe1cHyNZIXgerellsdcBgCGLVWehYJolS7AyuZSok3ncQKFFW+GGdeaZGVop4buQDTmJfZ17SgsJs9BY0Jlu9UC/IFn6c/CGBsGmQWDgOXXOR9LZnXj8TFzOZxP7IgyedtUhRj49p88fwOXl/kWnqwWAe/rsSh2pLLIUBCgSmAQxyjDZkkXNQGrejwdjagJ4FtGF+kYee7Z4YnXpeb5sOrZMcE5Wwl3zlbtO2ejgnP2ZGspZ6+Fo2gkWwRaNI6VSXyFbJSRy/oAjW46jbAbhCq7/wr7O11n9lwhut4wM59a/hZiINIJ8QY0CtKLbMA4m5mPB5PL7mjbf+buNALSuyU9m2k2rfzqlt4HThLbuFxQ7pJiolpXFn/Q+YL4PN8ZIv+9Hotkz9zhSdoV+dywcpsehlQGWa5ob1DK3SRdKGli0oNGiBoB83wmj2+DrK1ycfliGIW0xfPjaEJyexEGOGcbcM4ef52zS13n7AWcvRKOopEMoPiKNNfPRE2SBVkKGaDdTafpymMY4RWJMa/DPqRqeh8Ug63rPzTfGA2d3puqVVFzNvbQHeTvIBbdYiQkv/Y18s3JKYSaz0l8ucdw6aHga3UiTGSXuUIQyYblx/QuNIhSkm9zXU5ZdoXUrZeDSYAI+svEIuv4uzVIN+eL67KwgeKanBA2gTp9Vq4tC88vVynLytUac8zPpSdj6w3lLjhnO2c7ZztnX3fOXgnH00hOv4Igi2e0Z5H56DlQiRaoPAtVvOhikzKSaCvibMV1EqcW3k2yvQb3kZeTUZS6Ksy0SDUeW5M8NuLcyhLvLk1eCzP9aCc/hNxwmAhbdtvx7j1OpDTQlCYnEaabzTce4iXdcbleRBffTnZvtghDvESapAsUZSMh10u6WnfcVtON+Upx2laoLSKldAFbsrwe9m0oQ7HnqOCcrcM5m2XHOVvVU+Ocs/s5eyUcTyNZG3smf8VNrMkACinyY6rDyRAubKYb3Bjywa/PHLH2EqrFo8UM7NYD2rhhCtuXgHDFlm3mpzO9WZvCDidF2YPYfPko25i20uUPYzqWHos8Ti3pCUIaBsqL2vMuNJ76lsVVhegg32rBelE0Xu5u8mVl0ciTl5s3EM3uySWkC12X58sK27JrUREpy6d8USTZTHpWGvJYnFcEfQ7EfFHgnC3yAjhnCzhnO2efC2evhONoJKebX9sqNP0aMhopFovQC30rHYtoC7tA9mpIuSqfqFERryKkh5FJvmZi/dG2rFTsvAGpOlDODWLBzAYC6Tzp8LkkO0xENwDVlzsAECcjTqLxXHbhmcdhGjeHEO8RMZOaAATNtiyzQYgbI7ylA3SSLyOWvE5mireIEOXi9QeRrpYWdD1tK9RUBq2bcbRTk3vlacFkj5P0loVniDROeEPZ0YRzdofhZdG2rHO2feycfXNx9ko4jkYyxrIlQpudoMd+tdnJfMZzsqM+6xbJboAh1HZbxymgiBcCVleSNFZ1xXWQbe+9QYTuBeWbXW/ot9OVDmG8Zkp5MoFifGB2KLm0yEL5MVp4NALK7Uz59bLGssluuzyhBIz4KRI9m0mdCSblQRRI1m32ZhjhzZdfI06u+5oJuCIclh4jTZlUIk0eE1B3tSZ9bZcodbJG43p2ky7YtqYoSbSyrbxE1dnTSl3xelhzPc6LiMzr7Nc5e16kyoNztnO2c/Zyzl4BR9VILn7JCAfyjOjCW6Dop4dF2kCyoXgXBnaX9RJtTkuMvzPla5HFs5lnxXcdMnP2Gu9/1fRcQa1KTMTNiM1MV3vBhDoeGImO2yqucxyblmYfp/ukIFVOjNqxEpbGvUEZ81ZlhMVZHoilnoy5uIG/cJKsINlcB1beRXjV9dewy0kXGunKtNnxQNMaoCrpApU92Y1XdIEapAtB0i0P1ZrrcV5E5MfaOds5mwc6Z+v2lTjn7FKvm7NXwlE0ktmzNl68LdTuufTLl7rRyJQAYBjJj0ScTDehWHKIdJmWl6HHkSDDCpLtuKgtAp31ILSidsoz26q4NaG9oGjqhsth7FgSclX2HsJK8emlzYg36RMBpDz4kiB4GFGcoc3smi8QWra80Jrkm8bkVbLsZWKRJSfNoFYqKuJT7TRkqziINA1S1uyo4+osPU0+6VhE7TDhnL0gzjm7inPOng6dsw09TX5FHEUjOcHyHqfjghRb45c704G0uQ/RStsz5zLNOVjER9VBw0Y60GY1J8/MgpuLrIpunctuPkLRvSrl5zwTRVIGyZCww8k0x6dj2e0W7fJuO9Bkc8PJI+VBIw0IGwzFC8WQmSNfU16rPxGXSbeDAPOLxCBdi5Qt0t0SEGAsM6TVKeo0pdxW6mhELevBsFG9TFg+tiJPYoErB4NztmLXOds5W5N3zl6Xs1fC0TSSqwayINS8PJBFivKXyvqUunydSdWmsXTRqAy1i64ojzgfBmp/MSp5BGCu48njCv2ZfMm0AvudtbOkLbAgHxrkOK/iOrLMyrFjKskyPUlU1TsidbvxyEQ47JiTMVkEE+3x7sEQlLFgPP3WS0ch04M8FWFaZL+XdDVStSaGbBp2VA+AQbBanlqLyreImsC8RJYeWBpJQHsRaHXrqOCcXccV+s7ZztmyYM7Zh3P2SjieRrL45ceygVyQ4pmiJ+VYmGbPSndpnHZeDMJnY+oqHY1866AJC7wJphdhp9fV3vZ6K+qsQ6Zxn8vr1uzKE+QUUBIv2DObTs0xYPy4IA2FiLht5vFozn5ulFMl00a5u8g3EZEg3TQGTO+us8I7vRMiv4GT5wwBqmki2HLCzjaJpgZGjx6Uc3nsMOGczeCcnVWcszvlpY5zdj9nr4SjaSQDU9nT78DXTib9eS7qSD7AyRsdw6utToV3oZc/tK68PGFAzLK2YEmY4XPMbsm10FhYXrXTsn2gF6IrfUB9CPL1ReNLnulmUuDx8bzYPlUsPJ/JXSGD7HEQtvkLofB4KGm3oHbVNci7t2sv37uad4LryBdXg3TbBZE6JeluFJmkt1HSrPI3Q9TmZiCGXvRj6DblsaOCc/a8oHO2jKx1nbNR1YVztq6XOXslHE0jmVDeP9lzMLfbUvRMVCSI6QukIlpxfAjRyuNB6wcz7Fl2i/AZAu3lV1Vu1xCYe25k3pYQ/UzFN59ZqpPVuur48kP5nD1MG5GW9FJwG3zCBH+5yi4g2aUnbfPJIYCxtM8Meol0H3lJuq0XU2FHkC4QyjoSMlWXnsiv6eFR9JqL3Sv5Szopj1xPjjXWPDhbGbfkvr9J4Zw9b69bzjnbOds5O+s1OXslHE0jmZdtQ6Q+y9pzSjKgJSfjDT0Zp8qxsLlJHYtJttPGIrmFXoPFXoledORD9hoU62YqDwHvfrS68XgcsYeJaBq3ls61NLas+00Sq0UGfOH6KROsXFoXIYSOAbML0CDGs8bLjJdZLoVU1YcIt7wIW6kvZcQ1SJ4JaN1/Rhqc5JeOdZPlNgkegLoW54KX5M0M5+x5OGfPxzlnl3DOFrIoj9ecTH00jWTCVNZdCJMnGVPZLQKVYQUBsskcJqFa4WJdTn499iZZi+QVhZ7LXGRDzjxuycoETgCcsvOOl/9gVSJQsuRCVMvcMFRl6CDYSpeRpfbVrXkoso2BxqWH4g2RvB2t8W3gpK7YrohX5EdOGqmypeVXhG1E+BnKmc+SdFXvhCAw/uIqspMZtK2f88Nk1HFyUOwAIi/xwIiXYcV2rVIW4hgGqa/HwxcWztmGzQTnbOdsI8w5uwxbytlrYfaxIKKnENGvEdEbiegNRPQ/xvDHENFdRPSW+PvoGE5E9L1E9FYi+gMienZPRjiRDdGTTCIuYKqDoi5YKapJfoTSFpUPJW2McCVvxPJnloNq7sm2xVg6jf/IiiP2F8r8qnlQ/pYglbP1txidnpFhIPWvkgOKCqu8RzFMzrrmlVvVjYhTgvOkDim7kTrWjcTzzcvDyrlJf8ZLWq39uZuKocgre1YSMcsyboUs19HDaV5OhG2FLq/LrbQjbG1lWEc8aRdY5oudE3+497j9rxeuF2f3wDl74uzP+rsPw2f93YfZeXDOds7mYc7ZVfxSzl4DPZ7kUwBfFUL4PSJ6JIDfJaK7AHwJgNeEEL6DiF4K4KUAvhbAZwK4M/59PIDvj78mEpGlY/4LoFoOTiMjRBvFdebvtPoZmY41kmTHsx4IHm2Mtat0eu0ptkwnlmF0CEoBNXl+rn5tshNtDU3LltidqUeHUHsV0qSMfJ7M78JEFOI6V+PXgLoCpSciEk8IpR5fxigTUvIkFF095dJDxVg7ng7LaEovlTNnrdGtJ6svZ8+6jpoNKj0GqbzaxJCWd6I5KYTJFet2otaRuprXQPUkEMptUJX4CsybUU0w4XWXXghhrLBqIt/x4dw5uxfO2dNt9Utv+GC3Ueds52zThnM2ejl7Dcx6kkMI7woh/F48/gCANwF4EoAXAfiRKPYjAD47Hr8IwCvDiHsA3EFET2gmIh4STpLZq7AxnllGtmMeFTtC1zqW562vb9pM+dPyo9k2w5hnWCNrQp1nDYu8B8auSebfOXRjWEg3Za93ZRho7FKLfxyaHvdSaJ6ETNpUEqa8Tzdg5Ki9fMRv9SKlMS/8ZVFdf6VM6k1kBRuyPLzyGIj01TIQG9vWDLf1rXqqdDUZI2zg6Vn2hb7pIdbIoSV/JLgunN0J5+yyXBLO2c7ZztnnyNkrYNGYZCJ6GoB/AOC3ADw+hPCuGPVuAI+Px08C8Ham9o4Y9i4WBiJ6CYCXAMCHPPkpZf3M1LOUGYiqheQ1nao8htwSL4R1L1vyapggs55rXOWxc3LFokRaNoybN+dl5sFo6RBqj4SWh6QuZTfaVz3T08awJWKtJgXEuOwxiOE86wMb8xakTrKT9KLiIL0F3ONBdbmK3aW4HiuDYa4py/MlvRPWMkhreCfUyRfab6oPJcwaUzhQ9E5o9mVdyPCWV8KSP2KcF2fvl5fp2DkbztkMztnO2efC2Suge6g+ET0CwE8D+MoQwvt5XBhntCx6XYQQfiCE8JwQwnMe+SGPLcaZAciN5vRX5iVmnn11y2faet6tZz9B/aqJaRZfrIYNMuSlHaljlXXp2DLNm2B9zZu6QbHTsrHyeptFXjrSb8VvlK/6YklU5TprcYV9JZ2UhvRqaOPIinF5Rj6qNFk6PV4K6/60I5i3huUfqCeQVPYUnS4w3Y04zyJEZZyS1laJ48dz8SkdNT7ZEPmjRQW9MThPzl6el/H3ZufsT3/mbXX6ztkFnLNlRq0I52w1fmVq7mokE9EJRrL90RDCf4zBf5W65OLve2L4OwE8hak/OYbZ9tPvRpxLuU1JtklGkpVKsKykkhSTvbztqXLjq/m10rcIlZQw1MgTH7QF7tmuTd2EKGAR6hJY6bfIuuevqouZdFv5KsIFUVUyFrliCk9xMoynkfNs3EPqhJQbTbwNIs08ZHXhWaiI2NDvyEPbri4/iPQqXXa8kXnU9JR8Fl1+R4bz5uwe/Ni7/sY5G8ic/enPvA13velB5+xGfBHunG1HOGeXebT0VkDP6hYE4N8BeFMI4btY1M8D+OJ4/MUAfo6Ff1GcMf1cAA+wLj47HeVPxgPt1S9omCFdfiyJ1soP6XkrrodCAqqcUbbWjOCKlNhLx8JSUlPLzf924nzfLuaOT7K5PO8wOUF2GD0M6S/FnQpbHNJLoZErH18nx7alcDkuLsfx6ycudr43tOswR8SN9FTinTdXymrEJ8lNjuUzfi0y3Wok2JGfymPQyis7Vpe7mtGpZJfIHwmuF2fP5iP+OmePv3e96cEqz6aOc3aGc7aRrnO2LrsyH/eMSf5EAF8I4A+J6Pdj2NcD+A4AP0VEXwbgbQBeHONeDeCzALwVwAcBfGlPRnIZ40oWWlzaGanj3qgIUTvOF4StrSlttLjFIi/rOnIUxGqNy+sgx9mEOrGPepcOHy/Eldh4ttZYth1G0pN1vQu6x4LHZ/30AKb8ANPamRFya9JibFXMY7HjU5Qhql9AeYZxDhhlB3YsbWc5lkctrNJppSlt2cHZdrUgvChDwkbKit/KVg6fxroR2jbKuirHyBX50Y5TnVM8MMbCSZ1i4xBrDKKQP0JcF87ugXP2hBc+4zb8Cm8oO2c7Zztnnx9nr4TZRnII4fUsixIvUOQDgC9fmhH1iyv+FutoNpaDU731PCzeBBv5FafZSr8D6skl8iFo2OHQ1o1syffGmzpLxp3xF85cgfa9EY38EJVp8ORCmNQGoUNMhqPqOuM8xK6dnFiRSYLrc6KTx4xcUj42KUosxWMShExXSdvMjyj70okiOViUzVxEnpdLGrOIegZmekp9FRt6RBTbpaLWTdfDzGOL3DUZJY1jw/Xi7Dnk5d2cswGgbCBbOs7ZUUCkFcOcs52zuzl7JRywx875IS3/AygLzaMm26LLzFhoHkx2Jy6atKnapdqm4IkqrQS1Sy79acv6NOxXHgzCOKaspdPQr2zN3VxSf40JIB15auVtTkYLLzxVrPtL68pTj5Uweb9tWVdXNfFDvmS0vMfzgf9Reb6hckmiVB41n0YwoIy7i5HqAvasriSsJYYKfVFR1aL3Wga169CKa6TH4+0JJpTrbGvImHl2AHDOznDOXizjnF2nJ7PvnK3ocM5eCUezLXVCKjsfmyLrK28uQrWeJs9hrqEpz5kN9UOrY+kirXtu5plV7ZsE0Iku/fRAynSXLECvnWtf1q1jqSPNMxLKS/wYMiGUcUXXW5STX/XEPBQkvor5ceEV0OLj6TAQdrtQpqXIyzwW8UDttZB1RBgXV0+I996p5UHQwMpWdQ1SWdbknZjzKljxmoehyqOS13278KptpdHQl+laMoBdlw4Aztm2cBvO2SOcsw1dEeecLdLd45mzcDSN5HyDJs8xG3NGUH5Jj5PH3KY1jq3Ki7RN87wC6F1zTYK1ugQtxZ0i15LtvVF4nfAGQCdyfpQ092lDBKpJtFgPU6bL5UIZz0XSmDiicncmvrsS7/7ipMrJOl/mUI7zyjswiQd2iGtWSpIu5AH9IWcvh6zL47meErZl9+RuF8ZLLeSKatSIUuQtdZctId1Bi7fSY7/FC0iSJ5eFcSz1ELp1CA35PZ6Tmw0E52znbCNdLuecXYQ5Zwu9fTl7JRzNcAtr/UztD8qxDON2JQpdYgTLjjVZ7Vyb4SzzaoXxNIt0d7qe2r2jdXuxj4uuP5EH2RU292diJ2SNNLtsyXxaslZFow6XaRbHYja1dpxf+ko8f/cOij25JauWv54883zMhaUtYocZOa1c2jmAuhtvwe+iJYZEmLlGJju21vGcPbbqVyMdhwn5KGrVp93yztnT36c+6zbn7Ab/OWeXYc7ZxvkBOIpGskmireWBhpo4OFrLBOVjds2Kh0axJ8NaY9aqNBvbiWpQy6R8Gank2ciHSs6tL/1zWHB+Dj0ETPygRdQN4t1ZRCtIt1hCRyOiBunKtK01OVUCnXno99EBWAMB08NvzE0q82mRIsOmDpqFXGJIJV2DiIv0WsRZ1DXpcgYxn3QQu0PHQ4mzX/j02/DCp08bfSzl7Bd81G11HgLwqR9dbh6ylLN/7Q+VyX7O2c7ZztnznL0Sjm64hVHu2TiOYUPN8Wfae6/Lbs8SQA391rXLUUZDVlU9gBBzXhrdEmqakpBbldZTKTHcHOqk6fBuMSFHmGzx9TK1rr9RWKTDuvOS/IbPDqZJphr/JuxpZSq2C1XSb45jE+fdOkB1ndO4O/Mrmdux8pHqwpoV3vnbHOtmlQtMT8urIl+kh1COB2yUuRobZ9WLo8Kxc/YLP/w23PVnD+KuP3vwIM7+1TeLxmy8LX/tj0W4c7Zzdo8OUF1n5+xlnL0WjsKTnKA1hrUwGZegeSIKG4RqV78sM+h2tXRk3Jy89oUtF3uvbBP7M9JXZYM4N8JNW408NRsEczOo+blGRI28WfVpei2M+BTGb3rZxSbl87HiUeDx2Y5IU85Alt14srJnvQ3KxTmkK2+RTuu+kYvWMx1ttnUrvSS7beUpy7J0NdutdHt05sLX4+ILh4cCZ9/1tgeds3vOnbOZ4VLHOfuIOXsFHE0j2aoXvhxcVTcx911Ea1yX1vswnVvj1+R5EaY89N0Eq5GORqIz5DmLA7waqc7z32D/LcWS8nE57WZu1eUUgOJhL66ZQrqm/Xg8UBmn5qFRL2q5Z85bZWqFdZNu/N2QHm7qzUEjToi6M8lhJt198mrIzo6nc6hwzm5z9id/zDgc45OfeRs++ZnTsQnn7BgA52wtDR52k3P2WjiqRnLxp5Ckdg+pY9iUh6eHaGUavUTL0+0l2VmC5X/axdfGzMmtSNOf5alQ/lrEyQnWzLCClp0BNTFr3oH0x7/yLTkZt7HquEFic6Q7GPHWQ669EFreibn8qec9OkqYRrpdY9VYGTfcTqMO2vENlmsQoaZXvRiErWaj16hDdWyclYbjpuPsT7mTTbLr5Oy73zh6su9+44M57bvf+KBztnN2M8w5eyaNFTn5OBrJ8jrJ67+py6xOwkgPJlB00WnkKtPjabaIViPQfUhWgoCikZsRhEzjbxFuwASPOfR6MeY8Fla8+kKUcowYyToWxKJtwcrjK8LhInyiCddh6ao2+XmPzoyd5lJYHeVo2VF1qUHqLbKMkISaF5K39JWwoSIaRadlKx/7wGQNNxtnv/YtcfzxnpydGsomnLOLsCnAObsScc5eDcc3cY/EuZCrLqhYpL75LjPSsmxb+pquJpPlOmVV+9fz/SvHoJGIsx7aIH6BOItC0U3HrckniodiJxdYT7KM9NRJFyKtgkBZeF47EyJ/7JiYTJpEIePT2pKtSS1anLrET2if8+1fZZ2q6ch6t+4x7fpQufB9tp9kNduBbUFqQehr62kSjLS0tI28N+V64yHyh5my3cT42Xv/Fjgbj52zzxHO2TESxvPqnF3Zv1k4eyUchSeZgNFbLEhTltP6ctL0Zo+ZKblGs6WT9EwPxK6UIUJBYtK2tDn3tZ3zC6VbTQtL4ST+ghJGC8eicXI2XipNLHwR9YyZMz0+Vp2KPKhdcEJOeq9U2SjHJ4xoXX0bIC/rU3knpF3lPKXBtz+V8RUa1ymVp9imtEffemBluFKHFqTHgpbaMNJOx8k7kD0T2rWvHv6UNtWyjgKf/diHA3DOzvndg7Of/6zbnLNn8uCc7Zxd6cTj+19+/1yWu3BUnmTrug0Ua0jZJtSqJzU+nWyAIZAqo573Pgcd705NFkAuWzV2TDN0iKfC6rJLNgeMy+QEEacUurkCDPtS57qFisjL3BdbMcN5oFKeeS2qPe25V4FnR/nq13ZpylulEpCWEkq6W+6dSDaZnPXlnndAklmJiRbLF8m8Cu9AyiPASDd6LGS8aTOeDwNVyx3lJEU5Uvnk2pfZYyPCpW7OQxUXDRvpFXXAZAjG9qf8F/XxQISd9A4TsNW8Qlrajgo//94PjgfO2SP2uE9+/Y2Xi3RMm87Z46FztnP2RfUkA7FMQ1k2awZ0+s3HrU1HgOKrVPNAQNGRetQhPxcmH3TNM9CEZryFdGP1/HF0jn0rPClBnKe647bkbk5SVmBoZJPfuAToX/VJh2odAAgynL8wjWNQ6W0Apq95rftNfk1brYHqnml5KJRrVtUflR6LJR6K1ixuqVuVL0L12DTsyF91koZUVdKu9ObKzXhBzZN1vTry5xjhnN0WKeCc7ZwN52wzTXbcxdkr4GgayYB4oJQ7pEmqWjwbwiEJzbp/JQFYJKsR85wcgGKmsImkKAkTaG5pWmCJ56JFsJqdc5hAkkjh0HeORbxSUS5oX8gpcZJ0pawkmEEe8/M1SFc5b5XFrF8jLzKMWjJG3HZm5nSlZ5FuERa7vyThs7CtdhPNvPCacobemgvWX1Q4Z6Piy+d91K143kfdWttQuPZ5z1DkFJtzdpyza1nn7DruwnL2ATiaRnIqz7Cx189USdU65jebIFpLXl5fi5S5vKajkmxrFrBGrB1ofeHLOiNAX5y+sf1q719lI7RtWelqOgm9NyqfzWwRr3weKyIinZClnuWdaBGh5gG5nqSreijYeeq6bHomegm0gWKx+jn0yPWQp0W28dhsBGl6Oey0I3M3H5yzJ/AGMRHw+rdcrvJjcfbr33jZOds52znbOO7i7ANxNI1koC5wRbCDQbqkE6fVTXcw0SpDd1SShUKyvd1iWldYZyN3r643heR60SL7HnltTcxBkc36Qs5KawB72Rl5kGFaIvwSqms5kvIgCTkSv5oNLRhYl3SBedKt0tXKx2wV+rLcM54JUsKLSSjahbdsaHotItZsyjDrOB3u88DcJHDOHsNe/5bLRZ4/6c5b8fo/vrxfGs7ZVZiWiHO2c/ZaDeWjaCQTRAN5aJdZEmb6XUK0XFeNS+di9rOMz0G7Du+DAklQLaI6CAu74HKjXObpHNfqnCP8uZdCq/6she/5paqIyCLExkNakLsgKpV0ZQEU08D5kG41WcbSbdnb52Y9RMf6Zcdq/c4Ra4Q6c1qz05JxOGevAefs6ZiHO2fX2XDOPjc+PopGMockSB5meR8IyCXpIlqUulU6Qk7Kclv7LMVTEMcMgeU0td30OrzNmqeA12eF3QyhKelJfbWsoaEjIL0U2k2qEa+cGCKRXoZz5NVDuq346l5I4VoaVMYXyw5J8yuTLiBIVyPaBRNC+C/vmqs8E0JP80xY+TGzoL4kRLqdbOv4gwAAIABJREFU19JcrWCGrB0TLhpnP+/pt67G2b/x5ssVhzpnO2cXaVjycM7W8tO1wsyeOJol4ICZd5G8OEJuYGxsXa/e56jjPp2f1cz1525qGbb2l39jYp/6UFqEaIQ3yzejw0lILk9U2BWr67RkZFa0LNBA05I9QjiNWwviOMuFciH7QamzauF6+RuRluLh6pq9hDMt33KpIDG+sFpKyLDNlwWq9DS07pWGzkaph6YKTcsEbbS65Lbiccp/1rXybVwXPtHEl37bDxeJs1//55fteMA5W7PrnA3AOfuGcvYKOBpPcvVBwrailt4HYnLWovKSA7gtzSOhnlN5ri77I5VScCjTAlCsGZr/ei4kX9w+2pTdaiTSbNq1bnRlYX3p2bDy1UxnwXg7qzspFbLlreDlLrrnLJOsm9XyfPBjOZZLe9F0OaeizEbY12QkNhhnIG/ACHJGd872hhq2MM14bt5T1QNcpm16N2RdWr8dIGp89TN7WyWszg9VYebxSmR8keCcLfLknA3AOds5W5i6Hpx9II6qkcxJMf1a3vfWGDbL5iKi5Q+2RbLyxtaDzRcBgiJjdb3NkaiCTMwKcVZ5kaRonMuXhfZCUfPBXhQW1NnJDXuartTX0gjsGBBdbQ1y0uyqacUwvpxONau6x36jHInAEvFWL6qFpKuTjp1+SnvJPWl24Qmbqq5FBE3SFLqoZdQwK39KGt5AtuGc7Zwt7Wm6Ul9Lwzlbse2cfV14+GgayUBNCIBOprOzn/lxJ9FKUjMXi9dmSe/aJGuWdUYGwGHrInfoSvJUH6CZ9CwPhmUvhW8aaWr56ZntXBWsEc1ReCckL2ikmO4TJUxNoIMgCvuWHR4lvvQ3JOroENIVOrTEMyHOm9dIkzN+u1aS6MmfVvdq2WmxjmOEc3ZHmHO2XrBGNIdztp6Wc3aH3QU4mjHJvGxAPB5GMkvIRKsMS+LHxVctoez6Emly9IxZ0yQqtZ0StxPKOxEv9ExYY20k4VpyJMYtKUQdSHRBNaolLOmea8jwr+pkU15PYvGcWKQuz24qhzZWK90aeU/4gYrtPYnp8TFneWwbC8seFxZW2YSwxWWFrd4xaXKcHhEwxNOdotttu5WmsFGcU/QsKGMVQ4jE3Rr3Z/1qeWvJxuOcLontTzU7PWHg8aerEfFFQ6oW52w4Z8M5uyiDc/b14+wVcDSeZGK/JMKSdyDHKWtvag+n5IxCnkXO7aakfSET6jS4bfNrW8g00TsZZKFc5T2AKMfOOE6QHokgyqI8bPKvdeNp9SK75qy6a3k5tDFv1fUTX/qFLeMFpoUVuze1uqwM+4d4J7JnDXWX4axtEVd4aVg6sovNtCnCra65WVDqKhR1SWW8FpdV5AOspCHjurv9HAWcs9eVc852zu7JQ7LhnL0ejqqRLAlUjmGz5PLxgEK2JQ9hX93FSBBJk2SV8By3s+MzdjoxFX+hTItYHqWcZn8uzLTHSazxddbUa8hqEz+GjheSZp9YXI+8alcsZG9NENG6Ei0k0rUWtteODyHdIm1Ft4tHWjJ78FAmPmOx+qpu9uG6GZ2tlGmlNSe3LhdfGPzyfQ8CuDic/Qkfbm8N3cPZn3DnrfiEO28tOPsTPvrWSk6zPxfmnB3lnLNn07tpOftAHEUjWfMktCZ4mKRL8zLAePNbXoiWB0KVk1/goiFrpgHxJ4X3XVJIm6yBukz7dLWpZDpnZyd+DUhPiRaeUK2taVQ0X7uzmiSikTyXYQRWpK0RIiNfHiblK7C8ZQ+CFFnwoFt5Tmm0lY1jEdYidln2g4hTSTvnwfJMNHWEbkNvI+Lcm7wMF42zf/Ntlw/i7Hvechn3vKVcQu6eN7Nzg7M/4Zm3Omczm87Zel6qYxHmnH0YjqKRDEzl6/EeV2HswZolWuOGsUi2uA9DLcd1rXfpLEn1fOlrafeOuZFdbTI/vfa0MWIdNmRaS286ud2pCrLJraXTgklgrQcc+ixoYPJMqC8PTr5UkvBs2j15Rl0/XV6PjhfGIljELYhxL7Lel+B709Ti1+PiCwXn7MM5+543Xa7y6pzdTtc5eya9m42zV8DRTNwDUDWOAYzdcexLu4oXJCnjATR3Vtr3niMjspJtDKQ3ZeQEDsU7YI47ExkIPV12wl5AvBZDqbOTGdUmuzARLe3K6yC9OvmfPXEDSloyH9oi93lCBwsfYn74xBOevw2bZEE0pclfAq20stE4caXKMrNpHfPF8bWJHS3IvKQJKDsjnudrsO5dZWILT697Mgca4ZZc/K0mdWh2Kh2mi9DOV9KHSG+fvN9kcM6Gc7YR75w9D+dsrsN09+DsNXAknmTCsCkbyKQcF2E0PVxSNqE1uaOyJXRlempYsGW1tAioJ0ystVOTMaatqrvOcW4a+BJLar0aXX08vLrhWOaqlx+1b9BWtxgfM6et5dmSb11H7UYblDDri58vy7OoOy2lBX28WqHWmsgSdc20W60LmvJgyTevVysNblKpz+7JI/vyokyzeRMckM5NAufsDjhnF3DObufFOdvQO2dOPpJGsk6aaliDaNNxQQjKV29aVq7ZXafMKi7sKCQt5dNYNwsDKHcn5j+UpDYEqohO6qnoWSSebLmi3gwPSJH+gu7InBcjb1Z+VRtkk5emw2+L1iSO4kU7s/MQRyVqqC5eq1PkzxoPtwRzL6LWC6o1zq0WFr/SBtVjypr6SY0TQaeOWtdzRWmld07E/FCGc/a6nP3cZ93qnA3n7GRD2i2Sds7ui1+Ao2kkAzWBVmFLiLZl2yDaQl7KsPFlFSmkP4NkLDKt0LvmprQvSZoMQpa6O6NMoqxavFo+6yEcRpltQ6aapIH65mw945KMtHAAhWdBuwTWDOmCYFoPOEPlGUnpzpFV7wNOjckjHZ6JnC8Z30NgM/nqlu21tUS2Q6c5GU8jl1Z6jgLO2QIdnP3xH32rydm/9cZykp9ztp0P52wlzDn7IBxFI1kjUI0gi7BhD6JFWX/5XJldrOkXYY1l3WRDdSm4V2MWHTs5SbJvpgvx8IkxbKo675oblEa6yOMwEDYzdaMtMcTzoK6faeWvEUYye/Y7o9zhKYVrRG+QWyUHlt/OxliLOCsvSyfpakhdZV2eiQNI0VpayMxrJTceqPeLoXOIZ2Ii6tMZhZsbztkNdDSsnbPtMOdsHc7Zhq0DcTQT9wgABhQ77OW6IBRjyRJaSwLlY22SgXJc6Ya2HCAml8jdmWR+ZyZ2aBM4ivxYNqQOk7F2VhrkJymA3S6onuYKyvi8IOKljRaxji+DMh/aBIvq+ZNlBJNj15BYxKDIc1s9u/Xk3Zj4PZnyycIGfsxtxl++65Kmj0aeeL3IuFR3eZLHUO/uJHWHOCmkiDPqIHWxVfUo5UV5N5rODKq8dimV6fLfTTVZp97RaSP1NJsyzFEgN9ouGGc/5ym34HfedqWUb3D2cz7iFvzOn1wBCHjOR95Syf3OW65kO7/z5vHYOds52zl7+j2Ys1fAcTWSG8cq0TYetuoBbaUnI3cNkrX6laSdJRdIkHuIebBkeuzk/LAXQQi2nQGU5XYh4CwEbEXFVDOfxTatrYeDP3CtdsVGIYjROM8rO249DEpceoirdTuF/MDya3W3qGmLMGrkj5NhJsrO8syREVtgoAtJXrOrvhBSnFIGC5Ydc9vTiIoE5ctrCTPP1O9ZYOkZ8iNRz9i6iXFRObtqILN8aZz9O39ypTh+zkfeMjWMjTSds+s45+y2vHP2PGcfgqMYbpFAKAk2HyeOM7qeTD3FTuqekrKarYSq2yuUsnOzn6ud8gLLCyn5lPFSX0tTuykaC8u35NJEEymj1U1hH8J+R/pdY7OkXTXhOphPtOjpLmtNCuEympel2XXEzrVZzrIbkv81K7yVFrM724Wn5MOyOWdD1W9dNxyw7elcenM3K1CNc9soMrM2e6/RTQTn7FImeZKzl/nOW5yznbPVvALO2S3ZxZx9II6mkawSJnvIZomWycrnTz6sVbwSZk1s4ARplUP+NdG7+xGH+OqVpJ1IvUtvRk7Lg/qSUb5kNYKtXn5KHFCTRALfkal6Me7xUEgdooUPhUZ04oXSIqdNFC5khL450aOjvF1l6bBjvaSW5mc2TZFO8yVbyLUyZvz2yijypO2n7ADgnK3F/+5bJw8y0XjunO2crcE5u5Zdg7P3xdE0koFYrqF8EDVPhEaohQ0uJ4lWTmrgXUI0TWAo0lPIgeejINfGMAnVKyyIyYrX8pthpFnku6H3/7d3brHaXOV9/z/z7v19NjScDCKuTbARtAkXwQY3BSWqWqJUNI2SXBApUaRygUQPUZuKSgmoUqVc5qaEVmmUNLTNRdVGpYcgLprSQKTelMSAIRCX4sQEbAzGxBwK9udv73f1YtaaedaznnV6D3vP7O/5S3u/M+vwrDWn38w86zDRtnV268ie5y2DU5gNzc5moPx1mYnQvBDSY6BBMDrkbFmbu1Mu1+oU5WEXdPHiU+pT9VJk4gakN7CSZyI3ACdbbMudLgfQEN46evyA8GuC9bHrcAV1KzD7Dfdc72Y2f1A2Zqfhxuy4XGN2qU4XB+HqQzIR3UZEf0BEnySizxDRL/nwe4noo0T0CBH9NhFd8+HX/fojPv6elorI/VlqppvrxmAkbCTgzeRLypLNcrJ82YRVeRvPwVrLW4KU5lUhoLnbRbIt2peVIPYpoTiNksyXsz2wdDnJskMefvMrNa2VphDKhbXEZe3xemn5xQldLF/zTGTsDaK8HMCkNOi25ItuPjKqZT9fHMvi8mq/LXkr+SZv8sJ0UczW9L++9WwSdhWZ/fHQP/kCmP3A913PlmXMbo83Zhuzd1EL5W8AeLNz7nUA7gPwFiJ6I4BfBvAe59yrATwN4O0+/dsBPO3D3+PTVcUhtksfttxysp4DrY9LIOtSW1q91PiWJjBRt6KHoObxIKUuhWa3UlnNcFXqoOYT5ZVOPBmn9SebjqtSXq65jCi2ndybiO23hgtMA1hr82HOwxDVu2CrdoOp5anm64zrmag+e45kphaq/fZ6UVRbpTS9+S5fF8LsmozZaX7Jyzf8petVZn/s4RvGbC9jdiGxMfsoXK4+JLtR/8+vnvo/B+DNAN7vw38LwE/65Z/w6/DxP0wV33iIrHmPq6DdxullOl5GKCf3xq1CVEzknnR9UDwaOaDm8k7lVwaOqNIGn5DIp3gt1K9MbVN7TXAV+0jzSJDYsdKMZndTuKBL83OmgVkziaJ+arV8GvjlNrZc5K1lUL7fW8l+aT9W61WyW8mq5t93f0hz3EXZ8tuSt1K/JXqTL4LZNS2V2W+4U0zFdsnM/vhn49kujNlaYNZMImN2h91KVjX/FWB2r9r6iBNtiOghAE8C+BCAPwHwdedcmFH/MQB3+eW7AHwRAHz8NwDcodh8BxE9SEQPfv2przZ5j7WwHFwl1BIPBFLo5ZrlODDT7WB/Sl7k1nukQVKWLZvwMnYSUFb6oZVAnUy7pDTZhfxbDutoI9I8odykLgONf5l68vyTvRLYC3ZKqvVzayqooFbPBK9DzyNNt0ejxOg98x8s7y5l9OY58A3imDo2s7PlYtnM/viXbhyV2fe/6no2rzE7rSfPP9kzZqvp1bKyFSpE3UrMPoCaHpKdc+fOufsA3A3gBwB8774FO+d+wzn3gHPugRe99GVRXA6q0XlImfQCKLLvWg7S0nYCUJm+MoWQtE1K3giWhfhEhSY9Dsgor9YPT4YJe1P+CqhJrGuSL31BHMrNeTJ93pqhI06AAekuHTJpE1O1fm6K5GAQYPQWdPsk+XnemTWbvhX2hX3RchySNOFY574IpT151erYmj4UqZ6E9XyXQu6Kjs3sUrqLYPYDL72+SGY/9OiN+UGZiwHm/ldfN2aL9FUZs43ZWtm9zN5BXcfJOfd1AB8B8CYALyKi8DGSuwE87pcfB/AKAPDxLwTwtdYy+EXGt1UDapLGr8jmuSkfLwfKMS1c+GrzlihbAnRSySNR+2hIBs5FMdhm80iohm1xevgUT3qdZfqkL5ViS/UgyPpk8mT7vIkbcVhI7CgVynlEctdoax+9yGtQOXihOS7rmSjk3xBrQiuk6+mLdgiFLz6B/4a4A1claYLjdWg2In5b4xaoi2A216GY/Vdecr3I7I89dSOxHdVD4d79rKvFoZl9373Xcd+9zH7B9iceER8U8TaM2cbsnIzZNSPi94Bqmd3iZUT0Ir98O4AfAfAwRvC+1Sd7G4Df8csf8Ovw8R92rv5pFc0TQPxPxPNmtpA+6rfG85CwpdmXzXTiTTyyJexFQBVT9ORgLMuQaSHtMtvg+Z1I35BHnTCelVfyZsj+a1qft2QeS/87kNg+JU1Y4cc9p2xfLQWwuRup5iGQwIu9XIod5lFIwFq6EYXywjkmvC0bNABUCW+FS6mZNFtOZj8eUtwzoW5LZR83pc/YUIFdKudi711Nuihmq2Xzvz2Y/eDT6TzCif0OZt//3dfx0BOzzUMz+5Ofv4GHHr0BOOChP9WnetuF2a//vuvGbBFmzDZm898isw+gFk/ynQA+QkSfAvCHAD7knPsggF8E8E4iegRj/7X3+fTvA3CHD38ngHe1VmbarkHfl9r+AhTQijzRunLRSxDXwiPwyWY3brs20pmrcRBINj2UbcuUl9gp9F2LbGrNkxm4hornztXS22huRK86z2VoLirUK/F+aIVm6pO7QErXYK7/m+aZSLdVnJgQ4K0VzvKU0oX9Vt0XDWVpdosQ1i60QlmtHp0iNA+p1vpcni6M2Zrk6fPGF9y2M7PfcMc8H/Eb7pg9ta9/6fUo3f0vux7llYfmoSfYxzxWwuz7vy/2TEd2jNnG7Jx9Y/ZBdVJL4Jz7FID7lfA/xdjXTYY/C+Cneiui7VMZJvef7E7BB21oAIsMyAEMvIzMAI4IJiKuWz35xJt/+AZ6yddDWhrFDo/moE5Me2+EZi+Eq/vTB/J8yduwNshFlLUR663AK9msKTqnCHN/QBY+pR0IbqvcBZ2ePlvPTNqQXr1nZ/JsAJzrprqVeFNkeYV659JIr9Ze2sWWPD6l7TpkXY+si2K2Jo3ZH/3mPHdyL7M//ufzw+3Hn7ox2f3EUzeivA89KbowsLjXvfw6PvnlG0mc1Ovuuo5PPnYDr7t7/E10wcz+xMM3VDvG7LyM2XHZxfJuBWYfQIuav4iDlf/xOEB4IQjRG5B8yKaWMJeG5eqRg4PaLAexTpm/QtrSScTzR8oMConkRLySN2dP2w+l/mJRPiEScaUTMmcj14Snpa+d8Dt9JrWh3GzZ2gmuxXu76uCUjrpFpplnYp/mt2NAJDsYZEqAYnx1aqFS2SWvxg72biUtkdnRA3JIp7D3U4/diH6N2YpdGLON2boWy+w9tYiHZA2spMQVQbvV8/D1KIxSG1M4TyvehDUwVpWBHYDqwD0J51xzIK+TVn7RRsingVWRdmOSeXKDQEoeA+1YyHklw/GRGjJNUUl5IvM2ly5N2nQB1i6olmao2iCN7FybkwGlvIpq+6mlrCSqZCN7ElVsifik/1tvvVtAfATwXmUZs43Zxuy0DGP2qLUxu9rd4qIkAcl/5VyZji1o+XLr2TAeqHxhaVKpaWDLRu8qXTuyYmf6Vjb9KHDlZl0G1lFzWcGGY2EhX9K0VSgj1wyWg0Gt+S0MyAhpcuc5L7s+8pTVWYmqSjnP+PRD0c1goGhy0VJz1yHeTqOmvMyNNEm3i4LtQhndtnLrnTpH5yjomsLxJkIydk3uh0PsjysmY3ZahjHbmM1tGLMvkNkH0CI8yUHyrT+JFIv8NwKveHNNmuZcvpzECyA0TVWEecqigUid3gZA2euQNH+NdqY/5oXJTeFT9DSg4WaijJoO9rfyC4PSPimjopX9Jo+NDAPyXgyZUIKPSzbhZYEqIrQ38hqMa2/78i26xYvAvQ2RZyJ752m/gFvSdU3tU3iaOdR0RVU7lBnsEuqxR/Od6QAyZid2jNmxjNl5GbOV30vQYh6StX2RNNWxNFr66WLfpul4OVFYAb7B0zAMM2BVFSDanK7gDRgwQzhXRgI6J+IKTXpJPTJpkzKZ/bGe6QAP9bqsnPCFWYKqNnIXaeaajJQ7dJHJQt27LyZmi09r1NvHr7W5sDTSfFHKAjQTn8vXWk4JyC1pTJOM2aOM2aktY3Z7ucbsSvoeZu+pxXS3AMQD8oaSydNzFw2JyJaLqxQ+lM5QIAVV7kqVTXgyLpM/apJTPBfB5tTUx+GaBulNcwLIvJkvaZZT0srN0nbVIO0EG/7fLs1vpSTZdSV/tI21eKbcVEFTPj9iunR9Dg3bE5oHW5vcBgBbbrehDE3R6OpWG4V0OY9Zr53LUFPz3QLvV0uQMVvUzZit28ytG7ObZcyedYwuF4vzJOcGesgXBT6RfBTO1+WbeggT6WRznFa3bJNe6xXRetxcoSyh4C3R6jJto9Jcp5lMgEU+rwYdkVgbaTvdDDPhIS7XZFfKlyszp+rAkM74IF5+aRR0bXRzqbzqyOhaHTrKalLnQ2FxdPiONrnOK16DbPNdj9S8B+1VdyX0h9+5Ycw2ZmfrZ8xOw43ZSlGHZPYBtAhP8thPyj8Y8/DO5Wmd8uvRYI2tkjYo91YuAUQiXVgveBaidGy5OKhjK4J50x7RGDiknopwvskBIdITEYXlPn+KNK0cxax5LAJYi8eq4ulwmXBZL2Ds5yYH1Gj1lba064o3RfI5N4eel1XCfDwK5SdpvYcjpAmHPOcxCfa0ZwCepzgohICNi+fqnJoVtXM/E6bOQaqUlX0QkXbCetiOXN4QXrKtpcv9tuY1pQ+8DcvTujHbmG3Mjs0as8vpepi9hxbjSQZ0kFLDcss6MA+yiMokcTEpdeJ/kTJQbv5Kk1iOvBEFe/Lzq9xOGDyiboe4OWiAkfthqo+SVhs0UIIWv/7SY6PY4TfDzIOI5iEprUdlKCecvIHsIj4YJVs+ZX4LarpYaWEXda/EfjjUxPqR7Y7juuQvQS1Nxuy8PWN2Pp8x25hdtX2JzF7MsclBNYmn+EKogZaPaJZptAsqwK4GWN4EmPxxcCKzXHrj4YNYXArKqL5yO8KbJyeR5hVh2zGVWfBGyP2ueQa0fboLwErJal6EKZ0yuKEEY62JrKW6WvNjLf3OypWVs1koq1bn7s4Epe1q2pG9BbI8Mq8IJyId3MpN77xkN4nb2MOzkDHbmC1lzNbDc+lzMmYr+VuYvacW9ZBMteUe0FL6dq5BVEIykfQWhHQ5z0PO66BoKpsDPmOXA1uzT5SWl90HEqhKPYO9ZH9RCtHceZntu5ZJV4NRbVBvzSORs19rYQLar72mvmq1tPw8b7hx9NZDpimOlu7c583aA2rZ8+RID6y0113y1pExW6Q1ZhuzG8rYJY0xu1be4Qwv5iEZEHB18THhgz56QEs8jcvkk+ESrjVloJwro9T3LSo318dOg1ylOU+zweuSgFyB0AD9hEkATvkTq9rUltnfpcOglZeDem69qTxK8zZfigeGQcv8mPte3FnPxEU9M/pyqp873cHmXnn3uFlcZRmzYczmNjP2cuUZs43ZJZuXpUUM3AP0+w6JBOQycQ7q23eujJCnFh7llfAjZZmLj1ou5I2KU/q7AZXBIUo8SbsYmzC3PNR/xYmnO2FX8dmZy95siOYBBdX9XAirQRJAeUqiA0vdXnHe9agZeOxAyAEfhxQp+7I4IGTf8sTXrNozon8ARi6PDye58SG98nvu/A3tCINArrqM2X7RmN1kb18Zsw9cnjE70WIekgHxgMw2OPvgDP/GLb9fn4NpwY4a17vDQ/qOMzjyIoRzIgNeQIdvdC6xvnGOrQ/DCF04n3YT2+Dn4tlZuuE1OCZelMzxC2lrUxmWmrUkAAelaADJSGPNdktdWhX1lwuw8ftBrYPYZ3wuzhYQRvNjcnXaqZVxYc+KO4L23LHTWQKUaafPoTJgO+cU+zYVXJAxew43Zsd2jdmjjNm4UGYfQot5SCZ/ZpTgyte1Ec/q+p7wTdJJD4O2TCJc80Jk8kZwlScf91QIMG+GMWyLEa6yLk4pQ5uMnsTydgucCFqQ/6e95MmEuTf6EsB7mpwO0V9Iaz4sTdcDYC9vRUsdQMDgj2dpap4sdBU7zeoB35He3qvF7nOjrNW5xzNxDPfYimXMFhUwZlft7CJjdprHmH0cb/Li+iTnlsO62n+NkF2HX9deKkr917S+ak2qADnpO6dAdaoD9BsHMF/sA819wgjARngbou0R5eRuaCcb6upnlts3OagOSI9ZlK6ws3v7pVUHhhTytpSXy1g6X3pecFvK39QKPEAZXeo5SXrjdtnOcH0kYMj8tuY3RTJmG7NbbNbqYsw+TBlduqLMPoQW4UnmQC3tXwnaXLpp3cUR6onOB0EID4JMk21SE+UAlTcmN/9GddrqXovks6W+PpuBlSW9DrwpkGUmipv/uAcipD8/1yuvglGUq03+zvP2DtYohSdTFR3gDbJnpPOucbKpsQa8AfUmupp34pj92PbRFm3Ab5roPsmE43hMOCsuwSOzdBmzjdm5cGM2jNnFTFgcUxfxkByUe0OcQFt4k86tT2HKjqfpX6U+rW8lspkw5BMjo9VzgPVLi9KIz5a6LTAEzwOD6GRega8T5dcGcQTx6WYGIPoiUsZZok/hk2sG4zeEjPgLVK9y/d609WaPhN8eabtJewBgAuaRIHIQIB+ybj22ZNpD1INEvzlTVcbsNK8xu0/G7B3s7yNjdlWLeUiWF1Zp5HMRsgqUk3SyGUyGacuKl0Cz5WSYMnWQVp70RnCvinOszxq/0sN9iHlNSAnn3pOQlcMu6ds2bWjsZRgGAgHJ50NDteRmhapEm+qBX/NGRDBWLiDNu1F602+F9pkDTpTEPV6HlptYVqUbFMpQbInf62tIh4a9Zq+jDP7gcI62/mhbIgwtI6Yz8dEAPlMkYzaM2cbsJK8xmyW9aGZTfJc5AAAgAElEQVQfQIvpk5x7QOYPz/JBurbOw9TwCpz5hPHEwiYpy1GeABcJGC1fIc1mM9tJ5DJv/k6kV8rJ9TGLwjNpeHzShJZJP2TCE5uV+F1hWsoTWiv5fW1Ku8fF1tIsd5H2Sm/Zx4BBcdL7RiU3iUMc8AMB9NwelhMZs43ZUsbs3eON2XvYOIAW85AMxAM8JIB6QFuEbCW8BOGstDehAlTVASBKGoA10/G6KvlzA0uKsAfbbpZo8HNvygEmUtq+LIXn1HMStlw3NSDn6tyqUn2j87BlQvUjXPi7XNSHAOOxtVMdl79ZV0bG7HHdmJ3aLq1r9ozZdRmzL0aLeUge2OttMvJZWW5Z52FJOLHwjLufBhr/SPzK5UxYUcxjoYF3OCFsTmebPK6WP/Jg5Lweyj4JYYR5knqtZTk04eXyJuGUP9FaPQw1iDvhVehRbb+Uyu0pr7tu/Dpg59O+F+1FeyaatC8Yew5aq62MjXTE9cKofgn6zLPPTcvG7Mtl9mu//7oxu5DXmH0grYjZ+2gxfZIBv32ZFzkJ1lycts6hk+urQgPFcaV+MoX+bSGMBl8TYdPJUQ+8ic0BwynpXytixHR8JLPPr01oH3knpn9xvWsDQpLngTh7Ei6V6/em5dFs9OTXdCx4HkK1m9A+fdl61T0K+SIkHya0JOz8bc9D6XXYmJfbCFlMo9bO7FffeYpHnri5emb/8aduxPWIsyfhUsbs/vKM2V4LZvauWownucXzUPVK8Ddv/jbO39KnvLEnISut31r4GxTPhv91W6hgDmXysLA8nIzQn+wLm2FZ81JEW8BvMCjvs1wYAGyE96HkMdBUmlaoBZZ79/1qgEhtcvnEI1Mor5Q2saschKFiX2rX6Y2Alc3acKgnUW+nu7/cEb0UV0VXgdnTA7K0Y8wu5qnl70pvzM7KmN1h/4CsXsRDsnYRBqBN6xQvJ6CVQM1BlhjwlHoE0Em4TpJ9x/w3IBMYOyTT/vBl3swHeNgq5eQGnUTbIL0uTLUWREK6nwboUJaSgJBxWlk5W0l5e4Awp8s82XeF5z513jVva759miJ71QLJ7lHg9tB7UBmzfTpjtipj9v5l7pvvVmP2N9/7zd4SEi3iIRlIH5CnZQbOaXmbxoV8SRjlISsBmajSfOfOCvEA3DmSkdOaiAiOf5JbpEvyMg9HqRmx5I0YKD3fcv3QNPjmTpxcXOncboF7KV4rL5meqCFNTYe8WA71fHahF/ACW/eadKSH4b2mZrpiMmYr9TRmZ+ON2RckY/beWl6fZGU5ieMrLgWV9sYe2dCaxHgaWXjoo5brG6eEJd1neB8yx4rWIEmivxrL6wRgp6/aFDwTyb5Ttlv2Iwv9hjYDYbt1GLx7I3fuFs/pwoXacy2U+rpp6ZJqdAJjn5vEIUFY68tWii/F1b74dFFq/YJTtzLn+l5597F5xWXMTutpzK6ai9Il1TBmRzJmHylvQcv3JLN1+WadrAfvg0vTaBfP1PeNLU+qeCQmnSvhLrY7lTcggqf0NGyZrSmvBKxSB94LLSlTWZ+WqbBvlPBdYFuKa/WAcE+HhOaghLWU03XiL+ChaCkDVK68dnqiMBmzjdmyHsbsq13eYnRkZi9mv05gZBDQQJvEKU1zGmSjJjQJVy1N+HOZ3/A3CLhKT8KQKZP1X+ODPbbnSMAN4aGY0m8RfRo1mHcubZrj61P/QMV7oTXphTiuMECkBGsZN/WHcykoewDP7eXCtC9MyTS8/AHjmBFiv7WycnG19V2v3V0HfZTi1MEgl32DKeyg2jRd55X8vWWqHwuxB+ZExux53ZidlzF7/zhjdrnMQ3/gaTEPyUEkljXoAuiGrFaOBOikQtOeWt+cN8KNfdxCnDtnsBP2kwnxJXS19CwD/0ohPyeTfcLWQ5aB5QkQ4lMMtfQVm+wU4nJKjo8CvJw9Cc1auqKHogU0C27OOcbo597mzstQZkxXJnFlXdE59gD5LSZjNozZFXvG7FnG7JbElXVFh2T2YvokSygkyw7ZgRzbwYG2lOaRaRWvwSQn0sk4Yr+l/BwAG4yDOwZgexbHk//H+7FN6Xkc8umB+GLdEGHLMg2aDaEeEB7jrbjFA9ICOV5G8EgcCmT7eBUO/RZa6+t2yHwDDtz/7djw5tf3Ie3533MtzgTAmG3MFjJmR/aM2RldJLN31KI8yZpXYVoWFAxpt4Ob4lLPhYfngOiVzW1iG8TSah6DRByu24xHhDDNlezOR5hW4SI8DWpdFAgndirr4St6yX2F3QxaYat5LaJ4bT+6uQ5SpXJCWa1ekqk4xSOxz9eeSmXX7B3bGbmquTQ71Qo8NZ3Y8duSK6N0kI59AFeuq8Lse7771JgdFWTMPpaM2Udm9p5azEOy9ESE9amJzgdsBzfFbclh470R/MLengLuBNieANsNxq0kD9oTBtaepppCcx6fGzSAlfxykpbG8GEzwzV4S7aZASU8jBTA5vadXA/brXUR0m4aJbmty6Yt2SLxy6UN6BgKddKalXb2SGTOhX08Ei1fRNrlAtz1os3lOxik1+5Z7QVtzwVzxVVi9qtvP42Y/Zrbr43pFsLse+88TZj96OM357TG7KTOQcbsNhmzj6QL4O8iHpIdHJ6jm3iOznCTzvDccIabwxlubra4OZzjbDjH2bDF+WYLR8D5icP5iYMbxmVHDtvTEbTbk/iiJrYS7c/T8S8aKOjEL/8j8Rds+6Y0GjCNhKbBN8ERsDkBBhY+9d1ysy2+LJsX1b5tyC/zfm41T8W0j5TwIA14NdDmVCunJWzXfDt7JA4BkR1slPoK1nShnonKtl36p1PZSffckIa15GvOcwurxOzPPvdcxOzP3XhuUcz+s6/cjJh9712nxuxKvlBOS9iu+YzZR9KKmH3H3/2uJKwlX3OeBi3iITmI/NGbGcl75KSv6fNbPSlh3G4GUoSxV/YJ9LM004eN2FeZpnL8qOXoc9Ru7NcWwqakZ3H+4NUgSvvB8Xwc/nI7Sp4JbVsGqvdJ097IS7AtabpvKNdfM2xZXufSNNut2wnApXJKaVoGmHBF+6jgBRnEei7doVQaVb7IkdQNOme/z9H4dw7gmWH++/aG8OxAeHZD80AP005aM7Nf+fLTqKqff/ymMRvGbMCYfZHSmP3Yv/5WwuwX//0X4MX/4AUXxuzFDNybFY4mJ9l0amOcxCb8IqIRf9sPnbfJ/3KvQCgm6ntFAJ2y+JvMtpvDQ7+sKCv5deFx2PKvO7F6ALPXImyCC/Wl1D7fTLmsxfG800AQCWnFxmYAtpmRArl8fJcCKVBrID5GnzMu2Y9OHfkbbqSIf5MbTidoDrodChSbBnYoTaFanin8krwwB83v1QPQm5vxIr4JwDmH28NO0i5GkyIGmZUx+8+euGnMbsjH88u8xuxUxux+tTD7iV//FoDxcg/MvvPvfRee/lX/CeoDM3tBnuR4q2avcgCsTDdSkPd98xmmX2LrJK4mGZfEn/o/8RoxTcHD+sm5c+ZZmO8NiYdkmk7IH0TudQ6jpB2bQ1NrwpuqSbGXQPO8lMDcEg6Mb6wyPrz9aycP0fxmLeMlUDXYSuXCj+aRuEBVB5Ac+gbUCw6XWV6DSi40phyUnxmAZzbzb07fGda3a46lW43Zr7r3NMvse+89NWYLGbN3kDE7kcbsL/3aNyNmv/gfvuBg1VrKuef3jZtAC7/Ol1PozssJkBLb83KAbXJMcmGnwOY6YXNNHEH+NhvfByYNlIaFgSATdDHCWLZORv3oKtvEtcmMKtfC5ICQXJPn1LyTAVuuHCkNtlo8gKl5LvwF+5p3QLMnYd3kkeCQ48esUt5lXUgX0bS3JPU2rx2qOW4C8Ab4DvszSd06zH700ZtZZn/+0ZvVbeIyZs/5S+tj4PhjzF6HLoPZX/pX80Pzl4KHeUct4rhISMZ9k7fswdmxi5pPI8SgKzwMPIx7CaK3ewHaYaDxj+a/UIXNtTluc20OD9MKhd+T0zEuzJHJR2cHb8SwAYYB0+T14ctJYd5N6XHo9USUQCthEv25NN+4jSmxclMTabb5ycZNcbDKML6elVIvcvrJHYUJ2HKd7fkWrvUNVN/sxU22ai//DjkvttpqDI+eBRvK30VHGyviD24JvOfiT5vbt6S1OWyOoVuF2ffec2rMhjEbuTjNnjG7TxfA7B41PyQT0YaIPkFEH/Tr9xLRR4noESL6bSK65sOv+/VHfPw9bSXEr+5x0928PnshCNxTof3KsNIyCDNchSSUiYWdXCec3Db+8ZPu/KbwlhDmz6ESov5twPiwzMuSdVRhytOJPFnQsoAcKEk5KzSARPkzAM+JfyVqr+a1zE1AC6vazFz0WVhmygJQHSG8y9tpLyi7yzjm094lPEnu6pG4KoP4js9sUd4twOwvPDZPDXfvvadTuntfdZrU0ZidkTHbmJ3REpndc0x+HsDDbP2XAbzHOfdqAE8DeLsPfzuAp334e3y6qmawaA/KIs3kjeDhOnxry4AHLQuRb+mRxInDu0Sc3k44vS22s/EDgvgUQ8HO9mz8HYa5CY+IPTAz+7Ju2noTaOGbwTIXQOQdyPRjy4LU5e3K/APyECza4HEZqGn96nJ9x0o3hZwGUWzxImoEzSKadLgO4HFwW1cepLKj3b1huEu5u5wol6+jMlvTVWD29/zF0yZmT10qCPjCn83dK4zZaRmTjNnHkzE71oGY3XSciehuAH8bwG/6dQLwZgDv90l+C8BP+uWf8Ovw8T9Mjb7wskfBwU3NdRyuOSjz+s8Rsfd2bIYbV2bPwVQBv0z8b0DkXdB0ep2mvwDbgWjq06bOkhSq6Oamu3j76+BFIX7aZr3KVXu1Jjotjyw3udEV0u+qpr5vGmxlvj3eoptvUJp2LFfdl/xGk7lJlKYSWrMO4VVYszf5opg9lYcrxGwYs0O5xuwGGbMPoqUyu/Wc/xUAv4AZFXcA+LpzLkyY8xiAu/zyXQC+CAA+/hs+fSQiegcRPUhED/75U0+JB2TebFeD69hNw3mSOYxkcAyYydM3j/PhOWCRCFSb8IB5MnsOYgKGE+D0Go0jeQeaPMYDT+eAzcaDPNk+Ecbq6hRw5KCohSfb2Hnt8ZHPuTI1r0ZJGjBDX7XocGb6tOXqWBRLI82SiO+2XSmvKTmr1LG9F8U+bgfsz7arLn2i+/XoqMxO4q4Qs5946syY3WHTmK0kN2bPxa6c2dXjR0Q/BuBJ59zHDlmwc+43nHMPOOceeMlLX4oAToAjdDv9zdoyuIZwCeW0GY8vh0Ec4/bFgAzQ5BlV+FbEm/SIxkEhwwBcfz7hmm/iu3bbeEuZRlOzzSSHaQAJB2v0Vk+IRjr3ghbQoTHVCflt5zDVRiT37KupnAxsW9QMv5Ymu0yTItDWbHeMvm2t2vkmsFehmeVD2hWqDerYq9hL2YmH00UwO4nDrcXsV95zasyGMfsQMmYvm9ktHxP5QQA/TkQ/CuA2AC8A8F4ALyKiE+95uBvA4z794wBeAeAxIjoB8EIAXysXMcKVMIzNcwgXBEVpGCYQfBYjXIn9Ig73D6C+xW8e5BHe7sMFSIgOMMkFfqHmqsXWkwnaw0bN7wJTn7ibz7AbBK8HK3NgNgdhPwfaJMznyU2ro0FVU+1NfSjEB9jw6Jw9WX5pXk4VfDJcg63cj9rx7NCQy9J7DdfSK5Ab0AebAewen4Nm5TjmFN10erY9c24eRT03inU9N18As6VcRN8QdlWZ/YXP39TrYcxObBfLrIUbsyMZszvKOFAd6oNHnXu3c+5u59w9AH4awIedcz8L4CMA3uqTvQ3A7/jlD/h1+PgPu+bHfEYjv07+dZ1YPCVpncgfhwfGDuwVnj+Uyr5wst8aaeGV1+4pDyufQ5Vxf+4HR+OAEBr8L83pt+d6sSWPAzB7CErwjOqIPNgmz0En+EIZubgsbHPlsIu5F7aohbF6JvuMM6TxjK55P3ZRr1fjGF6Q6lejeuQOZ7N6w1nXw+5OulhmJ6Ubs2HMTsoxZh81fYuM2btpn2PxiwDeSUSPYOy/9j4f/j4Ad/jwdwJ4V5s5D8dpmTe/ea+DJFe0HJNg7gsnXkUD7Cqg5QM/uKKphbRlCVlfNQ7gpOoYoXtyjbA5IcDNoAxVz42Y1pr1ts4lYdE2FOJ4Gq6Sp6EK1FIZnbDlaoZtQ33UMsW6tFlttmu8uI/SlNfwxp1rYqy/OfeVc2wVb3571mnNg/cUHZjZXLc2s+9+5akx25i9n4zZPnI/24dmdkt3i0nOud8H8Pt++U8B/ICS5lkAP9VbkfFC2CJGgUN8iTiWOkDFw9inoyjfvLcHP5Gk2oeKLytMVznfIBLG5aAN5/+FprjgNDm5Nm/L2Q03wpdlIor3RGl7tHB1M5zIJ9dztqRjSLGbNdQBW+2iaoat2O9q2RcEC9k/rpoe7KJ3cbj2Fr/BDpBoAKjc/0uY/ugcYtL8gkK6gwJ0BV7pYzI7UyJuRWZ/+UtnUzpjtiiHyZidypit6yjM3kFL2G+J0k9T8y81jWEUxcv88e9AIc9MkQDDZNohljfrqQD7lcvBTgNM+OvAIMvxy3wqOSeuMA2QJS+EFP9qUgLQgkogjsoUDiO+j7qa8Vg9sXXF7UkD62Hq9jjgvPONO3sx1fIqN61pgE3hk7KJ7UI5xRHQPfJllJrZZNNqyc7O2iW/Y9vbkf+yIb0GGbON2VG4Mbuet1KOMRuLYHaXJ/m4mj0LwAzdOWweGEIiPb8Ayb8GzyDjoM7/QllXASAggkwa7kVwLH0In+bVZHAOoNW8ENfE16Hc1uHsZodXgtVVbrt6UfAbQObkVEdZt5zIGvA6PBTSBp/WSEtDYj0qo8U7ITwd2SbDnma7Ehwb8zZ5JnLHbs9peZKm3F3NieM4eRo0z1StzqVjyZYTD0VUh/QYdt+UblEZs2Nbxuy8DWN2LGO2sr4QZi/mITn9lCnHhmOpAlBn/GoAHmi2ETfrzV6DCK4cfOGfU+L5Lxc/uD6Nk/bAwrh9UZ9oJDQDL5i3AgPh5NRNcWfPxUl5WdJMUt+QhtWBQyU6b9nKoITllPNk9MBWm0R9n7fe1qmKmsrT7Mt67MG4HFwPqkxd+Q1tlzr0NLHtYnuX5rAuT4OyL0xSEorGbGO2MduYrdteE7MX1d0iflvm06JRMZ2WR0/LvR0sDenLYV2GtSoauCE8D8Rsy2Vejygt4rBhoCnu9Bpwci0uf2B/av3EX49UmxlwTqOr/V9UZq83gsVp8M/Vowl2Pk1osgv1aLlIqOEtX7PT3N+ttk0NYO+52GvHd9tQ3tGa7YTCTSCCaMP506qzepJbXsZsY7YxW69bNsyYvQpmL8STHKYNIgYV70mgEB+/xssvPPH37rm5zrG0FAEL5EGgeSj4Qngjm9rVkP8FJqhs2dk2Ndc5JAd7qgvLzusQwOREOcFzQQONTRp+/eQaQG7M/dwNN5crt62g4nRCDfmn9LteWEq+0qc4S7DNQl2GccjyMBbQO/l9V7wSpjZViaCipyAHwo4mxtw25+B9kK8r9XhyfHzRW3IA+J5hMbBcrIzZ868x25idS2fMHn/WwuyFcV/iJo4jFUvpxPRjjITtDN3wwRJHI5w4YDmEgfHNf3qjrogYJTd+JYJsODnOnT762s3eh2nkdAABzdAllhYMujwNHHDNDx4BGHxFnbWRzj1Q1fI3T+cjKpPLt2UDIZyLs03pNajmwjOwbZWso9um3rBEjWWUPAdHbb7rhNwW5bo23ZzEORNUbeo7ANNVs0rfNq4zWP/kPhmzjdnGbGM2uo9Xqy6C2Qt5SCb2P8DSgWgThUuozq+NM3QHGmLvA4DUK8HWPWHlRTiBNuSRV1SAnQLOxAvAvBfOzU1uQPoWF2ArR21PYQqAOXQHHs503Q8imcp1wDPP6KDIns8KIAHEXyxyeWCXvBSUycdhO6WV5TTCVk7nlMvL69rTh4/by8G+NX81LBfvl3umFdppCiKl7CaPROM+kdA9iLejo/ycjtlXb80yZhuzg4zZDXaM2e06ALP30UIekl0KSRpEuATt7GNof4+e00bl8ezkm+mCB4BBLQGs5lmAAueQjOWfPA9+HqHQ/BZVx81gJbmpDjFcGXRlHZ0ALTDmfd7thGeeiSsvwZIDTTRIpOEkrsFWKjTVyRHKaUXa7KmjqeVxy9SvtH3V6X5kObnlXrG8mrci2/y6ddHNsWTXHaquC1NtFDmXtg/OAWyu0P44lIzZc3nG7EI5xmxjdqf2ZfY+WshDMhDBVXgjkpHOLE8IcVP+GMZpcx9v6gspZxLmYEs0L2fBm27SBLxxu+K4qJlOAW9QYl7WS0A3wIpYmgDmwZcX6nT7bQTngGefFeDVgFeqk0wQgly+iafUVCfLVsu5ANhK7Tr/pToApGTqUG/hLeopqgFAGuxLHtgc1M7dxXlte7/CbB7lWZ977mv+AdmYHWTMzpRjzD6MjNndzN5Vi3hITk92DkMJWw7UMli55diKU5bd/IUnBjF1oIgoKoFvBbTShgbebfAuCJtaGVHfNwdsGHR5UdO68FQQjeAN9Xn2Wbd7p/qQxMO09KbfA9uW64FvUzFfx7VV80jsLA0yNXNut0Efu6admvRY2lz53c12jXU9BzDkBq3w4By024qJdYH3uqsjY7YxO03fUqYxe4fyMzJmH16LeEgGAkhp8kiMit+Dy16KeYQ04BRnwTwQJCpvyht6adFkNPFK8PLSAmYQhlURP319iRQbArwBmlHTHbclig/ehlCHgY2glt4L2VdO6jbvqQCAZ74zLpSa8KYKsbCaJ0IDcVNzXaEeJUhXB4vwfFsXJm3Nvk0nXht+3HNg2eVCrt0wCjYlHLsmdq+Ue6iX+GM6A+TNIi74QIXYA7UxG8ZsY3YljzG7SRfC7E4t5iEZgJ9bM/ZIzBeDm0LHX5/Hhw9Jc9+cL+ViDN34C0+sHIovxmlZAWBRHnQ06G/O0n743cgR0MjUR6xLGEfXUbCTO+EmQBO2zuH257EBMv73Ox7CwVMj3whzngENtNx7UuvLFuan3LK6aACXeZMvDc1VVUc951RtSiypA8It0whJcbhWIdZzE9CqIsK6P2namaara0Npe7I3a1dNo9XNulwEGbON2cbs3jKM2RXbhbhuZu+hxTwkp33agHkr/QTsESjn9Ri2Lkk3uwvkqzgl83NqdiYPBZA0w7WClzfjaR6JpGpCxBdCuU6YYHHOIR09jTlO7pLki1HajcGHP+95qdcit71BElZyDs0qbHk1AnhdvYmvBNskjNXp5tbhdNAPbnHOyh6YiXwJ0NVKMrh2lOXEjU02vw2OhXXUu6f5Mhn93FFOMliOH4IjQfKCurytXsZsXcZsVg1jtjF7pcxezEMyUO/Thig0zhvHcejKX57SQR6VOLWblwUoo1owAEqIJn3cxEGUt4LIDI3QBNiJnSRK68Gb5rTR0znocu8HMM4b6rwbRZ58wdzzbqfJ7rcz8OUg0SaYL424zgFT2u256EJQlF9O6+RYOANvETC5eh4JCHurVn7nzaPlGJyz5eygHA5Ttr/38txm6tY0+KOQZN/pha6KjNnG7CjOmH0cGbP3ZnavFvSQHDRuXQy+kkci9STk4DrbdD4vny1ScwukX37iduWypgDO0Lct6a/G4UiizhyGor8aBDRDORH85yLiCskbBLOXjLz20K1CmoDnP2+G73cU+HZ7IjRYNoZpb/k8WQm2IaF8k2+pn1qYEp7t/7dDsx23eS7SDgDOK19ryg2gKJUFoK3JrqDa5Pbdaq1Dw42hpwnysu+bly9j9pTPmJ3ImF22aczeI10vs3fQYh6SJVhHORaTehoG0sNlvrgEHsdjtNHWcaoIaiI2+gQqSxc+dcoBO+SrkgC4dCJrsI+21ueXA0JyvxFUo/qUoauJwxcIsCV828/xWZuvswgzZncX2E5hGbjlbqgtTXbJMWm5QDPb0J3nCNoghTiQ2XeacjAP54VfLg3SKdkpgXHDljWP70VNIXTVZcw2ZgPGbGN2m521MXsxD8kz8PLdLuZlx7wR0isRQp0SLy8IfYfLiybYnnwlbF7OaY5OJzL49ekrUIR4Ps0AVm5agyCzV/JMEJDxKuTzFqGrbEtOoYxtAcSDH/n9/NtpjuOQcsC3bzgVlgDa3pzDPteD57qgDbZRVE+TXSc0msoQedRpfXogXYN8x03gEG/wmodC2x+7Nt9x+AY7cWFsseVcMzEZs43ZqYzZcR5jdp+WwuyDes4Pq5Fi0+dOs+/gknYcrhqMx+W4yU/aC/m5fR7nAHLT/JhE4k8JA0bohM+bRtMT0fwr4/idgrwNLY/Mr/3KsrPpwjr7m/aXvHOxug5I8xGzNWTSBD3/OuH5txFuvz7+AYWLWcYpsE3PDIxfL2ppHgvwdWMeGdc9anrXC3cXMPLoDMSbL3wl+9DqkcjZySxr3o9S+n1GZQ/OYYNOeNvDc0XGbLExxmwhY3bdrjFbT7IPs7/wL7/ZkyvSYjzJMRTjiYQQxc05UqASix3D+FrQIDuAAUibDHk+/qrtovARQCm8aTObIcdODgdgQ9MFPU0v5OOjwR7hVyxPng6Wbrt188AFh7E/Ha92gCybyzOJT+g0xxGAzbRX44ROpIUDHLM37U0+IMWnzc3k4tg+k2DWjqp8q1U5tU2nlioCrQY7sZ5MFdUBhKhux34A06C1wwPgOfYc4KKkCV6HkodG9UzsWB4wj8A+R/kGb9I19wE2Zk+/xmxj9iFlzI50kcxezENyrHGr5xdfisIH2kTrGnwlBDUAxxdfKFPaCaHakdh6zIcrjfIAzgBOYX+3+MUaTpghUIpD0C9v+OhrBcoIVVKgmK9E/Mvn6SSMU//UFN14ANx+nfCMb86bislAcJgX0+jMF6FkYlLCAODMASfacSptUzgOMt2ux7oGf788fXEJAloN5SbNgZkbQ4/NnJ0kCQs/xx5NXHvs6w2AswPZuvVkzG0UxO8AAA18SURBVO6RMduYbcxuLyuni2D2gh6SS17kMV5flpqnAtIHhfD8rVCWAGefQ/VxssbaFsj4qFYBikpeHsa3vBRWU89ciSWbrVa0vV8yOqAN0lVTGmxzdnvCRZhzO0CiEaK5eLWPm6IonXbzOjRY9rSXhXruxtvzQFAKdyMQzzJJa3W6lWXMjmXM3l3GbGN2Mc2+zO7Ugh6Sg8atiT0SMQTTdcCBN8vkgR1/yjS1M5ep58/bJgHu1BMxgTN4JBRL2TCnxLs0Xta2lk7KAd1eiFaYhguJeyxK6Qef1gHpBwCUjNG1k5sKSMunwVKeIgUl+ysHgxw8ej49WrOr2dwFEIr9Y9gE4v2X3RciWJ2KqLFO3SOk7UG4ImO2GmbM1svPBBmzjdnZauzJ7O/5Ry/oy8+0mIfkeGTzhCYB0rlv2jwTBv8NORw4qLW+a7I8DfBxmPRIxHm4J4SXxm8R4QtJrZ4DZM7vKntcHa4akHl/siThlMalHJLwFXlKPBly6eQNxLH0IjzhXWYOTSnVJkt7tvVNdgVbu8BWnb+zlHcftcC/ENY8x2lPeRnYttSHh2/R2L8uKk+/qM5Kx7HB7q0s6bk1ZieLxmwRbswuyJh9PGbvoMU8JHONPcZyo6NzCnuCgzeGbTz4Q2vim+3UB4WEVJovJK37NK1PrfqZcBWCPeLnWegP5+IorSkwJ+6BqTUfBcCEcSklm7n+a4CYqzRTFx6duyCbp7+Z7/tqfDNsC+V0eSRcIaxHB7QZeQd64K5Vq6HJrslW5z4pTS1kD8VtMman4cZsY7Yxu9HWgpm9iIfk+IKJvQqpt6COBX0gxxwiPR9lyIYcqZ2QjtctB9RcK1B8C/DLHW9E1RG2EhIZ07JOxXziIm1tugOUZrsAfWbL8bDCCV9rgZGwVb8QpdhNyhLxg2arEbBZ2GbLk7ezei+6YetGiOwJC61JbZ8pfGRcU5NdyZRjo6Yb6qV5JHYeHW0PzEzGbGM2CzNmC2PGbJ7/0pi9oxbxkBzEEZiGiKtc8RDE61pYmrbVIyHD0htAWiqFfwqYtPSlNIlc9JONb1EAbAJ7tttGECrNdiJtDqjy86ah3NpNiGvrmGcio9yFq8K24Qal3uSUNC3ftG86JrW8Iqx7IAjLv/HAqtWRtnICqQ7tAv1D7b8GhTkXpoEf+5RtgjG7IGO2KmO2LmO2rotm9oI+JuKUv1hhdHI5fy2slFarSz5Mn+PTsfUGsSJaO8BzkSyrdGI4lla5gEn81crsSVeqjzZil7Rdz9L2vEmWmgOrYTVbDYBW7ew7oKJmd09Y9PRrO8+VVSg365Hwi9onSXP5Wya0zw788MEn/q9psnp7eJ706M2vwJhdTiN11Zl91w/dZszukDFbL/+gzN5Di/AkuywY05R58b5mbgqL12X4HBYPIuFNhXMqAqmT2nOb2ca76ETk9dCW+aKwlwEFlc4ncXLLGiZZXVqykwvsN4w9Lx2d0EQm34xDnDbdjVyfjpBjNr22aISYkldLO42eJkxzlXbDNgOfphtrDVy7QLrBpvRy1JrUmm98Efwa7ef2n5LlHPME8z11iYJZOLeVvaGYUN8hxuxbjtlMxuxKWE3G7NQuD74AZi/iIbldOujqoE0REw/faDmjdVuxZ4LSFNnPE7GAZFkpNwknuK3WaEMRDKtwRdzclqSZ4lyyVzFHRXakl0FO7aNNfj64FLr806I1L0+APjfhEO/+HtjK5QTyO8I2LawQ15m26dOtDfGtHomdplFqrcu++y86hg03uIKkl2LymOwJ31tDxmxesjF7ljHbmJ0LPzSz99ECu1vI9Tl863dcOsgjzuuSMblzmvjClWXOYU4pPyjAWvuLaDddrYVNDosaPLXqTflyF1em3gFiGMFIQLZe+zbJFeNdfuBFbmqY5mbQUATb1iH86Yc5yZebtqg01VEPbLtHAyf7ZLsTRKsA006ngsdA7p/W5rtak11kE2kTXskLUmvuy5WT2K0sH7t5b10yZlerN+UzZudkzK6EGbPT4J2ORb8W7knWtjBMNTQu6+nCaOuNj4sbobRR1/H0RcFeXEq9T5cyBZKEbvFirQFa8TEkYTJJ/ixRPRasnnNTWWYbXNLgmKSRzW28bK1fW/BaTJPYK/WeLlQ2IqTljTw7Klqp35SfWD6t1ba2zqP2+RxVJeteHokdYLwLiHqb+cKDaBgNvYsXJDfHZpymsV6ibP452VtV957eubeNr5x9DS8/uQMA8NWzp2HMXjezNRmzG20bs4/H7B21oIfklq12LF3+YTnM2emwnWLirzZpZQZPhN4El8yhiRTEkV3t4PLfnpPYpYHzBcYTUloWN7MVaUWdklcOl6RWqx1NLp8pkwM2mjpIlCWbzW47BZ69qdUfON86daL6RCUIKnHcg7HdZub6FDcJrRxupzhZfstyIWxApQvALnDcod9Z0sesALW2qZQwPYwW69AS3qrO4zJOZXSBxL6CCg/IAPCykxcfrZznts8as72Oyew//9/PGrNz+Vj5xuxKeKt6jsUOou7P/R1BRPQtAJ+97HrsoZcCeOqyK7Gj1lx3wOp/mVpz3YHD1f+VzrmXHcDOakREXwXwbaz3+Nu5e3lac92Bddd/zXUHDlv/Jm4v5SH5QefcA5ddj1215vqvue6A1f8ytea6A+uv/2VrzftvzXUH1l3/NdcdWHf911x34HLqv6CBeyaTyWQymUwm0zJkD8kmk8lkMplMJpPQUh6Sf+OyK7Cn1lz/NdcdsPpfptZcd2D99b9srXn/rbnuwLrrv+a6A+uu/5rrDlxC/RfRJ9lkMplMJpPJZFqSluJJNplMJpPJZDKZFqNLf0gmorcQ0WeJ6BEietdl10cTEf0bInqSiD7Nwl5CRB8ios/53xf7cCKif+G351NE9PrLqzlARK8goo8Q0R8T0WeI6OfXUn8iuo2I/oCIPunr/ks+/F4i+qiv428T0TUfft2vP+Lj77msunMR0YaIPkFEH/Trq6g/EX2eiP6IiB4iogd92OLPmyAiehERvZ+I/g8RPUxEb1pT/ZcqY/ZxtWZm+/qsnttrZbav02q5vURmX+pDMhFtAPwqgL8F4LUAfoaIXnuZdcro3wF4iwh7F4Dfc869BsDv+XVg3JbX+L93APi1C6pjTmcA/olz7rUA3gjg5/w+XkP9bwB4s3PudQDuA/AWInojgF8G8B7n3KsBPA3g7T792wE87cPf49MtQT8P4GG2vqb6/w3n3H1s2p01nDdB7wXw351z3wvgdRiPwZrqvzgZsy9Ea2Y2cDW4vWZmA+vl9vKY7Zy7tD8AbwLwu2z93QDefZl1KtT1HgCfZuufBXCnX74TwGf98q8D+Bkt3RL+APwOgB9ZW/0BPA/AxwH8VYyTiZ/IcwjA7wJ4k18+8enokut9N8YL+80APojxo1WrqD+AzwN4qQhbxXkD4IUAHpX7by31X+qfMftStmOVzPZ1WR2318xsX49VcnupzL7s7hZ3AfgiW3/Mh61BL3fOPeGXvwzg5X55sdvkm4LuB/BRrKT+vtnrIQBPAvgQgD8B8HXn3JlSv6nuPv4bAO7A5epXAPwC5q+/3oH11N8B+B9E9DEieocPW8V5A+BeAF8F8G99s+lvEtHzsZ76L1Vr3k+rO/ZrZDawem6vmdnAerm9SGZf9kPylZAbX2MWPU0IEf0FAP8ZwD92zn2Txy25/s65c+fcfRjf7n8AwPdecpWaRUQ/BuBJ59zHLrsuO+qHnHOvx9is9XNE9Nd45JLPG4xendcD+DXn3P0YP6Ec9Z9deP1NR9Qajv1amQ2sl9tXgNnAerm9SGZf9kPy4wBewdbv9mFr0FeI6E4A8L9P+vDFbRMRnWKE7b93zv0XH7ya+gOAc+7rAD6CsanrRUR04qN4/aa6+/gXAvjaBVeV6wcB/DgRfR7Af8TYfPderKT+zrnH/e+TAP4rxpvdWs6bxwA85pz7qF9/P0YAr6X+S9Wa99Nqjv1VYDawSm6vmtnAqrm9SGZf9kPyHwJ4jR85eg3ATwP4wCXXqVUfAPA2v/w2jP3GQvjf8SMv3wjgG6yp4MJFRATgfQAeds79cxa1+PoT0cuI6EV++XaM/fIexgjdt/pksu5hm94K4MP+zfNS5Jx7t3PubufcPRjP7Q87534WK6g/ET2fiL4rLAP4mwA+jRWcNwDgnPsygC8S0V/2QT8M4I+xkvovWMbsI2vNzAbWze01MxtYN7cXy+xDd3Lu/QPwowD+L8Y+S//0suuTqeN/APAEgJsY33bejrHf0e8B+ByA/wngJT4tYRz9/ScA/gjAA5dc9x/C2DzxKQAP+b8fXUP9AXw/gE/4un8awD/z4a8C8AcAHgHwnwBc9+G3+fVHfPyrLvvcYdvy1wF8cC3193X8pP/7TLg213DesG24D8CD/vz5bwBevKb6L/XPmH30uq+W2b4+V4Lba2M2q+dqub1EZtsX90wmk8lkMplMJqHL7m5hMplMJpPJZDItTvaQbDKZTCaTyWQyCdlDsslkMplMJpPJJGQPySaTyWQymUwmk5A9JJtMJpPJZDKZTEL2kGwymUwmk8lkMgnZQ7LJZDKZTCaTySRkD8kmk8lkMplMJpPQ/wcZjO3oFVYJJwAAAABJRU5ErkJggg==\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "flow = read_numpy_file(flow_list[data_ind])\n", + "flow_vis = flow2vis(flow)\n", + "\n", + "flow_mask = read_numpy_file(flow_mask_list[data_ind])\n", + "flow_vis_w_mask = flow2vis(flow, mask = flow_mask)\n", + "\n", + "plt.figure(figsize=(12, 5))\n", + "plt.subplot(121)\n", + "plt.imshow(flow_vis)\n", + "plt.title('Optical Flow')\n", + "plt.subplot(122)\n", + "plt.imshow(flow_vis_w_mask)\n", + "plt.title('Optical Flow w/ Mask')\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.17" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/thirdparty/tartanair_tools/data_type.md b/thirdparty/tartanair_tools/data_type.md new file mode 100644 index 00000000..a0416f5c --- /dev/null +++ b/thirdparty/tartanair_tools/data_type.md @@ -0,0 +1,93 @@ +### GRB Image + +The color images are stored as 640x480 8-bit RGB images in PNG format. + +* Load the image using OpenCV: +``` +import cv2 +img = cv2.imread(FILENAME) +cv2.imshow('img', img) +cv2.waitKey(0) +``` + +* Load the image using Pillow: +``` +from PIL import Image +img = Image.open(FILENAME) +img.show() +``` + +### Camera intrinsics +``` +fx = 320.0 # focal length x +fy = 320.0 # focal length y +cx = 320.0 # optical center x +cy = 240.0 # optical center y + +fov = 90 deg # field of view + +width = 640 +height = 480 +``` + +### Depth image + +The depth maps are stored as 640x480 16-bit numpy array in NPY format. In the Unreal Engine, the environment usually has a sky sphere at a large distance. So the infinite distant object such as the sky has a large depth value (e.g. 10000) instead of an infinite number. + +The unit of the depth value is meter. The baseline between the left and right cameras is 0.25m. + +* Load the depth image: +``` +import numpy as np +depth = np.load(FILENAME) + +# change to disparity image +disparity = 80.0 / depth +``` + +### Segmentation image + +The segmentation images are saved as a uint8 numpy array. AirSim assigns value 0 to 255 to each mesh available in the environment. + +[More details](https://github.com/microsoft/AirSim/blob/master/docs/image_apis.md#segmentation) + +* Load the segmentation image +``` +import numpy as np +depth = np.load(FILENAME) +``` + +### Optical flow + +The optical flow maps are saved as a float32 numpy array, which is calculated based on the ground truth depth and ground truth camera motion, using [this](https://github.com/huyaoyu/ImageFlow) code. Dynamic objects and occlusions are masked by the mask file, which is a uint8 numpy array. We currently provide the optical flow for the left camera. + +* Load the optical flow +``` +import numpy as np +flow = np.load(FILENAME) + +# load the mask +mask = np.load(MASKFILENAME) +``` + +### Pose file + +The camera pose file is a text file containing the translation and orientation of the camera in a fixed coordinate frame. Note that our automatic evaluation tool expects both the ground truth trajectory and the estimated trajectory to be in this format.  + +* Each line in the text file contains a single pose. + +* The number of lines/poses is the same as the number of image frames in that trajectory.  + +* The format of each line is '**tx ty tz qx qy qz qw**'.  + +* **tx ty tz** (3 floats) give the position of the optical center of the color camera with respect to the world origin in the world frame. + +* **qx qy qz qw** (4 floats) give the orientation of the optical center of the color camera in the form of a unit quaternion with respect to the world frame.  + +* The camera motion is defined in the NED frame. That is to say, the x-axis is pointing to the camera's forward, the y-axis is pointing to the camera's right, the z-axis is pointing to the camera's downward. + +* Load the pose file: +``` +import numpy as np +flow = np.loadtxt(FILENAME) +``` diff --git a/thirdparty/tartanair_tools/download_cvpr_slam_test.txt b/thirdparty/tartanair_tools/download_cvpr_slam_test.txt new file mode 100644 index 00000000..5bf1f012 --- /dev/null +++ b/thirdparty/tartanair_tools/download_cvpr_slam_test.txt @@ -0,0 +1,3 @@ +https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-mono-release.tar.gz +https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-stereo-release.tar.gz +https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-release.tar.gz \ No newline at end of file diff --git a/thirdparty/tartanair_tools/download_training.py b/thirdparty/tartanair_tools/download_training.py new file mode 100644 index 00000000..0515bc92 --- /dev/null +++ b/thirdparty/tartanair_tools/download_training.py @@ -0,0 +1,159 @@ +from os import system, mkdir +import argparse +from os.path import isdir, isfile + +def get_args(): + parser = argparse.ArgumentParser(description='TartanAir') + + parser.add_argument('--output-dir', default='./', + help='root directory for downloaded files') + + parser.add_argument('--rgb', action='store_true', default=False, + help='download rgb image') + + parser.add_argument('--depth', action='store_true', default=False, + help='download depth image') + + parser.add_argument('--flow', action='store_true', default=False, + help='download optical flow') + + parser.add_argument('--seg', action='store_true', default=False, + help='download segmentation image') + + parser.add_argument('--only-easy', action='store_true', default=False, + help='download only easy trajectories') + + parser.add_argument('--only-hard', action='store_true', default=False, + help='download only hard trajectories') + + parser.add_argument('--only-left', action='store_true', default=False, + help='download only left camera') + + parser.add_argument('--only-right', action='store_true', default=False, + help='download only right camera') + + parser.add_argument('--only-flow', action='store_true', default=False, + help='download only optical flow wo/ mask') + + parser.add_argument('--only-mask', action='store_true', default=False, + help='download only mask wo/ flow') + + parser.add_argument('--azcopy', action='store_true', default=False, + help='download the data with AzCopy, which is 10x faster in our test') + + args = parser.parse_args() + + return args + +def _help(): + print '' + +if __name__ == '__main__': + args = get_args() + + # output directory + outdir = args.output_dir + if not isdir(outdir): + print('Output dir {} does not exists!'.format(outdir)) + exit() + + # difficulty level + levellist = ['Easy', 'Hard'] + if args.only_easy: + levellist = ['Easy'] + if args.only_hard: + levellist = ['Hard'] + if args.only_easy and args.only_hard: + print('--only-eazy and --only-hard tags can not be set at the same time!') + exit() + + + # filetype + typelist = [] + if args.rgb: + typelist.append('image') + if args.depth: + typelist.append('depth') + if args.seg: + typelist.append('seg') + if args.flow: + typelist.append('flow') + if len(typelist)==0: + print('Specify the type of data you want to download by --rgb/depth/seg/flow') + exit() + + # camera + cameralist = ['left', 'right', 'flow', 'mask'] + if args.only_left: + cameralist.remove('right') + if args.only_right: + cameralist.remove('left') + if args.only_flow: + cameralist.remove('mask') + if args.only_mask: + cameralist.remove('flow') + if args.only_left and args.only_right: + print('--only-left and --only-right tags can not be set at the same time!') + exit() + if args.only_flow and args.only_mask: + print('--only-flow and --only-mask tags can not be set at the same time!') + exit() + + # read all the zip file urls + with open('download_training_zipfiles.txt') as f: + lines = f.readlines() + ziplist = [ll.strip() for ll in lines if ll.strip().endswith('.zip')] + + downloadlist = [] + for zipfile in ziplist: + zf = zipfile.split('/') + filename = zf[-1] + difflevel = zf[-2] + + # image/depth/seg/flow + filetype = filename.split('_')[0] + # left/right/flow/mask + cameratype = filename.split('.')[0].split('_')[-1] + + if (difflevel in levellist) and (filetype in typelist) and (cameratype in cameralist): + downloadlist.append(zipfile) + + if len(downloadlist)==0: + print('No file meets the condition!') + exit() + + print('{} files are going to be downloaded...'.format(len(downloadlist))) + for fileurl in downloadlist: + print fileurl + + for fileurl in downloadlist: + zf = fileurl.split('/') + filename = zf[-1] + difflevel = zf[-2] + envname = zf[-3] + + envfolder = outdir + '/' + envname + if not isdir(envfolder): + mkdir(envfolder) + print('Created a new env folder {}..'.format(envfolder)) + # else: + # print('Env folder {} already exists..'.format(envfolder)) + + levelfolder = envfolder + '/' + difflevel + if not isdir(levelfolder): + mkdir(levelfolder) + print(' Created a new level folder {}..'.format(levelfolder)) + # else: + # print('Level folder {} already exists..'.format(levelfolder)) + + targetfile = levelfolder + '/' + filename + if isfile(targetfile): + print('Target file {} already exists..'.format(targetfile)) + exit() + + if args.azcopy: + cmd = 'azcopy copy ' + fileurl + ' ' + targetfile + else: + cmd = 'wget -r -O ' + targetfile + ' ' + fileurl + print cmd + system(cmd) \ No newline at end of file diff --git a/thirdparty/tartanair_tools/download_training_zipfiles.txt b/thirdparty/tartanair_tools/download_training_zipfiles.txt new file mode 100644 index 00000000..ea04e549 --- /dev/null +++ b/thirdparty/tartanair_tools/download_training_zipfiles.txt @@ -0,0 +1,288 @@ +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/seg_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/depth_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/depth_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/flow_flow.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/flow_mask.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/image_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/image_right.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/seg_left.zip +https://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/seg_right.zip diff --git a/thirdparty/tartanair_tools/evaluation/__init__.py b/thirdparty/tartanair_tools/evaluation/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/thirdparty/tartanair_tools/evaluation/evaluate_ate_scale.py b/thirdparty/tartanair_tools/evaluation/evaluate_ate_scale.py new file mode 100644 index 00000000..cb568cb4 --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/evaluate_ate_scale.py @@ -0,0 +1,133 @@ +#!/usr/bin/python + +# Modified by Wenshan Wang +# Modified by Raul Mur-Artal +# Automatically compute the optimal scale factor for monocular VO/SLAM. + +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, Juergen Sturm, TUM +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of TUM nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Requirements: +# sudo apt-get install python-argparse + +""" +This script computes the absolute trajectory error from the ground truth +trajectory and the estimated trajectory. +""" + +import numpy + +def align(model,data,calc_scale=False): + """Align two trajectories using the method of Horn (closed-form). + + Input: + model -- first trajectory (3xn) + data -- second trajectory (3xn) + + Output: + rot -- rotation matrix (3x3) + trans -- translation vector (3x1) + trans_error -- translational error per point (1xn) + + """ + numpy.set_printoptions(precision=3,suppress=True) + model_zerocentered = model - model.mean(1) + data_zerocentered = data - data.mean(1) + + W = numpy.zeros( (3,3) ) + for column in range(model.shape[1]): + W += numpy.outer(model_zerocentered[:,column],data_zerocentered[:,column]) + U,d,Vh = numpy.linalg.linalg.svd(W.transpose()) + S = numpy.matrix(numpy.identity( 3 )) + if(numpy.linalg.det(U) * numpy.linalg.det(Vh)<0): + S[2,2] = -1 + rot = U*S*Vh + + if calc_scale: + rotmodel = rot*model_zerocentered + dots = 0.0 + norms = 0.0 + for column in range(data_zerocentered.shape[1]): + dots += numpy.dot(data_zerocentered[:,column].transpose(),rotmodel[:,column]) + normi = numpy.linalg.norm(model_zerocentered[:,column]) + norms += normi*normi + # s = float(dots/norms) + s = float(norms/dots) + else: + s = 1.0 + + # trans = data.mean(1) - s*rot * model.mean(1) + # model_aligned = s*rot * model + trans + # alignment_error = model_aligned - data + + # scale the est to the gt, otherwise the ATE could be very small if the est scale is small + trans = s*data.mean(1) - rot * model.mean(1) + model_aligned = rot * model + trans + data_alingned = s * data + alignment_error = model_aligned - data_alingned + + trans_error = numpy.sqrt(numpy.sum(numpy.multiply(alignment_error,alignment_error),0)).A[0] + + return rot,trans,trans_error, s + +def plot_traj(ax,stamps,traj,style,color,label): + """ + Plot a trajectory using matplotlib. + + Input: + ax -- the plot + stamps -- time stamps (1xn) + traj -- trajectory (3xn) + style -- line style + color -- line color + label -- plot legend + + """ + stamps.sort() + interval = numpy.median([s-t for s,t in zip(stamps[1:],stamps[:-1])]) + x = [] + y = [] + last = stamps[0] + for i in range(len(stamps)): + if stamps[i]-last < 2*interval: + x.append(traj[i][0]) + y.append(traj[i][1]) + elif len(x)>0: + ax.plot(x,y,style,color=color,label=label) + label="" + x=[] + y=[] + last= stamps[i] + if len(x)>0: + ax.plot(x,y,style,color=color,label=label) + + diff --git a/thirdparty/tartanair_tools/evaluation/evaluate_kitti.py b/thirdparty/tartanair_tools/evaluation/evaluate_kitti.py new file mode 100644 index 00000000..d6632a9a --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/evaluate_kitti.py @@ -0,0 +1,126 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. +# This is a python reinplementation of the KITTI metric: http://www.cvlibs.net/datasets/kitti/eval_odometry.php +# Cridit: Xiangwei Wang https://github.com/TimingSpace + +import numpy as np +import sys + +def trajectory_distances(poses): + distances = [] + distances.append(0) + for i in range(1,len(poses)): + p1 = poses[i-1] + p2 = poses[i] + delta = p1[0:3,3] - p2[0:3,3] + distances.append(distances[i-1]+np.linalg.norm(delta)) + return distances + +def last_frame_from_segment_length(dist,first_frame,length): + for i in range(first_frame,len(dist)): + if dist[i]>dist[first_frame]+length: + return i + return -1 + +def rotation_error(pose_error): + a = pose_error[0,0] + b = pose_error[1,1] + c = pose_error[2,2] + d = 0.5*(a+b+c-1) + rot_error = np.arccos(max(min(d,1.0),-1.0)) + return rot_error + +def translation_error(pose_error): + dx = pose_error[0,3] + dy = pose_error[1,3] + dz = pose_error[2,3] + return np.sqrt(dx*dx+dy*dy+dz*dz) + +# def line2matrix(pose_line): +# pose_line = np.array(pose_line) +# pose_m = np.matrix(np.eye(4)) +# pose_m[0:3,:] = pose_line.reshape(3,4) +# return pose_m + +def calculate_sequence_error(poses_gt,poses_result,lengths=[10,20,30,40,50,60,70,80]): + # error_vetor + errors = [] + + # paramet + step_size = 1 #10; # every second + num_lengths = len(lengths) + + # import ipdb;ipdb.set_trace() + # pre-compute distances (from ground truth as reference) + dist = trajectory_distances(poses_gt) + # for all start positions do + for first_frame in range(0, len(poses_gt), step_size): + # for all segment lengths do + for i in range(0,num_lengths): + # current length + length = lengths[i]; + + # compute last frame + last_frame = last_frame_from_segment_length(dist,first_frame,length); + # continue, if sequence not long enough + if (last_frame==-1): + continue; + + # compute rotational and translational errors + pose_delta_gt = np.linalg.inv(poses_gt[first_frame]).dot(poses_gt[last_frame]) + pose_delta_result = np.linalg.inv(poses_result[first_frame]).dot(poses_result[last_frame]) + pose_error = np.linalg.inv(pose_delta_result).dot(pose_delta_gt) + r_err = rotation_error(pose_error); + t_err = translation_error(pose_error); + + # compute speed + num_frames = (float)(last_frame-first_frame+1); + speed = length/(0.1*num_frames); + + # write to file + error = [first_frame,r_err/length,t_err/length,length,speed] + errors.append(error) + # return error vector + return errors + +def calculate_ave_errors(errors,lengths=[10,20,30,40,50,60,70,80]): + rot_errors=[] + tra_errors=[] + for length in lengths: + rot_error_each_length =[] + tra_error_each_length =[] + for error in errors: + if abs(error[3]-length)<0.1: + rot_error_each_length.append(error[1]) + tra_error_each_length.append(error[2]) + + if len(rot_error_each_length)==0: + # import ipdb;ipdb.set_trace() + continue + else: + rot_errors.append(sum(rot_error_each_length)/len(rot_error_each_length)) + tra_errors.append(sum(tra_error_each_length)/len(tra_error_each_length)) + return np.array(rot_errors)*180/np.pi, tra_errors + +def evaluate(gt, data,rescale_=False): + lens = [5,10,15,20,25,30,35,40] #[1,2,3,4,5,6] # + errors = calculate_sequence_error(gt, data, lengths=lens) + rot,tra = calculate_ave_errors(errors, lengths=lens) + return np.mean(rot), np.mean(tra) + +def main(): + # usage: python main.py path_to_ground_truth path_to_predict_pose + # load and preprocess data + ground_truth_data = np.loadtxt(sys.argv[1]) + predict_pose__data = np.loadtxt(sys.argv[2]) + errors = calculate_sequence_error(ground_truth_data,predict_pose__data) + rot,tra = calculate_ave_errors(errors) + print(rot,'\n',tra) + #print(error) + # evaluate the vo result + # save and visualization the evaluatation result + +if __name__ == "__main__": + main() + + diff --git a/thirdparty/tartanair_tools/evaluation/evaluate_rpe.py b/thirdparty/tartanair_tools/evaluation/evaluate_rpe.py new file mode 100644 index 00000000..b99dac47 --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/evaluate_rpe.py @@ -0,0 +1,219 @@ +#!/usr/bin/python +# Software License Agreement (BSD License) +# +# Modified by Wenshan Wang +# Copyright (c) 2013, Juergen Sturm, TUM +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of TUM nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +This script computes the relative pose error from the ground truth trajectory +and the estimated trajectory. +""" + +import random +import numpy as np +import sys + +def ominus(a,b): + """ + Compute the relative 3D transformation between a and b. + + Input: + a -- first pose (homogeneous 4x4 matrix) + b -- second pose (homogeneous 4x4 matrix) + + Output: + Relative 3D transformation from a to b. + """ + return np.dot(np.linalg.inv(a),b) + +def compute_distance(transform): + """ + Compute the distance of the translational component of a 4x4 homogeneous matrix. + """ + return np.linalg.norm(transform[0:3,3]) + +def compute_angle(transform): + """ + Compute the rotation angle from a 4x4 homogeneous matrix. + """ + # an invitation to 3-d vision, p 27 + return np.arccos( min(1,max(-1, (np.trace(transform[0:3,0:3]) - 1)/2) )) + +def distances_along_trajectory(traj): + """ + Compute the translational distances along a trajectory. + """ + motion = [ominus(traj[i+1],traj[i]) for i in range(len(traj)-1)] + distances = [0] + sum = 0 + for t in motion: + sum += compute_distance(t) + distances.append(sum) + return distances + + +def evaluate_trajectory(traj_gt, traj_est, param_max_pairs=10000, param_fixed_delta=False, + param_delta=1.00): + """ + Compute the relative pose error between two trajectories. + + Input: + traj_gt -- the first trajectory (ground truth) + traj_est -- the second trajectory (estimated trajectory) + param_max_pairs -- number of relative poses to be evaluated + param_fixed_delta -- false: evaluate over all possible pairs + true: only evaluate over pairs with a given distance (delta) + param_delta -- distance between the evaluated pairs + param_delta_unit -- unit for comparison: + "s": seconds + "m": meters + "rad": radians + "deg": degrees + "f": frames + param_offset -- time offset between two trajectories (to model the delay) + param_scale -- scale to be applied to the second trajectory + + Output: + list of compared poses and the resulting translation and rotation error + """ + + if not param_fixed_delta: + if(param_max_pairs==0 or len(traj_est)param_max_pairs): + pairs = random.sample(pairs,param_max_pairs) + + result = [] + for i,j in pairs: + + error44 = ominus( ominus( traj_est[j], traj_est[i] ), + ominus( traj_gt[j], traj_gt[i] ) ) + + trans = compute_distance(error44) + rot = compute_angle(error44) + + result.append([i,j,trans,rot]) + + if len(result)<2: + raise Exception("Couldn't find pairs between groundtruth and estimated trajectory!") + + return result + +# import argparse +# if __name__ == '__main__': +# random.seed(0) + +# parser = argparse.ArgumentParser(description=''' +# This script computes the relative pose error from the ground truth trajectory and the estimated trajectory. +# ''') +# parser.add_argument('groundtruth_file', help='ground-truth trajectory file (format: "timestamp tx ty tz qx qy qz qw")') +# parser.add_argument('estimated_file', help='estimated trajectory file (format: "timestamp tx ty tz qx qy qz qw")') +# parser.add_argument('--max_pairs', help='maximum number of pose comparisons (default: 10000, set to zero to disable downsampling)', default=10000) +# parser.add_argument('--fixed_delta', help='only consider pose pairs that have a distance of delta delta_unit (e.g., for evaluating the drift per second/meter/radian)', action='store_true') +# parser.add_argument('--delta', help='delta for evaluation (default: 1.0)',default=1.0) +# parser.add_argument('--delta_unit', help='unit of delta (options: \'s\' for seconds, \'m\' for meters, \'rad\' for radians, \'f\' for frames; default: \'s\')',default='s') +# parser.add_argument('--offset', help='time offset between ground-truth and estimated trajectory (default: 0.0)',default=0.0) +# parser.add_argument('--scale', help='scaling factor for the estimated trajectory (default: 1.0)',default=1.0) +# parser.add_argument('--save', help='text file to which the evaluation will be saved (format: stamp_est0 stamp_est1 stamp_gt0 stamp_gt1 trans_error rot_error)') +# parser.add_argument('--plot', help='plot the result to a file (requires --fixed_delta, output format: png)') +# parser.add_argument('--verbose', help='print all evaluation data (otherwise, only the mean translational error measured in meters will be printed)', action='store_true') +# args = parser.parse_args() + +# if args.plot and not args.fixed_delta: +# sys.exit("The '--plot' option can only be used in combination with '--fixed_delta'") + +# traj_gt = np.loadtxt(args.groundtruth_file) +# traj_est = np.loadtxt(args.estimated_file) + +# from trajectory_transform import trajectory_transform +# traj_gt, traj_est = trajectory_transform(traj_gt, traj_est) + +# traj_gt = tf.pos_quats2SE_matrices(traj_gt) +# traj_est = tf.pos_quats2SE_matrices(traj_est) + +# result = evaluate_trajectory(traj_gt, +# traj_est, +# int(args.max_pairs), +# args.fixed_delta, +# float(args.delta), +# args.delta_unit) + +# trans_error = np.array(result)[:,2] +# rot_error = np.array(result)[:,3] + +# if args.save: +# f = open(args.save,"w") +# f.write("\n".join([" ".join(["%f"%v for v in line]) for line in result])) +# f.close() + +# if args.verbose: +# print "compared_pose_pairs %d pairs"%(len(trans_error)) + +# print "translational_error.rmse %f m"%np.sqrt(np.dot(trans_error,trans_error) / len(trans_error)) +# print "translational_error.mean %f m"%np.mean(trans_error) +# print "translational_error.median %f m"%np.median(trans_error) +# print "translational_error.std %f m"%np.std(trans_error) +# print "translational_error.min %f m"%np.min(trans_error) +# print "translational_error.max %f m"%np.max(trans_error) + +# print "rotational_error.rmse %f deg"%(np.sqrt(np.dot(rot_error,rot_error) / len(rot_error)) * 180.0 / np.pi) +# print "rotational_error.mean %f deg"%(np.mean(rot_error) * 180.0 / np.pi) +# print "rotational_error.median %f deg"%(np.median(rot_error) * 180.0 / np.pi) +# print "rotational_error.std %f deg"%(np.std(rot_error) * 180.0 / np.pi) +# print "rotational_error.min %f deg"%(np.min(rot_error) * 180.0 / np.pi) +# print "rotational_error.max %f deg"%(np.max(rot_error) * 180.0 / np.pi) +# else: +# print np.mean(trans_error) + +# import ipdb;ipdb.set_trace() + +# if args.plot: +# import matplotlib +# matplotlib.use('Agg') +# import matplotlib.pyplot as plt +# import matplotlib.pylab as pylab +# fig = plt.figure() +# ax = fig.add_subplot(111) +# ax.plot(stamps - stamps[0],trans_error,'-',color="blue") +# #ax.plot([t for t,e in err_rot],[e for t,e in err_rot],'-',color="red") +# ax.set_xlabel('time [s]') +# ax.set_ylabel('translational error [m]') +# plt.savefig(args.plot,dpi=300) + + diff --git a/thirdparty/tartanair_tools/evaluation/evaluator_base.py b/thirdparty/tartanair_tools/evaluation/evaluator_base.py new file mode 100644 index 00000000..f9748a3f --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/evaluator_base.py @@ -0,0 +1,91 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. + +import numpy as np +from .trajectory_transform import trajectory_transform, rescale +from .transformation import pos_quats2SE_matrices, SE2pos_quat + + +np.set_printoptions(suppress=True, precision=2, threshold=100000) + +def transform_trajs(gt_traj, est_traj, cal_scale): + gt_traj, est_traj = trajectory_transform(gt_traj, est_traj) + if cal_scale : + est_traj, s = rescale(gt_traj, est_traj) + print(' Scale, {}'.format(s)) + else: + s = 1.0 + return gt_traj, est_traj, s + +def quats2SEs(gt_traj, est_traj): + gt_SEs = pos_quats2SE_matrices(gt_traj) + est_SEs = pos_quats2SE_matrices(est_traj) + return gt_SEs, est_SEs + +from .evaluate_ate_scale import align, plot_traj + + +class ATEEvaluator(object): + def __init__(self): + super(ATEEvaluator, self).__init__() + + + def evaluate(self, gt_traj, est_traj, scale): + gt_xyz = np.matrix(gt_traj[:,0:3].transpose()) + est_xyz = np.matrix(est_traj[:, 0:3].transpose()) + + rot, trans, trans_error, s = align(gt_xyz, est_xyz, scale) + print(' ATE scale: {}'.format(s)) + error = np.sqrt(np.dot(trans_error,trans_error) / len(trans_error)) + + # align two trajs + est_SEs = pos_quats2SE_matrices(est_traj) + T = np.eye(4) + T[:3,:3] = rot + T[:3,3:] = trans + T = np.linalg.inv(T) + est_traj_aligned = [] + for se in est_SEs: + se[:3,3] = se[:3,3] * s + se_new = T.dot(se) + se_new = SE2pos_quat(se_new) + est_traj_aligned.append(se_new) + + + return error, gt_traj, est_traj_aligned + +# ======================= + +from .evaluate_rpe import evaluate_trajectory + +class RPEEvaluator(object): + def __init__(self): + super(RPEEvaluator, self).__init__() + + + def evaluate(self, gt_SEs, est_SEs): + result = evaluate_trajectory(gt_SEs, est_SEs) + + trans_error = np.array(result)[:,2] + rot_error = np.array(result)[:,3] + + trans_error_mean = np.mean(trans_error) + rot_error_mean = np.mean(rot_error) + + # import ipdb;ipdb.set_trace() + + return (rot_error_mean, trans_error_mean) + +# ======================= + +from .evaluate_kitti import evaluate as kittievaluate + +class KittiEvaluator(object): + def __init__(self): + super(KittiEvaluator, self).__init__() + + # return rot_error, tra_error + def evaluate(self, gt_SEs, est_SEs): + # trajectory_scale(est_SEs, 0.831984631412) + error = kittievaluate(gt_SEs, est_SEs) + return error diff --git a/thirdparty/tartanair_tools/evaluation/pose_est.txt b/thirdparty/tartanair_tools/evaluation/pose_est.txt new file mode 100644 index 00000000..bf1d957a --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/pose_est.txt @@ -0,0 +1,734 @@ +0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 1.000000000000000000e+00 +-7.763581722974777222e-02 8.129438757896423340e-02 8.294846117496490479e-02 1.040334086665092687e-02 1.041169190809397287e-05 2.011712313020339732e-02 9.997435032193935367e-01 +-1.614615394973635265e-01 1.753936329237417158e-01 1.824119399153587007e-01 2.189289735848180471e-02 3.260965583645257884e-04 4.095062368656528229e-02 9.989212336112042179e-01 +-2.483997135085643793e-01 2.510054263822752985e-01 2.833032081283895498e-01 3.369437576438091830e-02 8.340466259779691837e-04 6.266394019408838556e-02 9.974653986514492310e-01 +-3.529906697922169379e-01 3.595898575063656288e-01 3.870853431034880776e-01 4.637325208655862507e-02 1.227550561596514080e-03 8.501253099674151159e-02 9.952993929278292073e-01 +-4.535691853102751248e-01 4.568637710855560918e-01 4.845526710044738561e-01 5.965438091144881216e-02 1.521359706053023028e-03 1.078180747714191229e-01 9.923781052491449373e-01 +-5.581615826024445282e-01 5.510385940212652045e-01 5.734740478287805310e-01 7.331615232253894943e-02 1.618413853996865165e-03 1.308376388366791765e-01 9.886878357407519191e-01 +-6.897704174794190290e-01 6.581356249561387539e-01 6.748434631430831887e-01 8.658215377582006989e-02 1.708541625585218663e-03 1.538210618132044571e-01 9.842965445244924449e-01 +-8.455515829656050641e-01 7.827321154762114652e-01 7.665332346157245347e-01 9.995978770471897201e-02 1.513542442906467460e-03 1.765521462832924382e-01 9.792012504960488917e-01 +-1.005513256527982735e+00 9.027695237376163195e-01 8.540858013618440880e-01 1.130726715079791306e-01 1.288185412497112490e-03 1.989259590578820736e-01 9.734687286525551819e-01 +-1.185129075147004274e+00 1.021053229676384566e+00 9.391665916590067331e-01 1.257653451526082322e-01 1.150079331193483694e-03 2.206728462822609149e-01 9.672048514541641273e-01 +-1.374462012916290554e+00 1.141221578215573240e+00 1.015970865367560094e+00 1.376554687585733461e-01 1.061026809043993544e-03 2.417534712645754424e-01 9.605233365418593960e-01 +-1.588499030350069452e+00 1.266209135639860373e+00 1.086002959009900071e+00 1.485755038267222716e-01 9.605313046758917573e-04 2.622085642178698661e-01 9.535046055003959520e-01 +-1.818806502634098043e+00 1.383276731247666813e+00 1.140712190299622009e+00 1.584588407539465338e-01 8.681071444247497352e-04 2.817861214627339073e-01 9.463015368426513918e-01 +-2.045776265470826250e+00 1.492418481673508657e+00 1.184797250600713614e+00 1.670675346700424002e-01 8.257189692240109700e-04 3.001841140278199149e-01 9.391364327290262493e-01 +-2.276180491460872535e+00 1.596256008567038975e+00 1.221639715698451978e+00 1.742704915296339196e-01 9.591303608554155227e-04 3.170547184699983312e-01 9.322580994966139789e-01 +-2.506512307163954123e+00 1.697691124429126175e+00 1.253975000882568303e+00 1.801102943798766620e-01 1.308365573539137326e-03 3.320161931722179216e-01 9.259178078324850070e-01 +-2.730647291904825469e+00 1.791590510575493456e+00 1.278466289637631537e+00 1.840968232324677878e-01 1.578886214964081739e-03 3.451396192693618192e-01 9.203175983449257691e-01 +-2.923433144178567922e+00 1.870891735631864616e+00 1.292601088431287737e+00 1.849707697653387994e-01 1.386025599471512292e-03 3.562485413351011987e-01 9.158989209312665691e-01 +-3.077175452596739635e+00 1.933593849915830720e+00 1.299696969678707736e+00 1.854755639593988203e-01 1.868600603979128421e-03 3.650181587589055865e-01 9.123360260273387645e-01 +-3.193939947754621311e+00 1.981891317735233304e+00 1.303578995604927293e+00 1.855183673014065560e-01 3.083188543593773021e-03 3.715047670010525604e-01 9.097019288038555862e-01 +-3.315409474942201840e+00 2.030990137869406187e+00 1.311135170562608199e+00 1.812982113234903048e-01 3.879075462185585434e-03 3.754939783009084153e-01 9.089115129713721819e-01 +-3.457097195304501103e+00 2.079057742802964626e+00 1.323314158036400512e+00 1.751551006930524568e-01 4.849743914728919456e-03 3.771605153527103349e-01 9.094212882393348796e-01 +-3.607751299212842433e+00 2.125597561155946114e+00 1.328744742853992244e+00 1.669760035300219270e-01 5.862731875882476289e-03 3.762797830799659016e-01 9.113167052387843858e-01 +-3.741661109607048896e+00 2.166749128476885389e+00 1.330438836879045406e+00 1.569512452791514689e-01 6.669659372063521142e-03 3.735049313371923141e-01 9.142296515067259710e-01 +-3.860063450797174944e+00 2.199894961373179303e+00 1.333838814317130472e+00 1.454407120026545708e-01 7.241853549464966934e-03 3.691224647884061572e-01 9.179014869378113728e-01 +-3.965440417418732100e+00 2.226800631160249289e+00 1.343206933663203984e+00 1.325379926970463584e-01 7.844176604592478091e-03 3.633626870690228605e-01 9.221386473454279420e-01 +-4.066402862077570290e+00 2.255844838276743314e+00 1.355485145997750829e+00 1.183286632454299964e-01 8.219612003103273987e-03 3.562999831573637755e-01 9.268123073828324898e-01 +-4.169311459254840813e+00 2.289886648958757487e+00 1.371346518212128496e+00 1.032299517681223161e-01 8.406974670792977805e-03 3.479357009271835111e-01 9.317798054429122789e-01 +-4.274304728659573449e+00 2.326110416854968665e+00 1.388732450883825464e+00 8.741415828963333690e-02 8.379913478480226913e-03 3.384163034407642878e-01 9.368900192068824184e-01 +-4.371023610733479003e+00 2.361730196758660583e+00 1.403553973261158161e+00 7.102109638379625056e-02 8.057980014233599719e-03 3.279150071870076122e-01 9.419993613653473430e-01 +-4.459560418429068918e+00 2.395030322184842575e+00 1.416461243442338258e+00 5.420612473697292849e-02 7.365064650816518024e-03 3.164921687723831201e-01 9.470164409778689674e-01 +-4.540001823203836828e+00 2.425599654086818990e+00 1.426464306582395425e+00 3.715621844980641908e-02 6.231494058011067053e-03 3.043837172282954362e-01 9.518041337804227231e-01 +-4.612358115392317437e+00 2.452776723440271756e+00 1.433268633649291468e+00 2.011834412594883451e-02 4.716985069882587492e-03 2.919181785674783702e-01 9.562200316515701015e-01 +-4.676197707866614373e+00 2.476170399256655941e+00 1.437578832081728653e+00 3.272165197888430091e-03 2.840839541992785672e-03 2.793353264558116611e-01 9.601838140965953672e-01 +-4.729394004887086389e+00 2.494799783342323884e+00 1.440516646926108590e+00 -1.318569206037614912e-02 7.089819845754987337e-04 2.668435421441125444e-01 9.636493737582385588e-01 +-4.773843758590919251e+00 2.507891700440353144e+00 1.442752113368175770e+00 -2.903920539287624045e-02 -1.910930719998760402e-03 2.545928327167661376e-01 9.666103197388770107e-01 +-4.810216717409360854e+00 2.516280950884616008e+00 1.445033489495043622e+00 -4.413449361689851524e-02 -5.156598890310192841e-03 2.426934570333589558e-01 9.690848176630005861e-01 +-4.842444961040081708e+00 2.521851936853974241e+00 1.448018661613891700e+00 -5.830208152581990710e-02 -9.081029144956875507e-03 2.314251854411013276e-01 9.710616495485874244e-01 +-4.866759795781309350e+00 2.525786235783391565e+00 1.452406291993692200e+00 -7.126999092386157586e-02 -1.369779941037953253e-02 2.210570242580389144e-01 9.725567772416677803e-01 +-4.884401443052239777e+00 2.527892111796247843e+00 1.457189468992783343e+00 -8.289824316857601072e-02 -1.915495834478810055e-02 2.119194481674736563e-01 9.735764284800602075e-01 +-4.892039541818142823e+00 2.529953841039938478e+00 1.458850563230165820e+00 -9.301414318055745145e-02 -2.547372208527273404e-02 2.043313470160121326e-01 9.741396701707516481e-01 +-4.899106108043921104e+00 2.532639924374405549e+00 1.459694477163018700e+00 -1.016629322170821970e-01 -3.248648335372286700e-02 1.980939191208750672e-01 9.743551761291968649e-01 +-4.913951589168281231e+00 2.534521876501546256e+00 1.461731588944155558e+00 -1.089088070086514509e-01 -4.010769518544383266e-02 1.929507514486798747e-01 9.743203648503796499e-01 +-4.933610942602353333e+00 2.538586854819794958e+00 1.464692314854086463e+00 -1.147749002202129304e-01 -4.828628938072188070e-02 1.886497650383399949e-01 9.741182319926873223e-01 +-4.958440654878941700e+00 2.543277612007893929e+00 1.468203406428834512e+00 -1.194863089348542767e-01 -5.696299705392537938e-02 1.853303060451857998e-01 9.737200862826957959e-01 +-4.990954677322402944e+00 2.549407909844580988e+00 1.471203394844951884e+00 -1.231642486268289260e-01 -6.604007246099961870e-02 1.828656214855920725e-01 9.731543130891747717e-01 +-5.025047938541398196e+00 2.558715939396833505e+00 1.473825988547360355e+00 -1.259017917447793344e-01 -7.542633386954311625e-02 1.811794706028058144e-01 9.724368823910578552e-01 +-5.056480018462073289e+00 2.564807758629558343e+00 1.475891196155413532e+00 -1.278915055890489927e-01 -8.509363100646011313e-02 1.800907271765929685e-01 9.715812114247180942e-01 +-5.086104798580855402e+00 2.569691283527485659e+00 1.477163312790321648e+00 -1.292293462264915427e-01 -9.496559244675582823e-02 1.794984267144049683e-01 9.705985276768369641e-01 +-5.112606255918975329e+00 2.573412687699331514e+00 1.477477854537477153e+00 -1.299627604284677995e-01 -1.049854785309249916e-01 1.792703541166686954e-01 9.695100505118784406e-01 +-5.134905255077595321e+00 2.576288036269610782e+00 1.477239630484135979e+00 -1.302426546338418811e-01 -1.150711451979672811e-01 1.792885473078411618e-01 9.683237916200010398e-01 +-5.153893624298311771e+00 2.578483882124743776e+00 1.476620330702864026e+00 -1.302009236249876412e-01 -1.251474567794172432e-01 1.794546117522611839e-01 9.670479499330235651e-01 +-5.170387700900536565e+00 2.580064156137910292e+00 1.475659244919312441e+00 -1.299670410286786204e-01 -1.351584452176034790e-01 1.796414632746508588e-01 9.656964250670172500e-01 +-5.184181027452599899e+00 2.581160090942109075e+00 1.474565384211478536e+00 -1.296418604936777075e-01 -1.450448905082182272e-01 1.797323884557865681e-01 9.642878788901542153e-01 +-5.193670199816169841e+00 2.581753477051173640e+00 1.473764585350773926e+00 -1.293351330843586777e-01 -1.547441736237192833e-01 1.795981723139647712e-01 9.628452851806021950e-01 +-5.199333265867458032e+00 2.582035217643015024e+00 1.473379856620376183e+00 -1.291569717635498993e-01 -1.641813293619758807e-01 1.791096871363017651e-01 9.613961617381699964e-01 +-5.202331774675752030e+00 2.581664544006828432e+00 1.473864297841081417e+00 -1.292272888139313625e-01 -1.732843541244645513e-01 1.782025435959828374e-01 9.599565502006950357e-01 +-5.206241793394302597e+00 2.582221202370767354e+00 1.474536803626558035e+00 -1.297041040826846792e-01 -1.820029342402989803e-01 1.766310062204095588e-01 9.585682842352059030e-01 +-5.210985438789853319e+00 2.583094789759607490e+00 1.474966989504564285e+00 -1.307007029242959195e-01 -1.902369471614826779e-01 1.743631391815418374e-01 9.572484572619643917e-01 +-5.216251160117276520e+00 2.583977407180919617e+00 1.475366210935058264e+00 -1.323205068189602929e-01 -1.979592096899689679e-01 1.712833846211577193e-01 9.560153302771712269e-01 +-5.222946233934185223e+00 2.586808942321393801e+00 1.472278643001111886e+00 -1.310237157238480776e-01 -2.045421318352779183e-01 1.680589194756306470e-01 9.553802323633658888e-01 +-5.231628991463434630e+00 2.589857794226577248e+00 1.469924268626294328e+00 -1.299914791537154501e-01 -2.105017348685536416e-01 1.642104059553242124e-01 9.548958446152637780e-01 +-5.242168825144799982e+00 2.592841460080200999e+00 1.468451453680363228e+00 -1.292111837068332103e-01 -2.159394456534998452e-01 1.599379638273054072e-01 9.545126345911275623e-01 +-5.253286415437917078e+00 2.595970513784641387e+00 1.467826428868046262e+00 -1.286807950362075514e-01 -2.209464468219945743e-01 1.552757326655797021e-01 9.542081801217947579e-01 +-5.265486490643125350e+00 2.599432535416068557e+00 1.467152445892538015e+00 -1.283580449028720871e-01 -2.256078437309221862e-01 1.503256341714759581e-01 9.539535620795475124e-01 +-5.278931683231727234e+00 2.602917166318048814e+00 1.466546231382643173e+00 -1.282128746978846989e-01 -2.299556577100002053e-01 1.452586887261335946e-01 9.537198972899648686e-01 +-5.294180719114427447e+00 2.606445447497604206e+00 1.466469015635006201e+00 -1.281738649061152646e-01 -2.340465156471444597e-01 1.402375308412729671e-01 9.534815137992896927e-01 +-5.312463140471031409e+00 2.609762618928178846e+00 1.467229721920807917e+00 -1.281673290126850717e-01 -2.379196270513008749e-01 1.354483648227918224e-01 9.532161404201969779e-01 +-5.335824573770256762e+00 2.613782928396423788e+00 1.469043526066431404e+00 -1.281189173127078307e-01 -2.416006561296493993e-01 1.310745825024880462e-01 9.529081867508989445e-01 +-5.363259463899353818e+00 2.617851172109413760e+00 1.471131569469693146e+00 -1.280001689701116829e-01 -2.451563298382018197e-01 1.272199112235238294e-01 9.525383605911197371e-01 +-5.395411344443875379e+00 2.623212074403216576e+00 1.472248485541352014e+00 -1.277061673877437353e-01 -2.486749857660476848e-01 1.239774978389931309e-01 9.520931477990380865e-01 +-5.426128985633432933e+00 2.629509303787030738e+00 1.472886535222979631e+00 -1.272485630563925385e-01 -2.522551300913905559e-01 1.214382283999674711e-01 9.515396978379735415e-01 +-5.452652039613852253e+00 2.636104068030554970e+00 1.473580777471113379e+00 -1.265948281006319676e-01 -2.558473110227643121e-01 1.197640264486956596e-01 9.508797857273025844e-01 +-5.472306931796175888e+00 2.641829902721481105e+00 1.473873320383656482e+00 -1.256680327166950772e-01 -2.594724547148206106e-01 1.191192015543088567e-01 9.501010974737226222e-01 +-5.492777734979259918e+00 2.648747575407238042e+00 1.473959231064704500e+00 -1.244619490961244718e-01 -2.631815118648019314e-01 1.198660794814391944e-01 9.491452656899548312e-01 +-5.517309030986859320e+00 2.656660512910526073e+00 1.473909882633906099e+00 -1.229588360211476133e-01 -2.670171479008756621e-01 1.220429262392918324e-01 9.479917596835117921e-01 +-5.548501007034063015e+00 2.665854748006321273e+00 1.473972335360250963e+00 -1.210092705313811912e-01 -2.710428319108487139e-01 1.256652081050372294e-01 9.466259477090569474e-01 +-5.582659995289544597e+00 2.676549627306799017e+00 1.473410706142274762e+00 -1.184397636966367240e-01 -2.754753876080917596e-01 1.309016614379956145e-01 9.449603036347121732e-01 +-5.618542000812452919e+00 2.688346823076197545e+00 1.473815846312817035e+00 -1.152002555259703243e-01 -2.803413333399834562e-01 1.378292494260122403e-01 9.429425343495222434e-01 +-5.658800331255713800e+00 2.701072122771759787e+00 1.476535456259537193e+00 -1.111809696889956428e-01 -2.856535347335066866e-01 1.466344650116992443e-01 9.404993667055564499e-01 +-5.723162393434017226e+00 2.711850001969680513e+00 1.472010511799559440e+00 -9.645960069527406699e-02 -2.899736214586458583e-01 1.603600069216811475e-01 9.385602750540950057e-01 +-5.789886399037957432e+00 2.724914339993221191e+00 1.467559068109455245e+00 -7.961234498813223037e-02 -2.944040355605375137e-01 1.761043348999501434e-01 9.359355020986513951e-01 +-5.857801027110975056e+00 2.744695431095274696e+00 1.463945204565434421e+00 -6.075934553055403753e-02 -2.988044004969594991e-01 1.932606735103165330e-01 9.325633481775772449e-01 +-5.928718842828847535e+00 2.767996982110530357e+00 1.460667842684073348e+00 -4.041363023151172545e-02 -3.030217965527199353e-01 2.116615388665777919e-01 9.283015556563347648e-01 +-6.002894602593839224e+00 2.792273267216474952e+00 1.458903479340398990e+00 -1.906988129351004299e-02 -3.068992941963777921e-01 2.311642366215765632e-01 9.230450172788735586e-01 +-6.080423592056320103e+00 2.816755985211592872e+00 1.457840699040749088e+00 2.989901128715029190e-03 -3.103978479901604026e-01 2.515253384808229797e-01 9.167219268166566515e-01 +-6.159821503433136058e+00 2.842283901774936172e+00 1.456838883270557883e+00 2.555327984341005526e-02 -3.134828696451882335e-01 2.725158317531349850e-01 9.092911994515439078e-01 +-6.242220272728821406e+00 2.869195785452348435e+00 1.457031532612975910e+00 4.835426017865434439e-02 -3.160287452290629906e-01 2.938780975588026201e-01 9.007903192073739573e-01 +-6.328228979922918107e+00 2.897916089429688480e+00 1.459431885899282078e+00 7.112281369337754289e-02 -3.179164658780405661e-01 3.153813211739048272e-01 8.912940786818626115e-01 +-6.418319400752959147e+00 2.929363133766030192e+00 1.463556676178051852e+00 9.361902027674687266e-02 -3.191164931957644613e-01 3.367341951773196729e-01 8.809143376209914722e-01 +-6.512459485064193032e+00 2.961652060875547221e+00 1.469992759476173250e+00 1.154273123828760544e-01 -3.196110203343623946e-01 3.576625340537895603e-01 8.698291177469383850e-01 +-6.608705668912721265e+00 2.993374042313872163e+00 1.477422440200679254e+00 1.362564011417555232e-01 -3.194120827828730858e-01 3.779349820944927774e-01 8.582395397556208394e-01 +-6.708860129414741635e+00 3.029684950161678270e+00 1.483726567384882733e+00 1.557847355957741042e-01 -3.186315622378103063e-01 3.972704498662247841e-01 8.463929817961677315e-01 +-6.819298594650499368e+00 3.074051487095454505e+00 1.490085988826882257e+00 1.736994998816114855e-01 -3.172153833985199012e-01 4.153375084553274088e-01 8.346840542764281112e-01 +-6.937727501343463388e+00 3.123999412892846994e+00 1.495942713530356682e+00 1.897426385614484623e-01 -3.152290908872911745e-01 4.316833056047169603e-01 8.235761676614492544e-01 +-7.053690389257425863e+00 3.175431624220932392e+00 1.500371635520052482e+00 2.035718323494609405e-01 -3.128428333350659618e-01 4.460332176324769415e-01 8.134753052567540443e-01 +-7.160507266271090465e+00 3.219836099753031089e+00 1.503678186645701187e+00 2.147192789143497760e-01 -3.101588794608615141e-01 4.586560715210674100e-01 8.045691677036902467e-01 +-7.263857222743489217e+00 3.259420686638322184e+00 1.507104829137044577e+00 2.230030551458123678e-01 -3.071117296537569374e-01 4.694030734605031951e-01 7.972531801455003952e-01 +-7.379427554787534760e+00 3.303978953117806316e+00 1.512684161807263727e+00 2.285458026868785741e-01 -3.033655638342385719e-01 4.783511397594756853e-01 7.917803892531537491e-01 +-7.513956051602586506e+00 3.354457427853559270e+00 1.517813172094303109e+00 2.313569936374561264e-01 -2.988858572686310944e-01 4.853137690080703837e-01 7.884234824257249086e-01 +-7.647871124811962851e+00 3.403524157911047343e+00 1.519694781159322883e+00 2.307807859810244722e-01 -2.941287420864104329e-01 4.897210142813168132e-01 7.876558226717300659e-01 +-7.783024520160962467e+00 3.454887356183196978e+00 1.531881838661782735e+00 2.270182624484105294e-01 -2.889180509553187504e-01 4.918595901670846371e-01 7.893434444840518038e-01 +-7.932927031712694088e+00 3.515541344819415048e+00 1.544813960111571349e+00 2.209137782161527952e-01 -2.832097413707863054e-01 4.918438846262578878e-01 7.931448797570244125e-01 +-8.066793397270458854e+00 3.569413410737276582e+00 1.559274798339227663e+00 2.119618830049600222e-01 -2.773903912958500806e-01 4.906034406410121340e-01 7.983951694859114934e-01 +-8.192223267129946862e+00 3.619156454846514492e+00 1.574389835259532466e+00 2.007164604924963069e-01 -2.714268003444554322e-01 4.875667565567802231e-01 8.051825387388809041e-01 +-8.320078886071526014e+00 3.669773930832634701e+00 1.589713284153562167e+00 1.873456602548720096e-01 -2.654088840600973831e-01 4.830340534420075049e-01 8.131037354177889087e-01 +-8.445641803750774557e+00 3.718161069698102228e+00 1.602382435863983989e+00 1.722686950193424715e-01 -2.592978863788403254e-01 4.770453874402176830e-01 8.218976054209284898e-01 +-8.585898597663639720e+00 3.763842337255594028e+00 1.612724215029670782e+00 1.559540902868197521e-01 -2.529943279552718249e-01 4.697196254227078427e-01 8.312854751181643076e-01 +-8.744284886021782555e+00 3.810431377428940003e+00 1.623718323368587235e+00 1.385303921116263770e-01 -2.465440258096578408e-01 4.612076909196240471e-01 8.410188561040446986e-01 +-8.917256787043321253e+00 3.857984143852772885e+00 1.635529520697025729e+00 1.200997614827219034e-01 -2.400285635394314998e-01 4.518427327995526710e-01 8.507645647184876037e-01 +-9.104064759810293950e+00 3.909468736568438185e+00 1.647792240600521207e+00 1.010256813838104617e-01 -2.334802681253919932e-01 4.416485369603997957e-01 8.603645783314409767e-01 +-9.301241223158305260e+00 3.966133280590436350e+00 1.659879276563957395e+00 8.162298523277151940e-02 -2.270393438443374656e-01 4.308338925838269828e-01 8.695819940915584523e-01 +-9.506898456077562898e+00 4.033050506019718817e+00 1.671615796186202152e+00 6.232921915732245188e-02 -2.207809463892332902e-01 4.195279425445178068e-01 8.782750198852098400e-01 +-9.719084547238489691e+00 4.107758244306594975e+00 1.683041549236502066e+00 4.339485462197354565e-02 -2.147223909901595229e-01 4.081630697574083477e-01 8.862358301817121475e-01 +-9.937901626828326229e+00 4.184882732919266601e+00 1.691597128612665424e+00 2.514333870120135858e-02 -2.090149953532211835e-01 3.970576489093294303e-01 8.933228028578739099e-01 +-1.016759103732679392e+01 4.263001199913111883e+00 1.695061943809942129e+00 7.951056979035085390e-03 -2.037524638280196476e-01 3.863944356921051870e-01 8.995114907978111196e-01 +-1.040311776555026668e+01 4.342138223454597323e+00 1.694155376650493539e+00 -7.860991495868187989e-03 -1.991039859389698297e-01 3.761993446063320312e-01 9.048589492432858039e-01 +-1.062897301257094007e+01 4.421929781002599036e+00 1.690288951959063590e+00 -2.214107243025818447e-02 -1.953405400448643969e-01 3.664771572666042365e-01 9.094207967402290205e-01 +-1.083888411301165178e+01 4.502998187798571195e+00 1.686517435052399483e+00 -3.432563094326723102e-02 -1.924284141359653699e-01 3.578962584641444677e-01 9.130734760142072970e-01 +-1.102600989759129213e+01 4.574895040257780821e+00 1.683943445938448136e+00 -4.432764650310910826e-02 -1.905976866897620137e-01 3.511897429252484604e-01 9.156272141432794109e-01 +-1.119162909577845610e+01 4.637566012598074217e+00 1.683328669899319951e+00 -5.190637318312452120e-02 -1.897319204890198785e-01 3.464870459511551481e-01 9.171990500328939255e-01 +-1.138509586620138769e+01 4.700995911950154316e+00 1.682164000735672182e+00 -5.716773658474903069e-02 -1.900562658324461418e-01 3.437203900201822315e-01 9.178597923492943789e-01 +-1.158554687652896398e+01 4.773839985834662514e+00 1.684945256451874096e+00 -5.996103732729100855e-02 -1.911621616282371816e-01 3.424860699307142875e-01 9.179133040169402680e-01 +-1.177760597264674303e+01 4.855169503782111207e+00 1.688083280889883353e+00 -6.048066505920299957e-02 -1.931844251355316622e-01 3.427646024985401829e-01 9.173517037762234372e-01 +-1.196887591957389496e+01 4.947745171815075338e+00 1.686750522816761855e+00 -5.925859327901381729e-02 -1.960387045525514016e-01 3.442936519395072281e-01 9.162526822346890309e-01 +-1.216992391604054902e+01 5.054905297112563645e+00 1.685436264709414989e+00 -5.622420424806187644e-02 -1.994930407666681560e-01 3.469751204847852932e-01 9.146854551281152768e-01 +-1.236532759982683061e+01 5.162857071153237776e+00 1.682019361756213582e+00 -5.158909614579330200e-02 -2.035015282505595879e-01 3.506607040282821997e-01 9.126678623466392137e-01 +-1.256170608523899901e+01 5.273156950802071030e+00 1.679515879409670953e+00 -4.537404264791386477e-02 -2.079235185402558694e-01 3.553344735306013802e-01 9.101902459545322399e-01 +-1.276708765983067906e+01 5.389368126411258508e+00 1.681734725436552669e+00 -3.773606152303884964e-02 -2.125714885631528328e-01 3.607183884419826736e-01 9.073430853038946253e-01 +-1.297045639587896915e+01 5.502656323061654753e+00 1.684277003464522693e+00 -2.895915841600426449e-02 -2.175540603194260902e-01 3.667778982942412891e-01 9.040494676300264709e-01 +-1.316619284720094640e+01 5.616050585154817476e+00 1.685634018354128516e+00 -1.912370531618038869e-02 -2.226372597372509310e-01 3.730394864934088450e-01 9.005044928755971956e-01 +-1.337143560244176044e+01 5.735008513802350549e+00 1.690148906924720640e+00 -8.392904909194753849e-03 -2.277444471868876330e-01 3.796126924332511310e-01 8.966359897929240264e-01 +-1.356737765708902188e+01 5.849611986405886199e+00 1.694239201507259596e+00 3.188069272633895900e-03 -2.328242933347296761e-01 3.861322106115112618e-01 8.925718311500835389e-01 +-1.377000282528432784e+01 5.965616664818147896e+00 1.699851328706560638e+00 1.545742103295346184e-02 -2.377059136115166060e-01 3.925069498358597642e-01 8.883665491224195243e-01 +-1.398212489561399607e+01 6.084928747493433043e+00 1.708285859510020321e+00 2.820644182687547311e-02 -2.423252529499348162e-01 3.987638062806674322e-01 8.840080159246346270e-01 +-1.420648560532310078e+01 6.210423501976889860e+00 1.718109657231867038e+00 4.128077843900963134e-02 -2.466187100076117078e-01 4.048654964394661215e-01 8.795219754325778183e-01 +-1.443425241573653572e+01 6.334786491546755549e+00 1.725589570138854167e+00 5.455567918078327305e-02 -2.505771213294181732e-01 4.106165240693651630e-01 8.750021179724133402e-01 +-1.466078662471714722e+01 6.456107463720189621e+00 1.731439103688600323e+00 6.788851507020579601e-02 -2.541798207114213670e-01 4.158866153694868451e-01 8.705296904758311749e-01 +-1.488285297923898121e+01 6.573529320482816907e+00 1.737718214085419266e+00 8.109585000858207660e-02 -2.573371237995916716e-01 4.204963649265053838e-01 8.662469212230400339e-01 +-1.509735422230190238e+01 6.686039798413209390e+00 1.743139241988748367e+00 9.393535441045894330e-02 -2.599591505149226878e-01 4.243821918820579464e-01 8.622627143897424462e-01 +-1.530865095285013311e+01 6.796819388747013413e+00 1.746061735856029085e+00 1.063152694493233186e-01 -2.619316692924129608e-01 4.275231495756733335e-01 8.586691296852853039e-01 +-1.551262471361659934e+01 6.907480535836007185e+00 1.748239987247944383e+00 1.182349415536220888e-01 -2.632263886307654177e-01 4.300142524946435896e-01 8.554647568458139117e-01 +-1.570625846627583577e+01 7.013312466228680542e+00 1.750445888451903187e+00 1.298043062854738749e-01 -2.639090550059828288e-01 4.318805497222688583e-01 8.526323214820138441e-01 +-1.589019998778768716e+01 7.112664845566693650e+00 1.752781886349465967e+00 1.409289133858263876e-01 -2.641656477315370011e-01 4.330758048961919071e-01 8.501768791463034658e-01 +-1.606792120950874647e+01 7.208294803460730371e+00 1.754591869893346701e+00 1.517765163723192312e-01 -2.638692742451970163e-01 4.336451467018893058e-01 8.481088428129829326e-01 +-1.624434227101607320e+01 7.303142846534119492e+00 1.753898109638208691e+00 1.623957051178717692e-01 -2.630526253297322259e-01 4.335576118085632813e-01 8.464387588780707405e-01 +-1.641625602811456019e+01 7.395043159563359225e+00 1.751152354780340259e+00 1.726525697619735733e-01 -2.619629885775675571e-01 4.328739764729817585e-01 8.450955121849976770e-01 +-1.658587085178702480e+01 7.485826733257320953e+00 1.748231259560814044e+00 1.826036761368338701e-01 -2.606393656664650615e-01 4.315508758716597448e-01 8.440892646836253288e-01 +-1.675089644930930177e+01 7.575510349925608011e+00 1.745856667694209330e+00 1.922807357009022056e-01 -2.591184385917666422e-01 4.297045137176721541e-01 8.433502304484872258e-01 +-1.691506089922895484e+01 7.665309506093168856e+00 1.743384547774412763e+00 2.017770353694364749e-01 -2.575116521304156580e-01 4.273549743327898498e-01 8.428174999857650507e-01 +-1.708644637763754659e+01 7.758788866789966043e+00 1.742004140810507806e+00 2.111321666661664098e-01 -2.558397527854995857e-01 4.245088266948168765e-01 8.424733385149421050e-01 +-1.726784494652930135e+01 7.856822001082897522e+00 1.742654404360780562e+00 2.202197341042913814e-01 -2.541798948408322545e-01 4.211774153635236551e-01 8.423213530536949323e-01 +-1.746024801472902865e+01 7.960010265021137954e+00 1.745074856908168881e+00 2.289213759479810650e-01 -2.526004026647560297e-01 4.175357519182459343e-01 8.422895932772127559e-01 +-1.766654731231349373e+01 8.070327666174712533e+00 1.749793661338604478e+00 2.372063226794104418e-01 -2.511936926804049786e-01 4.136414953630123126e-01 8.423392565676695032e-01 +-1.787788669118211615e+01 8.183003558841669189e+00 1.755478918113403175e+00 2.450457413536536733e-01 -2.501033031262356321e-01 4.096916862187967578e-01 8.423499753459694483e-01 +-1.809178068879210954e+01 8.297254115051348577e+00 1.760518962209867366e+00 2.524429972134340505e-01 -2.493763715999471331e-01 4.056703627689585701e-01 8.423273410439073849e-01 +-1.829889634534535148e+01 8.414415868617682648e+00 1.763164725088491425e+00 2.592251936228366360e-01 -2.490581846075268502e-01 4.017012901080917464e-01 8.422637539869913814e-01 +-1.851064610958139767e+01 8.534587540429054542e+00 1.764080181755627086e+00 2.655126382578260613e-01 -2.491929627978202721e-01 3.976523144453786296e-01 8.421866733400295013e-01 +-1.872454699617393103e+01 8.657280115236002160e+00 1.765527871483244526e+00 2.713811710415635625e-01 -2.498018764759534494e-01 3.935295657386952417e-01 8.420722093215934345e-01 +-1.894476973094467809e+01 8.784598810057248741e+00 1.768893760754383537e+00 2.767423065037515340e-01 -2.509284107718010581e-01 3.893340918734590206e-01 8.419426592142716936e-01 +-1.916930753403601884e+01 8.909285765942943414e+00 1.783316449746438659e+00 2.754078127414572585e-01 -2.555650128083557515e-01 3.828539219274156302e-01 8.439548559210982015e-01 +-1.939833876380693667e+01 9.043023693463442925e+00 1.795814343152166925e+00 2.741002434342232896e-01 -2.604431742157352625e-01 3.764380432859956715e-01 8.457734172403018613e-01 +-1.963030247248972771e+01 9.185783372552252857e+00 1.806329673449146300e+00 2.727671470290222167e-01 -2.654510008092491047e-01 3.701835801397498904e-01 8.474065255370455407e-01 +-1.985929403658107972e+01 9.327231473640164694e+00 1.814036488740335740e+00 2.714815194294271095e-01 -2.705141545889362398e-01 3.640393622045553501e-01 8.488787256893001176e-01 +-2.008724920614000098e+01 9.470197801790330772e+00 1.819776077373240097e+00 2.702972236686065344e-01 -2.755438478847290207e-01 3.581381006992591653e-01 8.501481949323179688e-01 +-2.032193039518956112e+01 9.621574230777977021e+00 1.825137553906702736e+00 2.692228019766066960e-01 -2.804239749088110467e-01 3.526741685036900997e-01 8.511769884460007596e-01 +-2.055983410568753911e+01 9.794256163438852525e+00 1.827306526060864522e+00 2.682162956675854248e-01 -2.850021063575245428e-01 3.477638855419329378e-01 8.519941087514807387e-01 +-2.080293224004554631e+01 9.972464334757884075e+00 1.829046400636300307e+00 2.672929664477728950e-01 -2.892413510317480285e-01 3.434828989686284917e-01 8.525920906990737125e-01 +-2.104319455191703980e+01 1.015193624681640117e+01 1.830505407648819860e+00 2.665293772039856735e-01 -2.930953321927718958e-01 3.398652204467554339e-01 8.529646562564245915e-01 +-2.127315204145920546e+01 1.034196338290001549e+01 1.829235382877234306e+00 2.661559915932656395e-01 -2.962545926634149174e-01 3.368958021106880918e-01 8.531677962679651284e-01 +-2.149062860136037401e+01 1.053373496479204618e+01 1.827213082327507676e+00 2.661038993072872283e-01 -2.986506387292243714e-01 3.347622233780889744e-01 8.531885073889062809e-01 +-2.171292379071395828e+01 1.072679453505857339e+01 1.826920523683371211e+00 2.661970591574436273e-01 -3.001603278758976923e-01 3.337948908485642852e-01 8.530086441499495908e-01 +-2.189600021112985573e+01 1.091582039776040247e+01 1.831307815889416490e+00 2.661770342769272935e-01 -3.005621832023218087e-01 3.342485374222869399e-01 8.526957074314620577e-01 +-2.206506251410940322e+01 1.109854080964264256e+01 1.836749905245590231e+00 2.663409260383603483e-01 -2.999053713265300014e-01 3.355388451102992997e-01 8.523689739125704934e-01 +-2.221763032385653958e+01 1.127820034525780635e+01 1.843343858713348604e+00 2.667725878069750478e-01 -2.981830404836873227e-01 3.379075340574845820e-01 8.519023768153046738e-01 +-2.234894315407058230e+01 1.147270415594502246e+01 1.843866628129394725e+00 2.676971524061693697e-01 -2.950622061617062530e-01 3.413938183935630866e-01 8.513088127639103497e-01 +-2.247386418036266420e+01 1.168154878226672722e+01 1.838370263703727359e+00 2.688546026644202946e-01 -2.906278576088964782e-01 3.454956517088636492e-01 8.508144985039610697e-01 +-2.259389337586892665e+01 1.190418644415488103e+01 1.838890700189365734e+00 2.593184761901075053e-01 -2.888925775979807042e-01 3.457696129264617446e-01 8.542471993748459447e-01 +-2.267702201622588731e+01 1.216089715596706355e+01 1.843454210563671092e+00 2.478898442015371739e-01 -2.860717404439759859e-01 3.474433750659513542e-01 8.579024277992634007e-01 +-2.274279138435072767e+01 1.244641240095573664e+01 1.844891758709419571e+00 2.350113954258568061e-01 -2.820010737368858766e-01 3.503205816576961951e-01 8.616962368834414354e-01 +-2.278776095047748029e+01 1.274748733955873803e+01 1.835676297077167174e+00 2.202462408517593673e-01 -2.770604558117971128e-01 3.543508626105592030e-01 8.655428624579093455e-01 +-2.279386004297854740e+01 1.306813583639917020e+01 1.834061530233466852e+00 2.036987851021139495e-01 -2.712513536126683333e-01 3.588190722062826188e-01 8.695851084366361672e-01 +-2.278229110269767332e+01 1.337783685125774547e+01 1.836618388344035457e+00 1.856512666883281815e-01 -2.643068830537648739e-01 3.638748649299665128e-01 8.736535110686377559e-01 +-2.277482624181896043e+01 1.367788348151518818e+01 1.843272471041611071e+00 1.662779501905558566e-01 -2.563450872855653762e-01 3.691014452839521676e-01 8.777259605980322066e-01 +-2.277517771992877016e+01 1.396731596792628061e+01 1.848943435838783289e+00 1.459242359544663803e-01 -2.476261045319048115e-01 3.742100104701540642e-01 8.816769275250099236e-01 +-2.277891014895916655e+01 1.424863148173696814e+01 1.855507995309751523e+00 1.248368063514628812e-01 -2.381565662526234917e-01 3.797117746949031369e-01 8.851644458579459585e-01 +-2.278123831349811113e+01 1.452426181633606639e+01 1.868045646144445682e+00 1.032021173666537867e-01 -2.278694164594527172e-01 3.852498782419169210e-01 8.882608259442732468e-01 +-2.279374700624046923e+01 1.481405841726335737e+01 1.886702130759408291e+00 8.099637708244554479e-02 -2.170287580511503500e-01 3.911035793876907474e-01 8.907165682039777099e-01 +-2.281929122668881504e+01 1.511389860255536099e+01 1.909525084692540009e+00 5.810858941600706429e-02 -2.058242624457075065e-01 3.971769791025749341e-01 8.924741634270476620e-01 +-2.286619277585237953e+01 1.543078205055002883e+01 1.936867770270033873e+00 3.522591846294927803e-02 -1.941157524976541426e-01 4.032522840365893591e-01 8.935690979229948816e-01 +-2.292728992030420443e+01 1.575137801941480475e+01 1.967793013318889006e+00 1.274691221836536832e-02 -1.820988605748549427e-01 4.089524268852030020e-01 8.941114926427708998e-01 +-2.299970283838371543e+01 1.607013826214909002e+01 2.003532377978304080e+00 -9.192614801675663347e-03 -1.696025980915364106e-01 4.142256496517094932e-01 8.941853775339785315e-01 +-2.308401849355340474e+01 1.639451031089354416e+01 2.044617845076738050e+00 -3.079224063408317683e-02 -1.570274799098854701e-01 4.190687514791211488e-01 8.937424258576105451e-01 +-2.317791519790469579e+01 1.671692564319279484e+01 2.086556150440285418e+00 -5.170548063332913724e-02 -1.445299529190750831e-01 4.234558570874848993e-01 8.928172885769531941e-01 +-2.328381015351661532e+01 1.704096193805269266e+01 2.128948609238156653e+00 -7.189672916997863483e-02 -1.323312869182792229e-01 4.270045605427215119e-01 8.916200578594382087e-01 +-2.340427795004438138e+01 1.735701626761366967e+01 2.171373466696040477e+00 -9.112431622345168458e-02 -1.205138629086791729e-01 4.296235839130483902e-01 8.902787695180095495e-01 +-2.353721495216070636e+01 1.764163672899979218e+01 2.210276193991378424e+00 -1.088210540981210811e-01 -1.092261746711385290e-01 4.313071902192137652e-01 8.889328804280178797e-01 +-2.368482889535566827e+01 1.788736550815216830e+01 2.241025979305187654e+00 -1.249783686403358601e-01 -9.859504380821511316e-02 4.321472169235637262e-01 8.876418983541274343e-01 +-2.384607928896862816e+01 1.811242521096227520e+01 2.266084136725431186e+00 -1.394825025042187583e-01 -8.852640207265864702e-02 4.321040839500001618e-01 8.865628536497245360e-01 +-2.401887021275577538e+01 1.831890565421714356e+01 2.279919748837222038e+00 -1.522484236699693239e-01 -7.954755114421421802e-02 4.316803821504608396e-01 8.855193733080354290e-01 +-2.417563814101417563e+01 1.849465333577828829e+01 2.280101357735958345e+00 -1.568609837457968781e-01 -6.905650246495133315e-02 4.320591088014251735e-01 8.854098853287528659e-01 +-2.435465239258103409e+01 1.866788034911684591e+01 2.278833551147209313e+00 -1.607272140386094283e-01 -6.017316194805825968e-02 4.319610751780899593e-01 8.854126046456390897e-01 +-2.456409566518592769e+01 1.884827946901418727e+01 2.269796614147971958e+00 -1.636609697667866792e-01 -5.291919348364309411e-02 4.311929497177032777e-01 8.857128064040995508e-01 +-2.479778785919083361e+01 1.903629896227497653e+01 2.257981623479938804e+00 -1.659125060591743195e-01 -4.713767011932128853e-02 4.300026166831247831e-01 8.861990328509232739e-01 +-2.505276016903864189e+01 1.922914089322856057e+01 2.243173278804790449e+00 -1.677053219712714149e-01 -4.237869624486044484e-02 4.284738455514192079e-01 8.868421699997788288e-01 +-2.531606684592797407e+01 1.942574769930528333e+01 2.229085231275929058e+00 -1.691240220535058791e-01 -3.869162175143402160e-02 4.265967679199939577e-01 8.876458319017992427e-01 +-2.557257251407279952e+01 1.962250513150229736e+01 2.216540469105335198e+00 -1.700231185885573981e-01 -3.605937356402070387e-02 4.245757510827790626e-01 8.885534334973053117e-01 +-2.580221087760002874e+01 1.982022611720514860e+01 2.213541204118973926e+00 -1.706118174258889064e-01 -3.421548493935728380e-02 4.221743612690299075e-01 8.896570216912565998e-01 +-2.601146817578661441e+01 2.002178072754179183e+01 2.220440591652892426e+00 -1.708795840907891550e-01 -3.305780614654894867e-02 4.195332938165493575e-01 8.908979080478455215e-01 +-2.620146402382770745e+01 2.022263752058559660e+01 2.232834173233681163e+00 -1.707515192904049961e-01 -3.259258493898324616e-02 4.166296946298410631e-01 8.923011074035356316e-01 +-2.637627819712720978e+01 2.042627191949194554e+01 2.246709810052124556e+00 -1.704933168163576263e-01 -3.283554693023437582e-02 4.135249830121538461e-01 8.937845782005444661e-01 +-2.654141434367915409e+01 2.064312858172237952e+01 2.261016826810119174e+00 -1.699567631640833132e-01 -3.375044009679307316e-02 4.102752691268951035e-01 8.953489432173035167e-01 +-2.669147582367332916e+01 2.090214578367661247e+01 2.266700491683564245e+00 -1.690759921526795440e-01 -3.505602877705428499e-02 4.072087389723742512e-01 8.968641789317577384e-01 +-2.680711447038204653e+01 2.118769864213084730e+01 2.259189892130341271e+00 -1.681949656527562675e-01 -3.650877260619080772e-02 4.037426557047869569e-01 8.985373429708651827e-01 +-2.691264022015269930e+01 2.147122141299361786e+01 2.251254662706501097e+00 -1.673685360070890360e-01 -3.799697171692978381e-02 4.002503107457208720e-01 9.001908829296069170e-01 +-2.701700745394519387e+01 2.175605453038072312e+01 2.244111561578600700e+00 -1.666208604647388680e-01 -3.938839449346565741e-02 3.967915708431682953e-01 9.017995479560309002e-01 +-2.711597343636304203e+01 2.203754618878080151e+01 2.239399721771621277e+00 -1.660184516917547204e-01 -4.057493926753620583e-02 3.935196243600725396e-01 9.032905269722538710e-01 +-2.721313862380371518e+01 2.231502709860468059e+01 2.233579569352742045e+00 -1.655366737945723477e-01 -4.146849096221055797e-02 3.903769855378326770e-01 9.047008969436354242e-01 +-2.730451173334633808e+01 2.258723126943073822e+01 2.232524467267274826e+00 -1.652420270226250820e-01 -4.183748958383041311e-02 3.873398158884339693e-01 9.060422117107009843e-01 +-2.739618781129729186e+01 2.285659210566472765e+01 2.229679291440306965e+00 -1.651158750932687769e-01 -4.190338686780778477e-02 3.845494507040361776e-01 9.072499716299705641e-01 +-2.747385408025323983e+01 2.309855032345035397e+01 2.227974427794786827e+00 -1.632434010926707146e-01 -4.056829921507414810e-02 3.822183543045849508e-01 9.086335181036162556e-01 +-2.750097978566391532e+01 2.334479347695600993e+01 2.221391878575035950e+00 -1.621176179697699782e-01 -3.882819126368952656e-02 3.796792465634049041e-01 9.099746408228959194e-01 +-2.726825350965150818e+01 2.325151116060946777e+01 2.175983573215688693e+00 -1.613709937062294542e-01 -3.628260994147344126e-02 3.772982732247785465e-01 9.112019044525625500e-01 +-2.702456224413602115e+01 2.309912761978292295e+01 2.139766417121252040e+00 -1.613481927529301363e-01 -3.349904736413328310e-02 3.751107976647562459e-01 9.122151078617489750e-01 +-2.679101439840390597e+01 2.293399738099144969e+01 2.103119306761279450e+00 -1.616097877716584919e-01 -3.051899457695839493e-02 3.729867941334186754e-01 9.131438330849267482e-01 +-2.657740017191866500e+01 2.277437930122923149e+01 2.078001530922096940e+00 -1.620419907806670556e-01 -2.735605387094369040e-02 3.708395914350989253e-01 9.140415652853018935e-01 +-2.637159897173790313e+01 2.262100277940090010e+01 2.066049215829654173e+00 -1.627234156896967820e-01 -2.407343051419220947e-02 3.688004373214123222e-01 9.148375486076620877e-01 +-2.615837650587571872e+01 2.247488982876452113e+01 2.071833704459263625e+00 -1.635572428108897081e-01 -2.066514976553302310e-02 3.666721118914089139e-01 9.156273725873216307e-01 +-2.594072159916872522e+01 2.231161067952020360e+01 2.083107860750283979e+00 -1.646165804832455115e-01 -1.722983316112723304e-02 3.645091161472031605e-01 9.163719516309467572e-01 +-2.574886541918168348e+01 2.215301706047239350e+01 2.091090146796715121e+00 -1.658629634766780880e-01 -1.383545216156034825e-02 3.623977673111308251e-01 9.170419007802971256e-01 +-2.556440423704056997e+01 2.198430157723035450e+01 2.098127451992665815e+00 -1.672358011107535902e-01 -1.058012178033332536e-02 3.600494200502910580e-01 9.177606457015089481e-01 +-2.538037160207138498e+01 2.181392663014435840e+01 2.108677686882134417e+00 -1.686931897332309416e-01 -7.448179926461856101e-03 3.575327469053996565e-01 9.185082539839041216e-01 +-2.520276902143701037e+01 2.165310427306733487e+01 2.120402607732097877e+00 -1.703342537738301854e-01 -4.561949277056037005e-03 3.549010508834821720e-01 9.192445919532085119e-01 +-2.502419845774825191e+01 2.148206206072395119e+01 2.130397958085426868e+00 -1.720280497022145250e-01 -2.082080681697975888e-03 3.520872298862169902e-01 9.200198588567216618e-01 +-2.486219346498838689e+01 2.132068850602420795e+01 2.134670903847158741e+00 -1.734560119174085036e-01 -8.512613343039085239e-05 3.491701646239731005e-01 9.208654370189738314e-01 +-2.471280762926851438e+01 2.118007644514408483e+01 2.144139937175970179e+00 -1.750086373768262038e-01 1.603936758375859323e-03 3.463092364640772969e-01 9.216503036123622206e-01 +-2.456835475227538268e+01 2.103812656267921000e+01 2.152434445001956576e+00 -1.763108370000965319e-01 2.732061531323511702e-03 3.431077662199614187e-01 9.225963561061628626e-01 +-2.442264628234016399e+01 2.089420069466747876e+01 2.161781400049501922e+00 -1.774873368601994905e-01 3.238134741228041770e-03 3.396101015079875940e-01 9.236626433839272288e-01 +-2.427355990026089927e+01 2.073994110416465730e+01 2.170807444422401478e+00 -1.783772892155512380e-01 3.164213493379939256e-03 3.356419573651723276e-01 9.249410412238524559e-01 +-2.411143338788069457e+01 2.058005725822879839e+01 2.181711413896941121e+00 -1.789011116774514576e-01 2.533429513252270782e-03 3.312247041750007170e-01 9.264329941860981465e-01 +-2.395358374681939395e+01 2.043156042038951981e+01 2.193466375655354295e+00 -1.781820297642631445e-01 1.518440338007657478e-03 3.265133176735959819e-01 9.282444887438395797e-01 +-2.378137291698228850e+01 2.027731198521926004e+01 2.202544851885130051e+00 -1.772231022939589340e-01 -1.142698712680511951e-04 3.213388908752234374e-01 9.302328688441559024e-01 +-2.360820039485843225e+01 2.012826763343965908e+01 2.210462999475496293e+00 -1.760922286042515550e-01 -2.334194068303546785e-03 3.158412220681679483e-01 9.323252258603759168e-01 +-2.343254729893018506e+01 1.998287346412564602e+01 2.220826320731257297e+00 -1.747725618769842004e-01 -5.082887453721562400e-03 3.100518298367477832e-01 9.345033420507886657e-01 +-2.326255796617168414e+01 1.983837668300360235e+01 2.229804523609773437e+00 -1.733364359478628547e-01 -8.348776079163816588e-03 3.038379501885040690e-01 9.367855656332416681e-01 +-2.310235838765634142e+01 1.970584173074448131e+01 2.241947866511607490e+00 -1.717849912618561181e-01 -1.199786572547334104e-02 2.973837773282887453e-01 9.390999819259777670e-01 +-2.295028196114595787e+01 1.958286525374220943e+01 2.255424051517243456e+00 -1.701818409947707111e-01 -1.595036499586073228e-02 2.905897082064004544e-01 9.414569948030672153e-01 +-2.280736594859218513e+01 1.946862924924761273e+01 2.267797479466579169e+00 -1.685447598422293580e-01 -2.013834440397856140e-02 2.835267542321208145e-01 9.438218124474053727e-01 +-2.267118424034019597e+01 1.935690750043622543e+01 2.280219219544293185e+00 -1.669499012363294399e-01 -2.445635087061915486e-02 2.760323207101295639e-01 9.462217993880225331e-01 +-2.254359611888131099e+01 1.924570146442235341e+01 2.290289369338574854e+00 -1.653825843482539248e-01 -2.890006054022439819e-02 2.681149157090276236e-01 9.486451883395159435e-01 +-2.242508383706413611e+01 1.913420649682531760e+01 2.298669420917671236e+00 -1.638814594322881013e-01 -3.334227193822694724e-02 2.600662318870630707e-01 9.509977030939973375e-01 +-2.231183483397288114e+01 1.902501793763106264e+01 2.308454712118715335e+00 -1.625786648799470435e-01 -3.758926290786378938e-02 2.517783702289140835e-01 9.532905131090511075e-01 +-2.220400006045826657e+01 1.891547836354818202e+01 2.318149300855755879e+00 -1.613833449136288234e-01 -4.173159024063542027e-02 2.433500179162118027e-01 9.555075035627831337e-01 +-2.209845338351153643e+01 1.880975098162064896e+01 2.329158518475625161e+00 -1.603213535040028948e-01 -4.556253125266216536e-02 2.346356194645030369e-01 9.576884541883025070e-01 +-2.199799084197544730e+01 1.870655874788373296e+01 2.340223438454463789e+00 -1.594738115004466772e-01 -4.897948336942856834e-02 2.258455659957382677e-01 9.597722787657028132e-01 +-2.190095719256446216e+01 1.859784303157948671e+01 2.351705863539985231e+00 -1.587822881713953915e-01 -5.191858353588252317e-02 2.169134396992903335e-01 9.617905909233496198e-01 +-2.180016806990845168e+01 1.847877138637376504e+01 2.364258134753425278e+00 -1.583307346781289426e-01 -5.435581923632944873e-02 2.077876944491077460e-01 9.637432388082685097e-01 +-2.169832459632621635e+01 1.834041881565324061e+01 2.371908520050601155e+00 -1.580906530827755618e-01 -5.627824353758310166e-02 1.985031164445777430e-01 9.656275424787137407e-01 +-2.161548383546879748e+01 1.821752885545812362e+01 2.373340289822982285e+00 -1.580645006030164668e-01 -5.749209138725010215e-02 1.891466165768861118e-01 9.674367010008695367e-01 +-2.153422843287851407e+01 1.810552516173234494e+01 2.377717464229693878e+00 -1.582610487034898650e-01 -5.781615261480226725e-02 1.797060467473474143e-01 9.691833749751642690e-01 +-2.145644821540220448e+01 1.800209728838094847e+01 2.381849807874012903e+00 -1.587154231477732047e-01 -5.729026022789755757e-02 1.700788142442150874e-01 9.708760857212688222e-01 +-2.138004282181617910e+01 1.789385514207005556e+01 2.382619277185873408e+00 -1.592238091682391388e-01 -5.593437977958651275e-02 1.603099744843234087e-01 9.725326580684515720e-01 +-2.131597834516782441e+01 1.779451138764849105e+01 2.380707270552539612e+00 -1.597441991719376064e-01 -5.398242832653989132e-02 1.506953849547642277e-01 9.740936845584099446e-01 +-2.126265806665829672e+01 1.770139245316920551e+01 2.377305864217933884e+00 -1.602471603559134095e-01 -5.139311720526714561e-02 1.412382715028596691e-01 9.755671451721739107e-01 +-2.121685694350008689e+01 1.761415606179631865e+01 2.373554570508440431e+00 -1.607831530752041049e-01 -4.823766780015736194e-02 1.320171000100557046e-01 9.769305603099242008e-01 +-2.117367240235097370e+01 1.752188071591168139e+01 2.367590729108215442e+00 -1.612903379465737419e-01 -4.463757036160696801e-02 1.230275604278528445e-01 9.781907060963731526e-01 +-2.113100143682661169e+01 1.742278791756978151e+01 2.362691670404515332e+00 -1.618331352219359032e-01 -4.061698168306866752e-02 1.142921155128258093e-01 9.793352532705437152e-01 +-2.109492570797476318e+01 1.733146658600596979e+01 2.358713281992010025e+00 -1.623646253406837714e-01 -3.634335667160287081e-02 1.059958855915424519e-01 9.803477332634522590e-01 +-2.106526439786156502e+01 1.724624616177715808e+01 2.355980308482712449e+00 -1.628528046406527985e-01 -3.176630233078926724e-02 9.806486672466814547e-02 9.812507632677880398e-01 +-2.103936426292183626e+01 1.716172325856282654e+01 2.353005008951581267e+00 -1.632545499615026263e-01 -2.699483486846433744e-02 9.055017290930690577e-02 9.820487892613617431e-01 +-2.101316994183832421e+01 1.707674261872273291e+01 2.353074067198606567e+00 -1.636490478128985460e-01 -2.195947066909571810e-02 8.355952919697588743e-02 9.827280953470782787e-01 +-2.098479064496500612e+01 1.699431492942678545e+01 2.358596145165361868e+00 -1.639983383793207072e-01 -1.668269947733160008e-02 7.701321204686938093e-02 9.833082601240621390e-01 +-2.096163967115072779e+01 1.692453467350348362e+01 2.361175419977556977e+00 -1.642102349878315215e-01 -1.137705240406010516e-02 7.111908588094235928e-02 9.837924535274802373e-01 +-2.094336156452694908e+01 1.685937661067343285e+01 2.360740008996073946e+00 -1.644046833924985573e-01 -6.180734840807129878e-03 6.576125912326838407e-02 9.841790107169632318e-01 +-2.091996040243015997e+01 1.679113249666621854e+01 2.358775558375123094e+00 -1.645912914975021790e-01 -1.145647390666358926e-03 6.090789961009554498e-02 9.844788459438268413e-01 +-2.089543578595064233e+01 1.672696514289351555e+01 2.357740460916899483e+00 -1.648569860265175491e-01 3.843779565520111068e-03 5.679655997310179699e-02 9.846733111862938648e-01 +-2.087405016091337373e+01 1.666244969984196800e+01 2.352794701593329929e+00 -1.651557222290719329e-01 8.705447299667892769e-03 5.350871175046966605e-02 9.847764234466773736e-01 +-2.084682301696283702e+01 1.659373989436810604e+01 2.347284577116218962e+00 -1.653984696066861937e-01 1.343221752683440400e-02 5.098368829005908709e-02 9.848165100232305624e-01 +-2.082007325794588581e+01 1.651314920667093133e+01 2.338474942774067866e+00 -1.656639873016375331e-01 1.789091360014482060e-02 4.940161429136621929e-02 9.847816052548349353e-01 +-2.080010771656053237e+01 1.643467478336274468e+01 2.327420048648610518e+00 -1.658959161410687166e-01 2.207375510463954749e-02 4.874050405911737466e-02 9.846906230381583525e-01 +-2.077628596253444471e+01 1.633766415659650306e+01 2.311139872091339420e+00 -1.632495460536843579e-01 2.578267823255039892e-02 4.885143635650564947e-02 9.850372287332536114e-01 +-2.074269164923461872e+01 1.624306984938383636e+01 2.298012188524479971e+00 -1.599678110252953922e-01 2.918402575743999500e-02 4.992603871806279570e-02 9.854267835299000966e-01 +-2.071488868840863873e+01 1.616813284508246085e+01 2.287606128844659636e+00 -1.561182751816872494e-01 3.226338163908769319e-02 5.183087125454018812e-02 9.858497283236083986e-01 +-2.069429637576661563e+01 1.611479893213525827e+01 2.281165493657008714e+00 -1.517945123779943506e-01 3.510028329535292563e-02 5.447281094409707480e-02 9.862854932444228284e-01 +-2.067553701424431623e+01 1.606311297660372617e+01 2.278231674796024286e+00 -1.470623601140047809e-01 3.762818768044523532e-02 5.780810384592470486e-02 9.867192945718008534e-01 +-2.066005838233551373e+01 1.601730414076842379e+01 2.273252518070416617e+00 -1.419792709351021809e-01 3.989278958783632617e-02 6.172065692333886938e-02 9.871377693749885385e-01 +-2.064257134839859731e+01 1.597737853305197220e+01 2.269208534476636174e+00 -1.366602495681482621e-01 4.195775416104875061e-02 6.614564021603631938e-02 9.875162004661860449e-01 +-2.061997488949099022e+01 1.594087837935035168e+01 2.267951612735017886e+00 -1.312409524567876851e-01 4.379814446672567613e-02 7.104242182550495055e-02 9.878311914263957494e-01 +-2.059128170228992616e+01 1.589691802007559573e+01 2.268632761416656596e+00 -1.258040767870452492e-01 4.544670677981129531e-02 7.643959187395041321e-02 9.880611720875707160e-01 +-2.056995440351705540e+01 1.586070097046617988e+01 2.269894712831388439e+00 -1.203359303490808413e-01 4.699870185379919491e-02 8.214074553465268436e-02 9.882121447876437426e-01 +-2.055072368872220423e+01 1.582903563376351919e+01 2.271289033989540407e+00 -1.148204424327542300e-01 4.844133874280111274e-02 8.821176639260819297e-02 9.882754465886016693e-01 +-2.053411520233666110e+01 1.580249573892884030e+01 2.271322097049400579e+00 -1.092922895106014647e-01 4.977367090376329933e-02 9.463243089736995961e-02 9.882420982243942387e-01 +-2.052063436617159908e+01 1.578139047222228086e+01 2.269965081994594236e+00 -1.037949162151052540e-01 5.102594258875241262e-02 1.012866999303133758e-01 9.881112975901364948e-01 +-2.051109816762516047e+01 1.576614547502966701e+01 2.267769777918209773e+00 -9.840104008533895330e-02 5.227638024267977634e-02 1.081710706902907354e-01 9.878681065840148046e-01 +-2.050568321714575859e+01 1.575574744993795129e+01 2.265118931868119301e+00 -9.318094791277606315e-02 5.357389269048426494e-02 1.152212324396054838e-01 9.875075575476254253e-01 +-2.050166382423019229e+01 1.574690267938842325e+01 2.263077717368975339e+00 -8.821430977653496597e-02 5.492012921237273554e-02 1.223792101330696547e-01 9.870285202846668104e-01 +-2.049881720857412049e+01 1.574049373021817644e+01 2.261503709674841378e+00 -8.356314648832394165e-02 5.630909305222969730e-02 1.294914206530896894e-01 9.864473735640079122e-01 +-2.049634004631608164e+01 1.573664397208897192e+01 2.260506344301061787e+00 -7.936371613926523905e-02 5.776690852868199971e-02 1.364776028964898302e-01 9.857678233796330902e-01 +-2.049218710833437740e+01 1.572331693234137262e+01 2.258134984051995975e+00 -7.554488226594657796e-02 5.917387585839132408e-02 1.434541500898740829e-01 9.849935446105722026e-01 +-2.048657437881676557e+01 1.569756930055372379e+01 2.255590004990317254e+00 -7.234952555513138317e-02 6.067932273964941892e-02 1.500437064990849667e-01 9.841597448593090158e-01 +-2.047843582579944410e+01 1.566225449672118231e+01 2.252243725286425136e+00 -6.971624011045358948e-02 6.231747739621338461e-02 1.563830270621933693e-01 9.832601318403235702e-01 +-2.046442239506922434e+01 1.561154057414355201e+01 2.247412752498196831e+00 -6.753753647134667915e-02 6.408830427774044047e-02 1.625061682465696600e-01 9.823049831204545557e-01 +-2.044462728535043183e+01 1.553935775085130544e+01 2.239074167287379513e+00 -6.574968329266300815e-02 6.597160830403327181e-02 1.684161561215151981e-01 9.813056078961603923e-01 +-2.041817639042516319e+01 1.544780975665219280e+01 2.225232816334454355e+00 -6.428081985558835310e-02 6.796958880377335088e-02 1.743106238010578568e-01 9.802366497841802362e-01 +-2.037827970100034491e+01 1.535655819445656256e+01 2.215730549141833094e+00 -6.314394592599967271e-02 7.012749691860384327e-02 1.802301429577914393e-01 9.790873554259137412e-01 +-2.034304301221650135e+01 1.525750656497740110e+01 2.208270842005666257e+00 -6.228750850023884178e-02 7.234470415608308669e-02 1.860913730315238990e-01 9.778836844129077388e-01 +-2.030496317045575339e+01 1.515266078113735482e+01 2.201351717315796819e+00 -6.176481948095294966e-02 7.464613919449145096e-02 1.919754907470901106e-01 9.766055802156206056e-01 +-2.026302311912285603e+01 1.502794260271870108e+01 2.194500827666788556e+00 -6.150353105975184254e-02 7.689509711329897690e-02 1.977486174561704779e-01 9.752947917744485551e-01 +-2.020849726341433339e+01 1.490013804558936172e+01 2.179868191048701220e+00 -6.134829259082300729e-02 7.915527343069228561e-02 2.037013814230680120e-01 9.738976099600501479e-01 +-2.015865252051629852e+01 1.478943384765494073e+01 2.172600629379263903e+00 -6.130733305315389653e-02 8.150632296801041399e-02 2.099363517575650873e-01 9.723810155697343305e-01 +-2.010697506542285140e+01 1.469454277800677389e+01 2.169887108051629099e+00 -6.122343169573608856e-02 8.385772232222171718e-02 2.160867110524038737e-01 9.708378266261108447e-01 +-2.004333324686132300e+01 1.459155794196276901e+01 2.168254593386185203e+00 -6.121813631254290067e-02 8.620945953303266185e-02 2.221014920901688283e-01 9.692735309063055249e-01 +-1.995536522431518733e+01 1.449161916155743590e+01 2.176704636767818002e+00 -6.121831844503336506e-02 8.849909393654395440e-02 2.282178498163161540e-01 9.676449822251577126e-01 +-1.986852694734326619e+01 1.442672928122935261e+01 2.184905732446394300e+00 -6.079935440944351371e-02 9.076774558049814645e-02 2.348681532696405838e-01 9.658682934572044854e-01 +-1.977248391560454621e+01 1.435172719976702815e+01 2.195254625368472823e+00 -5.995056471532162617e-02 9.312418594182914067e-02 2.418719696773432015e-01 9.639666560933002337e-01 +-1.969067993194185107e+01 1.426944732331360122e+01 2.199145282308047289e+00 -5.868241001951993857e-02 9.537467557572931742e-02 2.493537768367389829e-01 9.619161504109252636e-01 +-1.960956707831019941e+01 1.417168327337953571e+01 2.203751693175549420e+00 -5.704751587468308988e-02 9.750129778798000135e-02 2.568054443738436721e-01 9.598385176861311541e-01 +-1.955079876767694813e+01 1.409388215135465394e+01 2.206114221758293858e+00 -5.500135549751854203e-02 9.950490433384594213e-02 2.647950310287480735e-01 9.575787960004964461e-01 +-1.949116912884880648e+01 1.402973278451732142e+01 2.205298159181333872e+00 -5.209322678538553381e-02 1.017655153258788803e-01 2.732479988458092479e-01 9.551259315684987872e-01 +-1.942543732676718093e+01 1.397021949839072974e+01 2.204714454798081924e+00 -4.870392115491865848e-02 1.040523361421392540e-01 2.825111603538412730e-01 9.523594029970722241e-01 +-1.929821494239357804e+01 1.378497043399655553e+01 2.205750938714737153e+00 -4.492083545822482538e-02 1.061211487241495860e-01 2.917518127459385879e-01 9.495268583346441194e-01 +-1.912665396715104649e+01 1.353795928427117978e+01 2.205938936536770090e+00 -4.050387523008284335e-02 1.083404317492605851e-01 3.015274564377538047e-01 9.464158367774282432e-01 +-1.890935921934523023e+01 1.327559809124179502e+01 2.224901666802643785e+00 -3.551371582259577053e-02 1.104073315128968891e-01 3.113157326726145313e-01 9.432027635009208044e-01 +-1.871895692483319706e+01 1.304034078023417109e+01 2.240376825580436826e+00 -3.059565958570060334e-02 1.122690636555179616e-01 3.210416825095556703e-01 9.398892217118648418e-01 +-1.858533960095937232e+01 1.285581032850718053e+01 2.239556104990208851e+00 -2.533638816897254217e-02 1.134705182592263134e-01 3.306192625627465409e-01 9.365753419114675182e-01 +-1.846637934944839188e+01 1.267245711276296838e+01 2.232190393417010199e+00 -1.996472408195707968e-02 1.142426246977342186e-01 3.400037153505683363e-01 9.332456640499179334e-01 +-1.834424743626685128e+01 1.248542095186074086e+01 2.224726272720475517e+00 -1.461782668039461608e-02 1.147569380941151490e-01 3.490302168913915204e-01 9.299435636087323154e-01 +-1.821656758056435876e+01 1.228891383911369317e+01 2.218094745620765806e+00 -9.473427686408660356e-03 1.150921517709838637e-01 3.575202265649736200e-01 9.267379901628109984e-01 +-1.808473947371998847e+01 1.208766941031786146e+01 2.211148295661107710e+00 -4.591869651937877973e-03 1.152099924134651621e-01 3.652709483137638879e-01 9.237330117737343471e-01 +-1.796212633515017743e+01 1.190028077422488195e+01 2.202906659710205606e+00 -2.268098271442152251e-04 1.150432754928166768e-01 3.721879461725837723e-01 9.210000560270295011e-01 +-1.785453028213330029e+01 1.173500074493014900e+01 2.196422447926726473e+00 3.584831690984122479e-03 1.146186967401746082e-01 3.781439587308655925e-01 9.186167999001022544e-01 +-1.776411908157643182e+01 1.159193336663456186e+01 2.188055005070835168e+00 6.860951809147601901e-03 1.138170436653504064e-01 3.829512423719652614e-01 9.167043907533920510e-01 +-1.769734221398674023e+01 1.147952232355739000e+01 2.179243348434104721e+00 9.447360004739294159e-03 1.127334212492174664e-01 3.865639640853909542e-01 9.152978760535983582e-01 +-1.763255751500428303e+01 1.137085906132285018e+01 2.171910293257880653e+00 1.110555655371989886e-02 1.114242542141882925e-01 3.885893432651385537e-01 9.145816551065322209e-01 +-1.757316524267253399e+01 1.127964602695488061e+01 2.166473754292252529e+00 1.185933542491708452e-02 1.098771284046711066e-01 3.892181435789570099e-01 9.144919826590290901e-01 +-1.752693756265603753e+01 1.120474242156642752e+01 2.162020643769047012e+00 1.173225842753999187e-02 1.079556522185817213e-01 3.881986992109021650e-01 9.151555493068490588e-01 +-1.749635054128563993e+01 1.114842258175177214e+01 2.159801109387699203e+00 1.068457498525992276e-02 1.054529732056452701e-01 3.853574005046796480e-01 9.166597900985391512e-01 +-1.746987484039617655e+01 1.109833512739065675e+01 2.160562514213641094e+00 8.361420198932255701e-03 1.023366124301905711e-01 3.807866783946503575e-01 9.189443942600107329e-01 +-1.743961018697540410e+01 1.103295869616226099e+01 2.160514159081406760e+00 4.759838570044848741e-03 9.862923242753426911e-02 3.740671675138654284e-01 9.221297941097912343e-01 +-1.738209358789312020e+01 1.092662162694817951e+01 2.159551026333672574e+00 -4.267478026647154540e-04 9.451641194703352955e-02 3.648909327282914838e-01 9.262402779090995741e-01 +-1.728429936725947869e+01 1.078156544320308186e+01 2.161188781995482699e+00 -7.344681234861672250e-03 8.979843880021999569e-02 3.532146170640036997e-01 9.311937065706878958e-01 +-1.717129514951847469e+01 1.060954244656145207e+01 2.161881636377004146e+00 -1.558728871856538897e-02 8.459577425049155663e-02 3.393465364544549501e-01 9.367200835681316340e-01 +-1.706168993742090123e+01 1.044539723171767776e+01 2.164013818496068442e+00 -2.499361266717898752e-02 7.909483822218456306e-02 3.234376213958564672e-01 9.426067187801692171e-01 +-1.696109414029760387e+01 1.029391974573971957e+01 2.167050192972648226e+00 -3.532126478746205889e-02 7.333142691594213280e-02 3.056241350394299783e-01 9.486668460192403396e-01 +-1.687467613593777571e+01 1.016347404306224256e+01 2.168212206345208504e+00 -4.622486579764858300e-02 6.725972925270648495e-02 2.862841285846667305e-01 9.546626484609582741e-01 +-1.679382067074978124e+01 1.004178731367571586e+01 2.169404071549860369e+00 -5.744366751608519228e-02 6.090054550451711596e-02 2.656675949095181899e-01 9.604228510589920553e-01 +-1.671502872125901007e+01 9.928769784441687563e+00 2.172637553329854754e+00 -6.892427977923976101e-02 5.424888258536680885e-02 2.438624215285866981e-01 9.658351854806833670e-01 +-1.663799007586359480e+01 9.817469086452909721e+00 2.178387655751162555e+00 -8.060115121284738837e-02 4.751327452176265509e-02 2.213335174097662561e-01 9.706994426515963559e-01 +-1.656408488197978457e+01 9.712851673770579453e+00 2.188949668821842831e+00 -9.216847508597671157e-02 4.077806440951327327e-02 1.983061332690445600e-01 9.749445003683047117e-01 +-1.649973487856637533e+01 9.614714016748605374e+00 2.200081186862143046e+00 -1.034956853282595624e-01 3.406593713696950271e-02 1.751033563911676694e-01 9.785024007734179907e-01 +-1.644145189377235994e+01 9.518645326628329073e+00 2.211673619938637980e+00 -1.143697992967085963e-01 2.747856742179980924e-02 1.520167501308666569e-01 9.813538443386329302e-01 +-1.639295111415408002e+01 9.438464491340159412e+00 2.223216243399236181e+00 -1.246647215866305419e-01 2.102622803237862506e-02 1.291460620602334630e-01 9.835333673742464589e-01 +-1.635229191864688758e+01 9.368127702486257036e+00 2.233562520519563499e+00 -1.342134310043322509e-01 1.479586287658969657e-02 1.068738640728450623e-01 9.850613124757330308e-01 +-1.631830051074468457e+01 9.307242259240959825e+00 2.244426700517038853e+00 -1.428014414319911107e-01 8.879592283973461453e-03 8.562554733092427039e-02 9.860005750991928108e-01 +-1.628619582107893038e+01 9.255500505683029289e+00 2.258414306512610548e+00 -1.503244219381807412e-01 3.270482471886472942e-03 6.561739121335170843e-02 9.864513117733360037e-01 +-1.625537509089395627e+01 9.209283319931946821e+00 2.273578104608310557e+00 -1.566462438607570395e-01 -2.030606906476295839e-03 4.723166892274411471e-02 9.865226583743368360e-01 +-1.622515917466837010e+01 9.168472316023480673e+00 2.287756380059410954e+00 -1.615980304750979923e-01 -6.849638316913116316e-03 3.080643644438940676e-02 9.863519073006619120e-01 +-1.619263194700837261e+01 9.132351626603893990e+00 2.302137466604272209e+00 -1.648971126317285152e-01 -1.098738770568819141e-02 1.663825802873680412e-02 9.861091961530722427e-01 +-1.615948541636274527e+01 9.105472748325324162e+00 2.317080591805684708e+00 -1.655842833399760461e-01 -1.447054216107828729e-02 5.040399209603840455e-03 9.860765656444495653e-01 +-1.613543561889148137e+01 9.089246719148793119e+00 2.330073713023355531e+00 -1.656461391315860177e-01 -1.718069026848557598e-02 -3.816953218732600274e-03 9.860281758057878321e-01 +-1.611969485803400559e+01 9.080030284385308903e+00 2.333121595778725244e+00 -1.630190628763794614e-01 -1.919318291760680265e-02 -9.716719758919092897e-03 9.863883371728771055e-01 +-1.611101792298105551e+01 9.077893633231999715e+00 2.332891359582450086e+00 -1.585215352822811896e-01 -2.029516156287563405e-02 -1.268769550646510827e-02 9.870653532020081666e-01 +-1.610786570749139557e+01 9.074754689125031248e+00 2.332373661696823586e+00 -1.522359735163119898e-01 -2.072530759265489228e-02 -1.317284282213836144e-02 9.880390140301673618e-01 +-1.610707111008888148e+01 9.074273188830556336e+00 2.330908070778615393e+00 -1.444230926660645953e-01 -2.059467730056086660e-02 -1.135002870264241633e-02 9.892365560008224978e-01 +-1.610051076023561123e+01 9.067454666629032545e+00 2.329856523599523221e+00 -1.354194888253757445e-01 -2.003183825100954274e-02 -7.444247601461353135e-03 9.905578304610710427e-01 +-1.608561065131056012e+01 9.055431567141054572e+00 2.333570903625997950e+00 -1.253950029047078696e-01 -1.897163984724062682e-02 -1.641236612165737933e-03 9.919241008659176462e-01 +-1.604942488873723505e+01 9.047208141752495436e+00 2.347260763556520580e+00 -1.144697698682805159e-01 -1.762930797492083534e-02 5.740325714956262711e-03 9.932536784984982159e-01 +-1.599780400830240801e+01 9.036078121086683623e+00 2.365797423118996434e+00 -1.028793770958119497e-01 -1.601182389409760293e-02 1.438189170857957951e-02 9.944609331068434699e-01 +-1.597493526484967674e+01 9.054104035289602948e+00 2.375230004990104948e+00 -9.116612313425521974e-02 -1.402592871805455159e-02 2.404947248203979926e-02 9.954464178891656578e-01 +-1.596623212574137796e+01 9.088837732746416265e+00 2.379756223421016781e+00 -7.920706450329700887e-02 -1.186981575955644609e-02 3.411035148029154668e-02 9.962036791399401237e-01 +-1.596954706205692354e+01 9.145630681692750841e+00 2.378335418541498658e+00 -6.713151095836895899e-02 -9.939073942417494395e-03 4.453442322185163782e-02 9.967001579566676650e-01 +-1.597713426819272442e+01 9.209867560630165428e+00 2.375847369721776126e+00 -5.513994028047861096e-02 -8.117924896497836357e-03 5.531919823089394977e-02 9.969119332950577839e-01 +-1.599726395083548702e+01 9.286978546016371183e+00 2.368917688079634765e+00 -4.346590881166189496e-02 -6.423142916541952317e-03 6.621660902030318541e-02 9.968373749311695287e-01 +-1.602325280615994174e+01 9.384730327165568653e+00 2.360474174448691898e+00 -3.231471166577935122e-02 -4.952948608179501104e-03 7.695102274079493321e-02 9.964987172343905408e-01 +-1.606731305965451639e+01 9.504301408337655133e+00 2.347623184502842797e+00 -2.189820861151870954e-02 -3.729460773636685943e-03 8.743663417366816237e-02 9.959223462074408006e-01 +-1.612083081086907654e+01 9.644930870353693564e+00 2.335521445274497676e+00 -1.240500041987740651e-02 -2.751275237990671516e-03 9.731352131216068624e-02 9.951726225457058206e-01 +-1.618099947206566469e+01 9.795013133979924902e+00 2.324490477150014112e+00 -4.103948224691608693e-03 -2.038100836592279547e-03 1.062099577466320416e-01 9.943331278112087501e-01 +-1.624217904165843152e+01 9.942615724029280955e+00 2.313414108981703077e+00 2.671543113858131438e-03 -1.817275572975684834e-03 1.139050986658751985e-01 9.934863396660439383e-01 +-1.629124780354753099e+01 1.006938740591245995e+01 2.303920311212641181e+00 7.578488459806609866e-03 -2.268273374107130595e-03 1.198967946776430676e-01 9.927548071932547069e-01 +-1.633472385079273792e+01 1.017595524124036643e+01 2.290903076987572895e+00 1.049449308106667478e-02 -3.410735886430148710e-03 1.241520308463849587e-01 9.922018096698036471e-01 +-1.637793268302061378e+01 1.028165325764400073e+01 2.274641803603773660e+00 1.135478531300459365e-02 -5.504453293259703277e-03 1.267870953564638192e-01 9.918496433009207358e-01 +-1.642822846916649837e+01 1.040742890945908350e+01 2.257948914225482273e+00 1.029881112775398767e-02 -8.313216204557929631e-03 1.277369548604467553e-01 9.917197144658432828e-01 +-1.647931254011575319e+01 1.052246117433054451e+01 2.243167421829907582e+00 7.634594890201421881e-03 -1.166218571425032755e-02 1.268715450056190353e-01 9.918211601256338161e-01 +-1.653516030257644331e+01 1.065070388833428439e+01 2.229596635922036718e+00 3.412057472295177384e-03 -1.565310569281696748e-02 1.246696696394519049e-01 9.920689093088246313e-01 +-1.659536502724029816e+01 1.079629368550196133e+01 2.219560690459061458e+00 -2.277955605083687059e-03 -2.008936474288094270e-02 1.213646936867543435e-01 9.924020086246534422e-01 +-1.666574160083146339e+01 1.095804922228458267e+01 2.206575003680418590e+00 -9.232634428867562970e-03 -2.485068396863391454e-02 1.169590881075668609e-01 9.927827994400153511e-01 +-1.674190989691862796e+01 1.113371931954566918e+01 2.190580694345738877e+00 -1.729123396301393556e-02 -2.983821393142610523e-02 1.116249497908161081e-01 9.931517888250256387e-01 +-1.682084807372992330e+01 1.131155062160362057e+01 2.171354591314961446e+00 -2.627781006345874734e-02 -3.505250642584061688e-02 1.055596444750812601e-01 9.934474642225414875e-01 +-1.690339518644142913e+01 1.149827905820425400e+01 2.151008411228464645e+00 -3.600895897540373758e-02 -4.038228984364392038e-02 9.883217843337271935e-02 9.936320924692395584e-01 +-1.699017092537654250e+01 1.169579789143146975e+01 2.131659798115800530e+00 -4.632514640753965934e-02 -4.565426019546325875e-02 9.170207545078250255e-02 9.936600517883820149e-01 +-1.709386783254561593e+01 1.190758659631958771e+01 2.114919487083909200e+00 -5.697037751959511953e-02 -5.086295538998143045e-02 8.444393908915696911e-02 9.934970847992861120e-01 +-1.721252576975277293e+01 1.212821192215514188e+01 2.102066421114354267e+00 -6.762684478981473291e-02 -5.597921324432133389e-02 7.717879162941922166e-02 9.931446415325295707e-01 +-1.734414723779302037e+01 1.234817916102151791e+01 2.094966851470915437e+00 -7.811016813160526207e-02 -6.091964018158538274e-02 7.004974020309484573e-02 9.926129889366381853e-01 +-1.749466391275494104e+01 1.255966252000725802e+01 2.090670235722457804e+00 -8.825476276087608485e-02 -6.557760250153599202e-02 6.300433027933761976e-02 9.919380279893152963e-01 +-1.766160084761688864e+01 1.275175773625625197e+01 2.088632206476979558e+00 -9.801771896044846055e-02 -6.981677485633164260e-02 5.643833537049062349e-02 9.911270216109892006e-01 +-1.784674088814451665e+01 1.293479071192559005e+01 2.084145789414349359e+00 -1.072340540274417386e-01 -7.358196782590170626e-02 5.072332308422956154e-02 9.902088707269739443e-01 +-1.804303659319181818e+01 1.312350271965192761e+01 2.086779122422094623e+00 -1.156308791144170789e-01 -7.684132591609062202e-02 4.584309259977438489e-02 9.892538760014278898e-01 +-1.823680545551879106e+01 1.330054306159428457e+01 2.100665654473128807e+00 -1.231424855552845504e-01 -7.936709817534590150e-02 4.193402412085699832e-02 9.883209154678385122e-01 +-1.841567601464123882e+01 1.346193909844716075e+01 2.134129752566813476e+00 -1.293208643605408825e-01 -8.103128912829450636e-02 3.909683664104095929e-02 9.875127227309660194e-01 +-1.858253985886641146e+01 1.360433933777828486e+01 2.168064371091896980e+00 -1.341300029799911697e-01 -8.204923167606985313e-02 3.767319669960150774e-02 9.868422817252924251e-01 +-1.872528555110619308e+01 1.371417458432784997e+01 2.190000764840207115e+00 -1.374762638688906968e-01 -8.210701065406829369e-02 3.764342635540047360e-02 9.863780127125750807e-01 +-1.886174992968339836e+01 1.381813799764337958e+01 2.202999472521771196e+00 -1.395160263736313910e-01 -8.129732852998228232e-02 3.901140679525193222e-02 9.861054839331668820e-01 +-1.900846804434779713e+01 1.392831097412183361e+01 2.206856974323029519e+00 -1.403293273126852980e-01 -7.988191194438465370e-02 4.150051939448869132e-02 9.860041399728640688e-01 +-1.916571367673935811e+01 1.403579048606478530e+01 2.207071381292480261e+00 -1.400379638015649963e-01 -7.790403469512195700e-02 4.501333120722775250e-02 9.860497042400393486e-01 +-1.932336268452755590e+01 1.413904396895380522e+01 2.204120642705144295e+00 -1.388513136416683336e-01 -7.536944635375898704e-02 4.938366621938568984e-02 9.862053041473500814e-01 +-1.948019051283263892e+01 1.423741841155265675e+01 2.200146855982614724e+00 -1.367630726654870954e-01 -7.234988442363499139e-02 5.469348488684781101e-02 9.864430411568382295e-01 +-1.964875955572989952e+01 1.433830687080092581e+01 2.194627629322277063e+00 -1.337558056365891479e-01 -6.896716357587492907e-02 6.103991920834043322e-02 9.867253612628513748e-01 +-1.982736775656775308e+01 1.443923626581344166e+01 2.187412016870568632e+00 -1.299336473950004622e-01 -6.540464313115372519e-02 6.827843064796437766e-02 9.870042669290723936e-01 +-2.003310344387709208e+01 1.455450267049625701e+01 2.188406739971098691e+00 -1.251762827996395766e-01 -6.150402563108019194e-02 7.655005314683840933e-02 9.872629464605172656e-01 +-2.020370104676618084e+01 1.463269892318620791e+01 2.183445481404470812e+00 -1.201726246628413569e-01 -5.755515563868281170e-02 8.478117842600900456e-02 9.874502375473758198e-01 +-2.039944575523385950e+01 1.473814869357466328e+01 2.171863244999892029e+00 -1.150452482359691914e-01 -5.377802125628649427e-02 9.345944491593065340e-02 9.874906169596617822e-01 +-2.058323154692209656e+01 1.482187808651007543e+01 2.162320377892114731e+00 -1.095851340567848969e-01 -5.021388268546568556e-02 1.027892628893974369e-01 9.873722237646116451e-01 +-2.077850243723293033e+01 1.491262548729414306e+01 2.155145278297261324e+00 -1.039155139600953515e-01 -4.681374706100800004e-02 1.126103102700283937e-01 9.870809676505636343e-01 +-2.097268377603544209e+01 1.499967083972508064e+01 2.144085471811068899e+00 -9.854660583477990732e-02 -4.354060165108766811e-02 1.221308656917521052e-01 9.866492309360290758e-01 +-2.117992613839238203e+01 1.510366820591486459e+01 2.131473250414687381e+00 -9.318340102928472646e-02 -4.053285809127053774e-02 1.316266821970481227e-01 9.860771868811744056e-01 +-2.134511741496542925e+01 1.527708983157364031e+01 2.103044743210867207e+00 -8.748968684153357600e-02 -3.735379189054816723e-02 1.413872393545844153e-01 9.853728963266293883e-01 +-2.111324512817924770e+01 1.530666291996512385e+01 2.083534390417496773e+00 -8.253825544210410814e-02 -3.501602564173068866e-02 1.505422105512969067e-01 9.845294345390187551e-01 +-2.087389369854814447e+01 1.529357879033045009e+01 2.075755340018088368e+00 -7.785113952916211666e-02 -3.342901890145941191e-02 1.591765119103717985e-01 9.836078446930101027e-01 +-2.064248619497521631e+01 1.526955410168450200e+01 2.074871614817053622e+00 -7.357602023898533738e-02 -3.232203097506882589e-02 1.671843552861336235e-01 9.826449531754252176e-01 +-2.043162307627387975e+01 1.524231419457743542e+01 2.074558946751290822e+00 -7.006468207152179162e-02 -3.194303482292529944e-02 1.745368820176589897e-01 9.816350169486763866e-01 +-2.023100473798250221e+01 1.520814818070421737e+01 2.068743045828157268e+00 -6.718428342995476366e-02 -3.238310953251236773e-02 1.810233746475911343e-01 9.806467197504810107e-01 +-2.003008189925847660e+01 1.517409903606462507e+01 2.070659101001316671e+00 -6.525167378786993211e-02 -3.344579123601653520e-02 1.870358849538260870e-01 9.796126902291274474e-01 +-1.982494515732422968e+01 1.513063637487507229e+01 2.074430086483830316e+00 -6.416746726491839858e-02 -3.519578605880979011e-02 1.918981645418474380e-01 9.786821423416809385e-01 +-1.965384943012049135e+01 1.508698024869777399e+01 2.076389137955708009e+00 -6.378019514722951810e-02 -3.763855786655878610e-02 1.957479091285511952e-01 9.778537888697909075e-01 +-1.948961096498404544e+01 1.505179097379046205e+01 2.072284817075018992e+00 -6.389437410566929654e-02 -4.044202187162802831e-02 1.987253473825571493e-01 9.771335832118609455e-01 +-1.933258911723182294e+01 1.502003635824399730e+01 2.070368887616188314e+00 -6.470998510553505056e-02 -4.345444887374317472e-02 2.009126418589243790e-01 9.765030957275405710e-01 +-1.917320681512573799e+01 1.499041699506302194e+01 2.072088841608691112e+00 -6.618339888423839523e-02 -4.693590890032925400e-02 2.019804236340539960e-01 9.760228275395445019e-01 +-1.902034381543474240e+01 1.496555965102183450e+01 2.075386078124768829e+00 -6.810809804166763348e-02 -5.054610197927305454e-02 2.020383533922505970e-01 9.756980827019108293e-01 +-1.887027065573176543e+01 1.494518788345334670e+01 2.078513958520793903e+00 -7.050182936655541299e-02 -5.418052228721418478e-02 2.010213896943786327e-01 9.755430435144810675e-01 +-1.874056917559722280e+01 1.492958187260158986e+01 2.082164290731034928e+00 -7.336861876315663167e-02 -5.773025156134082431e-02 1.988567967143820836e-01 9.755716779770967628e-01 +-1.863255263101379811e+01 1.491530607359389649e+01 2.085717404095332572e+00 -7.655764968775266577e-02 -6.113532483107075866e-02 1.956919154001892924e-01 9.757591584624414338e-01 +-1.853528160626419918e+01 1.490112845445516321e+01 2.088775495282948036e+00 -8.005915433033353179e-02 -6.435110930606666169e-02 1.914672314884831583e-01 9.761094407317428834e-01 +-1.844534103986456230e+01 1.488481591228454626e+01 2.092963753052159426e+00 -8.382208454099877859e-02 -6.742247592598546446e-02 1.861089373675393344e-01 9.766224457108689805e-01 +-1.836223704409640689e+01 1.486653652516606883e+01 2.096376783761374263e+00 -8.766101706523214687e-02 -7.022268758169866731e-02 1.796967982783925499e-01 9.772887180412758168e-01 +-1.828559200289143760e+01 1.484661298079097413e+01 2.097336750536834327e+00 -9.162121050648702747e-02 -7.262208661281341349e-02 1.722005733861409760e-01 9.780993763408689645e-01 +-1.821208011980237984e+01 1.482685568067020832e+01 2.095806705510431911e+00 -9.574690372886669743e-02 -7.452372176215169008e-02 1.634387164022577388e-01 9.790640306001334725e-01 +-1.813626085198079707e+01 1.480494398657802613e+01 2.095515815191007380e+00 -9.993557997899722711e-02 -7.582870961633583762e-02 1.535873062232560315e-01 9.801396184984921822e-01 +-1.806150641619427688e+01 1.478309008123216906e+01 2.096079684485329331e+00 -1.040516534877436727e-01 -7.641651660915249611e-02 1.425483410307718801e-01 9.813325570462070324e-01 +-1.798716727284493189e+01 1.476309320501279920e+01 2.097857943105324363e+00 -1.079974499821066969e-01 -7.626260043230576047e-02 1.302367427375733522e-01 9.826285163278722923e-01 +-1.792035828452866042e+01 1.474847287771143378e+01 2.099481093561671674e+00 -1.118371981574265428e-01 -7.520129091147600975e-02 1.168578180182255205e-01 9.839620417255634521e-01 +-1.786896633246229271e+01 1.473883459295010745e+01 2.100079897133919182e+00 -1.155498340418688458e-01 -7.296937675020730152e-02 1.024256137683263873e-01 9.853083491927672188e-01 +-1.782955813724623795e+01 1.473018792611420480e+01 2.101394596507172086e+00 -1.191334854201221288e-01 -6.976046563237510434e-02 8.680260521505843430e-02 9.866133172349799141e-01 +-1.780025780684731629e+01 1.472016275391155737e+01 2.106005668767443328e+00 -1.227530299644173234e-01 -6.568173737006395563e-02 7.021006128590007167e-02 9.877692035547255278e-01 +-1.778024323699494857e+01 1.471179777764218244e+01 2.111474266157935542e+00 -1.263361315597076040e-01 -6.082715310475720477e-02 5.267126556216187444e-02 9.887187798754073498e-01 +-1.776688363602180232e+01 1.470608652646782666e+01 2.114623548761825234e+00 -1.298361307518257068e-01 -5.531859876520795610e-02 3.432665932972633893e-02 9.893957596410226651e-01 +-1.776180378205032184e+01 1.470420970695452212e+01 2.115301687685079202e+00 -1.332139316602710677e-01 -4.932799815798065424e-02 1.516235116415115894e-02 9.897427758281290844e-01 +-1.776083762602299743e+01 1.470488575887673122e+01 2.115395313544910838e+00 -1.364343403737725557e-01 -4.288589963293847063e-02 -4.614807795886593025e-03 9.897095679667489154e-01 +-1.776346128225869947e+01 1.470799042157793757e+01 2.115089730487588859e+00 -1.394610445813741495e-01 -3.610019484816001656e-02 -2.484307627542065369e-02 9.892573303291761766e-01 +-1.776381347894344742e+01 1.471083074267056467e+01 2.115187686400317180e+00 -1.423418346008326618e-01 -2.899275916591693286e-02 -4.518123988528639778e-02 9.883606354666614191e-01 +-1.776124323303142205e+01 1.471304403810461281e+01 2.115470615317164960e+00 -1.450500884313442873e-01 -2.167426971983349437e-02 -6.550171346812502793e-02 9.870157493613137545e-01 +-1.775576822200288873e+01 1.471449152830182072e+01 2.116163165305680938e+00 -1.475710839897600157e-01 -1.423157851761065913e-02 -8.564796990829237622e-02 9.852332354915237511e-01 +-1.774671665487562322e+01 1.471525345178032396e+01 2.117798358331107966e+00 -1.498742727731608437e-01 -6.744801397174555319e-03 -1.054758811063421786e-01 9.830396339459467336e-01 +-1.773425008782144374e+01 1.471524935046138793e+01 2.120497156016112772e+00 -1.519542430216485329e-01 6.908105285363304055e-04 -1.248346645081095108e-01 9.804721340744722013e-01 +-1.771933772421600040e+01 1.471452123882868968e+01 2.124018873593796375e+00 -1.538148544917070648e-01 7.945132713633333565e-03 -1.435659849898861251e-01 9.775819838768001757e-01 +-1.770158892031110298e+01 1.471332367211089220e+01 2.128353228040870793e+00 -1.554512998809085833e-01 1.487580230637751237e-02 -1.615518430521011850e-01 9.744303333156587588e-01 +-1.768070659655806054e+01 1.471178483285920890e+01 2.133486153904172511e+00 -1.568672270639969446e-01 2.137023449095604155e-02 -1.786748408674451449e-01 9.710876148719804757e-01 +-1.765520583790828368e+01 1.470953312904325827e+01 2.139785298003943126e+00 -1.580715135408298500e-01 2.735972551992696747e-02 -1.948075342638374841e-01 9.676335654745908954e-01 +-1.763257909878102581e+01 1.470792589631183667e+01 2.145768696274809262e+00 -1.591307992913066627e-01 3.274421947091263330e-02 -2.098386170646575899e-01 9.641435573131417192e-01 +-1.761154506912698992e+01 1.470756849560478763e+01 2.150759440345031859e+00 -1.600752148866937674e-01 3.748578752557860799e-02 -2.237643708399396081e-01 9.606768854753626741e-01 +-1.759346871674128110e+01 1.470832716101988602e+01 2.153318594371060435e+00 -1.609509316239397247e-01 4.145880040599969618e-02 -2.363738737888267105e-01 9.573417213092957345e-01 +-1.757715898289109191e+01 1.470985754540407342e+01 2.156877113365502474e+00 -1.602667494947415394e-01 4.430118789341638830e-02 -2.476207932373343801e-01 9.544819165735920485e-01 +-1.756470525599414501e+01 1.471083080869373916e+01 2.160252285466500055e+00 -1.596877662244635121e-01 4.645445504920311941e-02 -2.575108597271836275e-01 9.518559635896126636e-01 +-1.755430864807247460e+01 1.471272029587783514e+01 2.164736519679076654e+00 -1.592736919425307984e-01 4.799229735555288201e-02 -2.661396745097128758e-01 9.494725491621541780e-01 +-1.754858573576068537e+01 1.471440250282627815e+01 2.166458189873719853e+00 -1.590557544306516191e-01 4.882832573250100311e-02 -2.734190187995648724e-01 9.473958580849505262e-01 +-1.754552770370608528e+01 1.471451448183227662e+01 2.167897316934680241e+00 -1.589529114605628402e-01 4.913746779228266720e-02 -2.794246577992133274e-01 9.456432448388171208e-01 +-1.754428721701840033e+01 1.471336620128529304e+01 2.168646122790431008e+00 -1.589759204067289211e-01 4.899210478298784976e-02 -2.843120574432076442e-01 9.441890061790466637e-01 +-1.754390638424300519e+01 1.471321537899052601e+01 2.168568871272051002e+00 -1.591757036192298358e-01 4.847914298886440293e-02 -2.882517089297858548e-01 9.429865401738088959e-01 +-1.753290603074790610e+01 1.471363162880962250e+01 2.169377446536030707e+00 -1.594643028330341994e-01 4.763583741186019904e-02 -2.911380238452138114e-01 9.420936299997494379e-01 +-1.751853244776126672e+01 1.471280485397276472e+01 2.169986494430891089e+00 -1.597935945782330835e-01 4.660807173512841045e-02 -2.931362906841420979e-01 9.414693874770819759e-01 +-1.749360712046400579e+01 1.470823595765781810e+01 2.168300470524465950e+00 -1.602048833166648811e-01 4.531525870765994862e-02 -2.941799139575875244e-01 9.411370248698095464e-01 +-1.745801525471232907e+01 1.470027967859899221e+01 2.166110862214427168e+00 -1.607828737305490308e-01 4.380865285503965367e-02 -2.943071296303092499e-01 9.410700126972115775e-01 +-1.741882322495211710e+01 1.469317200249942168e+01 2.163938381328017080e+00 -1.613279033958738840e-01 4.226787651504165105e-02 -2.936509542937228434e-01 9.412521680717634842e-01 +-1.737896885794033963e+01 1.468541492320332864e+01 2.164267197864405468e+00 -1.619048546725881388e-01 4.080061870030021742e-02 -2.923728871494927772e-01 9.416156437917089228e-01 +-1.732517095217490066e+01 1.467056184203279656e+01 2.166301326430514429e+00 -1.624501422565838293e-01 3.924979473063118507e-02 -2.905188307762270328e-01 9.421613522439444832e-01 +-1.726126185485400200e+01 1.465085560410666332e+01 2.171132953640088736e+00 -1.628620259007576287e-01 3.778866383611321350e-02 -2.880354133628819646e-01 9.429121825691334502e-01 +-1.719660886337743122e+01 1.463240272352795657e+01 2.175043059578144256e+00 -1.631772076012331096e-01 3.651314370467392822e-02 -2.850262011098593229e-01 9.438219432046217605e-01 +-1.712681734994837868e+01 1.461326579475347565e+01 2.179298359770279525e+00 -1.633524409900261043e-01 3.540889622928487107e-02 -2.816128215824896253e-01 9.448577738285589556e-01 +-1.704915580289160459e+01 1.459310383259100341e+01 2.183854887157135050e+00 -1.634045079515848709e-01 3.457048599237469433e-02 -2.778413567799292161e-01 9.459956815391612484e-01 +-1.696043605798555021e+01 1.457022790767244835e+01 2.188178644843842946e+00 -1.633968358729152026e-01 3.400307237291030210e-02 -2.737401073632363402e-01 9.472124447289032023e-01 +-1.686445452943246082e+01 1.454556340935098113e+01 2.192252050279553721e+00 -1.633193504788871819e-01 3.373760357456163234e-02 -2.693973164946810162e-01 9.484795406941164408e-01 +-1.676247652571894164e+01 1.451863900828790932e+01 2.195668851689526857e+00 -1.627230258886791237e-01 3.363081066303381245e-02 -2.648764450952924565e-01 9.498581159229988469e-01 +-1.665414071784867289e+01 1.448945165759921316e+01 2.199309790274477816e+00 -1.620861716074133430e-01 3.386812534102041222e-02 -2.601942143283090259e-01 9.512516870670147950e-01 +-1.654096545727008305e+01 1.445813648103237803e+01 2.201809227910159095e+00 -1.614146099625347330e-01 3.438326190478429439e-02 -2.554701948352409158e-01 9.526268243938107450e-01 +-1.642521524600244476e+01 1.442424229103463773e+01 2.204874207459998292e+00 -1.607356232978392752e-01 3.514888531803071064e-02 -2.508221460753407017e-01 9.539479241986402736e-01 +-1.630276064959747018e+01 1.438910735164141386e+01 2.207111311065022452e+00 -1.600734291322964964e-01 3.610716151405037738e-02 -2.463145030052167894e-01 9.551972140610355266e-01 +-1.617531324703833562e+01 1.435379086875449950e+01 2.208392404173166401e+00 -1.594634551745424123e-01 3.718634443121759947e-02 -2.420772117923132294e-01 9.563404116826896839e-01 +-1.604214904655785645e+01 1.431703333398411360e+01 2.210212697699383000e+00 -1.588795560143457797e-01 3.834523471075730605e-02 -2.382154889010023868e-01 9.573609992253030443e-01 +-1.590417679979208465e+01 1.427947412300661867e+01 2.210313007287423748e+00 -1.583865263573699944e-01 3.944165915495820990e-02 -2.348361943610171310e-01 9.582326377184082755e-01 +-1.576631978958427638e+01 1.424097358560167592e+01 2.207741055732447499e+00 -1.580269097823363833e-01 4.041997628330624287e-02 -2.320227947900415644e-01 9.589363356533610050e-01 +-1.562145330482072936e+01 1.420406578287582988e+01 2.203849486508297595e+00 -1.576936287658199654e-01 4.130167230877271334e-02 -2.297510513434703472e-01 9.595004439268123297e-01 +-1.546460777698472633e+01 1.416602655418754253e+01 2.202303482841406090e+00 -1.573713487654057608e-01 4.207713230364828333e-02 -2.282462273944179942e-01 9.598787356885335464e-01 +-1.530606226785305068e+01 1.413256628063003717e+01 2.199627038052340389e+00 -1.571426035282546818e-01 4.259567267890640441e-02 -2.278114988057656221e-01 9.599966085586523201e-01 +-1.514087565949761860e+01 1.409378848750856150e+01 2.199873242883951807e+00 -1.570254715378673060e-01 4.286541684680277020e-02 -2.283332991658232058e-01 9.598797937163758842e-01 +-1.498034452942751749e+01 1.405489914660284789e+01 2.200973272957193583e+00 -1.571775213891299372e-01 4.280269431575939310e-02 -2.299371452910466684e-01 9.594747592803697378e-01 +-1.482121006184025980e+01 1.401708694435837543e+01 2.197753955363283218e+00 -1.576473983988297967e-01 4.214352245069670488e-02 -2.325262432191075035e-01 9.588026482315483712e-01 +-1.466983996292526271e+01 1.397496022545172778e+01 2.194572255859627674e+00 -1.582920265446358388e-01 4.094213490888980872e-02 -2.361841713341422955e-01 9.578539371333814056e-01 +-1.453352887369791446e+01 1.393358679012593271e+01 2.190418074615139599e+00 -1.592016359939976422e-01 3.915596996180333716e-02 -2.409854874862833729e-01 9.565810926802701397e-01 +-1.439827424546816204e+01 1.388542956385763638e+01 2.183351167213614108e+00 -1.604243221444694723e-01 3.654193201848164596e-02 -2.472768717811687222e-01 9.548730884675132868e-01 +-1.425669761309909767e+01 1.383277627131903920e+01 2.173425473550271381e+00 -1.620682001990153831e-01 3.307854631736246998e-02 -2.551892415462925778e-01 9.526373409199061504e-01 +-1.412590162618181289e+01 1.377712114185407088e+01 2.167234427590452928e+00 -1.639446513721360132e-01 2.899553668503442386e-02 -2.648674162229788243e-01 9.498033491687686292e-01 +-1.399604943682839142e+01 1.372158914898174764e+01 2.163970265701970597e+00 -1.657858129734203489e-01 2.406582795187409488e-02 -2.762822044488303930e-01 9.463634454060370071e-01 +-1.384661139511829120e+01 1.365143058518259167e+01 2.161904520263594698e+00 -1.678233245218127556e-01 1.828506504258629178e-02 -2.893916232965937363e-01 9.422065621608289865e-01 +-1.368006921888726701e+01 1.356123087789077530e+01 2.166096155544508850e+00 -1.701283568415986325e-01 1.191197093043556629e-02 -3.039668466991156670e-01 9.372930924319964330e-01 +-1.350985440111793068e+01 1.345763383471481056e+01 2.175242283285886202e+00 -1.725710839785354611e-01 5.075239848615055449e-03 -3.194541419225832568e-01 9.317415178968395661e-01 +-1.333697703434933857e+01 1.334215600679860358e+01 2.185838791556650396e+00 -1.750679068924898552e-01 -2.337291607788242933e-03 -3.355921660815493479e-01 9.255935483312971446e-01 +-1.316622061469933058e+01 1.322387309937271560e+01 2.197136583342674587e+00 -1.775351457546254785e-01 -1.014724224601772258e-02 -3.520047064885605259e-01 9.189508931296438421e-01 +-1.299703565313839526e+01 1.310376719126060507e+01 2.215860596135141858e+00 -1.799735251964539040e-01 -1.806386358304223894e-02 -3.686207810301289078e-01 9.118123200612366919e-01 +-1.283168503003983929e+01 1.298131717868560742e+01 2.235696275939695443e+00 -1.824075464885830389e-01 -2.615885946035455267e-02 -3.851350973103248032e-01 9.042753526796357688e-01 +-1.267741113485115889e+01 1.286063583119418219e+01 2.260013652335474799e+00 -1.848076219677117216e-01 -3.410309760761479764e-02 -4.011888836470370312e-01 8.965100939703536387e-01 +-1.253201695949777950e+01 1.273853756466149889e+01 2.289854396520654589e+00 -1.871327884395841412e-01 -4.181670002319468060e-02 -4.167913561875874473e-01 8.885479215972782452e-01 +-1.239863978088368057e+01 1.262283651605162049e+01 2.320628911511395387e+00 -1.892500114284657031e-01 -4.925487165030190823e-02 -4.318127606038639765e-01 8.805088769975960572e-01 +-1.227396043270233683e+01 1.251183608098020805e+01 2.351509364719013728e+00 -1.912744275848471676e-01 -5.635579653835351421e-02 -4.460962716794354965e-01 8.724883850854173728e-01 +-1.216051823961005240e+01 1.240915076818466822e+01 2.382139946864808344e+00 -1.932260904940433788e-01 -6.292957144351564447e-02 -4.594119531511073329e-01 8.646640758342634125e-01 +-1.205266159099152823e+01 1.230780791279903319e+01 2.416061604298839871e+00 -1.949856614867817584e-01 -6.886831191208621361e-02 -4.715655968278623100e-01 8.572417331603260360e-01 +-1.194514238363695569e+01 1.220397806549690145e+01 2.455611748650547099e+00 -1.966094868358854442e-01 -7.416589001951345850e-02 -4.823695417288748066e-01 8.503902129255297426e-01 +-1.183827173554612244e+01 1.208747529584322855e+01 2.510145093144891426e+00 -1.982654813135747707e-01 -7.852441961796580161e-02 -4.916076360240347887e-01 8.443023175323814966e-01 +-1.173756014225560662e+01 1.196418221569341789e+01 2.581550381106281655e+00 -1.998543923968104929e-01 -8.183923493788647363e-02 -4.989418827405184831e-01 8.392957352908562152e-01 +-1.163732329880508054e+01 1.182568728239220590e+01 2.672790209931520167e+00 -2.011187590883487530e-01 -8.439271952813923172e-02 -5.044072222011399820e-01 8.354652951616321488e-01 +-1.153635173778608802e+01 1.166349977492017231e+01 2.788874222994223384e+00 -2.023787857096887022e-01 -8.622784410876796479e-02 -5.079827912772086895e-01 8.328030155242747146e-01 +-1.143950013689890000e+01 1.149166655351469402e+01 2.928524681772375349e+00 -2.035215056948520007e-01 -8.740878554344684581e-02 -5.095161711255729031e-01 8.314636210992372156e-01 +-1.135773304335328859e+01 1.133922297177344163e+01 3.075193507733003262e+00 -2.041824177583614619e-01 -8.757948540178962793e-02 -5.088236989862157111e-01 8.317076320332140726e-01 +-1.128699032941793767e+01 1.120075420766714025e+01 3.230513953070606181e+00 -2.047516830280953493e-01 -8.649289447884173088e-02 -5.060204106363749288e-01 8.333899617835321960e-01 +-1.122313447529674590e+01 1.107289294214347919e+01 3.385157011413508776e+00 -2.053711844052330260e-01 -8.408611022249672107e-02 -5.012543003408139741e-01 8.363588315347345592e-01 +-1.115248117688900820e+01 1.094133733651713491e+01 3.555691288090234714e+00 -2.056462033375179854e-01 -8.075730723813241696e-02 -4.951674025132455914e-01 8.402362303435323421e-01 +-1.108732048213619414e+01 1.081456404053830234e+01 3.717121101071051648e+00 -2.059910685309201961e-01 -7.650109225546963820e-02 -4.874224662550116771e-01 8.450647273734225307e-01 +-1.101494070912414713e+01 1.068284157588535521e+01 3.886119635478032297e+00 -2.061466384733158519e-01 -7.127643491142374166e-02 -4.784386800959306019e-01 8.505994696215272155e-01 +-1.093524173425383594e+01 1.054803923807605948e+01 4.058019727573429769e+00 -2.061099341383379191e-01 -6.507997307295336487e-02 -4.681790076260793354e-01 8.567914006080686873e-01 +-1.084763447487299537e+01 1.041268831336648404e+01 4.229629705735738376e+00 -2.057315387040039856e-01 -5.772430254235429853e-02 -4.568317663531050177e-01 8.635085207620848413e-01 +-1.074511561564592022e+01 1.027247535588492511e+01 4.400687582912439666e+00 -2.046454030423378867e-01 -4.918420410341037274e-02 -4.446273787415646606e-01 8.706362310051629638e-01 +-1.062932761967035589e+01 1.012820442647781150e+01 4.553728133787957155e+00 -2.029565690760325170e-01 -3.949167088139289572e-02 -4.311415380845254330e-01 8.782743283105247656e-01 +-1.049700918522519721e+01 9.987838589611772733e+00 4.669379209295867028e+00 -2.008189702976947155e-01 -2.903101795731325221e-02 -4.166969991530746209e-01 8.861107850649578843e-01 +-1.035518267560249939e+01 9.861969085908372179e+00 4.751070819784137811e+00 -1.958454252688869301e-01 -1.868715204652300274e-02 -4.016501144514015298e-01 8.944117098230366381e-01 +-1.020832808150564475e+01 9.749660002455138752e+00 4.807984829444467145e+00 -1.903070630035642863e-01 -7.593968791745912307e-03 -3.861295325734883654e-01 9.025681642910160507e-01 +-1.006462358990678396e+01 9.652235384479599389e+00 4.846173601572889567e+00 -1.847445601796558479e-01 4.365578917755052676e-03 -3.701214127740822257e-01 9.104176421348203485e-01 +-9.928657381585725972e+00 9.568888013689392125e+00 4.867075191618293495e+00 -1.792362421215590584e-01 1.718675473453972966e-02 -3.538081418758112218e-01 9.178227182108023019e-01 +-9.795577920659157556e+00 9.494090355712675233e+00 4.878113693445429888e+00 -1.737343257625819093e-01 3.081909256437668707e-02 -3.375861476186318155e-01 9.246090618534862360e-01 +-9.661176967701988971e+00 9.423962946457072221e+00 4.882171328813533329e+00 -1.681756565410551796e-01 4.502750568400982339e-02 -3.216238190481252035e-01 9.307240917155382709e-01 +-9.526235813569117639e+00 9.358046157154838340e+00 4.879546246116782449e+00 -1.627319079534192414e-01 5.965657446638202022e-02 -3.062229051444254613e-01 9.360484561081945376e-01 +-9.390715066920950704e+00 9.294511340234727470e+00 4.872074737937317046e+00 -1.575600456324180998e-01 7.452147882480016083e-02 -2.916078133009603612e-01 9.405243241610005134e-01 +-9.255741124676109877e+00 9.233168477068076641e+00 4.862719929474887515e+00 -1.526083636231672647e-01 8.970028692292388028e-02 -2.779558671478457588e-01 9.441423766854085686e-01 +-9.110115748703927707e+00 9.160656321856599504e+00 4.853119718596683008e+00 -1.448805444527668240e-01 1.042704447501368176e-01 -2.654940920189678422e-01 9.474438960705133805e-01 +-8.960508298635936342e+00 9.086392725294514250e+00 4.844143091669125489e+00 -1.368322183912593359e-01 1.191111185464089617e-01 -2.543805445511533869e-01 9.499367212115463754e-01 +-8.802053506879710554e+00 9.010855401599721759e+00 4.832301039463605896e+00 -1.284837162166377333e-01 1.338807568014935556e-01 -2.445762298229477716e-01 9.517090363254917529e-01 +-8.636209778905397982e+00 8.932626204285671889e+00 4.818409796669749667e+00 -1.199414029479377447e-01 1.484064460215570591e-01 -2.359549264073556307e-01 9.528455386988187170e-01 +-8.464140448895715707e+00 8.850351050039439116e+00 4.803352734674167124e+00 -1.112792292450228149e-01 1.626455393506967828e-01 -2.284682760107906996e-01 9.533967514881616090e-01 +-8.285842459073196054e+00 8.773383956707331066e+00 4.782369279912356497e+00 -1.025146313610508786e-01 1.764788996614772842e-01 -2.221124353490130932e-01 9.534210932004744121e-01 +-8.114133289484326994e+00 8.705543691922068561e+00 4.757856858937089761e+00 -9.388423022029269982e-02 1.897102117440097879e-01 -2.167248350967028725e-01 9.530088667976455152e-01 +-7.966413532293470823e+00 8.649262174225476940e+00 4.732697675124038383e+00 -8.546786416506156614e-02 2.021958267635559636e-01 -2.122202162550722582e-01 9.522470547132205754e-01 +-7.838296370121983436e+00 8.602142342702320477e+00 4.706681049907486702e+00 -7.722082121429661716e-02 2.138807004510542842e-01 -2.086132058058942085e-01 9.511951941279739309e-01 +-7.722460607913379960e+00 8.555961850315631168e+00 4.682140683149526694e+00 -6.926594664978155680e-02 2.246589746999888837e-01 -2.057724656928235640e-01 9.499410831019948764e-01 +-7.623831137275054459e+00 8.512771062322395110e+00 4.657138786462549085e+00 -6.168996695748747705e-02 2.343784833952097801e-01 -2.037189628972736477e-01 9.485565157627455779e-01 +-7.546843188356539223e+00 8.472208031328831268e+00 4.633192190619449313e+00 -5.450375163225126135e-02 2.430585373033365970e-01 -2.024227503969243946e-01 9.470885500355606945e-01 +-7.486476728816337634e+00 8.440815148072747576e+00 4.610710309118721817e+00 -4.770571378634198140e-02 2.506317554601256714e-01 -2.020770809235940546e-01 9.455540866581557680e-01 +-7.440299964705224589e+00 8.416958122596488678e+00 4.593164121767197905e+00 -4.140588616186403198e-02 2.570514082178247950e-01 -2.025012668505896951e-01 9.440355657182665228e-01 +-7.396345226618334046e+00 8.397243593556252605e+00 4.580928575928226998e+00 -3.559464193890889833e-02 2.619480351332992840e-01 -2.040529019416751078e-01 9.425913457587361544e-01 +-7.359082997625071343e+00 8.384106685373392764e+00 4.568838528947360977e+00 -3.082171805157595326e-02 2.643322252904545810e-01 -2.069175931235628374e-01 9.414687456203280069e-01 +-7.302026356289392339e+00 8.357480387139352374e+00 4.544941278909785609e+00 -2.705147037784246672e-02 2.635474766097758992e-01 -2.108188989966877647e-01 9.409389584548618624e-01 +-7.249194796845570998e+00 8.332448662081926472e+00 4.522177037968137192e+00 -2.348931618740522642e-02 2.629461495568421459e-01 -2.151934143954868928e-01 9.402122886374607580e-01 +-7.192574988222773413e+00 8.304052243351245366e+00 4.498606689260705949e+00 -2.019453168423964579e-02 2.624139011815839195e-01 -2.200437222374501678e-01 9.393144602230939499e-01 +-7.134046519940341113e+00 8.271338824996039563e+00 4.475103494481515121e+00 -1.720243089105051582e-02 2.619425976925379151e-01 -2.252009680059845753e-01 9.382827111412271881e-01 +-7.101496752580978011e+00 8.256352049370411450e+00 4.464792718273583816e+00 -1.608926579076124311e-02 2.563946365376729153e-01 -2.316767545295572439e-01 9.382582764825715405e-01 +-7.066311361565515980e+00 8.229456314921264948e+00 4.452957677367096245e+00 -1.588172072373412666e-02 2.486992594060363493e-01 -2.384370209333511736e-01 9.386394576744967466e-01 +-7.023231946952388505e+00 8.189605347353088760e+00 4.440963527834605351e+00 -1.649931232245117549e-02 2.391868458650006912e-01 -2.455518537738545781e-01 9.392664750276934482e-01 +-6.979041839034425543e+00 8.143272453791784216e+00 4.430181111014941386e+00 -1.786565177166500942e-02 2.279937541361085895e-01 -2.529972316317633529e-01 9.400488617876656683e-01 +-6.935183589108718571e+00 8.089564188639213782e+00 4.422930206766563899e+00 -1.998480485305475368e-02 2.154290072454379257e-01 -2.606377633159859819e-01 9.408818707293717942e-01 +-6.888868303451047836e+00 8.030702240266915481e+00 4.417015406419602996e+00 -2.287103566259705151e-02 2.016401886372044816e-01 -2.684141293202135237e-01 9.416856130777121470e-01 +-6.840674241225232599e+00 7.967394404473957081e+00 4.412340650852007329e+00 -2.640110625360386071e-02 1.867330320427368351e-01 -2.761348269065626027e-01 9.424346671394686625e-01 +-6.783646706868969645e+00 7.893077095892037320e+00 4.406745275081826563e+00 -3.049310860789122488e-02 1.707747820104351943e-01 -2.838466760501241470e-01 9.430466609513866727e-01 +-6.706675553581081139e+00 7.805858116523429757e+00 4.399698552885772607e+00 -3.517078950191957626e-02 1.539407376304821329e-01 -2.915211517472718339e-01 9.434407566295304193e-01 +-6.608358311218235137e+00 7.714939868202249862e+00 4.390607292666790507e+00 -4.032984107040732402e-02 1.362637847355430420e-01 -2.991954937832328465e-01 9.435504829919811876e-01 +-6.496344793411751084e+00 7.635577509875125735e+00 4.374959519035974687e+00 -4.606334997161197486e-02 1.176713080147281237e-01 -3.069104571995260322e-01 9.433119127938537352e-01 +-6.377487104502294279e+00 7.559796599687431673e+00 4.357834903699150608e+00 -5.216803244863016387e-02 9.851820270137630342e-02 -3.145480621841146851e-01 9.426727619600988595e-01 +-6.253332481168209611e+00 7.486272953676961883e+00 4.337973343863350983e+00 -5.869621212591501908e-02 7.896475123581589428e-02 -3.220200705284214648e-01 9.416061618763930108e-01 +-6.125955660049786644e+00 7.416734456754976890e+00 4.318464720724177752e+00 -6.561700398737782547e-02 5.905604672987263548e-02 -3.295377877320313509e-01 9.400060645074467258e-01 +-6.003543153951099498e+00 7.348223801923311704e+00 4.300963972352018772e+00 -7.299305252052640247e-02 3.916334266508965378e-02 -3.366025357079139857e-01 9.379961291790802624e-01 +-5.880512867404823041e+00 7.277274617380643740e+00 4.282508140535700392e+00 -8.085000752411357350e-02 1.931657739625739292e-02 -3.431589170379617526e-01 9.355917188810530805e-01 +-5.752199727943890117e+00 7.205898979355740863e+00 4.264124981893480104e+00 -8.880612838383861174e-02 -1.839939236060274318e-04 -3.490965591188769923e-01 9.328691180592872945e-01 +-5.620867968844497575e+00 7.133680648589026951e+00 4.248143531305163201e+00 -9.684880036799936587e-02 -1.922477257833903747e-02 -3.542156685044489661e-01 9.299364131219416407e-01 +-5.487357874667395663e+00 7.063942181732535630e+00 4.235131167686096987e+00 -1.048774302590843588e-01 -3.769935494056864816e-02 -3.586219151837029551e-01 9.268061084962051499e-01 +-5.351468054219385984e+00 7.001415512029576682e+00 4.221427222353877795e+00 -1.129437658115804433e-01 -5.559397401524718285e-02 -3.623312765097851940e-01 9.235089714721697041e-01 +-5.215343083461586815e+00 6.942455538290364991e+00 4.209360461916056728e+00 -1.210502069832659344e-01 -7.255572553426346827e-02 -3.652346965790361222e-01 9.201553656388268276e-01 +-5.077978219438366914e+00 6.884623083408889066e+00 4.199271436486815112e+00 -1.293062233471359845e-01 -8.853527020957462079e-02 -3.674283988327597394e-01 9.167538155023878810e-01 +-4.936981366718767639e+00 6.825944957851960204e+00 4.184431251317998424e+00 -1.377268663162275475e-01 -1.038090277746670370e-01 -3.689458283477936029e-01 9.133092345837549031e-01 +-4.799067951959267830e+00 6.767530718028485381e+00 4.167587916588884056e+00 -1.462227977877073315e-01 -1.183681824697107587e-01 -3.697480938739740042e-01 9.098868043232711811e-01 +-4.659851106914774554e+00 6.708264457925801061e+00 4.146864561326532694e+00 -1.546790427632031839e-01 -1.322488951593409623e-01 -3.700943353112481904e-01 9.064295818552727813e-01 +-4.522188911375335962e+00 6.649766699923481461e+00 4.125261756970721727e+00 -1.630881252217175059e-01 -1.453561096703797351e-01 -3.699021021501966988e-01 9.030205405840713295e-01 +-4.384336257272807735e+00 6.592750756864155015e+00 4.104585628073848191e+00 -1.713861896820074171e-01 -1.577184267005262430e-01 -3.692641992798849082e-01 8.996640653209384553e-01 +-4.250973995207671052e+00 6.537395187942486530e+00 4.087722524472261476e+00 -1.795708065933855901e-01 -1.692032476285243170e-01 -3.683439904464128056e-01 8.963521108677855453e-01 +-4.119881159089879397e+00 6.483124114210427891e+00 4.074099790579315261e+00 -1.875247269533678318e-01 -1.798487727683729109e-01 -3.671948340929857002e-01 8.931162726885953917e-01 +-3.986719846703399739e+00 6.430081682505231377e+00 4.063457033507956950e+00 -1.950501282673557935e-01 -1.897321176069262927e-01 -3.657920878694423394e-01 8.900298624484728194e-01 +-3.857806398098146961e+00 6.376368202825703158e+00 4.050154850419703578e+00 -2.025033880086890281e-01 -1.989905774586621656e-01 -3.640499842730823832e-01 8.870527416890000572e-01 +-3.733261705384908868e+00 6.323539375167103849e+00 4.034584292157113339e+00 -2.097529231168790420e-01 -2.076064800471262295e-01 -3.621125463825130009e-01 8.841818827288916438e-01 +-3.608895954391719840e+00 6.268594256964607148e+00 4.018608938499705019e+00 -2.167298606279331741e-01 -2.157054293662292455e-01 -3.599471943344783043e-01 8.814404110978438789e-01 +-3.484578877128846841e+00 6.211247339903801290e+00 4.002878100488556967e+00 -2.233355575556960071e-01 -2.232795469326028792e-01 -3.575758573962185549e-01 8.788667835228113345e-01 +-3.361961781382274861e+00 6.152604211490512398e+00 3.987491560176556593e+00 -2.296326114300094590e-01 -2.303731593773752084e-01 -3.550985408290596168e-01 8.764142549027159612e-01 +-3.232963224561080207e+00 6.092362024818040567e+00 3.971946792803201731e+00 -2.355387531475781060e-01 -2.370476390156331381e-01 -3.525263185246546027e-01 8.741023728411995153e-01 +-3.096806288696448473e+00 6.032428544600991316e+00 3.957059679993236934e+00 -2.409063130901048233e-01 -2.432742862646420090e-01 -3.499663749929467493e-01 8.719547870850730131e-01 +-2.947835898989248804e+00 5.971301466077779452e+00 3.941377327530580121e+00 -2.457396268570619657e-01 -2.491844071049651721e-01 -3.474969933653390686e-01 8.699223264919266896e-01 +-2.785655452816519606e+00 5.908597375916054162e+00 3.925311168851185695e+00 -2.499514306323248614e-01 -2.546738318261297929e-01 -3.451455502244761275e-01 8.680667693277970276e-01 +-2.612704489809447139e+00 5.843342742627270603e+00 3.908542328851709158e+00 -2.535515842518141771e-01 -2.598313598438937166e-01 -3.429015539914031518e-01 8.663819208033343156e-01 +-2.455399236820277942e+00 5.785151754944600100e+00 3.892242304149701848e+00 -2.539072761237607390e-01 -2.659010252763311377e-01 -3.403582355159561201e-01 8.654385333501263267e-01 +-2.293190962984199999e+00 5.723915231927273695e+00 3.876423312901263962e+00 -2.542894226008700631e-01 -2.714890557432704798e-01 -3.381377392628824308e-01 8.644612780053019252e-01 +-2.132373455540924390e+00 5.660935038304082845e+00 3.860920394488562835e+00 -2.547217607893528246e-01 -2.766660536020267291e-01 -3.362315999067881922e-01 8.634355157012689741e-01 +-1.971021436458088694e+00 5.595174079862699656e+00 3.846183329849794941e+00 -2.551964250719007121e-01 -2.814446574914436505e-01 -3.345882303122783008e-01 8.623887001362717797e-01 +-1.807598528662877957e+00 5.524880524458068543e+00 3.830543208442553027e+00 -2.557911745855398489e-01 -2.858331761697825990e-01 -3.331920886003421067e-01 8.613089869330943227e-01 +-1.636396750634920849e+00 5.449308591653828415e+00 3.814179987336483002e+00 -2.564356646716348109e-01 -2.898095296325224335e-01 -3.320076105548865342e-01 8.602453154731618534e-01 +-1.462849563296797939e+00 5.371808452666209099e+00 3.797672266084052506e+00 -2.570846326308839913e-01 -2.934042790718436877e-01 -3.310843152500332343e-01 8.591882670241032249e-01 +-1.288959287414961796e+00 5.292917677155276834e+00 3.781545168563773984e+00 -2.577150435771182191e-01 -2.966579214383787133e-01 -3.303889811051302083e-01 8.581491827892056001e-01 +-1.110384294059284738e+00 5.211388943277480479e+00 3.765021413855301535e+00 -2.582909199352131369e-01 -2.996411462888850519e-01 -3.299194320397960123e-01 8.571196094334919691e-01 +-9.306947922898101133e-01 5.129943480558734947e+00 3.748700907305206886e+00 -2.588553676685850791e-01 -3.023829077184999603e-01 -3.296466100733500548e-01 8.560908006544866167e-01 +-7.494490685971613164e-01 5.049509158624354122e+00 3.732439212189940125e+00 -2.593950529272124883e-01 -3.049098097719332712e-01 -3.295787314463892170e-01 8.550566825203730348e-01 +-5.667012248128854290e-01 4.970188515249279071e+00 3.716356193768302063e+00 -2.599189540195596115e-01 -3.071948295083041791e-01 -3.296747320403945469e-01 8.540421010068511842e-01 +-3.860252854679036005e-01 4.892396188679936309e+00 3.700342768031741336e+00 -2.604240794617456167e-01 -3.092307619911773275e-01 -3.299333368873552663e-01 8.530530468325369098e-01 +-2.072054335978287809e-01 4.816065056247569309e+00 3.683928818633339208e+00 -2.608932064002745799e-01 -3.110089615292314091e-01 -3.303045370677028525e-01 8.521190897992432234e-01 +-2.447975579075292729e-02 4.740467106325708890e+00 3.665415456885624312e+00 -2.613135702090207402e-01 -3.126000364908323448e-01 -3.308125963372271494e-01 8.512105144502563059e-01 +1.595740249002560729e-01 4.665596905702058095e+00 3.644972489376070879e+00 -2.616471515267254078e-01 -3.140208114602017209e-01 -3.314132164393753244e-01 8.503510167153639498e-01 +3.471288447045393077e-01 4.592472284345312517e+00 3.621866047608115924e+00 -2.619265891786012879e-01 -3.153883736017398798e-01 -3.320535384187794925e-01 8.495086451738068645e-01 +5.396921092991235902e-01 4.519869961037433548e+00 3.596445246442431909e+00 -2.621150676509559907e-01 -3.167384979479005991e-01 -3.326630847997775198e-01 8.487093440523550969e-01 +7.346148540931147775e-01 4.446154606730820191e+00 3.569251401890256137e+00 -2.622470510724456694e-01 -3.180828556285650865e-01 -3.331491282575469448e-01 8.479748298607119317e-01 +9.277145905395938197e-01 4.371409091765972477e+00 3.540091949644653901e+00 -2.626230253190023900e-01 -3.193624715034126260e-01 -3.335856134824063957e-01 8.472055639799496163e-01 +1.147408349023798069e+00 4.281853873535411026e+00 3.511632800095275897e+00 -2.628203931086945389e-01 -3.193106846024571510e-01 -3.337710710169577433e-01 8.470908282256689459e-01 +1.371228197384347425e+00 4.190689634470587954e+00 3.482504849926784107e+00 -2.630578164411414566e-01 -3.193105176189386385e-01 -3.338745359760006415e-01 8.469764171327285318e-01 +1.602631115346870860e+00 4.097610571536848489e+00 3.453718898542426530e+00 -2.632061328141644396e-01 -3.193060045923379331e-01 -3.339019271168552905e-01 8.469212385752546979e-01 +1.842365399673236093e+00 4.002317572365756249e+00 3.425523951207936957e+00 -2.633080283766072172e-01 -3.192899564009949454e-01 -3.338950352034970037e-01 8.468983398369697158e-01 +2.094720218907040632e+00 3.903878329413128512e+00 3.398803037233063318e+00 -2.633433159475628282e-01 -3.192180823322913752e-01 -3.338741291112674592e-01 8.469227088957377303e-01 +2.354262591754949341e+00 3.802152009202809158e+00 3.371593096554410085e+00 -2.633424979717358116e-01 -3.191920957378263646e-01 -3.337663848244893927e-01 8.469752245128163715e-01 +2.604197411746636881e+00 3.703220435939146959e+00 3.344303562073439817e+00 -2.633523283509775492e-01 -3.191927118787689643e-01 -3.336429326564991360e-01 8.470205656605683808e-01 +2.849775638970309721e+00 3.605343351638679028e+00 3.316527186966311547e+00 -2.633916373959189206e-01 -3.191995139476732080e-01 -3.334907466265020770e-01 8.470657089718527377e-01 +3.097269574732867792e+00 3.506807682250299152e+00 3.289455236294969609e+00 -2.634189178173160228e-01 -3.191981926378932299e-01 -3.333384052945241316e-01 8.471176831536757490e-01 +3.342667446625483318e+00 3.406404482585304372e+00 3.262533902487871007e+00 -2.635555257933511752e-01 -3.191790282508754628e-01 -3.331869385297593911e-01 8.471420100346495063e-01 +3.593692424357135540e+00 3.301117941430975478e+00 3.236380047578341745e+00 -2.637593801182107622e-01 -3.191393166883175203e-01 -3.330730963503033548e-01 8.471382904737906339e-01 +3.852259093578912719e+00 3.192793752004558172e+00 3.213368726070757742e+00 -2.640442641389767475e-01 -3.189400741266654737e-01 -3.330624427466959414e-01 8.471287691376589990e-01 +4.113682057355155131e+00 3.082963511105495158e+00 3.191243107632094844e+00 -2.643981242925143027e-01 -3.187506099625990741e-01 -3.331401395710793523e-01 8.470591522750866575e-01 +4.370650574498331942e+00 2.977905077017091617e+00 3.169436135804180488e+00 -2.645646206709125758e-01 -3.185704737972833156e-01 -3.334163189360682122e-01 8.469662612022570425e-01 +4.620010054486803242e+00 2.871391553607040237e+00 3.146975411462293870e+00 -2.647681049364830619e-01 -3.183207930799472063e-01 -3.337982696995875909e-01 8.468461048975165495e-01 +4.863105136758973934e+00 2.762516502334317892e+00 3.123525705996005097e+00 -2.651349630960089243e-01 -3.180136252111560591e-01 -3.342822003727763946e-01 8.466558281521140428e-01 +5.106965073624266438e+00 2.652677746937647907e+00 3.098733993142643417e+00 -2.655768091290671706e-01 -3.176437851507328269e-01 -3.348761857328731439e-01 8.464214163404696345e-01 +5.354525067790735449e+00 2.541683752404830798e+00 3.074547760560428333e+00 -2.659806296365726519e-01 -3.173161632991127190e-01 -3.356035998930727571e-01 8.461293501372315617e-01 +5.597027485204747244e+00 2.429894493447691151e+00 3.050253510475960272e+00 -2.664232896895293301e-01 -3.169067121365465312e-01 -3.365219601688203555e-01 8.457787065808948235e-01 +5.836457741611654981e+00 2.315672829549108691e+00 3.025680323846295483e+00 -2.668654645992337149e-01 -3.164087699659623443e-01 -3.375767531686643674e-01 8.454053050542151837e-01 +6.117179288033596229e+00 2.190876188079310172e+00 3.010688665963426658e+00 -2.625925915965534596e-01 -3.144352311098035924e-01 -3.373157174925847657e-01 8.475810285781371078e-01 +6.392460556058090049e+00 2.067228880174349470e+00 2.996010438678178733e+00 -2.575668981622772358e-01 -3.123728920230591788e-01 -3.369449988173235377e-01 8.500296443946259162e-01 +6.658490381244710044e+00 1.939125647571039002e+00 2.981245968920347877e+00 -2.517209370236194732e-01 -3.102719220936205891e-01 -3.366281794051740883e-01 8.526718178173181562e-01 +6.912966313485639169e+00 1.809531368391803952e+00 2.966588253924220098e+00 -2.453541443386767218e-01 -3.081337647487315534e-01 -3.361372045666425334e-01 8.554919993791344490e-01 +7.166081066372939290e+00 1.678144150695186188e+00 2.953539738913553148e+00 -2.383598649625162380e-01 -3.059262103830030499e-01 -3.355485534593488084e-01 8.584874814499373619e-01 +7.407934894783917201e+00 1.540454532724790937e+00 2.940250316007217535e+00 -2.308189700194129834e-01 -3.039631380850821296e-01 -3.349167410328621752e-01 8.614868743738993695e-01 +7.645869190725107956e+00 1.402894482678236576e+00 2.927984272082231776e+00 -2.226982507458010185e-01 -3.019744150717587616e-01 -3.342011298824619780e-01 8.645960845077699242e-01 +7.879217222833892365e+00 1.263399767335893875e+00 2.916618247588234958e+00 -2.140442592818645184e-01 -3.000658136006504884e-01 -3.333421032048318744e-01 8.677721226945004362e-01 +8.101334182756193769e+00 1.114780728356713269e+00 2.903659326891121051e+00 -2.054042949094037063e-01 -2.983662472546353972e-01 -3.324355015884601916e-01 8.707888081023515969e-01 +8.316225389912437649e+00 9.739550368439301442e-01 2.890432379311826061e+00 -1.964004584317672053e-01 -2.967803379525187912e-01 -3.314081403746222954e-01 8.737944784908888707e-01 +8.518734735201679342e+00 8.313422478980142527e-01 2.874659751083602721e+00 -1.873391067637601437e-01 -2.954759115789979962e-01 -3.305242338919597844e-01 8.765566865973857258e-01 +8.714223449303062807e+00 6.901135551082709929e-01 2.853743022883866498e+00 -1.783814212996334136e-01 -2.947715811138956754e-01 -3.296676214527598514e-01 8.789817337026891719e-01 +8.901441703891322277e+00 5.477546585134192014e-01 2.829696535221562392e+00 -1.695609075824687784e-01 -2.944237726621946050e-01 -3.287275382093225451e-01 8.811933876497437534e-01 +9.078252217730501172e+00 4.047536081228386706e-01 2.802179636631398463e+00 -1.607081968684333506e-01 -2.945056761842785309e-01 -3.277574482865859284e-01 8.831841102795328080e-01 +9.256796672624741262e+00 2.524054102349223561e-01 2.773384531365481021e+00 -1.521706827702955511e-01 -2.949674485666893275e-01 -3.268486962327947776e-01 8.848774271648428558e-01 +9.437211480952583997e+00 1.019943370345930134e-01 2.740277687602983736e+00 -1.435440180017515943e-01 -2.962383808567644605e-01 -3.259722865758864496e-01 8.862165957787457859e-01 +9.614766413691938851e+00 -4.729431208288253918e-02 2.704138251970213069e+00 -1.351058412327545422e-01 -2.977652060887240881e-01 -3.255769416052359810e-01 8.871763062267944422e-01 +9.770680202075253007e+00 -2.137748156193516880e-01 2.660377981225994670e+00 -1.277980964958311261e-01 -2.994357142642493641e-01 -3.253508338443577008e-01 8.877795700325497030e-01 +9.895132899960527695e+00 -3.858343836036971508e-01 2.598976673030808371e+00 -1.209923776176651394e-01 -3.012916446279859106e-01 -3.253564029833109772e-01 8.881031691856229315e-01 +1.000784447976543312e+01 -5.542553917153727472e-01 2.539350212476968682e+00 -1.150348663748838318e-01 -3.041427652656003011e-01 -3.249411924668446083e-01 8.880750053336999850e-01 +1.011265858691146668e+01 -7.179240050332311718e-01 2.470303229771022568e+00 -1.093006246538966303e-01 -3.081398019909077357e-01 -3.242624791160269027e-01 8.876693710704502971e-01 +1.022179692454391642e+01 -8.938462439381638092e-01 2.398513353490872024e+00 -1.035879986039058426e-01 -3.130950296430229929e-01 -3.240235413764137040e-01 8.867071670131574379e-01 +1.031148418984229131e+01 -1.040490301961203068e+00 2.307379810975608070e+00 -9.895497979985456993e-02 -3.183025159083416877e-01 -3.241619410384071198e-01 8.853305944841912689e-01 +1.037458622336226632e+01 -1.199648378737218524e+00 2.155572717082807621e+00 -9.703088203751170093e-02 -3.235862015959237725e-01 -3.236099439488839824e-01 8.838288200747589363e-01 +1.033318031932382652e+01 -1.293788436612981485e+00 1.905604072331350318e+00 -9.583695922994829586e-02 -3.271036389910402797e-01 -3.223569286728097949e-01 8.831218936305078593e-01 +1.023160183727370587e+01 -1.297948238006191302e+00 1.686275207041092905e+00 -9.387844954349483517e-02 -3.285142537315361988e-01 -3.222070139403097611e-01 8.828633200513485990e-01 +1.013119133191871235e+01 -1.261453794927615002e+00 1.542548847588035343e+00 -9.191333695847365981e-02 -3.317726228408854894e-01 -3.209426832334480451e-01 8.823119792264556560e-01 +9.993068328826669955e+00 -1.199750050880664665e+00 1.419193056000999986e+00 -8.955600720068797316e-02 -3.350458152737550988e-01 -3.208571001218437635e-01 8.813481293069412859e-01 +9.839563844464670694e+00 -1.128046972397543257e+00 1.338773818802253768e+00 -8.716823732184753037e-02 -3.382973192498133219e-01 -3.202054633799073513e-01 8.805821249443431809e-01 +9.728775802832204889e+00 -1.067105695522975850e+00 1.317468721063768111e+00 -8.511297273402342045e-02 -3.411115703857309223e-01 -3.203872894876689248e-01 8.796308638173925276e-01 +9.592023064321383075e+00 -9.725138047100572170e-01 1.308323457140910140e+00 -8.324578925318551481e-02 -3.431697891317079252e-01 -3.206000584852718993e-01 8.789311876194231266e-01 +9.442514675688185477e+00 -8.865337403329596189e-01 1.309883048538571071e+00 -8.166234106319285313e-02 -3.443225012511207939e-01 -3.203618421632400404e-01 8.787157501268997306e-01 +9.243589006673698094e+00 -7.912641982220930403e-01 1.325250630842437660e+00 -8.058690716438521306e-02 -3.443962014632983015e-01 -3.198974240769477673e-01 8.789553095603842570e-01 +9.018713194484710982e+00 -6.973293621360053818e-01 1.349168903506297035e+00 -7.925052868461171518e-02 -3.430578774573275203e-01 -3.191651674739566236e-01 8.798659243559093790e-01 +8.794012934437590800e+00 -6.187998979776567765e-01 1.382093492347846064e+00 -7.754037262700048949e-02 -3.400949725598375606e-01 -3.182367278169105362e-01 8.815033030004451042e-01 +8.581093571463386027e+00 -5.678327707402348601e-01 1.432173235376540177e+00 -7.591787169801128554e-02 -3.351992479099216160e-01 -3.175150776307634204e-01 8.837770662728448023e-01 +8.356264859884369400e+00 -5.286084301729339074e-01 1.484533567428590217e+00 -7.475072075718444675e-02 -3.282424444301498823e-01 -3.172419918661169014e-01 8.865813747828040770e-01 +8.118141635712989412e+00 -4.533118041249175612e-01 1.546988785181073300e+00 -7.313787077684372195e-02 -3.184073158508980428e-01 -3.174481306661658953e-01 8.902213780012463440e-01 +7.885570979441841821e+00 -3.983022579506699801e-01 1.601614041429946012e+00 -7.222139811872199666e-02 -3.061747143521878489e-01 -3.167312789249355776e-01 8.948308206659270070e-01 +7.682280939427666766e+00 -3.426629948067420051e-01 1.660634392982965668e+00 -7.179067418860048122e-02 -2.919527620693291858e-01 -3.160240699340598480e-01 8.998545718211709010e-01 +7.483608420427465546e+00 -2.961222204354244103e-01 1.719483263801687478e+00 -7.238493429684997316e-02 -2.753927756205827304e-01 -3.125801758836983524e-01 9.062078343684074611e-01 +7.309593075800011164e+00 -2.491927950743856868e-01 1.762921616388872792e+00 -7.432672740303010450e-02 -2.591273842264239513e-01 -3.102336817168699912e-01 9.116377394746917329e-01 +7.186201407452266210e+00 -1.870181783399862685e-01 1.766995228434814047e+00 -7.570759026599568897e-02 -2.432403940302289014e-01 -3.089772647673496020e-01 9.163161567725046641e-01 +7.040016477131526784e+00 -1.254953908139266883e-01 1.774089566325022238e+00 -7.670085028303229302e-02 -2.236201011955259443e-01 -3.070589235930023531e-01 9.218598784147321590e-01 +6.883667222996407986e+00 -6.709789548504513368e-02 1.768740016452765795e+00 -7.695912179331232394e-02 -2.017136002352660218e-01 -3.033548059118340579e-01 9.280972875644398767e-01 +6.722489697222223448e+00 -7.132980592086404781e-03 1.773727667361867155e+00 -7.704205922201358414e-02 -1.771477949789016793e-01 -2.990543712304484791e-01 9.344781770924713848e-01 +6.553664031184613492e+00 4.363647910078472664e-02 1.788075056764896420e+00 -7.705471421229488638e-02 -1.507743054792893000e-01 -2.944771267846891249e-01 9.405385123347719256e-01 +6.399744872508970950e+00 9.213386090419793673e-02 1.804570210033077604e+00 -7.626469955704046066e-02 -1.232300052429474158e-01 -2.889706227736842936e-01 9.463053576260282984e-01 +6.283577945003052889e+00 1.409379348652331776e-01 1.817695696466347099e+00 -7.497477266826389763e-02 -9.556048504081869621e-02 -2.839805537480736830e-01 9.511055689135718971e-01 +6.165654234236661146e+00 1.886136316691612858e-01 1.828152981630380758e+00 -7.364911608445168234e-02 -6.751080611787575736e-02 -2.786812776149009130e-01 9.551725629693529340e-01 +6.006019668023494518e+00 2.544104705378745779e-01 1.826357011983414491e+00 -7.209285452247593540e-02 -3.768186370331205043e-02 -2.730092473174886014e-01 9.585658163086976380e-01 +5.851285669886095775e+00 3.135814254923192101e-01 1.831344793058397036e+00 -7.008086715476420647e-02 -7.712049288828025199e-03 -2.676113689847374744e-01 9.609438667054630567e-01 +5.687481187047801257e+00 3.753294979574372525e-01 1.826613185591021926e+00 -6.757506981026646653e-02 2.210565334137030991e-02 -2.620294546172630690e-01 9.624371524220843854e-01 +5.572482549207586899e+00 4.318711072780065385e-01 1.824131582377623184e+00 -6.455514472084453170e-02 5.101699181857401871e-02 -2.566402477532203075e-01 9.629981458207059752e-01 +5.463498683954522761e+00 4.789541105287173361e-01 1.817043558246825841e+00 -6.089649783964248136e-02 7.818583888336987087e-02 -2.515926628039379387e-01 9.627457985270306828e-01 +5.373660904996192755e+00 5.170222625909541847e-01 1.821363672678161016e+00 -5.648860974444370325e-02 1.046954015972235003e-01 -2.467684888537582666e-01 9.617447518947903617e-01 +5.292031383098232844e+00 5.478507349686534411e-01 1.826529350585744726e+00 -5.207748258217679421e-02 1.296791723418434794e-01 -2.422735039362444998e-01 9.600908974973291210e-01 +5.195276546738191392e+00 5.905541172720901733e-01 1.826909895560539621e+00 -4.731428839170495615e-02 1.533120260154208769e-01 -2.386195653872892619e-01 9.577667865653205492e-01 +5.092197376701467881e+00 6.452614676134084126e-01 1.829453752892473695e+00 -4.220872745835693024e-02 1.750102993576923560e-01 -2.355782546923148313e-01 9.550353076768015592e-01 +4.999395722764114147e+00 6.867274119595971893e-01 1.829890949949061207e+00 -3.705983355028762138e-02 1.937000885286660201e-01 -2.327405117138519886e-01 9.523331489764216284e-01 +4.904188612785413071e+00 7.230854418774752546e-01 1.825964567083782963e+00 -3.180907193893355023e-02 2.089741586944637297e-01 -2.299984308363392516e-01 9.499570750882178061e-01 +4.836359910417331598e+00 7.418748113249656884e-01 1.821516767781382384e+00 -2.630853752681055688e-02 2.213746912648067722e-01 -2.275513831475613480e-01 9.479035899050954894e-01 +4.774702623194593265e+00 7.594512672561393174e-01 1.823385491238055156e+00 -2.038097436678299595e-02 2.317929447355764339e-01 -2.254099005143083423e-01 9.460691130506385660e-01 +4.711944631315355458e+00 7.833726412195742839e-01 1.833813714964690034e+00 -1.423762970859515295e-02 2.407079291359719986e-01 -2.235820730232180864e-01 9.443875096112156475e-01 +4.657523108621798080e+00 8.003853495378130400e-01 1.840671087893041236e+00 -8.219002226126889341e-03 2.476918705681500910e-01 -2.220298698167657014e-01 9.430183694484783885e-01 +4.596358931879579224e+00 8.077105411340720353e-01 1.840197358001297578e+00 -2.252653806068338673e-03 2.528540218873879253e-01 -2.201001484410734788e-01 9.421334441070958743e-01 +4.513729575748419265e+00 8.234347702564530636e-01 1.845918812490166871e+00 2.441912602580241422e-03 2.517728788032461140e-01 -2.181656276710544906e-01 9.428721816207311646e-01 +4.446834005879682472e+00 8.332576422366795299e-01 1.848173300475050240e+00 7.337880936797516913e-03 2.507708835141969073e-01 -2.157774837802976520e-01 9.436630473104179462e-01 +4.367832664500934214e+00 8.495117597821696398e-01 1.847862784825574423e+00 1.255189815650801198e-02 2.498591285665464901e-01 -2.130857943807204780e-01 9.444612557364822081e-01 +4.278047546831988512e+00 8.726757823392047309e-01 1.852963461240989318e+00 1.783265084550779075e-02 2.490205004779956488e-01 -2.100835157820606092e-01 9.452700485000359309e-01 +4.187759666223808352e+00 8.966909365192722303e-01 1.861003620416938009e+00 2.304002229000207819e-02 2.483107479673281881e-01 -2.064868752841157451e-01 9.461362815581543240e-01 +4.100515627667462581e+00 9.191911665850622803e-01 1.871205763894083107e+00 2.811443648596686357e-02 2.476812695549159282e-01 -2.021626360448621762e-01 9.470974643019459682e-01 +4.017590127056370974e+00 9.457163438563104263e-01 1.882360796148873749e+00 3.310663952318108894e-02 2.472080442372935616e-01 -1.971543544096434342e-01 9.481150086226399765e-01 +3.935537952426522601e+00 9.747118430788668242e-01 1.888131497135645986e+00 3.778238227017630124e-02 2.469453856496486299e-01 -1.913063301364711921e-01 9.492060512382806126e-01 +3.844863648313443072e+00 1.006040667570216041e+00 1.891954198035363133e+00 4.200956620979449940e-02 2.469007605187059640e-01 -1.846575290367432620e-01 9.503560332466997052e-01 +3.752119776379838623e+00 1.030921014336568131e+00 1.895160540559985618e+00 4.572982454506694522e-02 2.471328095683613391e-01 -1.767601364033251354e-01 9.516248252162111676e-01 +3.655449276242216605e+00 1.047527968549495148e+00 1.896577398359254651e+00 4.889846738913333768e-02 2.476125954583918709e-01 -1.673065434560853382e-01 9.530505022535807891e-01 +3.551634402061322415e+00 1.052695227407163925e+00 1.897153145950726927e+00 5.158017875574462396e-02 2.484179267617634135e-01 -1.563113387765038831e-01 9.545651179835072941e-01 +3.433367344687048295e+00 1.057388574327681185e+00 1.893019431761171711e+00 5.351107157230604316e-02 2.495089121239796870e-01 -1.437991192074766500e-01 9.561398703838684954e-01 +3.304394071475590611e+00 1.063090447397548655e+00 1.885639777352333457e+00 5.468254737695817103e-02 2.508713596432330384e-01 -1.297737954647030512e-01 9.577222524999897679e-01 +3.174884511557202860e+00 1.057595977742291415e+00 1.871923674892396861e+00 5.512959625100254807e-02 2.515747685992416049e-01 -1.138548032405743704e-01 9.595351525592590303e-01 +3.042828940095391399e+00 1.054878158578969272e+00 1.859796949775027519e+00 5.502964306928410931e-02 2.531697064694624077e-01 -9.643531647962980125e-02 9.610290470209132963e-01 +2.886904068324312789e+00 1.051820898911627999e+00 1.850082813414826610e+00 5.445278744204544441e-02 2.554650968723521931e-01 -7.775334808345839288e-02 9.621468976568758880e-01 +2.737246884887406750e+00 1.044871013432058682e+00 1.843313201603032025e+00 5.342934757180003297e-02 2.584251323516172372e-01 -5.798309113619418143e-02 9.628081215938619764e-01 +2.595539215649875331e+00 1.036570209460514702e+00 1.838660812688639901e+00 5.194429891562304946e-02 2.619595488542477146e-01 -3.706639850511356943e-02 9.629666748603040727e-01 +2.471655378637240386e+00 1.020278307185802591e+00 1.832890396937285393e+00 5.025958364461263067e-02 2.659871585894769686e-01 -1.512084190171237956e-02 9.625465771267009973e-01 +2.361805375437458387e+00 9.946352421541702071e-01 1.819262243611750929e+00 4.831907901680129042e-02 2.703590516105336405e-01 7.970878288176675916e-03 9.615131114867041529e-01 +2.254798573921629412e+00 9.657731475642721275e-01 1.801584821853835949e+00 4.607461141922492703e-02 2.744682041790506011e-01 3.195523318727293283e-02 9.599598623523349916e-01 +2.156331200628903044e+00 9.354610770299200961e-01 1.785182304753967220e+00 4.349284820289647802e-02 2.783964684725468985e-01 5.682084500715660347e-02 9.577969054901966928e-01 +2.081093664573391511e+00 9.146482249127811937e-01 1.775003960629129685e+00 4.067061785910941474e-02 2.825575148398388192e-01 8.211915980762943268e-02 9.548629899942776555e-01 +2.003133753503066661e+00 8.867706236324429669e-01 1.756695982983064619e+00 3.802693536825232229e-02 2.864982988596169178e-01 1.078791048614142212e-01 9.512278924864361329e-01 +1.947019822678452305e+00 8.674125084140920094e-01 1.743373598653120915e+00 3.509895256714958695e-02 2.906579821852781631e-01 1.337572597115262718e-01 9.467812376610010849e-01 +1.927366560612738144e+00 8.604708776888644328e-01 1.735590456236154155e+00 3.182196997947735889e-02 2.946261339476313190e-01 1.595424884228644480e-01 9.416627401571485700e-01 diff --git a/thirdparty/tartanair_tools/evaluation/pose_gt.txt b/thirdparty/tartanair_tools/evaluation/pose_gt.txt new file mode 100644 index 00000000..e29064ce --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/pose_gt.txt @@ -0,0 +1,734 @@ +8.257375717163085938e+00 -2.730143547058105469e+01 -3.229445695877075195e+00 -0.000000000000000000e+00 -0.000000000000000000e+00 1.324519515037536621e-01 9.911894202232360840e-01 +8.150029182434082031e+00 -2.726499938964843750e+01 -3.124113798141479492e+00 1.005725376307964325e-02 1.408183714374899864e-03 1.519933491945266724e-01 9.883292913436889648e-01 +8.035955429077148438e+00 -2.722590827941894531e+01 -3.013025999069213867e+00 2.116696164011955261e-02 2.910247072577476501e-03 1.725988239049911499e-01 9.847604036331176758e-01 +7.914939880371093750e+00 -2.718400382995605469e+01 -2.896314620971679688e+00 3.313439339399337769e-02 4.488728940486907959e-03 1.940394788980484009e-01 9.804237484931945801e-01 +7.786039829254150391e+00 -2.713848495483398438e+01 -2.775121927261352539e+00 4.576298221945762634e-02 6.125640124082565308e-03 2.160865813493728638e-01 9.752818942070007324e-01 +7.648814678192138672e+00 -2.708902359008789062e+01 -2.649977922439575195e+00 5.885510146617889404e-02 7.802580017596483231e-03 2.385131120681762695e-01 9.693228006362915039e-01 +7.502609729766845703e+00 -2.703505706787109375e+01 -2.521782159805297852e+00 7.221274077892303467e-02 9.501649998128414154e-03 2.610951364040374756e-01 9.625613689422607422e-01 +7.346512317657470703e+00 -2.697579002380371094e+01 -2.391965389251708984e+00 8.563899993896484375e-02 1.120452024042606354e-02 2.836139798164367676e-01 9.550411701202392578e-01 +7.179455280303955078e+00 -2.691020011901855469e+01 -2.262508392333984375e+00 9.893891215324401855e-02 1.289336383342742920e-02 3.058579564094543457e-01 9.468346238136291504e-01 +7.000294685363769531e+00 -2.683707046508789062e+01 -2.136049747467041016e+00 1.119204610586166382e-01 1.455131731927394867e-02 3.276241421699523926e-01 9.380428791046142578e-01 +6.807950973510742188e+00 -2.675503349304199219e+01 -2.016015529632568359e+00 1.243962049484252930e-01 1.616092585027217865e-02 3.487199246883392334e-01 9.287942051887512207e-01 +6.599474906921386719e+00 -2.666633796691894531e+01 -1.908085942268371582e+00 1.361834555864334106e-01 1.770585030317306519e-02 3.689627945423126221e-01 9.192425608634948730e-01 +6.370777606964111328e+00 -2.657961273193359375e+01 -1.817972421646118164e+00 1.471050679683685303e-01 1.917048171162605286e-02 3.881823122501373291e-01 9.095642566680908203e-01 +6.139701843261718750e+00 -2.650517082214355469e+01 -1.749771714210510254e+00 1.569896787405014038e-01 2.053925022482872009e-02 4.062187373638153076e-01 8.999547958374023438e-01 +5.910547256469726562e+00 -2.644154167175292969e+01 -1.696130275726318359e+00 1.656711250543594360e-01 2.179830893874168396e-02 4.229246973991394043e-01 8.906247615814208984e-01 +5.684411525726318359e+00 -2.639022445678710938e+01 -1.656192541122436523e+00 1.729882657527923584e-01 2.293346077203750610e-02 4.381606578826904297e-01 8.817959427833557129e-01 +5.464765071868896484e+00 -2.634597015380859375e+01 -1.622294902801513672e+00 1.787836253643035889e-01 2.393117547035217285e-02 4.517953991889953613e-01 8.736959099769592285e-01 +5.251664161682128906e+00 -2.630884170532226562e+01 -1.594280958175659180e+00 1.825749278068542480e-01 2.460363134741783142e-02 4.637119174003601074e-01 8.666211366653442383e-01 +5.046442508697509766e+00 -2.627592277526855469e+01 -1.568546056747436523e+00 1.834198236465454102e-01 2.448996528983116150e-02 4.738091528415679932e-01 8.609658479690551758e-01 +4.848206520080566406e+00 -2.625026321411132812e+01 -1.548382520675659180e+00 1.838009655475616455e-01 2.502397820353507996e-02 4.818847477436065674e-01 8.563749194145202637e-01 +4.658301830291748047e+00 -2.622618103027343750e+01 -1.529111266136169434e+00 1.836267709732055664e-01 2.628898248076438904e-02 4.877998232841491699e-01 8.530189990997314453e-01 +4.476706981658935547e+00 -2.620547866821289062e+01 -1.510836124420166016e+00 1.795126795768737793e-01 2.640318125486373901e-02 4.915642440319061279e-01 8.517292737960815430e-01 +4.302931308746337891e+00 -2.619043922424316406e+01 -1.495709180831909180e+00 1.732770353555679321e-01 2.629615366458892822e-02 4.932430088520050049e-01 8.520532846450805664e-01 +4.137679100036621094e+00 -2.617677116394042969e+01 -1.480880141258239746e+00 1.651134490966796875e-01 2.594937756657600403e-02 4.929910898208618164e-01 8.538290262222290039e-01 +3.980953931808471680e+00 -2.616441345214843750e+01 -1.466370820999145508e+00 1.552121192216873169e-01 2.534341439604759216e-02 4.909519553184509277e-01 8.568739891052246094e-01 +3.832751274108886719e+00 -2.615327072143554688e+01 -1.452200889587402344e+00 1.437613666057586670e-01 2.445927262306213379e-02 4.872626960277557373e-01 8.609933257102966309e-01 +3.692717790603637695e+00 -2.614628410339355469e+01 -1.440113544464111328e+00 1.309500336647033691e-01 2.327736094594001770e-02 4.820578396320343018e-01 8.659853339195251465e-01 +3.561160087585449219e+00 -2.614063453674316406e+01 -1.428563237190246582e+00 1.169686764478683472e-01 2.177853137254714966e-02 4.754727780818939209e-01 8.716476559638977051e-01 +3.438129901885986328e+00 -2.613575172424316406e+01 -1.417299747467041016e+00 1.020105704665184021e-01 1.994415000081062317e-02 4.676474928855895996e-01 8.777823448181152344e-01 +3.323622465133666992e+00 -2.613155174255371094e+01 -1.406351327896118164e+00 8.627232909202575684e-02 1.775621995329856873e-02 4.587280750274658203e-01 8.842004537582397461e-01 +3.217639923095703125e+00 -2.612795257568359375e+01 -1.395756840705871582e+00 6.995402276515960693e-02 1.519817486405372620e-02 4.488692879676818848e-01 8.907254338264465332e-01 +3.120190143585205078e+00 -2.612490653991699219e+01 -1.385557889938354492e+00 5.325971171259880066e-02 1.225320342928171158e-02 4.382355511188507080e-01 8.971971869468688965e-01 +3.031288385391235352e+00 -2.612232780456542969e+01 -1.375803232192993164e+00 3.639610856771469116e-02 8.906225673854351044e-03 4.270016551017761230e-01 9.034742116928100586e-01 +2.950957059860229492e+00 -2.612017059326171875e+01 -1.366545438766479492e+00 1.957202330231666565e-02 5.143407732248306274e-03 4.153527021408081055e-01 9.094352722167968750e-01 +2.879151344299316406e+00 -2.611909103393554688e+01 -1.358444809913635254e+00 2.997935982421040535e-03 9.512035176157951355e-04 4.034842848777770996e-01 9.149811863899230957e-01 +2.815986633300781250e+00 -2.611833000183105469e+01 -1.350934982299804688e+00 -1.311498880386352539e-02 -3.683640155941247940e-03 3.916012048721313477e-01 9.200341701507568359e-01 +2.761515855789184570e+00 -2.611777305603027344e+01 -1.344009995460510254e+00 -2.855683118104934692e-02 -8.773547597229480743e-03 3.799151778221130371e-01 9.245388507843017578e-01 +2.715790271759033203e+00 -2.611742591857910156e+01 -1.337728261947631836e+00 -4.311827197670936584e-02 -1.433096732944250107e-02 3.686465024948120117e-01 9.284585118293762207e-01 +2.678865909576416016e+00 -2.611726570129394531e+01 -1.332148432731628418e+00 -5.659235641360282898e-02 -2.036875113844871521e-02 3.580188453197479248e-01 9.317751526832580566e-01 +2.650802850723266602e+00 -2.611730003356933594e+01 -1.327322959899902344e+00 -6.877423077821731567e-02 -2.690066583454608917e-02 3.482596874237060547e-01 9.344847798347473145e-01 +2.631665229797363281e+00 -2.611752891540527344e+01 -1.323305606842041016e+00 -7.946231216192245483e-02 -3.394139930605888367e-02 3.395984470844268799e-01 9.365930557250976562e-01 +2.621506929397583008e+00 -2.611796760559082031e+01 -1.320130586624145508e+00 -8.851067721843719482e-02 -4.149623960256576538e-02 3.322108387947082520e-01 9.381257891654968262e-01 +2.604746103286743164e+00 -2.611786651611328125e+01 -1.316929936408996582e+00 -9.599139541387557983e-02 -4.952628165483474731e-02 3.260566592216491699e-01 9.391590952873229980e-01 +2.581374406814575195e+00 -2.611726570129394531e+01 -1.313673019409179688e+00 -1.020307838916778564e-01 -5.798066779971122742e-02 3.210361599922180176e-01 9.397679567337036133e-01 +2.551380872726440430e+00 -2.611620140075683594e+01 -1.310332059860229492e+00 -1.067542657256126404e-01 -6.680898368358612061e-02 3.170435726642608643e-01 9.400123953819274902e-01 +2.514750719070434570e+00 -2.611468696594238281e+01 -1.306879878044128418e+00 -1.102860048413276672e-01 -7.595979422330856323e-02 3.139690458774566650e-01 9.399418234825134277e-01 +2.471467494964599609e+00 -2.611276245117187500e+01 -1.303287267684936523e+00 -1.127503067255020142e-01 -8.538196235895156860e-02 3.116994798183441162e-01 9.395960569381713867e-01 +2.421512603759765625e+00 -2.611042404174804688e+01 -1.299526333808898926e+00 -1.142703592777252197e-01 -9.502364695072174072e-02 3.101196289062500000e-01 9.390093684196472168e-01 +2.376385927200317383e+00 -2.610828590393066406e+01 -1.296202421188354492e+00 -1.149689331650733948e-01 -1.048334240913391113e-01 3.091127574443817139e-01 9.382117986679077148e-01 +2.336065053939819336e+00 -2.610634613037109375e+01 -1.293288588523864746e+00 -1.149692237377166748e-01 -1.147588342428207397e-01 3.085614442825317383e-01 9.372311830520629883e-01 +2.300527811050415039e+00 -2.610463714599609375e+01 -1.290760517120361328e+00 -1.143935322761535645e-01 -1.247479841113090515e-01 3.083480596542358398e-01 9.360948801040649414e-01 +2.269750118255615234e+00 -2.610315322875976562e+01 -1.288591265678405762e+00 -1.133648008108139038e-01 -1.347490549087524414e-01 3.083551526069641113e-01 9.348304867744445801e-01 +2.243707180023193359e+00 -2.610190773010253906e+01 -1.286761403083801270e+00 -1.120056807994842529e-01 -1.447095274925231934e-01 3.084664642810821533e-01 9.334679245948791504e-01 +2.222373247146606445e+00 -2.610091781616210938e+01 -1.285245299339294434e+00 -1.104394048452377319e-01 -1.545778214931488037e-01 3.085660040378570557e-01 9.320386052131652832e-01 +2.205722808837890625e+00 -2.610018539428710938e+01 -1.284022212028503418e+00 -1.087885349988937378e-01 -1.643026769161224365e-01 3.085390627384185791e-01 9.305768609046936035e-01 +2.193727970123291016e+00 -2.609972190856933594e+01 -1.283072471618652344e+00 -1.071762964129447937e-01 -1.738324314355850220e-01 3.082725405693054199e-01 9.291197657585144043e-01 +2.186362266540527344e+00 -2.609954452514648438e+01 -1.282379150390625000e+00 -1.057260483503341675e-01 -1.831168383359909058e-01 3.076536953449249268e-01 9.277065396308898926e-01 +2.183596372604370117e+00 -2.609965705871582031e+01 -1.281921386718750000e+00 -1.045607924461364746e-01 -1.921051144599914551e-01 3.065711855888366699e-01 9.263783693313598633e-01 +2.178739786148071289e+00 -2.609973526000976562e+01 -1.281318306922912598e+00 -1.038029193878173828e-01 -2.007473111152648926e-01 3.049142658710479736e-01 9.251772165298461914e-01 +2.171762704849243164e+00 -2.609978866577148438e+01 -1.280552983283996582e+00 -1.035755872726440430e-01 -2.089937329292297363e-01 3.025719523429870605e-01 9.241449236869812012e-01 +2.162633657455444336e+00 -2.609983253479003906e+01 -1.279610514640808105e+00 -1.040007025003433228e-01 -2.167947590351104736e-01 2.994336187839508057e-01 9.233219027519226074e-01 +2.151756286621093750e+00 -2.609991073608398438e+01 -1.279266357421875000e+00 -1.018563807010650635e-01 -2.230551093816757202e-01 2.962332963943481445e-01 9.231020808219909668e-01 +2.138787031173706055e+00 -2.609995079040527344e+01 -1.278807401657104492e+00 -1.000821962952613831e-01 -2.287934869527816772e-01 2.924018502235412598e-01 9.231132864952087402e-01 +2.123752832412719727e+00 -2.609994125366210938e+01 -1.278233647346496582e+00 -9.863399714231491089e-02 -2.340759038925170898e-01 2.880798876285552979e-01 9.233037829399108887e-01 +2.106680870056152344e+00 -2.609985733032226562e+01 -1.277545094490051270e+00 -9.746373444795608521e-02 -2.389639019966125488e-01 2.834067344665527344e-01 9.236220121383666992e-01 +2.087599992752075195e+00 -2.609968185424804688e+01 -1.276743173599243164e+00 -9.652115404605865479e-02 -2.435137331485748291e-01 2.785216569900512695e-01 9.240186214447021484e-01 +2.066539525985717773e+00 -2.609939956665039062e+01 -1.275826334953308105e+00 -9.575416892766952515e-02 -2.477771490812301636e-01 2.735641896724700928e-01 9.244459271430969238e-01 +2.043530464172363281e+00 -2.609897804260253906e+01 -1.274796128273010254e+00 -9.510961920022964478e-02 -2.518011033535003662e-01 2.686747014522552490e-01 9.248589873313903809e-01 +2.018604755401611328e+00 -2.609842681884765625e+01 -1.273653507232666016e+00 -9.453330934047698975e-02 -2.556293010711669922e-01 2.639941573143005371e-01 9.252157807350158691e-01 +1.991794824600219727e+00 -2.609771347045898438e+01 -1.272398710250854492e+00 -9.397020936012268066e-02 -2.593019306659698486e-01 2.596642374992370605e-01 9.254763126373291016e-01 +1.963134527206420898e+00 -2.609683036804199219e+01 -1.271032691001892090e+00 -9.336430579423904419e-02 -2.628570795059204102e-01 2.558271884918212891e-01 9.256033897399902344e-01 +1.932657837867736816e+00 -2.609576606750488281e+01 -1.269554376602172852e+00 -9.265825897455215454e-02 -2.663317620754241943e-01 2.526248395442962646e-01 9.255605936050415039e-01 +1.900395274162292480e+00 -2.609452629089355469e+01 -1.268021225929260254e+00 -9.179296344518661499e-02 -2.697627544403076172e-01 2.501989006996154785e-01 9.253121614456176758e-01 +1.866372346878051758e+00 -2.609314346313476562e+01 -1.266556382179260254e+00 -9.070674329996109009e-02 -2.731886208057403564e-01 2.486893981695175171e-01 9.248208999633789062e-01 +1.830633640289306641e+00 -2.609154319763183594e+01 -1.264996290206909180e+00 -8.933471143245697021e-02 -2.766507267951965332e-01 2.482342422008514404e-01 9.240472912788391113e-01 +1.790276765823364258e+00 -2.608957481384277344e+01 -1.263203144073486328e+00 -8.760775625705718994e-02 -2.801944017410278320e-01 2.489677965641021729e-01 9.229469299316406250e-01 +1.745332121849060059e+00 -2.608722686767578125e+01 -1.261175513267517090e+00 -8.545089513063430786e-02 -2.838713824748992920e-01 2.510198652744293213e-01 9.214685559272766113e-01 +1.695828557014465332e+00 -2.608447265625000000e+01 -1.258919596672058105e+00 -8.278183639049530029e-02 -2.877405583858489990e-01 2.545136511325836182e-01 9.195516109466552734e-01 +1.641791701316833496e+00 -2.608129310607910156e+01 -1.256438016891479492e+00 -7.950858026742935181e-02 -2.918704450130462646e-01 2.595636546611785889e-01 9.171241521835327148e-01 +1.583243012428283691e+00 -2.607766532897949219e+01 -1.253734111785888672e+00 -7.552697509527206421e-02 -2.963385283946990967e-01 2.662736177444458008e-01 9.140993356704711914e-01 +1.520200014114379883e+00 -2.607355880737304688e+01 -1.250813007354736328e+00 -7.071685791015625000e-02 -3.012339174747467041e-01 2.747328281402587891e-01 9.103729724884033203e-01 +1.454235196113586426e+00 -2.606877899169921875e+01 -1.249844908714294434e+00 -5.525906383991241455e-02 -3.035594820976257324e-01 2.882252037525177002e-01 9.064901471138000488e-01 +1.383903503417968750e+00 -2.606328582763671875e+01 -1.248920917510986328e+00 -3.777214884757995605e-02 -3.056705296039581299e-01 3.037523031234741211e-01 9.015948772430419922e-01 +1.309079766273498535e+00 -2.605702018737792969e+01 -1.247990727424621582e+00 -1.855715364217758179e-02 -3.074791133403778076e-01 3.209738135337829590e-01 8.955936431884765625e-01 +1.229634761810302734e+00 -2.604996109008789062e+01 -1.246994614601135254e+00 2.079017460346221924e-03 -3.089032173156738281e-01 3.395516574382781982e-01 8.884138464927673340e-01 +1.145437955856323242e+00 -2.604207992553710938e+01 -1.245875239372253418e+00 2.382044494152069092e-02 -3.098701834678649902e-01 3.591489195823669434e-01 8.800143003463745117e-01 +1.056360840797424316e+00 -2.603338813781738281e+01 -1.244570255279541016e+00 4.634601622819900513e-02 -3.103204071521759033e-01 3.794378042221069336e-01 8.703909516334533691e-01 +9.622811079025268555e-01 -2.602390480041503906e+01 -1.243022441864013672e+00 6.933062523603439331e-02 -3.102084100246429443e-01 4.001006484031677246e-01 8.595832586288452148e-01 +8.630869388580322266e-01 -2.601369476318359375e+01 -1.241176724433898926e+00 9.244732558727264404e-02 -3.095055222511291504e-01 4.208358526229858398e-01 8.476773500442504883e-01 +7.586755752563476562e-01 -2.600251388549804688e+01 -1.239426255226135254e+00 1.153714805841445923e-01 -3.082002401351928711e-01 4.413614571094512939e-01 8.348065614700317383e-01 +6.489708423614501953e-01 -2.599065780639648438e+01 -1.237429141998291016e+00 1.377833187580108643e-01 -3.062991797924041748e-01 4.614176154136657715e-01 8.211518526077270508e-01 +5.339149236679077148e-01 -2.597833442687988281e+01 -1.235021948814392090e+00 1.593710333108901978e-01 -3.038252592086791992e-01 4.807699918746948242e-01 8.069394826889038086e-01 +4.134708344936370850e-01 -2.596566772460937500e+01 -1.232172846794128418e+00 1.798333376646041870e-01 -3.008187711238861084e-01 4.992105662822723389e-01 7.924372553825378418e-01 +2.876244187355041504e-01 -2.595279312133789062e+01 -1.228863477706909180e+00 1.988817751407623291e-01 -2.973341047763824463e-01 5.165591239929199219e-01 7.779493331909179688e-01 +1.563831120729446411e-01 -2.593984222412109375e+01 -1.225079298019409180e+00 2.162414491176605225e-01 -2.934379577636718750e-01 5.326616168022155762e-01 7.638098597526550293e-01 +1.977386511862277985e-02 -2.592696762084960938e+01 -1.220815420150756836e+00 2.316501736640930176e-01 -2.892060577869415283e-01 5.473881959915161133e-01 7.503760457038879395e-01 +-1.221602037549018860e-01 -2.591429710388183594e+01 -1.216070532798767090e+00 2.448578178882598877e-01 -2.847204804420471191e-01 5.606288909912109375e-01 7.380204200744628906e-01 +-2.693642973899841309e-01 -2.590196228027343750e+01 -1.210849523544311523e+00 2.556236982345581055e-01 -2.800659835338592529e-01 5.722882151603698730e-01 7.271215915679931641e-01 +-4.217575490474700928e-01 -2.588953018188476562e+01 -1.205434560775756836e+00 2.637114226818084717e-01 -2.753245532512664795e-01 5.822781920433044434e-01 7.180562615394592285e-01 +-5.792719125747680664e-01 -2.587693214416503906e+01 -1.199920654296875000e+00 2.688854634761810303e-01 -2.705728113651275635e-01 5.905099511146545410e-01 7.111884951591491699e-01 +-7.418780326843261719e-01 -2.586498069763183594e+01 -1.193951368331909180e+00 2.709034085273742676e-01 -2.658755183219909668e-01 5.968830585479736328e-01 7.068607807159423828e-01 +-9.095315337181091309e-01 -2.585373878479003906e+01 -1.187517046928405762e+00 2.696073949337005615e-01 -2.612811923027038574e-01 6.013295054435729980e-01 7.052990794181823730e-01 +-1.082196712493896484e+00 -2.584315872192382812e+01 -1.180628657341003418e+00 2.652037143707275391e-01 -2.568131983280181885e-01 6.039624810218811035e-01 7.063591480255126953e-01 +-1.259857892990112305e+00 -2.583313941955566406e+01 -1.173294663429260254e+00 2.579801678657531738e-01 -2.524796426296234131e-01 6.049149036407470703e-01 7.097733616828918457e-01 +-1.442517638206481934e+00 -2.582359313964843750e+01 -1.165510177612304688e+00 2.482134401798248291e-01 -2.482767254114151001e-01 6.042959094047546387e-01 7.152449488639831543e-01 +-1.630190968513488770e+00 -2.581442260742187500e+01 -1.157275319099426270e+00 2.361755520105361938e-01 -2.441955357789993286e-01 6.021990776062011719e-01 7.224583029747009277e-01 +-1.822792649269104004e+00 -2.580361747741699219e+01 -1.149105191230773926e+00 2.221380621194839478e-01 -2.402243912220001221e-01 5.987128615379333496e-01 7.310880422592163086e-01 +-2.020425319671630859e+00 -2.579247474670410156e+01 -1.140615224838256836e+00 2.063753902912139893e-01 -2.363522201776504517e-01 5.939273834228515625e-01 7.408083677291870117e-01 +-2.223135709762573242e+00 -2.578133201599121094e+01 -1.131688237190246582e+00 1.891683191061019897e-01 -2.325716316699981689e-01 5.879410505294799805e-01 7.512996196746826172e-01 +-2.430940866470336914e+00 -2.577008819580078125e+01 -1.122332692146301270e+00 1.708054840564727783e-01 -2.288807183504104614e-01 5.808661580085754395e-01 7.622555494308471680e-01 +-2.643848896026611328e+00 -2.575863647460937500e+01 -1.112574458122253418e+00 1.515839397907257080e-01 -2.252849787473678589e-01 5.728331804275512695e-01 7.733894586563110352e-01 +-2.861857891082763672e+00 -2.574687385559082031e+01 -1.102440118789672852e+00 1.318101584911346436e-01 -2.217981219291687012e-01 5.639927983283996582e-01 7.844384908676147461e-01 +-3.084932088851928711e+00 -2.573441886901855469e+01 -1.092018961906433105e+00 1.117970794439315796e-01 -2.184428274631500244e-01 5.545181632041931152e-01 7.951689958572387695e-01 +-3.312824249267578125e+00 -2.571818351745605469e+01 -1.081887125968933105e+00 9.186533093452453613e-02 -2.152512967586517334e-01 5.446047186851501465e-01 8.053777217864990234e-01 +-3.545735597610473633e+00 -2.570132827758789062e+01 -1.071532011032104492e+00 7.233910262584686279e-02 -2.122652828693389893e-01 5.344696044921875000e-01 8.148942589759826660e-01 +-3.783617496490478516e+00 -2.568376922607421875e+01 -1.061015605926513672e+00 5.354552716016769409e-02 -2.095348089933395386e-01 5.243495106697082520e-01 8.235809803009033203e-01 +-4.026412487030029297e+00 -2.566546249389648438e+01 -1.050401568412780762e+00 3.581195324659347534e-02 -2.071186453104019165e-01 5.144988298416137695e-01 8.313304185867309570e-01 +-4.274055004119873047e+00 -2.564637565612792969e+01 -1.039759516716003418e+00 1.946479082107543945e-02 -2.050815224647521973e-01 5.051854252815246582e-01 8.380634784698486328e-01 +-4.526473522186279297e+00 -2.562646865844726562e+01 -1.029154062271118164e+00 4.827596247196197510e-03 -2.034938782453536987e-01 4.966876506805419922e-01 8.437229394912719727e-01 +-4.783144950866699219e+00 -2.560096168518066406e+01 -1.019245624542236328e+00 -7.779009640216827393e-03 -2.024299055337905884e-01 4.892896711826324463e-01 8.482671976089477539e-01 +-5.044416904449462891e+00 -2.557433128356933594e+01 -1.009541034698486328e+00 -1.803756505250930786e-02 -2.019653618335723877e-01 4.832766652107238770e-01 8.516620397567749023e-01 +-5.302582263946533203e+00 -2.554758262634277344e+01 -1.000302672386169434e+00 -2.571143954992294312e-02 -2.021553814411163330e-01 4.788711369037628174e-01 8.539054393768310547e-01 +-5.557634353637695312e+00 -2.552076148986816406e+01 -9.915307164192199707e-01 -3.087937086820602417e-02 -2.029705345630645752e-01 4.760487377643585205e-01 8.551180958747863770e-01 +-5.809582233428955078e+00 -2.549390983581542969e+01 -9.832091927528381348e-01 -3.369780629873275757e-02 -2.043549120426177979e-01 4.747093617916107178e-01 8.554264307022094727e-01 +-6.058428287506103516e+00 -2.546691322326660156e+01 -9.753307700157165527e-01 -3.432291001081466675e-02 -2.062465548515319824e-01 4.747377634048461914e-01 8.549318313598632812e-01 +-6.303567409515380859e+00 -2.543446159362792969e+01 -9.683629870414733887e-01 -3.290986269712448120e-02 -2.085783779621124268e-01 4.760079979896545410e-01 8.537144064903259277e-01 +-6.557874202728271484e+00 -2.540054130554199219e+01 -9.614318609237670898e-01 -2.961410582065582275e-02 -2.112799137830734253e-01 4.783855676651000977e-01 8.518398404121398926e-01 +-6.821374893188476562e+00 -2.536515998840332031e+01 -9.545104503631591797e-01 -2.458949387073516846e-02 -2.142781317234039307e-01 4.817292094230651855e-01 8.493627309799194336e-01 +-7.094101905822753906e+00 -2.532833862304687500e+01 -9.475768804550170898e-01 -1.799146831035614014e-02 -2.174982428550720215e-01 4.858947098255157471e-01 8.463315367698669434e-01 +-7.376088142395019531e+00 -2.529010200500488281e+01 -9.406054615974426270e-01 -9.974963963031768799e-03 -2.208639681339263916e-01 4.907353818416595459e-01 8.427920341491699219e-01 +-7.667158603668212891e+00 -2.524897003173828125e+01 -9.337072372436523438e-01 -6.955191493034362793e-04 -2.242999076843261719e-01 4.961045384407043457e-01 8.387904167175292969e-01 +-7.959429264068603516e+00 -2.520267486572265625e+01 -9.273742437362670898e-01 9.689696133136749268e-03 -2.277305126190185547e-01 5.018569231033325195e-01 8.343767523765563965e-01 +-8.253588676452636719e+00 -2.515594100952148438e+01 -9.211474657058715820e-01 2.102287113666534424e-02 -2.310820966958999634e-01 5.078500509262084961e-01 8.296068310737609863e-01 +-8.541360855102539062e+00 -2.511005783081054688e+01 -9.152233600616455078e-01 3.314618766307830811e-02 -2.342820912599563599e-01 5.139456987380981445e-01 8.245441317558288574e-01 +-8.822777748107910156e+00 -2.506504249572753906e+01 -9.095849394798278809e-01 4.589994251728057861e-02 -2.372606992721557617e-01 5.200105309486389160e-01 8.192616105079650879e-01 +-9.097865104675292969e+00 -2.502093696594238281e+01 -9.042126536369323730e-01 5.912540107965469360e-02 -2.399505525827407837e-01 5.259176492691040039e-01 8.138417601585388184e-01 +-9.365920066833496094e+00 -2.497324180603027344e+01 -8.995105028152465820e-01 7.266320288181304932e-02 -2.422876656055450439e-01 5.315462946891784668e-01 8.083781599998474121e-01 +-9.627545356750488281e+00 -2.492558479309082031e+01 -8.951293826103210449e-01 8.635501563549041748e-02 -2.442109286785125732e-01 5.367828607559204102e-01 8.029744625091552734e-01 +-9.882925987243652344e+00 -2.487905693054199219e+01 -8.909606933593750000e-01 1.000431627035140991e-01 -2.456623315811157227e-01 5.415208935737609863e-01 7.977446317672729492e-01 +-1.013208103179931641e+01 -2.483370018005371094e+01 -8.869934082031250000e-01 1.135715693235397339e-01 -2.465868890285491943e-01 5.456603169441223145e-01 7.928122282028198242e-01 +-1.037502384185791016e+01 -2.478955459594726562e+01 -8.832201957702636719e-01 1.267857998609542847e-01 -2.469325810670852661e-01 5.491075515747070312e-01 7.883086204528808594e-01 +-1.061176395416259766e+01 -2.474665451049804688e+01 -8.796362280845642090e-01 1.395600289106369019e-01 -2.466690540313720703e-01 5.517964959144592285e-01 7.843455076217651367e-01 +-1.084166145324707031e+01 -2.470154762268066406e+01 -8.765624761581420898e-01 1.518780887126922607e-01 -2.458456903696060181e-01 5.537524223327636719e-01 7.809297442436218262e-01 +-1.106510353088378906e+01 -2.465637207031250000e+01 -8.737902641296386719e-01 1.637502014636993408e-01 -2.445301562547683716e-01 5.550203323364257812e-01 7.780380845069885254e-01 +-1.128235054016113281e+01 -2.461257743835449219e+01 -8.711816072463989258e-01 1.751865893602371216e-01 -2.427901923656463623e-01 5.556436181068420410e-01 7.756434082984924316e-01 +-1.149339485168457031e+01 -2.457016563415527344e+01 -8.687292337417602539e-01 1.861974149942398071e-01 -2.406913191080093384e-01 5.556635260581970215e-01 7.737158536911010742e-01 +-1.169823074340820312e+01 -2.452912521362304688e+01 -8.664233088493347168e-01 1.967928707599639893e-01 -2.382993102073669434e-01 5.551197528839111328e-01 7.722227573394775391e-01 +-1.189685535430908203e+01 -2.448945236206054688e+01 -8.642578125000000000e-01 2.069828212261199951e-01 -2.356788516044616699e-01 5.540509819984436035e-01 7.711297273635864258e-01 +-1.208925914764404297e+01 -2.445113754272460938e+01 -8.622229099273681641e-01 2.167773693799972534e-01 -2.328945249319076538e-01 5.524944663047790527e-01 7.704008221626281738e-01 +-1.227489948272705078e+01 -2.441156768798828125e+01 -8.605554103851318359e-01 2.261860370635986328e-01 -2.300098091363906860e-01 5.504872798919677734e-01 7.699993848800659180e-01 +-1.245398521423339844e+01 -2.437176132202148438e+01 -8.591491580009460449e-01 2.352190017700195312e-01 -2.270886003971099854e-01 5.480658411979675293e-01 7.698873877525329590e-01 +-1.262686634063720703e+01 -2.433344650268554688e+01 -8.578307628631591797e-01 2.438857853412628174e-01 -2.241941392421722412e-01 5.452659130096435547e-01 7.700272202491760254e-01 +-1.280683422088623047e+01 -2.429367637634277344e+01 -8.563159108161926270e-01 2.521966099739074707e-01 -2.213897407054901123e-01 5.421235561370849609e-01 7.703801989555358887e-01 +-1.299388980865478516e+01 -2.425245094299316406e+01 -8.545935153961181641e-01 2.601614594459533691e-01 -2.187384665012359619e-01 5.386744737625122070e-01 7.709079980850219727e-01 +-1.318802261352539062e+01 -2.420975112915039062e+01 -8.526562452316284180e-01 2.677903175354003906e-01 -2.163032144308090210e-01 5.349546074867248535e-01 7.715730667114257812e-01 +-1.338922119140625000e+01 -2.416558074951171875e+01 -8.504919409751892090e-01 2.750933170318603516e-01 -2.141466438770294189e-01 5.309993624687194824e-01 7.723371386528015137e-01 +-1.359730148315429688e+01 -2.411916542053222656e+01 -8.481615781784057617e-01 2.820808291435241699e-01 -2.123317122459411621e-01 5.268448591232299805e-01 7.731623649597167969e-01 +-1.381124687194824219e+01 -2.406614685058593750e+01 -8.460729718208312988e-01 2.887633442878723145e-01 -2.109213173389434814e-01 5.225268006324768066e-01 7.740113139152526855e-01 +-1.403218841552734375e+01 -2.401143455505371094e+01 -8.437451124191284180e-01 2.951512634754180908e-01 -2.099776864051818848e-01 5.180809497833251953e-01 7.748466134071350098e-01 +-1.426011848449707031e+01 -2.395502471923828125e+01 -8.411706089973449707e-01 3.012549281120300293e-01 -2.095633149147033691e-01 5.135427117347717285e-01 7.756304144859313965e-01 +-1.449502277374267578e+01 -2.389689826965332031e+01 -8.383386135101318359e-01 3.070848882198333740e-01 -2.097403109073638916e-01 5.089473724365234375e-01 7.763249278068542480e-01 +-1.473693466186523438e+01 -2.383842658996582031e+01 -8.338268995285034180e-01 3.065032660961151123e-01 -2.145159691572189331e-01 5.026563405990600586e-01 7.793427705764770508e-01 +-1.498472881317138672e+01 -2.377401351928710938e+01 -8.295714855194091797e-01 3.060118556022644043e-01 -2.194902896881103516e-01 4.964650571346282959e-01 7.821146249771118164e-01 +-1.523827362060546875e+01 -2.370317268371582031e+01 -8.256250023841857910e-01 3.055872321128845215e-01 -2.245676517486572266e-01 4.904325902462005615e-01 7.846412062644958496e-01 +-1.549872779846191406e+01 -2.363027381896972656e+01 -8.215686082839965820e-01 3.052128553390502930e-01 -2.296506762504577637e-01 4.846248924732208252e-01 7.869207262992858887e-01 +-1.576608371734619141e+01 -2.355529212951660156e+01 -8.174071907997131348e-01 3.048793077468872070e-01 -2.346402853727340698e-01 4.791148006916046143e-01 7.889497280120849609e-01 +-1.604001426696777344e+01 -2.347719192504882812e+01 -8.132445812225341797e-01 3.045835494995117188e-01 -2.394354343414306641e-01 4.739812910556793213e-01 7.907220125198364258e-01 +-1.631705474853515625e+01 -2.338483428955078125e+01 -8.101818561553955078e-01 3.043285310268402100e-01 -2.439338266849517822e-01 4.693088233470916748e-01 7.922308444976806641e-01 +-1.660086822509765625e+01 -2.329003334045410156e+01 -8.070617318153381348e-01 3.041211366653442383e-01 -2.480305284261703491e-01 4.651857912540435791e-01 7.934691309928894043e-01 +-1.688272476196289062e+01 -2.319570350646972656e+01 -8.039770126342773438e-01 3.039715886116027832e-01 -2.516188025474548340e-01 4.617031812667846680e-01 7.944301962852478027e-01 +-1.715821075439453125e+01 -2.309016036987304688e+01 -8.021142482757568359e-01 3.038906455039978027e-01 -2.545894980430603027e-01 4.589523375034332275e-01 7.951083183288574219e-01 +-1.742863082885742188e+01 -2.297690391540527344e+01 -8.011242747306823730e-01 3.038873672485351562e-01 -2.568305432796478271e-01 4.570226073265075684e-01 7.955004572868347168e-01 +-1.769711875915527344e+01 -2.286419296264648438e+01 -8.001745343208312988e-01 3.039654791355133057e-01 -2.582265436649322510e-01 4.559979438781738281e-01 7.956066131591796875e-01 +-1.795545768737792969e+01 -2.273483276367187500e+01 -8.009973168373107910e-01 3.041208386421203613e-01 -2.586601376533508301e-01 4.559538066387176514e-01 7.954316139221191406e-01 +-1.820840263366699219e+01 -2.259877395629882812e+01 -8.026000857353210449e-01 3.043361306190490723e-01 -2.580100297927856445e-01 4.569530785083770752e-01 7.949869632720947266e-01 +-1.845356178283691406e+01 -2.245384216308593750e+01 -8.052062988281250000e-01 3.045781552791595459e-01 -2.561534345149993896e-01 4.590417444705963135e-01 7.942910790443420410e-01 +-1.868462753295898438e+01 -2.228983306884765625e+01 -8.098449707031250000e-01 3.047925829887390137e-01 -2.529663443565368652e-01 4.622446596622467041e-01 7.933721542358398438e-01 +-1.890363311767578125e+01 -2.211425209045410156e+01 -8.157787919044494629e-01 3.049005568027496338e-01 -2.483250051736831665e-01 4.665615260601043701e-01 7.922693490982055664e-01 +-1.910454940795898438e+01 -2.192168426513671875e+01 -8.215343952178955078e-01 2.945684194564819336e-01 -2.481755763292312622e-01 4.688011407852172852e-01 7.948985695838928223e-01 +-1.927557182312011719e+01 -2.170585823059082031e+01 -8.294323682785034180e-01 2.825427353382110596e-01 -2.472493946552276611e-01 4.717763364315032959e-01 7.977871894836425781e-01 +-1.942508697509765625e+01 -2.146347045898437500e+01 -8.392358422279357910e-01 2.687639594078063965e-01 -2.454302906990051270e-01 4.755074381828308105e-01 8.008886575698852539e-01 +-1.954216575622558594e+01 -2.119265556335449219e+01 -8.509130477905273438e-01 2.531774640083312988e-01 -2.426455467939376831e-01 4.799710512161254883e-01 8.041468262672424316e-01 +-1.962533950805664062e+01 -2.090949630737304688e+01 -8.627063035964965820e-01 2.359070032835006714e-01 -2.389250248670578003e-01 4.850493669509887695e-01 8.074588775634765625e-01 +-1.969269943237304688e+01 -2.062216758728027344e+01 -8.727245926856994629e-01 2.171254158020019531e-01 -2.343276143074035645e-01 4.906017482280731201e-01 8.107138276100158691e-01 +-1.976142501831054688e+01 -2.033530235290527344e+01 -8.793127536773681641e-01 1.970101296901702881e-01 -2.289136946201324463e-01 4.964909851551055908e-01 8.138071894645690918e-01 +-1.983432769775390625e+01 -2.004959869384765625e+01 -8.815551400184631348e-01 1.757451593875885010e-01 -2.227488011121749878e-01 5.025841593742370605e-01 8.166429996490478516e-01 +-1.991426658630371094e+01 -1.976594161987304688e+01 -8.786755204200744629e-01 1.535205245018005371e-01 -2.159026265144348145e-01 5.087547302246093750e-01 8.191374540328979492e-01 +-2.000371360778808594e+01 -1.948537635803222656e+01 -8.701708912849426270e-01 1.305329352617263794e-01 -2.084505409002304077e-01 5.148843526840209961e-01 8.212208151817321777e-01 +-2.010437202453613281e+01 -1.920896911621093750e+01 -8.559069633483886719e-01 1.069843769073486328e-01 -2.004730701446533203e-01 5.208641290664672852e-01 8.228398561477661133e-01 +-2.021696090698242188e+01 -1.893766021728515625e+01 -8.361364603042602539e-01 8.308219909667968750e-02 -1.920559257268905640e-01 5.265967249870300293e-01 8.239585757255554199e-01 +-2.034121322631835938e+01 -1.867202568054199219e+01 -8.114489316940307617e-01 5.903753638267517090e-02 -1.832901090383529663e-01 5.319957137107849121e-01 8.245604038238525391e-01 +-2.047609901428222656e+01 -1.841223526000976562e+01 -7.826293706893920898e-01 3.506408631801605225e-02 -1.742717623710632324e-01 5.369876623153686523e-01 8.246477842330932617e-01 +-2.062051963806152344e+01 -1.815816879272460938e+01 -7.515124082565307617e-01 1.137626916170120239e-02 -1.651008129119873047e-01 5.415123105049133301e-01 8.242430686950683594e-01 +-2.077400016784667969e+01 -1.790994644165039062e+01 -7.193176150321960449e-01 -1.181076467037200928e-02 -1.558807641267776489e-01 5.455222725868225098e-01 8.233875632286071777e-01 +-2.093643760681152344e+01 -1.766792488098144531e+01 -6.869445443153381348e-01 -3.428380936384201050e-02 -1.467182040214538574e-01 5.489829778671264648e-01 8.221411108970642090e-01 +-2.110804367065429688e+01 -1.743272018432617188e+01 -6.551440358161926270e-01 -5.583245679736137390e-02 -1.377217173576354980e-01 5.518721938133239746e-01 8.205806016921997070e-01 +-2.128930091857910156e+01 -1.720520401000976562e+01 -6.246276497840881348e-01 -7.624924182891845703e-02 -1.290009617805480957e-01 5.541790723800659180e-01 8.187981843948364258e-01 +-2.148101425170898438e+01 -1.698668479919433594e+01 -5.961560010910034180e-01 -9.533132612705230713e-02 -1.206667348742485046e-01 5.559023618698120117e-01 8.168990612030029297e-01 +-2.168679428100585938e+01 -1.678162574768066406e+01 -5.714086890220642090e-01 -1.128805875778198242e-01 -1.128291189670562744e-01 5.570487380027770996e-01 8.149995803833007812e-01 +-2.190575408935546875e+01 -1.659123039245605469e+01 -5.512145757675170898e-01 -1.287030577659606934e-01 -1.055976971983909607e-01 5.576310157775878906e-01 8.132233619689941406e-01 +-2.213914299011230469e+01 -1.641951560974121094e+01 -5.370470881462097168e-01 -1.426087766885757446e-01 -9.908163547515869141e-02 5.576655268669128418e-01 8.116985559463500977e-01 +-2.238475036621093750e+01 -1.626752853393554688e+01 -5.304577350616455078e-01 -1.490601301193237305e-01 -8.964521437883377075e-02 5.577902197837829590e-01 8.115508556365966797e-01 +-2.264039993286132812e+01 -1.613380813598632812e+01 -5.288525223731994629e-01 -1.544735133647918701e-01 -8.161737024784088135e-02 5.572797656059265137e-01 8.117362856864929199e-01 +-2.290334701538085938e+01 -1.601597213745117188e+01 -5.312219262123107910e-01 -1.589248329401016235e-01 -7.490587979555130005e-02 5.562464594841003418e-01 8.122325539588928223e-01 +-2.317114639282226562e+01 -1.591066360473632812e+01 -5.363464355468750000e-01 -1.624944806098937988e-01 -6.941533088684082031e-02 5.547821521759033203e-01 8.130152821540832520e-01 +-2.344164657592773438e+01 -1.581360816955566406e+01 -5.427783131599426270e-01 -1.652654111385345459e-01 -6.504709273576736450e-02 5.529615283012390137e-01 8.140575289726257324e-01 +-2.371278762817382812e+01 -1.571944808959960938e+01 -5.487646460533142090e-01 -1.673214584589004517e-01 -6.169995665550231934e-02 5.508458018302917480e-01 8.153315186500549316e-01 +-2.398210716247558594e+01 -1.562127399444580078e+01 -5.520458817481994629e-01 -1.687461286783218384e-01 -5.927060544490814209e-02 5.484846234321594238e-01 8.168085813522338867e-01 +-2.424491691589355469e+01 -1.550804615020751953e+01 -5.487365722656250000e-01 -1.696220040321350098e-01 -5.765402317047119141e-02 5.459191203117370605e-01 8.184599280357360840e-01 +-2.449951553344726562e+01 -1.537872505187988281e+01 -5.386352539062500000e-01 -1.700302809476852417e-01 -5.674361437559127808e-02 5.431839823722839355e-01 8.202565908432006836e-01 +-2.474444007873535156e+01 -1.523342704772949219e+01 -5.220702886581420898e-01 -1.700503081083297729e-01 -5.643201619386672974e-02 5.403098464012145996e-01 8.221699595451354980e-01 +-2.497766494750976562e+01 -1.507148361206054688e+01 -4.995800554752349854e-01 -1.697595268487930298e-01 -5.661123991012573242e-02 5.373245477676391602e-01 8.241718411445617676e-01 +-2.519788742065429688e+01 -1.489331054687500000e+01 -4.744763076305389404e-01 -1.692334264516830444e-01 -5.717277154326438904e-02 5.342547893524169922e-01 8.262342810630798340e-01 +-2.539336204528808594e+01 -1.468873500823974609e+01 -4.596862792968750000e-01 -1.685453206300735474e-01 -5.800805985927581787e-02 5.311273932456970215e-01 8.283303380012512207e-01 +-2.555798339843750000e+01 -1.445811462402343750e+01 -4.592394828796386719e-01 -1.677662283182144165e-01 -5.900888144969940186e-02 5.279706120491027832e-01 8.304332494735717773e-01 +-2.571812248229980469e+01 -1.422478961944580078e+01 -4.612707495689392090e-01 -1.669649779796600342e-01 -6.006729975342750549e-02 5.248143672943115234e-01 8.325169086456298828e-01 +-2.587863731384277344e+01 -1.399217700958251953e+01 -4.633276164531707764e-01 -1.662081480026245117e-01 -6.107582896947860718e-02 5.216907262802124023e-01 8.345557451248168945e-01 +-2.603939819335937500e+01 -1.376019477844238281e+01 -4.652734398841857910e-01 -1.655599474906921387e-01 -6.192769110202789307e-02 5.186341404914855957e-01 8.365246057510375977e-01 +-2.620061683654785156e+01 -1.352896499633789062e+01 -4.669726490974426270e-01 -1.650823801755905151e-01 -6.251683831214904785e-02 5.156816840171813965e-01 8.383983969688415527e-01 +-2.636240959167480469e+01 -1.329857921600341797e+01 -4.683166444301605225e-01 -1.648352891206741333e-01 -6.273782253265380859e-02 5.128720402717590332e-01 8.401520252227783203e-01 +-2.652549934387207031e+01 -1.306953620910644531e+01 -4.689233303070068359e-01 -1.648764610290527344e-01 -6.248602271080017090e-02 5.102450251579284668e-01 8.417608141899108887e-01 +-2.668920898437500000e+01 -1.284157180786132812e+01 -4.689306616783142090e-01 -1.635180413722991943e-01 -6.064473092555999756e-02 5.079550147056579590e-01 8.435435891151428223e-01 +-2.678941345214843750e+01 -1.259829521179199219e+01 -4.772912561893463135e-01 -1.627251207828521729e-01 -5.846070125699043274e-02 5.058341622352600098e-01 8.451240658760070801e-01 +-2.651661872863769531e+01 -1.259877395629882812e+01 -5.171887278556823730e-01 -1.624446660280227661e-01 -5.598696693778038025e-02 5.038542747497558594e-01 8.465270996093750000e-01 +-2.624497032165527344e+01 -1.265571308135986328e+01 -5.533349514007568359e-01 -1.626231074333190918e-01 -5.327646434307098389e-02 5.019860267639160156e-01 8.477767109870910645e-01 +-2.597594642639160156e+01 -1.272301197052001953e+01 -5.885253548622131348e-01 -1.632073819637298584e-01 -5.038213729858398438e-02 5.001997947692871094e-01 8.488964438438415527e-01 +-2.570717620849609375e+01 -1.279211902618408203e+01 -6.183996200561523438e-01 -1.641437411308288574e-01 -4.735671356320381165e-02 4.984661638736724854e-01 8.499091863632202148e-01 +-2.543681907653808594e+01 -1.285688400268554688e+01 -6.373022198677062988e-01 -1.653789579868316650e-01 -4.425322264432907104e-02 4.967552125453948975e-01 8.508382439613342285e-01 +-2.515522003173828125e+01 -1.291918945312500000e+01 -6.406725645065307617e-01 -1.668590009212493896e-01 -4.112435504794120789e-02 4.950375556945800781e-01 8.517069220542907715e-01 +-2.486792182922363281e+01 -1.299890136718750000e+01 -6.366809010505676270e-01 -1.685309559106826782e-01 -3.802309930324554443e-02 4.932837784290313721e-01 8.525389432907104492e-01 +-2.459251213073730469e+01 -1.309572219848632812e+01 -6.340332031250000000e-01 -1.703415215015411377e-01 -3.500250354409217834e-02 4.914650619029998779e-01 8.533584475517272949e-01 +-2.432781219482421875e+01 -1.320330047607421875e+01 -6.343395709991455078e-01 -1.722373217344284058e-01 -3.211538866162300110e-02 4.895527064800262451e-01 8.541902303695678711e-01 +-2.407213020324707031e+01 -1.331618118286132812e+01 -6.366015672683715820e-01 -1.741653680801391602e-01 -2.941481396555900574e-02 4.875183403491973877e-01 8.550596237182617188e-01 +-2.382385635375976562e+01 -1.343023872375488281e+01 -6.396130323410034180e-01 -1.760728061199188232e-01 -2.695365622639656067e-02 4.853337705135345459e-01 8.559924364089965820e-01 +-2.358245468139648438e+01 -1.354421329498291016e+01 -6.429601907730102539e-01 -1.779067516326904297e-01 -2.478495612740516663e-02 4.829712510108947754e-01 8.570144176483154297e-01 +-2.334757423400878906e+01 -1.365731906890869141e+01 -6.463440060615539551e-01 -1.796139925718307495e-01 -2.296158671379089355e-02 4.804029166698455811e-01 8.581519126892089844e-01 +-2.311899566650390625e+01 -1.376906681060791016e+01 -6.494702100753784180e-01 -1.811420321464538574e-01 -2.153661847114562988e-02 4.776009321212768555e-01 8.594307899475097656e-01 +-2.289647483825683594e+01 -1.387895011901855469e+01 -6.519653201103210449e-01 -1.824380159378051758e-01 -2.056293934583663940e-02 4.745368361473083496e-01 8.608764410018920898e-01 +-2.267963409423828125e+01 -1.398621082305908203e+01 -6.532312035560607910e-01 -1.834485381841659546e-01 -2.009310945868492126e-02 4.711823761463165283e-01 8.625138401985168457e-01 +-2.246773719787597656e+01 -1.408929157257080078e+01 -6.521801352500915527e-01 -1.841205060482025146e-01 -2.018003538250923157e-02 4.675078690052032471e-01 8.643661141395568848e-01 +-2.226006698608398438e+01 -1.418655204772949219e+01 -6.480712890625000000e-01 -1.844001263380050659e-01 -2.087630331516265869e-02 4.634829461574554443e-01 8.664549589157104492e-01 +-2.205663490295410156e+01 -1.427795410156250000e+01 -6.416552662849426270e-01 -1.835716813802719116e-01 -2.185546979308128357e-02 4.591004848480224609e-01 8.689364194869995117e-01 +-2.185772132873535156e+01 -1.436379337310791016e+01 -6.333520412445068359e-01 -1.824225485324859619e-01 -2.347820624709129333e-02 4.543474614620208740e-01 8.716301321983337402e-01 +-2.166368293762207031e+01 -1.444483852386474609e+01 -6.238781809806823730e-01 -1.810006201267242432e-01 -2.567527443170547485e-02 4.492349326610565186e-01 8.745098710060119629e-01 +-2.147487449645996094e+01 -1.452191352844238281e+01 -6.138256788253784180e-01 -1.793531924486160278e-01 -2.837654948234558105e-02 4.437734782695770264e-01 8.775489926338195801e-01 +-2.129187965393066406e+01 -1.459654712677001953e+01 -6.037365794181823730e-01 -1.775269359350204468e-01 -3.151117265224456787e-02 4.379730820655822754e-01 8.807217478752136230e-01 +-2.111501884460449219e+01 -1.466954517364501953e+01 -5.938305258750915527e-01 -1.755676269531250000e-01 -3.500741720199584961e-02 4.318441450595855713e-01 8.840028047561645508e-01 +-2.094495010375976562e+01 -1.474252891540527344e+01 -5.844531059265136719e-01 -1.735200583934783936e-01 -3.879258409142494202e-02 4.253970980644226074e-01 8.873687386512756348e-01 +-2.078098678588867188e+01 -1.481380367279052734e+01 -5.754565596580505371e-01 -1.714278608560562134e-01 -4.279293864965438843e-02 4.186428785324096680e-01 8.907969594001770020e-01 +-2.062461853027343750e+01 -1.488681602478027344e+01 -5.673596262931823730e-01 -1.693332791328430176e-01 -4.693398624658584595e-02 4.115937650203704834e-01 8.942673206329345703e-01 +-2.047404289245605469e+01 -1.495735359191894531e+01 -5.595715045928955078e-01 -1.672767847776412964e-01 -5.114042758941650391e-02 4.042624533176422119e-01 8.977610468864440918e-01 +-2.033163452148437500e+01 -1.503049278259277344e+01 -5.529308915138244629e-01 -1.652971953153610229e-01 -5.533592775464057922e-02 3.966634571552276611e-01 9.012618064880371094e-01 +-2.019488525390625000e+01 -1.510086917877197266e+01 -5.465551614761352539e-01 -1.634310036897659302e-01 -5.944371595978736877e-02 3.888122439384460449e-01 9.047551155090332031e-01 +-2.006615447998046875e+01 -1.517303657531738281e+01 -5.412658452987670898e-01 -1.617124378681182861e-01 -6.338612735271453857e-02 3.807254731655120850e-01 9.082287549972534180e-01 +-1.994371604919433594e+01 -1.524365234375000000e+01 -5.364623665809631348e-01 -1.601731330156326294e-01 -6.708491593599319458e-02 3.724210858345031738e-01 9.116724133491516113e-01 +-1.982761192321777344e+01 -1.531261730194091797e+01 -5.321472287178039551e-01 -1.588416397571563721e-01 -7.046176493167877197e-02 3.639198243618011475e-01 9.150775074958801270e-01 +-1.971994972229003906e+01 -1.538352966308593750e+01 -5.290173292160034180e-01 -1.577431112527847290e-01 -7.343824952840805054e-02 3.552419245243072510e-01 9.184372425079345703e-01 +-1.961760330200195312e+01 -1.545106887817382812e+01 -5.260412693023681641e-01 -1.568995416164398193e-01 -7.593537867069244385e-02 3.464096486568450928e-01 9.217464923858642578e-01 +-1.952189826965332031e+01 -1.551718235015869141e+01 -5.236254930496215820e-01 -1.563290804624557495e-01 -7.787409424781799316e-02 3.374458253383636475e-01 9.250012040138244629e-01 +-1.943454551696777344e+01 -1.558438968658447266e+01 -5.222949385643005371e-01 -1.560456752777099609e-01 -7.917611300945281982e-02 3.283739984035491943e-01 9.281979203224182129e-01 +-1.934015464782714844e+01 -1.565674781799316406e+01 -5.208557248115539551e-01 -1.560593098402023315e-01 -7.976308465003967285e-02 3.192176818847656250e-01 9.313342571258544922e-01 +-1.924914169311523438e+01 -1.572825622558593750e+01 -5.196911692619323730e-01 -1.563673317432403564e-01 -7.958032190799713135e-02 3.100039660930633545e-01 9.344055056571960449e-01 +-1.916583824157714844e+01 -1.580432605743408203e+01 -5.200195312500000000e-01 -1.569329351186752319e-01 -7.866371423006057739e-02 3.007761240005493164e-01 9.373994469642639160e-01 +-1.908487319946289062e+01 -1.587828063964843750e+01 -5.203344821929931641e-01 -1.577120125293731689e-01 -7.707326114177703857e-02 2.915808260440826416e-01 9.403016567230224609e-01 +-1.900623321533203125e+01 -1.595010185241699219e+01 -5.206396579742431641e-01 -1.586629748344421387e-01 -7.486814260482788086e-02 2.824644148349761963e-01 9.430984258651733398e-01 +-1.893425178527832031e+01 -1.602438926696777344e+01 -5.220336914062500000e-01 -1.597469151020050049e-01 -7.210765033960342407e-02 2.734732627868652344e-01 9.457767605781555176e-01 +-1.886517524719238281e+01 -1.609718704223632812e+01 -5.235705375671386719e-01 -1.609278172254562378e-01 -6.885146349668502808e-02 2.646539509296417236e-01 9.483247995376586914e-01 +-1.879824447631835938e+01 -1.616769027709960938e+01 -5.250585675239562988e-01 -1.621732115745544434e-01 -6.515870243310928345e-02 2.560534775257110596e-01 9.507316946983337402e-01 +-1.873452568054199219e+01 -1.623689460754394531e+01 -5.267516970634460449e-01 -1.634541451930999756e-01 -6.108817085623741150e-02 2.477196604013442993e-01 9.529878497123718262e-01 +-1.867581558227539062e+01 -1.630647850036621094e+01 -5.290759205818176270e-01 -1.647452563047409058e-01 -5.669882893562316895e-02 2.397010773420333862e-01 9.550851583480834961e-01 +-1.861907958984375000e+01 -1.637364196777343750e+01 -5.313208103179931641e-01 -1.660249382257461548e-01 -5.204921215772628784e-02 2.320473194122314453e-01 9.570164680480957031e-01 +-1.856431198120117188e+01 -1.643838310241699219e+01 -5.334875583648681641e-01 -1.672755330801010132e-01 -4.719660058617591858e-02 2.248092293739318848e-01 9.587763547897338867e-01 +-1.851239585876464844e+01 -1.650145912170410156e+01 -5.357751250267028809e-01 -1.684827357530593872e-01 -4.219894483685493469e-02 2.180386632680892944e-01 9.603602290153503418e-01 +-1.846445465087890625e+01 -1.656378936767578125e+01 -5.384314060211181641e-01 -1.696358472108840942e-01 -3.711352124810218811e-02 2.117889374494552612e-01 9.617648720741271973e-01 +-1.841833114624023438e+01 -1.662360763549804688e+01 -5.409862995147705078e-01 -1.707274615764617920e-01 -3.199715912342071533e-02 2.061144709587097168e-01 9.629875421524047852e-01 +-1.837400627136230469e+01 -1.668091773986816406e+01 -5.434387326240539551e-01 -1.717531234025955200e-01 -2.690691873431205750e-02 2.010709494352340698e-01 9.640266299247741699e-01 +-1.833147239685058594e+01 -1.673570823669433594e+01 -5.457910299301147461e-01 -1.727110296487808228e-01 -2.190021425485610962e-02 1.967148929834365845e-01 9.648805260658264160e-01 +-1.829236221313476562e+01 -1.678922843933105469e+01 -5.483788847923278809e-01 -1.736016720533370972e-01 -1.703507639467716217e-02 1.931038051843643188e-01 9.655480384826660156e-01 +-1.825531387329101562e+01 -1.684044837951660156e+01 -5.509252548217773438e-01 -1.744272559881210327e-01 -1.237064786255359650e-02 1.902956515550613403e-01 9.660277962684631348e-01 +-1.821992683410644531e+01 -1.688907623291015625e+01 -5.533496141433715820e-01 -1.751911938190460205e-01 -7.967818528413772583e-03 1.883485168218612671e-01 9.663174152374267578e-01 +-1.818618583679199219e+01 -1.693511199951171875e+01 -5.556518435478210449e-01 -1.758974492549896240e-01 -3.889763727784156799e-03 1.873202025890350342e-01 9.664139747619628906e-01 +-1.815403366088867188e+01 -1.697879791259765625e+01 -5.585265755653381348e-01 -1.736778020858764648e-01 3.683120012283325195e-04 1.872485131025314331e-01 9.668369889259338379e-01 +-1.812410545349121094e+01 -1.702033615112304688e+01 -5.615234375000000000e-01 -1.708639562129974365e-01 4.365487024188041687e-03 1.880719512701034546e-01 9.671686887741088867e-01 +-1.809640502929687500e+01 -1.705971717834472656e+01 -5.646276473999023438e-01 -1.675173193216323853e-01 8.118055760860443115e-03 1.897289156913757324e-01 9.674062728881835938e-01 +-1.807031250000000000e+01 -1.709648895263671875e+01 -5.677074790000915527e-01 -1.636992692947387695e-01 1.164237223565578461e-02 1.921575218439102173e-01 9.675445556640625000e-01 +-1.804584503173828125e+01 -1.713065338134765625e+01 -5.707470774650573730e-01 -1.594703197479248047e-01 1.495485939085483551e-02 1.952953934669494629e-01 9.675769805908203125e-01 +-1.802301406860351562e+01 -1.716219711303710938e+01 -5.737353563308715820e-01 -1.548913419246673584e-01 1.807173900306224823e-02 1.990799605846405029e-01 9.674964547157287598e-01 +-1.800183868408203125e+01 -1.719112205505371094e+01 -5.766589045524597168e-01 -1.500232070684432983e-01 2.100928872823715210e-02 2.034485489130020142e-01 9.672953486442565918e-01 +-1.798233222961425781e+01 -1.721742630004882812e+01 -5.795056223869323730e-01 -1.449269354343414307e-01 2.378391660749912262e-02 2.083385735750198364e-01 9.669671654701232910e-01 +-1.796454048156738281e+01 -1.724111747741699219e+01 -5.822631716728210449e-01 -1.396637409925460815e-01 2.641172707080841064e-02 2.136875092983245850e-01 9.665061235427856445e-01 +-1.794881820678710938e+01 -1.726243591308593750e+01 -5.849756002426147461e-01 -1.342951357364654541e-01 2.890913002192974091e-02 2.194330692291259766e-01 9.659079313278198242e-01 +-1.793476104736328125e+01 -1.728108406066894531e+01 -5.875573754310607910e-01 -1.288829147815704346e-01 3.129223734140396118e-02 2.255132198333740234e-01 9.651703834533691406e-01 +-1.792238235473632812e+01 -1.729707527160644531e+01 -5.899950861930847168e-01 -1.234894543886184692e-01 3.357748687267303467e-02 2.318663746118545532e-01 9.642929434776306152e-01 +-1.791169548034667969e+01 -1.731039047241210938e+01 -5.922704935073852539e-01 -1.181771308183670044e-01 3.578108549118041992e-02 2.384315133094787598e-01 9.632779359817504883e-01 +-1.790271568298339844e+01 -1.732105445861816406e+01 -5.943713188171386719e-01 -1.130089387297630310e-01 3.791945800185203552e-02 2.451479583978652954e-01 9.621296525001525879e-01 +-1.789545440673828125e+01 -1.732906150817871094e+01 -5.962817072868347168e-01 -1.080475375056266785e-01 4.000906646251678467e-02 2.519558668136596680e-01 9.608554244041442871e-01 +-1.788992500305175781e+01 -1.733441925048828125e+01 -5.979833602905273438e-01 -1.033566072583198547e-01 4.206611216068267822e-02 2.587959468364715576e-01 9.594647884368896484e-01 +-1.788613891601562500e+01 -1.733712768554687500e+01 -5.994641184806823730e-01 -9.899981319904327393e-02 4.410721734166145325e-02 2.656095325946807861e-01 9.579692482948303223e-01 +-1.788411140441894531e+01 -1.733719635009765625e+01 -6.007080078125000000e-01 -9.504061937332153320e-02 4.614873975515365601e-02 2.723386883735656738e-01 9.563834071159362793e-01 +-1.787696456909179688e+01 -1.734501457214355469e+01 -6.022863388061523438e-01 -9.154327213764190674e-02 4.820729792118072510e-02 2.789262533187866211e-01 9.547230601310729980e-01 +-1.786470603942871094e+01 -1.736057662963867188e+01 -6.041833162307739258e-01 -8.857118338346481323e-02 5.029954761266708374e-02 2.853153944015502930e-01 9.530058503150939941e-01 +-1.784735107421875000e+01 -1.738390541076660156e+01 -6.063903570175170898e-01 -8.616801351308822632e-02 5.243882536888122559e-02 2.914660573005676270e-01 9.512479901313781738e-01 +-1.782488632202148438e+01 -1.741499900817871094e+01 -6.089184284210205078e-01 -8.429352939128875732e-02 5.462608486413955688e-02 2.974020540714263916e-01 9.494538903236389160e-01 +-1.779734039306640625e+01 -1.745387077331542969e+01 -6.117821931838989258e-01 -8.288758993148803711e-02 5.685858055949211121e-02 3.031627237796783447e-01 9.476228952407836914e-01 +-1.776491355895996094e+01 -1.750066947937011719e+01 -6.150036454200744629e-01 -8.188873529434204102e-02 5.913389846682548523e-02 3.087868690490722656e-01 9.457526803016662598e-01 +-1.772739982604980469e+01 -1.755525779724121094e+01 -6.185900568962097168e-01 -8.123598992824554443e-02 6.144924834370613098e-02 3.143127262592315674e-01 9.438390731811523438e-01 +-1.768478775024414062e+01 -1.761763572692871094e+01 -6.225597858428955078e-01 -8.086805045604705811e-02 6.380198150873184204e-02 3.197781145572662354e-01 9.418767094612121582e-01 +-1.763625717163085938e+01 -1.768726539611816406e+01 -6.266626119613647461e-01 -8.072343468666076660e-02 6.618919223546981812e-02 3.252205848693847656e-01 9.398586750030517578e-01 +-1.758230400085449219e+01 -1.776447677612304688e+01 -6.310778856277465820e-01 -8.074045926332473755e-02 6.860806047916412354e-02 3.306772112846374512e-01 9.377774000167846680e-01 +-1.752128601074218750e+01 -1.784814834594726562e+01 -6.353161334991455078e-01 -8.085796236991882324e-02 7.105553895235061646e-02 3.361848294734954834e-01 9.356243014335632324e-01 +-1.745257949829101562e+01 -1.793774414062500000e+01 -6.392089724540710449e-01 -8.101430535316467285e-02 7.352856546640396118e-02 3.417798578739166260e-01 9.333900213241577148e-01 +-1.737313652038574219e+01 -1.803073692321777344e+01 -6.418249607086181641e-01 -8.114737272262573242e-02 7.602420449256896973e-02 3.474985361099243164e-01 9.310639500617980957e-01 +-1.727821540832519531e+01 -1.812207412719726562e+01 -6.416015625000000000e-01 -8.119583874940872192e-02 7.853914797306060791e-02 3.533766865730285645e-01 9.286354780197143555e-01 +-1.716444396972656250e+01 -1.820580101013183594e+01 -6.372119188308715820e-01 -8.109773695468902588e-02 8.107020705938339233e-02 3.594494760036468506e-01 9.260922670364379883e-01 +-1.703792572021484375e+01 -1.828765106201171875e+01 -6.308032274246215820e-01 -8.079120516777038574e-02 8.361406624317169189e-02 3.657518625259399414e-01 9.234213232994079590e-01 +-1.690320205688476562e+01 -1.837402725219726562e+01 -6.242114305496215820e-01 -8.021453022956848145e-02 8.616720885038375854e-02 3.723181784152984619e-01 9.206085205078125000e-01 +-1.676093673706054688e+01 -1.846594619750976562e+01 -6.178197860717773438e-01 -7.930594682693481445e-02 8.872600644826889038e-02 3.791821002960205078e-01 9.176378250122070312e-01 +-1.661141777038574219e+01 -1.856386184692382812e+01 -6.118798851966857910e-01 -7.800345122814178467e-02 9.128685295581817627e-02 3.863770961761474609e-01 9.144915938377380371e-01 +-1.645495605468750000e+01 -1.866820716857910156e+01 -6.066784262657165527e-01 -7.624515146017074585e-02 9.384562075138092041e-02 3.939341008663177490e-01 9.111507534980773926e-01 +-1.629194259643554688e+01 -1.877953529357910156e+01 -6.025720238685607910e-01 -7.396907359361648560e-02 9.639839082956314087e-02 4.018841981887817383e-01 9.075930118560791016e-01 +-1.612274742126464844e+01 -1.889830017089843750e+01 -5.998827815055847168e-01 -7.111330330371856689e-02 9.894046932458877563e-02 4.102570116519927979e-01 9.037936329841613770e-01 +-1.594792461395263672e+01 -1.902517127990722656e+01 -5.990747213363647461e-01 -6.764376163482666016e-02 1.014612764120101929e-01 4.190501570701599121e-01 8.997371196746826172e-01 +-1.576822853088378906e+01 -1.916101074218750000e+01 -6.007885336875915527e-01 -6.363680213689804077e-02 1.039256975054740906e-01 4.281411468982696533e-01 8.954579234123229980e-01 +-1.558430385589599609e+01 -1.930643463134765625e+01 -6.056188941001892090e-01 -5.919722840189933777e-02 1.062933802604675293e-01 4.373798668384552002e-01 8.910086154937744141e-01 +-1.539637660980224609e+01 -1.946148300170898438e+01 -6.137255430221557617e-01 -5.443003028631210327e-02 1.085248515009880066e-01 4.466195404529571533e-01 8.864483833312988281e-01 +-1.520430183410644531e+01 -1.962582397460937500e+01 -6.249060034751892090e-01 -4.944133758544921875e-02 1.105812788009643555e-01 4.557167887687683105e-01 8.818444013595581055e-01 +-1.500771331787109375e+01 -1.979891586303710938e+01 -6.387646198272705078e-01 -4.433740675449371338e-02 1.124248802661895752e-01 4.645321965217590332e-01 8.772711157798767090e-01 +-1.480619621276855469e+01 -1.998026275634765625e+01 -6.548547148704528809e-01 -3.922503814101219177e-02 1.140190213918685913e-01 4.729304611682891846e-01 8.728103041648864746e-01 +-1.459937191009521484e+01 -2.016944694519042969e+01 -6.727819442749023438e-01 -3.421109169721603394e-02 1.153278648853302002e-01 4.807797670364379883e-01 8.685504198074340820e-01 +-1.438695049285888672e+01 -2.036620521545410156e+01 -6.922289729118347168e-01 -2.940253913402557373e-02 1.163163855671882629e-01 4.879520535469055176e-01 8.645858764648437500e-01 +-1.416900730133056641e+01 -2.057060050964355469e+01 -7.132446169853210449e-01 -2.490628883242607117e-02 1.169503927230834961e-01 4.943219423294067383e-01 8.610157370567321777e-01 +-1.395810794830322266e+01 -2.076930618286132812e+01 -7.336339950561523438e-01 -2.082914486527442932e-02 1.171961426734924316e-01 4.997668564319610596e-01 8.579419851303100586e-01 +-1.375402069091796875e+01 -2.096210861206054688e+01 -7.532275319099426270e-01 -1.727757975459098816e-02 1.170200556516647339e-01 5.041647553443908691e-01 8.554680943489074707e-01 +-1.355647563934326172e+01 -2.114881706237792969e+01 -7.714196443557739258e-01 -1.435786113142967224e-02 1.163884699344635010e-01 5.073940157890319824e-01 8.536972403526306152e-01 +-1.336550045013427734e+01 -2.132947158813476562e+01 -7.884838581085205078e-01 -1.217595487833023071e-02 1.152671799063682556e-01 5.093313455581665039e-01 8.527289628982543945e-01 +-1.318074798583984375e+01 -2.150379371643066406e+01 -8.037194609642028809e-01 -1.083766296505928040e-02 1.136212199926376343e-01 5.098505020141601562e-01 8.526577949523925781e-01 +-1.300255870819091797e+01 -2.167208480834960938e+01 -8.177490234375000000e-01 -1.044839248061180115e-02 1.114140003919601440e-01 5.088196992874145508e-01 8.535690903663635254e-01 +-1.283029842376708984e+01 -2.183377456665039062e+01 -8.294262290000915527e-01 -1.111348345875740051e-02 1.086074858903884888e-01 5.061002373695373535e-01 8.555368781089782715e-01 +-1.266489505767822266e+01 -2.198973655700683594e+01 -8.402550816535949707e-01 -1.293786615133285522e-02 1.051610410213470459e-01 5.015448331832885742e-01 8.586189746856689453e-01 +-1.250496673583984375e+01 -2.213861274719238281e+01 -8.478466868400573730e-01 -1.602597907185554504e-02 1.010316461324691772e-01 4.949942231178283691e-01 8.628536462783813477e-01 +-1.235201644897460938e+01 -2.228182601928710938e+01 -8.545812964439392090e-01 -2.048139087855815887e-02 9.617313742637634277e-02 4.862766563892364502e-01 8.682547211647033691e-01 +-1.220498275756835938e+01 -2.241820335388183594e+01 -8.585851788520812988e-01 -2.635845541954040527e-02 9.055834263563156128e-02 4.752687513828277588e-01 8.747708797454833984e-01 +-1.206440067291259766e+01 -2.254821205139160156e+01 -8.607397079467773438e-01 -3.351867198944091797e-02 8.424679934978485107e-02 4.620925784111022949e-01 8.821844458580017090e-01 +-1.193075942993164062e+01 -2.267219161987304688e+01 -8.618810772895812988e-01 -4.177390038967132568e-02 7.732103765010833740e-02 4.469355344772338867e-01 8.902387619018554688e-01 +-1.180233383178710938e+01 -2.278814315795898438e+01 -8.590893149375915527e-01 -5.093406885862350464e-02 6.986640393733978271e-02 4.299928843975067139e-01 8.986826539039611816e-01 +-1.168124580383300781e+01 -2.289830017089843750e+01 -8.560631871223449707e-01 -6.080749630928039551e-02 6.197084113955497742e-02 4.114713370800018311e-01 9.072780609130859375e-01 +-1.156612873077392578e+01 -2.300089836120605469e+01 -8.504064679145812988e-01 -7.120185345411300659e-02 5.372554808855056763e-02 3.915930092334747314e-01 9.158050417900085449e-01 +-1.145700263977050781e+01 -2.309589767456054688e+01 -8.422644138336181641e-01 -8.192436397075653076e-02 4.522506892681121826e-02 3.705942034721374512e-01 9.240686893463134766e-01 +-1.135530757904052734e+01 -2.318506240844726562e+01 -8.344018459320068359e-01 -9.278335422277450562e-02 3.656715154647827148e-02 3.487282693386077881e-01 9.319027662277221680e-01 +-1.125894165039062500e+01 -2.326542854309082031e+01 -8.236218094825744629e-01 -1.035891473293304443e-01 2.785192057490348816e-02 3.262639045715332031e-01 9.391727447509765625e-01 +-1.116942977905273438e+01 -2.333920860290527344e+01 -8.125329613685607910e-01 -1.141555085778236389e-01 1.918116211891174316e-02 3.034849464893341064e-01 9.457788467407226562e-01 +-1.108734512329101562e+01 -2.340727424621582031e+01 -8.022240996360778809e-01 -1.243009939789772034e-01 1.065819710493087769e-02 2.806864678859710693e-01 9.516568779945373535e-01 +-1.101012325286865234e+01 -2.346564865112304688e+01 -7.894347906112670898e-01 -1.338488608598709106e-01 2.386640757322311401e-03 2.581741809844970703e-01 9.567784667015075684e-01 +-1.094018077850341797e+01 -2.351834869384765625e+01 -7.775878906250000000e-01 -1.426293998956680298e-01 -5.530703812837600708e-03 2.362618595361709595e-01 9.611486196517944336e-01 +-1.087761116027832031e+01 -2.356570243835449219e+01 -7.669897079467773438e-01 -1.504779756069183350e-01 -1.299132406711578369e-02 2.152677923440933228e-01 9.648043513298034668e-01 +-1.081989383697509766e+01 -2.360318374633789062e+01 -7.549633383750915527e-01 -1.572377234697341919e-01 -1.989493519067764282e-02 1.955124735832214355e-01 9.678095579147338867e-01 +-1.076939964294433594e+01 -2.363549232482910156e+01 -7.443163990974426270e-01 -1.627555489540100098e-01 -2.614275738596916199e-02 1.773162335157394409e-01 9.702506065368652344e-01 +-1.072629261016845703e+01 -2.366316795349121094e+01 -7.353747487068176270e-01 -1.668835878372192383e-01 -3.163781389594078064e-02 1.609973907470703125e-01 9.722288250923156738e-01 +-1.068942451477050781e+01 -2.368360710144042969e+01 -7.270935177803039551e-01 -1.694756001234054565e-01 -3.628516569733619690e-02 1.468703299760818481e-01 9.738534092903137207e-01 +-1.065877342224121094e+01 -2.369713401794433594e+01 -7.197473049163818359e-01 -1.697092056274414062e-01 -3.989725559949874878e-02 1.352724879980087280e-01 9.753503203392028809e-01 +-1.063575077056884766e+01 -2.370730972290039062e+01 -7.143371701240539551e-01 -1.694652587175369263e-01 -4.266242682933807373e-02 1.264244019985198975e-01 9.764621257781982422e-01 +-1.062023162841796875e+01 -2.371432495117187500e+01 -7.113623023033142090e-01 -1.666205227375030518e-01 -4.424036294221878052e-02 1.206160113215446472e-01 9.776155352592468262e-01 +-1.061051654815673828e+01 -2.371881866455078125e+01 -7.102355957031250000e-01 -1.619942039251327515e-01 -4.480173811316490173e-02 1.176587045192718506e-01 9.787273406982421875e-01 +-1.060666942596435547e+01 -2.372078132629394531e+01 -7.109069824218750000e-01 -1.557830721139907837e-01 -4.445625096559524536e-02 1.172960177063941956e-01 9.797943234443664551e-01 +-1.060481262207031250e+01 -2.372170448303222656e+01 -7.124841213226318359e-01 -1.481798291206359863e-01 -4.331202805042266846e-02 1.192679628729820251e-01 9.807863831520080566e-01 +-1.059402942657470703e+01 -2.372573280334472656e+01 -7.125634551048278809e-01 -1.393745392560958862e-01 -4.147681593894958496e-02 1.233121752738952637e-01 9.816560149192810059e-01 +-1.057428169250488281e+01 -2.373179626464843750e+01 -7.108715772628784180e-01 -1.295560449361801147e-01 -3.905843943357467651e-02 1.291646510362625122e-01 9.823472499847412109e-01 +-1.054468154907226562e+01 -2.373078536987304688e+01 -7.053527832031250000e-01 -1.189149618148803711e-01 -3.616411983966827393e-02 1.365606486797332764e-01 9.828034639358520508e-01 +-1.050600719451904297e+01 -2.372926712036132812e+01 -6.974206566810607910e-01 -1.076428443193435669e-01 -3.290275484323501587e-02 1.452350765466690063e-01 9.829736351966857910e-01 +-1.047626781463623047e+01 -2.370073127746582031e+01 -6.884130835533142090e-01 -9.593401104211807251e-02 -2.938275039196014404e-02 1.549237966537475586e-01 9.828183650970458984e-01 +-1.046522426605224609e+01 -2.364887619018554688e+01 -6.820385456085205078e-01 -8.398548513650894165e-02 -2.571449242532253265e-02 1.653640419244766235e-01 9.823135137557983398e-01 +-1.048062133789062500e+01 -2.358564949035644531e+01 -6.827343702316284180e-01 -7.199695706367492676e-02 -2.200762741267681122e-02 1.762954741716384888e-01 9.814540743827819824e-01 +-1.050563335418701172e+01 -2.351642608642578125e+01 -6.861621141433715820e-01 -6.017067655920982361e-02 -1.837365329265594482e-02 1.874611973762512207e-01 9.802551865577697754e-01 +-1.054297256469726562e+01 -2.344232940673828125e+01 -6.934130787849426270e-01 -4.871069639921188354e-02 -1.492377743124961853e-02 1.986082196235656738e-01 9.787539839744567871e-01 +-1.058514404296875000e+01 -2.336031723022460938e+01 -7.011474370956420898e-01 -3.782265260815620422e-02 -1.176953222602605820e-02 2.094882875680923462e-01 9.770084619522094727e-01 +-1.063856792449951172e+01 -2.327448272705078125e+01 -7.121984958648681641e-01 -2.771227434277534485e-02 -9.021600708365440369e-03 2.198581695556640625e-01 9.750964045524597168e-01 +-1.069721889495849609e+01 -2.318099975585937500e+01 -7.237438559532165527e-01 -1.858626678586006165e-02 -6.791889201849699020e-03 2.294794023036956787e-01 9.731123447418212891e-01 +-1.076325702667236328e+01 -2.308148384094238281e+01 -7.366576790809631348e-01 -1.065042708069086075e-02 -5.190695635974407196e-03 2.381179630756378174e-01 9.711639881134033203e-01 +-1.083692359924316406e+01 -2.297613716125488281e+01 -7.509692311286926270e-01 -4.110292997211217880e-03 -4.328842274844646454e-03 2.455432265996932983e-01 9.693673253059387207e-01 +-1.091626167297363281e+01 -2.286353874206542969e+01 -7.657372951507568359e-01 8.294742438010871410e-04 -4.317172802984714508e-03 2.515261769294738770e-01 9.678404927253723145e-01 +-1.100432872772216797e+01 -2.274613761901855469e+01 -7.821130156517028809e-01 3.964609466493129730e-03 -5.266502965241670609e-03 2.558379769325256348e-01 9.666971564292907715e-01 +-1.109833145141601562e+01 -2.262172889709472656e+01 -7.989257574081420898e-01 5.153934471309185028e-03 -7.251162547618150711e-03 2.583153545856475830e-01 9.660197496414184570e-01 +-1.119967460632324219e+01 -2.249148941040039062e+01 -8.166686892509460449e-01 4.504605196416378021e-03 -1.019955892115831375e-02 2.590637207031250000e-01 9.657959342002868652e-01 +-1.130787372589111328e+01 -2.235502433776855469e+01 -8.352453708648681641e-01 2.185793127864599228e-03 -1.400303561240434647e-02 2.582513689994812012e-01 9.659738540649414062e-01 +-1.142283821105957031e+01 -2.221224975585937500e+01 -8.545776009559631348e-01 -1.633108127862215042e-03 -1.855275034904479980e-02 2.560428678989410400e-01 9.664859771728515625e-01 +-1.154491806030273438e+01 -2.206347084045410156e+01 -8.747839331626892090e-01 -6.783263292163610458e-03 -2.373933419585227966e-02 2.526000142097473145e-01 9.672556519508361816e-01 +-1.167372322082519531e+01 -2.190831565856933594e+01 -8.956835865974426270e-01 -1.309422217309474945e-02 -2.945379167795181274e-02 2.480840981006622314e-01 9.682021141052246094e-01 +-1.180952262878417969e+01 -2.174700164794921875e+01 -9.173119664192199707e-01 -2.039594948291778564e-02 -3.558594360947608948e-02 2.426568120718002319e-01 9.692447185516357422e-01 +-1.195242786407470703e+01 -2.157956504821777344e+01 -9.393078684806823730e-01 -2.851795963943004608e-02 -4.202570021152496338e-02 2.364814728498458862e-01 9.703077077865600586e-01 +-1.210221576690673828e+01 -2.140580940246582031e+01 -9.616162180900573730e-01 -3.728902339935302734e-02 -4.866314306855201721e-02 2.297237962484359741e-01 9.713229537010192871e-01 +-1.225943660736083984e+01 -2.122608375549316406e+01 -9.834057688713073730e-01 -4.653758928179740906e-02 -5.538772046566009521e-02 2.225524336099624634e-01 9.722328782081604004e-01 +-1.242544555664062500e+01 -2.104152297973632812e+01 -1.003858566284179688e+00 -5.609222501516342163e-02 -6.208969652652740479e-02 2.151391804218292236e-01 9.729921221733093262e-01 +-1.259703445434570312e+01 -2.086024856567382812e+01 -1.021265864372253418e+00 -6.578211486339569092e-02 -6.865978240966796875e-02 2.076589465141296387e-01 9.735688567161560059e-01 +-1.277709674835205078e+01 -2.068539428710937500e+01 -1.034840106964111328e+00 -7.543698698282241821e-02 -7.498934864997863770e-02 2.002898007631301880e-01 9.739454984664916992e-01 +-1.297280883789062500e+01 -2.052606964111328125e+01 -1.043343424797058105e+00 -8.488766103982925415e-02 -8.097057044506072998e-02 1.932124793529510498e-01 9.741185307502746582e-01 +-1.318554782867431641e+01 -2.038809967041015625e+01 -1.050672531127929688e+00 -9.396622329950332642e-02 -8.649715036153793335e-02 1.866097748279571533e-01 9.740972518920898438e-01 +-1.340810298919677734e+01 -2.026439857482910156e+01 -1.056845664978027344e+00 -1.025063842535018921e-01 -9.146361798048019409e-02 1.806665956974029541e-01 9.739026427268981934e-01 +-1.363603401184082031e+01 -2.014865112304687500e+01 -1.056191325187683105e+00 -1.103432998061180115e-01 -9.576536715030670166e-02 1.755688339471817017e-01 9.735651016235351562e-01 +-1.386581039428710938e+01 -2.003540420532226562e+01 -1.043540000915527344e+00 -1.173135638236999512e-01 -9.929943084716796875e-02 1.715029180049896240e-01 9.731207489967346191e-01 +-1.409475421905517578e+01 -1.992141151428222656e+01 -1.015662789344787598e+00 -1.232542917132377625e-01 -1.019623205065727234e-01 1.686556339263916016e-01 9.726085066795349121e-01 +-1.432707595825195312e+01 -1.981404304504394531e+01 -9.837145805358886719e-01 -1.280037760734558105e-01 -1.036513596773147583e-01 1.672129184007644653e-01 9.720654487609863281e-01 +-1.456527996063232422e+01 -1.971718215942382812e+01 -9.577209353446960449e-01 -1.314439326524734497e-01 -1.042973548173904419e-01 1.673095226287841797e-01 9.715204834938049316e-01 +-1.480920982360839844e+01 -1.963162612915039062e+01 -9.416223168373107910e-01 -1.336328685283660889e-01 -1.039666831493377686e-01 1.688769906759262085e-01 9.709860086441040039e-01 +-1.505674266815185547e+01 -1.955385780334472656e+01 -9.336132407188415527e-01 -1.346721351146697998e-01 -1.027587950229644775e-01 1.717943102121353149e-01 9.704590439796447754e-01 +-1.530693912506103516e+01 -1.948230361938476562e+01 -9.326086044311523438e-01 -1.346603780984878540e-01 -1.007723584771156311e-01 1.759385019540786743e-01 9.699262976646423340e-01 +-1.555902957916259766e+01 -1.941506385803222656e+01 -9.368615746498107910e-01 -1.336965858936309814e-01 -9.810473024845123291e-02 1.811851710081100464e-01 9.693671464920043945e-01 +-1.581249237060546875e+01 -1.935045433044433594e+01 -9.446935653686523438e-01 -1.318787783384323120e-01 -9.485309571027755737e-02 1.874091774225234985e-01 9.687562584877014160e-01 +-1.606719398498535156e+01 -1.928809928894042969e+01 -9.559924006462097168e-01 -1.293048858642578125e-01 -9.111483395099639893e-02 1.944845765829086304e-01 9.680672287940979004e-01 +-1.632287406921386719e+01 -1.922676658630371094e+01 -9.694970250129699707e-01 -1.260729134082794189e-01 -8.698722720146179199e-02 2.022854983806610107e-01 9.672741889953613281e-01 +-1.657949256896972656e+01 -1.916606903076171875e+01 -9.848546981811523438e-01 -1.222814619541168213e-01 -8.256836235523223877e-02 2.106860280036926270e-01 9.663545489311218262e-01 +-1.683703422546386719e+01 -1.910580062866210938e+01 -1.001964092254638672e+00 -1.180305927991867065e-01 -7.795666903257369995e-02 2.195609360933303833e-01 9.652899503707885742e-01 +-1.709544563293457031e+01 -1.904576110839843750e+01 -1.021319508552551270e+00 -1.134206950664520264e-01 -7.325114309787750244e-02 2.287859469652175903e-01 9.640679359436035156e-01 +-1.735464859008789062e+01 -1.898541450500488281e+01 -1.042510986328125000e+00 -1.085525155067443848e-01 -6.855186820030212402e-02 2.382379472255706787e-01 9.626835584640502930e-01 +-1.761455535888671875e+01 -1.892434120178222656e+01 -1.065726280212402344e+00 -1.035291403532028198e-01 -6.395925581455230713e-02 2.477953881025314331e-01 9.611391425132751465e-01 +-1.787494087219238281e+01 -1.886177253723144531e+01 -1.091593027114868164e+00 -9.845310449600219727e-02 -5.957423523068428040e-02 2.573384940624237061e-01 9.594449996948242188e-01 +-1.813428115844726562e+01 -1.879277229309082031e+01 -1.122253417968750000e+00 -9.342893958091735840e-02 -5.549824237823486328e-02 2.667495608329772949e-01 9.576197862625122070e-01 +-1.833241462707519531e+01 -1.866669464111328125e+01 -1.176586866378784180e+00 -8.856072276830673218e-02 -5.183271691203117371e-02 2.759130597114562988e-01 9.556894898414611816e-01 +-1.808251571655273438e+01 -1.856697273254394531e+01 -1.208829283714294434e+00 -8.395332098007202148e-02 -4.868030920624732971e-02 2.847153842449188232e-01 9.536872506141662598e-01 +-1.782111358642578125e+01 -1.851432037353515625e+01 -1.220994830131530762e+00 -7.971203327178955078e-02 -4.614233970642089844e-02 2.930452525615692139e-01 9.516519308090209961e-01 +-1.756674957275390625e+01 -1.847419929504394531e+01 -1.227602481842041016e+00 -7.594230771064758301e-02 -4.432166740298271179e-02 3.007927834987640381e-01 9.496273398399353027e-01 +-1.732123565673828125e+01 -1.843797302246093750e+01 -1.232556104660034180e+00 -7.274919003248214722e-02 -4.332016408443450928e-02 3.078496754169464111e-01 9.476599693298339844e-01 +-1.708448410034179688e+01 -1.840636253356933594e+01 -1.235462665557861328e+00 -7.021540403366088867e-02 -4.320727288722991943e-02 3.141236603260040283e-01 9.457956552505493164e-01 +-1.685700225830078125e+01 -1.837602424621582031e+01 -1.238062739372253418e+00 -6.833245605230331421e-02 -4.392163828015327454e-02 3.195825815200805664e-01 9.440701603889465332e-01 +-1.663839530944824219e+01 -1.835005760192871094e+01 -1.238934278488159180e+00 -6.706956028938293457e-02 -4.536860436201095581e-02 3.242086470127105713e-01 9.425137042999267578e-01 +-1.642906761169433594e+01 -1.832528686523437500e+01 -1.239571452140808105e+00 -6.639516353607177734e-02 -4.745297878980636597e-02 3.279826641082763672e-01 9.411520957946777344e-01 +-1.622902488708496094e+01 -1.830168914794921875e+01 -1.240007281303405762e+00 -6.627741456031799316e-02 -5.008045583963394165e-02 3.308842480182647705e-01 9.400079250335693359e-01 +-1.603810691833496094e+01 -1.828070259094238281e+01 -1.239680171012878418e+00 -6.668455898761749268e-02 -5.315614491701126099e-02 3.328922688961029053e-01 9.391008615493774414e-01 +-1.585641098022460938e+01 -1.826147842407226562e+01 -1.238952636718750000e+00 -6.758426874876022339e-02 -5.658433213829994202e-02 3.339850008487701416e-01 9.384479522705078125e-01 +-1.568401622772216797e+01 -1.824333953857421875e+01 -1.238115191459655762e+00 -6.894429028034210205e-02 -6.027023121714591980e-02 3.341394960880279541e-01 9.380645155906677246e-01 +-1.552092266082763672e+01 -1.822630310058593750e+01 -1.237186193466186523e+00 -7.073239982128143311e-02 -6.411853432655334473e-02 3.333325684070587158e-01 9.379633069038391113e-01 +-1.536710643768310547e+01 -1.821068763732910156e+01 -1.236071705818176270e+00 -7.291604578495025635e-02 -6.803405284881591797e-02 3.315400183200836182e-01 9.381555318832397461e-01 +-1.522249126434326172e+01 -1.819730377197265625e+01 -1.234512925148010254e+00 -7.546215504407882690e-02 -7.192133367061614990e-02 3.287371993064880371e-01 9.386504292488098145e-01 +-1.508719921112060547e+01 -1.818493080139160156e+01 -1.232949137687683105e+00 -7.833813130855560303e-02 -7.568459212779998779e-02 3.248988687992095947e-01 9.394549727439880371e-01 +-1.496123886108398438e+01 -1.817356491088867188e+01 -1.231396436691284180e+00 -8.151099085807800293e-02 -7.922795414924621582e-02 3.199989199638366699e-01 9.405741095542907715e-01 +-1.484461498260498047e+01 -1.816320228576660156e+01 -1.229871749877929688e+00 -8.494706451892852783e-02 -8.245579898357391357e-02 3.140104711055755615e-01 9.420098066329956055e-01 +-1.473733615875244141e+01 -1.815383720397949219e+01 -1.228391051292419434e+00 -8.861301839351654053e-02 -8.527182042598724365e-02 3.069058656692504883e-01 9.437612295150756836e-01 +-1.463940525054931641e+01 -1.814546394348144531e+01 -1.226967692375183105e+00 -9.247442334890365601e-02 -8.757954835891723633e-02 2.986566722393035889e-01 9.458237290382385254e-01 +-1.455079936981201172e+01 -1.813845634460449219e+01 -1.225509047508239746e+00 -9.649711102247238159e-02 -8.928236365318298340e-02 2.892331182956695557e-01 9.481883049011230469e-01 +-1.447151565551757812e+01 -1.813287544250488281e+01 -1.224000215530395508e+00 -1.006453931331634521e-01 -9.028363227844238281e-02 2.786045968532562256e-01 9.508411288261413574e-01 +-1.440161228179931641e+01 -1.812816429138183594e+01 -1.222614765167236328e+00 -1.048841774463653564e-01 -9.048581123352050781e-02 2.667394876480102539e-01 9.537618160247802734e-01 +-1.434109973907470703e+01 -1.812429237365722656e+01 -1.221358656883239746e+00 -1.091762632131576538e-01 -8.979181945323944092e-02 2.536047101020812988e-01 9.569235444068908691e-01 +-1.428998184204101562e+01 -1.812124443054199219e+01 -1.220239281654357910e+00 -1.134869679808616638e-01 -8.813484013080596924e-02 2.391924560070037842e-01 9.602811336517333984e-01 +-1.424823951721191406e+01 -1.811898422241210938e+01 -1.219243168830871582e+00 -1.177903041243553162e-01 -8.556693792343139648e-02 2.236001640558242798e-01 9.637461304664611816e-01 +-1.421585559844970703e+01 -1.811746978759765625e+01 -1.218361735343933105e+00 -1.220636069774627686e-01 -8.217258751392364502e-02 2.069532722234725952e-01 9.672220349311828613e-01 +-1.419280338287353516e+01 -1.811666488647460938e+01 -1.217582941055297852e+00 -1.262835711240768433e-01 -7.803602516651153564e-02 1.893805265426635742e-01 9.706172347068786621e-01 +-1.417905616760253906e+01 -1.811654281616210938e+01 -1.216898202896118164e+00 -1.304282695055007935e-01 -7.324372977018356323e-02 1.710139065980911255e-01 9.738470911979675293e-01 +-1.417458438873291016e+01 -1.811705970764160156e+01 -1.216296315193176270e+00 -1.344764232635498047e-01 -6.788312643766403198e-02 1.519887447357177734e-01 9.768354892730712891e-01 +-1.417400646209716797e+01 -1.811774826049804688e+01 -1.215728759765625000e+00 -1.384075284004211426e-01 -6.204353272914886475e-02 1.324436813592910767e-01 9.795166254043579102e-01 +-1.417728614807128906e+01 -1.811858940124511719e+01 -1.215190410614013672e+00 -1.422036290168762207e-01 -5.581462383270263672e-02 1.125206649303436279e-01 9.818360805511474609e-01 +-1.417791461944580078e+01 -1.811901283264160156e+01 -1.214627623558044434e+00 -1.458467990159988403e-01 -4.928795993328094482e-02 9.236415475606918335e-02 9.837521910667419434e-01 +-1.417585754394531250e+01 -1.811901855468750000e+01 -1.214035630226135254e+00 -1.493225842714309692e-01 -4.255578666925430298e-02 7.212089747190475464e-02 9.852362275123596191e-01 +-1.417107486724853516e+01 -1.811859321594238281e+01 -1.213415503501892090e+00 -1.526171863079071045e-01 -3.571120649576187134e-02 5.193909257650375366e-02 9.862733483314514160e-01 +-1.416352653503417969e+01 -1.811774444580078125e+01 -1.212767362594604492e+00 -1.557197868824005127e-01 -2.884677797555923462e-02 3.196797147393226624e-02 9.868622422218322754e-01 +-1.415317249298095703e+01 -1.811647415161132812e+01 -1.212092280387878418e+00 -1.586212366819381714e-01 -2.205622941255569458e-02 1.235679350793361664e-02 9.870157241821289062e-01 +-1.413997554779052734e+01 -1.811479949951171875e+01 -1.211398839950561523e+00 -1.613143682479858398e-01 -1.543178688734769821e-02 -6.745595484972000122e-03 9.867593050003051758e-01 +-1.412389755249023438e+01 -1.811273384094238281e+01 -1.210687279701232910e+00 -1.637944579124450684e-01 -9.066479280591011047e-03 -2.519115246832370758e-02 9.861310720443725586e-01 +-1.410490608215332031e+01 -1.811030197143554688e+01 -1.209967017173767090e+00 -1.660586595535278320e-01 -3.051096573472023010e-03 -4.283371195197105408e-02 9.851804375648498535e-01 +-1.408296585083007812e+01 -1.810753822326660156e+01 -1.209245562553405762e+00 -1.681053489446640015e-01 2.523428294807672501e-03 -5.952922254800796509e-02 9.839667081832885742e-01 +-1.406326961517333984e+01 -1.810489273071289062e+01 -1.208572983741760254e+00 -1.699351519346237183e-01 7.567468099296092987e-03 -7.513505220413208008e-02 9.825576543807983398e-01 +-1.404578781127929688e+01 -1.810241699218750000e+01 -1.207955241203308105e+00 -1.715495586395263672e-01 1.199221983551979065e-02 -8.951156586408615112e-02 9.810273051261901855e-01 +-1.403049373626708984e+01 -1.810012626647949219e+01 -1.207407236099243164e+00 -1.729509383440017700e-01 1.571034267544746399e-02 -1.025211811065673828e-01 9.794542193412780762e-01 +-1.401740169525146484e+01 -1.809819793701171875e+01 -1.207285165786743164e+00 -1.726683527231216431e-01 1.848724856972694397e-02 -1.140902489423751831e-01 9.781754612922668457e-01 +-1.400649261474609375e+01 -1.809649848937988281e+01 -1.207183837890625000e+00 -1.724350452423095703e-01 2.053248509764671326e-02 -1.242277249693870544e-01 9.769400954246520996e-01 +-1.399778175354003906e+01 -1.809504318237304688e+01 -1.207100749015808105e+00 -1.722651720046997070e-01 2.192180231213569641e-02 -1.329989433288574219e-01 9.757844805717468262e-01 +-1.399128532409667969e+01 -1.809384727478027344e+01 -1.207037329673767090e+00 -1.721656471490859985e-01 2.272762730717658997e-02 -1.404699087142944336e-01 9.747360944747924805e-01 +-1.398701858520507812e+01 -1.809292030334472656e+01 -1.206994652748107910e+00 -1.721377372741699219e-01 2.301858924329280853e-02 -1.467078775167465210e-01 9.738149046897888184e-01 +-1.398499679565429688e+01 -1.809226608276367188e+01 -1.206970214843750000e+00 -1.721778661012649536e-01 2.286203764379024506e-02 -1.517801433801651001e-01 9.730338454246520996e-01 +-1.398523807525634766e+01 -1.809188461303710938e+01 -1.206966519355773926e+00 -1.722793132066726685e-01 2.232120744884014130e-02 -1.557542830705642700e-01 9.724001884460449219e-01 +-1.397761917114257812e+01 -1.809093666076660156e+01 -1.206903100013732910e+00 -1.724327653646469116e-01 2.145808935165405273e-02 -1.586971580982208252e-01 9.719166159629821777e-01 +-1.396215820312500000e+01 -1.808941841125488281e+01 -1.206783413887023926e+00 -1.726271212100982666e-01 2.033315971493721008e-02 -1.606758087873458862e-01 9.715810418128967285e-01 +-1.393886661529541016e+01 -1.808732795715332031e+01 -1.206604003906250000e+00 -1.728504449129104614e-01 1.900516077876091003e-02 -1.617571413516998291e-01 9.713887572288513184e-01 +-1.390776252746582031e+01 -1.808465385437011719e+01 -1.206368327140808105e+00 -1.730903536081314087e-01 1.753239706158638000e-02 -1.620070487260818481e-01 9.713321328163146973e-01 +-1.386885452270507812e+01 -1.808140182495117188e+01 -1.206072926521301270e+00 -1.733345538377761841e-01 1.597235724329948425e-02 -1.614910960197448730e-01 9.714013934135437012e-01 +-1.382213211059570312e+01 -1.807789993286132812e+01 -1.205638408660888672e+00 -1.735712736845016479e-01 1.438270509243011475e-02 -1.602747738361358643e-01 9.715853929519653320e-01 +-1.376761054992675781e+01 -1.807411575317382812e+01 -1.205068349838256836e+00 -1.737896353006362915e-01 1.282062474638223648e-02 -1.584229916334152222e-01 9.718718528747558594e-01 +-1.370531749725341797e+01 -1.806981468200683594e+01 -1.204416513442993164e+00 -1.739798337221145630e-01 1.134419813752174377e-02 -1.559999138116836548e-01 9.722481369972229004e-01 +-1.363526439666748047e+01 -1.806501007080078125e+01 -1.203685283660888672e+00 -1.741333454847335815e-01 1.001187786459922791e-02 -1.530704051256179810e-01 9.727007746696472168e-01 +-1.355746555328369141e+01 -1.805967712402343750e+01 -1.202871084213256836e+00 -1.742431223392486572e-01 8.882367983460426331e-03 -1.496979445219039917e-01 9.732167720794677734e-01 +-1.347193241119384766e+01 -1.805382728576660156e+01 -1.201976299285888672e+00 -1.743036210536956787e-01 8.014990016818046570e-03 -1.459468007087707520e-01 9.737830758094787598e-01 +-1.337867641448974609e+01 -1.804744148254394531e+01 -1.200998544692993164e+00 -1.743105649948120117e-01 7.470415905117988586e-03 -1.418801993131637573e-01 9.743869900703430176e-01 +-1.327770996093750000e+01 -1.804051780700683594e+01 -1.199940204620361328e+00 -1.742613017559051514e-01 7.308905944228172302e-03 -1.375627517700195312e-01 9.750158786773681641e-01 +-1.316905403137207031e+01 -1.803308486938476562e+01 -1.198902606964111328e+00 -1.737243086099624634e-01 7.511528208851814270e-03 -1.330658644437789917e-01 9.757340550422668457e-01 +-1.305272388458251953e+01 -1.802510261535644531e+01 -1.197773456573486328e+00 -1.731890290975570679e-01 8.101944811642169952e-03 -1.284751296043395996e-01 9.764395356178283691e-01 +-1.292867183685302734e+01 -1.801776313781738281e+01 -1.196290254592895508e+00 -1.726641356945037842e-01 9.012149646878242493e-03 -1.238846331834793091e-01 9.771173596382141113e-01 +-1.279695129394531250e+01 -1.801057624816894531e+01 -1.194560527801513672e+00 -1.721579730510711670e-01 1.017384883016347885e-02 -1.193878725171089172e-01 9.777548909187316895e-01 +-1.265762901306152344e+01 -1.800292396545410156e+01 -1.192717313766479492e+00 -1.716792434453964233e-01 1.151873078197240829e-02 -1.150800734758377075e-01 9.783405065536499023e-01 +-1.251072597503662109e+01 -1.799479866027832031e+01 -1.190762877464294434e+00 -1.712377369403839111e-01 1.297887600958347321e-02 -1.110554561018943787e-01 9.788646101951599121e-01 +-1.235627460479736328e+01 -1.798620986938476562e+01 -1.188693761825561523e+00 -1.708422154188156128e-01 1.448602043092250824e-02 -1.074089184403419495e-01 9.793193936347961426e-01 +-1.219427490234375000e+01 -1.797763061523437500e+01 -1.186416029930114746e+00 -1.705030798912048340e-01 1.597205176949501038e-02 -1.042353734374046326e-01 9.796981811523437500e-01 +-1.202464580535888672e+01 -1.797151756286621094e+01 -1.183442354202270508e+00 -1.702296584844589233e-01 1.736923307180404663e-02 -1.016294136643409729e-01 9.799957871437072754e-01 +-1.184753894805908203e+01 -1.796508789062500000e+01 -1.180319786071777344e+00 -1.700322329998016357e-01 1.860933378338813782e-02 -9.968673437833786011e-02 9.802067875862121582e-01 +-1.166297626495361328e+01 -1.795832443237304688e+01 -1.177045822143554688e+00 -1.699207425117492676e-01 1.962437480688095093e-02 -9.850159287452697754e-02 9.803261756896972656e-01 +-1.147096920013427734e+01 -1.795227050781250000e+01 -1.173431396484375000e+00 -1.699048429727554321e-01 2.034642919898033142e-02 -9.816955029964447021e-02 9.803473353385925293e-01 +-1.127146911621093750e+01 -1.795106887817382812e+01 -1.168714523315429688e+00 -1.699938774108886719e-01 2.070740051567554474e-02 -9.878458082675933838e-02 9.802626967430114746e-01 +-1.106458854675292969e+01 -1.794975471496582031e+01 -1.163802504539489746e+00 -1.701969504356384277e-01 2.063925191760063171e-02 -1.004416123032569885e-01 9.800604581832885742e-01 +-1.085038566589355469e+01 -1.795021438598632812e+01 -1.158355712890625000e+00 -1.705220788717269897e-01 2.007384411990642548e-02 -1.032341718673706055e-01 9.797254204750061035e-01 +-1.062896347045898438e+01 -1.795693778991699219e+01 -1.151569843292236328e+00 -1.709766089916229248e-01 1.894273981451988220e-02 -1.072558686137199402e-01 9.792366027832031250e-01 +-1.040914535522460938e+01 -1.796353530883789062e+01 -1.144811987876892090e+00 -1.715665906667709351e-01 1.717771589756011963e-02 -1.125989109277725220e-01 9.785659313201904297e-01 +-1.019149208068847656e+01 -1.797900390625000000e+01 -1.136512398719787598e+00 -1.722959578037261963e-01 1.471004076302051544e-02 -1.193545386195182800e-01 9.776769280433654785e-01 +-9.975522041320800781e+00 -1.799488258361816406e+01 -1.128155469894409180e+00 -1.731677055358886719e-01 1.147142145782709122e-02 -1.276125013828277588e-01 9.765226840972900391e-01 +-9.762405395507812500e+00 -1.802145957946777344e+01 -1.118013858795166016e+00 -1.741821318864822388e-01 7.393093779683113098e-03 -1.374605298042297363e-01 9.750438332557678223e-01 +-9.551672935485839844e+00 -1.805210876464843750e+01 -1.107297301292419434e+00 -1.751508414745330811e-01 2.409156411886215210e-03 -1.489315479993820190e-01 9.732089638710021973e-01 +-9.343825340270996094e+00 -1.809015655517578125e+01 -1.095410108566284180e+00 -1.763336509466171265e-01 -3.357563167810440063e-03 -1.618455797433853149e-01 9.709279537200927734e-01 +-9.140208244323730469e+00 -1.813973617553710938e+01 -1.081787109375000000e+00 -1.778234690427780151e-01 -9.767286479473114014e-03 -1.759740561246871948e-01 9.681510329246520996e-01 +-8.940580368041992188e+00 -1.819780158996582031e+01 -1.067119121551513672e+00 -1.793223172426223755e-01 -1.674799993634223938e-02 -1.910861283540725708e-01 9.649089574813842773e-01 +-8.744725227355957031e+00 -1.826290512084960938e+01 -1.051865220069885254e+00 -1.807363778352737427e-01 -2.420132979750633240e-02 -2.069481462240219116e-01 9.612082242965698242e-01 +-8.550765037536621094e+00 -1.832936477661132812e+01 -1.037139892578125000e+00 -1.821496188640594482e-01 -3.199212625622749329e-02 -2.233315557241439819e-01 9.570375680923461914e-01 +-8.358754158020019531e+00 -1.839709854125976562e+01 -1.021613717079162598e+00 -1.835409551858901978e-01 -4.000447690486907959e-02 -2.400090098381042480e-01 9.524222612380981445e-01 +-8.169313430786132812e+00 -1.846738243103027344e+01 -1.003211617469787598e+00 -1.848921775817871094e-01 -4.812299087643623352e-02 -2.567564845085144043e-01 9.474044442176818848e-01 +-7.983161926269531250e+00 -1.854133224487304688e+01 -9.799682497978210449e-01 -1.861882060766220093e-01 -5.623311549425125122e-02 -2.733535170555114746e-01 9.420455098152160645e-01 +-7.801586627960205078e+00 -1.862045860290527344e+01 -9.491564631462097168e-01 -1.874181628227233887e-01 -6.422104686498641968e-02 -2.895855307579040527e-01 9.364241957664489746e-01 +-7.624364376068115234e+00 -1.870360755920410156e+01 -9.116979837417602539e-01 -1.885739862918853760e-01 -7.197412848472595215e-02 -3.052431046962738037e-01 9.306375980377197266e-01 +-7.451340675354003906e+00 -1.879007339477539062e+01 -8.682433962821960449e-01 -1.896513700485229492e-01 -7.938150316476821899e-02 -3.201229274272918701e-01 9.247984290122985840e-01 +-7.282464981079101562e+00 -1.887909126281738281e+01 -8.187023997306823730e-01 -1.906493306159973145e-01 -8.633489906787872314e-02 -3.340278267860412598e-01 9.190346002578735352e-01 +-7.118041038513183594e+00 -1.897014999389648438e+01 -7.621923685073852539e-01 -1.915690600872039795e-01 -9.272623807191848755e-02 -3.467673957347869873e-01 9.134853482246398926e-01 +-6.958520412445068359e+00 -1.906286621093750000e+01 -6.979882717132568359e-01 -1.924146562814712524e-01 -9.845100343227386475e-02 -3.581552803516387939e-01 9.083000421524047852e-01 +-6.804482936859130859e+00 -1.915691375732421875e+01 -6.254442930221557617e-01 -1.931910961866378784e-01 -1.034047901630401611e-01 -3.680100739002227783e-01 9.036333560943603516e-01 +-6.656631469726562500e+00 -1.925200653076171875e+01 -5.439599752426147461e-01 -1.939039826393127441e-01 -1.074857339262962341e-01 -3.761520385742187500e-01 8.996430635452270508e-01 +-6.515871524810791016e+00 -1.934782600402832031e+01 -4.528369009494781494e-01 -1.945595145225524902e-01 -1.105909198522567749e-01 -3.824028372764587402e-01 8.964843153953552246e-01 +-6.385496616363525391e+00 -1.944392967224121094e+01 -3.488501012325286865e-01 -1.951622217893600464e-01 -1.126182675361633301e-01 -3.865822553634643555e-01 8.943058252334594727e-01 +-6.265444755554199219e+00 -1.953947257995605469e+01 -2.338836640119552612e-01 -1.957140564918518066e-01 -1.134633868932723999e-01 -3.885057568550109863e-01 8.932442069053649902e-01 +-6.157030582427978516e+00 -1.963372993469238281e+01 -1.080126911401748657e-01 -1.962120831012725830e-01 -1.130470186471939087e-01 -3.880454897880554199e-01 8.933877944946289062e-01 +-6.059088706970214844e+00 -1.972624015808105469e+01 2.670959383249282837e-02 -1.966399848461151123e-01 -1.113923639059066772e-01 -3.853203356266021729e-01 8.946801424026489258e-01 +-5.969214439392089844e+00 -1.981676292419433594e+01 1.674096584320068359e-01 -1.969755291938781738e-01 -1.085469126701354980e-01 -3.805048465728759766e-01 8.970141410827636719e-01 +-5.885583877563476562e+00 -1.990472602844238281e+01 3.124322295188903809e-01 -1.971935629844665527e-01 -1.045555323362350464e-01 -3.737675249576568604e-01 9.002670049667358398e-01 +-5.803256034851074219e+00 -1.999086380004882812e+01 4.581799209117889404e-01 -1.972658038139343262e-01 -9.946345537900924683e-02 -3.652730286121368408e-01 9.043057560920715332e-01 +-5.719892024993896484e+00 -2.007541465759277344e+01 6.031121611595153809e-01 -1.971632838249206543e-01 -9.331437945365905762e-02 -3.551842272281646729e-01 9.089902639389038086e-01 +-5.633288860321044922e+00 -2.015843200683593750e+01 7.457769513130187988e-01 -1.968562752008438110e-01 -8.615399897098541260e-02 -3.436643779277801514e-01 9.141771793365478516e-01 +-5.540076732635498047e+00 -2.023985862731933594e+01 8.839520215988159180e-01 -1.963153928518295288e-01 -7.802811264991760254e-02 -3.308785259723663330e-01 9.197234511375427246e-01 +-5.434156894683837891e+00 -2.031917953491210938e+01 1.012612223625183105e+00 -1.955126374959945679e-01 -6.898463517427444458e-02 -3.169950842857360840e-01 9.254890680313110352e-01 +-5.314202308654785156e+00 -2.039573287963867188e+01 1.128260493278503418e+00 -1.944207549095153809e-01 -5.907347053289413452e-02 -3.021857738494873047e-01 9.313402175903320312e-01 +-5.178050518035888672e+00 -2.046792030334472656e+01 1.225153803825378418e+00 -1.930157095193862915e-01 -4.834614321589469910e-02 -2.866281270980834961e-01 9.371509552001953125e-01 +-5.027757644653320312e+00 -2.053473663330078125e+01 1.300881981849670410e+00 -1.893039792776107788e-01 -3.742266073822975159e-02 -2.704261243343353271e-01 9.432036876678466797e-01 +-4.867827892303466797e+00 -2.059556579589843750e+01 1.357622623443603516e+00 -1.852363497018814087e-01 -2.571909502148628235e-02 -2.538959681987762451e-01 9.489797949790954590e-01 +-4.701978206634521484e+00 -2.065056037902832031e+01 1.398209810256958008e+00 -1.813626885414123535e-01 -1.315394416451454163e-02 -2.372401058673858643e-01 9.542806744575500488e-01 +-4.532223224639892578e+00 -2.069898414611816406e+01 1.422392487525939941e+00 -1.777279376983642578e-01 1.920461654663085938e-04 -2.206349968910217285e-01 9.590271115303039551e-01 +-4.361598491668701172e+00 -2.074292373657226562e+01 1.436777949333190918e+00 -1.743630915880203247e-01 1.422951556742191315e-02 -2.042547166347503662e-01 9.631588459014892578e-01 +-4.190948486328125000e+00 -2.078312873840332031e+01 1.443652868270874023e+00 -1.712842732667922974e-01 2.886412292718887329e-02 -1.882722675800323486e-01 9.666343331336975098e-01 +-4.020798206329345703e+00 -2.082008171081542969e+01 1.444533705711364746e+00 -1.684927195310592651e-01 4.399876669049263000e-02 -1.728609502315521240e-01 9.694294333457946777e-01 +-3.851472377777099609e+00 -2.085371017456054688e+01 1.439882755279541016e+00 -1.659740358591079712e-01 5.953872203826904297e-02 -1.581941694021224976e-01 9.715360999107360840e-01 +-3.683309555053710938e+00 -2.088486862182617188e+01 1.432135581970214844e+00 -1.636987477540969849e-01 7.539305090904235840e-02 -1.444470286369323730e-01 9.729613065719604492e-01 +-3.516623497009277344e+00 -2.091453170776367188e+01 1.422302246093750000e+00 -1.584810763597488403e-01 9.103906154632568359e-02 -1.320538371801376343e-01 9.742470979690551758e-01 +-3.351352214813232422e+00 -2.094268989562988281e+01 1.411395192146301270e+00 -1.529230773448944092e-01 1.067758351564407349e-01 -1.208692938089370728e-01 9.749891757965087891e-01 +-3.186737537384033203e+00 -2.096947669982910156e+01 1.399062514305114746e+00 -1.470785140991210938e-01 1.224749907851219177e-01 -1.108664870262145996e-01 9.752315282821655273e-01 +-3.022862434387207031e+00 -2.099501991271972656e+01 1.384777188301086426e+00 -1.410022526979446411e-01 1.380095779895782471e-01 -1.020165681838989258e-01 9.750201702117919922e-01 +-2.859816312789916992e+00 -2.101975059509277344e+01 1.368644952774047852e+00 -1.347483843564987183e-01 1.532539427280426025e-01 -9.429048746824264526e-02 9.744052290916442871e-01 +-2.697672605514526367e+00 -2.104387092590332031e+01 1.350438237190246582e+00 -1.283714473247528076e-01 1.680841445922851562e-01 -8.765873312950134277e-02 9.734395146369934082e-01 +-2.536515951156616211e+00 -2.106760787963867188e+01 1.329924345016479492e+00 -1.219269409775733948e-01 1.823779642581939697e-01 -8.209069073200225830e-02 9.721795916557312012e-01 +-2.376441240310668945e+00 -2.109122467041015625e+01 1.306878685951232910e+00 -1.154689937829971313e-01 1.960151493549346924e-01 -7.755572348833084106e-02 9.706854224205017090e-01 +-2.217573881149291992e+00 -2.111502838134765625e+01 1.280995488166809082e+00 -1.090524122118949890e-01 2.088771462440490723e-01 -7.402298599481582642e-02 9.690194129943847656e-01 +-2.060139656066894531e+00 -2.113944244384765625e+01 1.251676559448242188e+00 -1.027315035462379456e-01 2.208474874496459961e-01 -7.146216928958892822e-02 9.672465920448303223e-01 +-1.904189229011535645e+00 -2.116470146179199219e+01 1.219267606735229492e+00 -9.656047075986862183e-02 2.318109124898910522e-01 -6.984190642833709717e-02 9.654335379600524902e-01 +-1.749730229377746582e+00 -2.119121551513671875e+01 1.184332847595214844e+00 -9.059253334999084473e-02 2.416539192199707031e-01 -6.913200020790100098e-02 9.636478424072265625e-01 +-1.596755623817443848e+00 -2.121939849853515625e+01 1.147445678710937500e+00 -8.488062024116516113e-02 2.502637505531311035e-01 -6.930173933506011963e-02 9.619567394256591797e-01 +-1.445254445075988770e+00 -2.124968147277832031e+01 1.109163761138916016e+00 -7.947713881731033325e-02 2.575280368328094482e-01 -7.032090425491333008e-02 9.604257345199584961e-01 +-1.295220732688903809e+00 -2.128248977661132812e+01 1.070039033889770508e+00 -7.443322986364364624e-02 2.633346617221832275e-01 -7.215952128171920776e-02 9.591181874275207520e-01 +-1.146725416183471680e+00 -2.131830596923828125e+01 1.030656099319458008e+00 -6.996620446443557739e-02 2.663185894489288330e-01 -7.495104521512985229e-02 9.584161043167114258e-01 +-9.999613165855407715e-01 -2.135830497741699219e+01 9.917449951171875000e-01 -6.614603102207183838e-02 2.662808001041412354e-01 -7.866744697093963623e-02 9.584000706672668457e-01 +-8.547224998474121094e-01 -2.140241241455078125e+01 9.539013504981994629e-01 -6.259322166442871094e-02 2.662970125675201416e-01 -8.287088572978973389e-02 9.582799673080444336e-01 +-7.111460566520690918e-01 -2.145109748840332031e+01 9.177319407463073730e-01 -5.932302400469779968e-02 2.663649320602416992e-01 -8.752603083848953247e-02 9.580551385879516602e-01 +-5.694254040718078613e-01 -2.150481796264648438e+01 8.838702440261840820e-01 -5.633988976478576660e-02 2.664817869663238525e-01 -9.259188920259475708e-02 9.577264785766601562e-01 +-4.298233687877655029e-01 -2.156326675415039062e+01 8.526470661163330078e-01 -5.446594208478927612e-02 2.611390650272369385e-01 -9.870256483554840088e-02 9.586958885192871094e-01 +-2.920832037925720215e-01 -2.162565803527832031e+01 8.238085508346557617e-01 -5.321475118398666382e-02 2.537637054920196533e-01 -1.053738519549369812e-01 9.600356817245483398e-01 +-1.560231447219848633e-01 -2.169121932983398438e+01 7.971881031990051270e-01 -5.256302654743194580e-02 2.444927394390106201e-01 -1.125296354293823242e-01 9.616639018058776855e-01 +-2.139944955706596375e-02 -2.175920295715332031e+01 7.726220488548278809e-01 -5.248617380857467651e-02 2.334626466035842896e-01 -1.200938150286674500e-01 9.634925127029418945e-01 +1.120875328779220581e-01 -2.182886123657226562e+01 7.500683665275573730e-01 -5.295992642641067505e-02 2.208105325698852539e-01 -1.279888451099395752e-01 9.654309749603271484e-01 +2.449163943529129028e-01 -2.189912986755371094e+01 7.292101979255676270e-01 -5.395935475826263428e-02 2.066756784915924072e-01 -1.361361443996429443e-01 9.673885107040405273e-01 +3.775641918182373047e-01 -2.196906280517578125e+01 7.098785042762756348e-01 -5.545983836054801941e-02 1.911994516849517822e-01 -1.444572955369949341e-01 9.692776799201965332e-01 +5.106136798858642578e-01 -2.203748512268066406e+01 6.919341683387756348e-01 -5.743588507175445557e-02 1.745266765356063843e-01 -1.528737545013427734e-01 9.710155129432678223e-01 +6.447994709014892578e-01 -2.210284042358398438e+01 6.752325296401977539e-01 -5.986256152391433716e-02 1.568054258823394775e-01 -1.613068580627441406e-01 9.725269079208374023e-01 +7.830833792686462402e-01 -2.215785598754882812e+01 6.589977741241455078e-01 -6.271472573280334473e-02 1.381875276565551758e-01 -1.696794927120208740e-01 9.737452864646911621e-01 +9.247810244560241699e-01 -2.220174217224121094e+01 6.425030231475830078e-01 -6.596759706735610962e-02 1.188281029462814331e-01 -1.779153048992156982e-01 9.746149182319641113e-01 +1.067692518234252930e+00 -2.223961830139160156e+01 6.257092356681823730e-01 -6.959612667560577393e-02 9.888577461242675781e-02 -1.859395205974578857e-01 9.750919938087463379e-01 +1.211504101753234863e+00 -2.227413940429687500e+01 6.087017655372619629e-01 -7.357654720544815063e-02 7.852183282375335693e-02 -1.936799436807632446e-01 9.751455783843994141e-01 +1.356289744377136230e+00 -2.230418968200683594e+01 5.912957787513732910e-01 -7.788492739200592041e-02 5.789966508746147156e-02 -2.010660767555236816e-01 9.747585058212280273e-01 +1.501374959945678711e+00 -2.233302116394042969e+01 5.737719535827636719e-01 -8.249861747026443481e-02 3.718444705009460449e-02 -2.080305963754653931e-01 9.739274382591247559e-01 +1.646695852279663086e+00 -2.236085891723632812e+01 5.561267137527465820e-01 -8.739582449197769165e-02 1.654189079999923706e-02 -2.145096361637115479e-01 9.726633429527282715e-01 +1.792532801628112793e+00 -2.238619613647460938e+01 5.381982326507568359e-01 -9.255601465702056885e-02 -3.862014040350914001e-03 -2.204417586326599121e-01 9.709911942481994629e-01 +1.938458919525146484e+00 -2.241155624389648438e+01 5.202868580818176270e-01 -9.795944392681121826e-02 -2.386232092976570129e-02 -2.257693856954574585e-01 9.689492583274841309e-01 +2.084487915039062500e+00 -2.243694686889648438e+01 5.024065971374511719e-01 -1.035886555910110474e-01 -4.329508915543556213e-02 -2.304384112358093262e-01 9.665883779525756836e-01 +2.230934143066406250e+00 -2.246038055419921875e+01 4.842815995216369629e-01 -1.094269901514053345e-01 -6.199895590543746948e-02 -2.343970835208892822e-01 9.639708995819091797e-01 +2.377528190612792969e+00 -2.248369598388671875e+01 4.661981165409088135e-01 -1.154559776186943054e-01 -7.984423637390136719e-02 -2.376135885715484619e-01 9.611631035804748535e-01 +2.524234294891357422e+00 -2.250704956054687500e+01 4.481854140758514404e-01 -1.216437593102455139e-01 -9.682249277830123901e-02 -2.401245534420013428e-01 9.582110643386840820e-01 +2.671039104461669922e+00 -2.253044891357421875e+01 4.302423000335693359e-01 -1.279535591602325439e-01 -1.129571571946144104e-01 -2.419821918010711670e-01 9.551507830619812012e-01 +2.818022966384887695e+00 -2.255319786071777344e+01 4.122344851493835449e-01 -1.343493461608886719e-01 -1.282716542482376099e-01 -2.432388663291931152e-01 9.520144462585449219e-01 +2.965167999267578125e+00 -2.257532119750976562e+01 3.941674828529357910e-01 -1.407942622900009155e-01 -1.427913308143615723e-01 -2.439457178115844727e-01 9.488298296928405762e-01 +3.112375974655151367e+00 -2.259748077392578125e+01 3.761584460735321045e-01 -1.472518146038055420e-01 -1.565414667129516602e-01 -2.441536337137222290e-01 9.456219077110290527e-01 +3.259636163711547852e+00 -2.261967277526855469e+01 3.582000732421875000e-01 -1.536853909492492676e-01 -1.695484369993209839e-01 -2.439132332801818848e-01 9.424121379852294922e-01 +3.406939029693603516e+00 -2.264188385009765625e+01 3.402874767780303955e-01 -1.600580364465713501e-01 -1.818387359380722046e-01 -2.432737946510314941e-01 9.392198324203491211e-01 +3.554276466369628906e+00 -2.266412544250488281e+01 3.224102854728698730e-01 -1.663337945938110352e-01 -1.934393793344497681e-01 -2.422850728034973145e-01 9.360620379447937012e-01 +3.701730251312255859e+00 -2.268562889099121094e+01 3.043792545795440674e-01 -1.724757254123687744e-01 -2.043778002262115479e-01 -2.409955710172653198e-01 9.329538941383361816e-01 +3.849213838577270508e+00 -2.270705032348632812e+01 2.863415479660034180e-01 -1.784478276968002319e-01 -2.146816551685333252e-01 -2.394533157348632812e-01 9.299087524414062500e-01 +3.996708631515502930e+00 -2.272849464416503906e+01 2.683117687702178955e-01 -1.842135637998580933e-01 -2.243779599666595459e-01 -2.377061247825622559e-01 9.269389510154724121e-01 +4.144206523895263672e+00 -2.274995613098144531e+01 2.502771019935607910e-01 -1.897367388010025024e-01 -2.334952950477600098e-01 -2.358017265796661377e-01 9.240548610687255859e-01 +4.291700839996337891e+00 -2.277143096923828125e+01 2.322283834218978882e-01 -1.949817240238189697e-01 -2.420607805252075195e-01 -2.337866723537445068e-01 9.212667942047119141e-01 +4.439185619354248047e+00 -2.279292488098144531e+01 2.141534388065338135e-01 -1.999120414257049561e-01 -2.501026988029479980e-01 -2.317075878381729126e-01 9.185833930969238281e-01 +4.586654663085937500e+00 -2.281444358825683594e+01 1.960394233465194702e-01 -2.044924050569534302e-01 -2.576487660408020020e-01 -2.296108454465866089e-01 9.160124063491821289e-01 +4.734113693237304688e+00 -2.283577537536621094e+01 1.777484118938446045e-01 -2.086867988109588623e-01 -2.647267580032348633e-01 -2.275423109531402588e-01 9.135611653327941895e-01 +4.881546497344970703e+00 -2.285709953308105469e+01 1.593688875436782837e-01 -2.124596685171127319e-01 -2.713642418384552002e-01 -2.255471348762512207e-01 9.112358093261718750e-01 +5.028945446014404297e+00 -2.287844276428222656e+01 1.409149169921875000e-01 -2.157747149467468262e-01 -2.775894701480865479e-01 -2.236704975366592407e-01 9.090417027473449707e-01 +5.176304817199707031e+00 -2.289980506896972656e+01 1.223730444908142090e-01 -2.185968756675720215e-01 -2.834294438362121582e-01 -2.219573408365249634e-01 9.069829583168029785e-01 +5.323926448822021484e+00 -2.292157745361328125e+01 1.032061725854873657e-01 -2.183007597923278809e-01 -2.895419895648956299e-01 -2.196118384599685669e-01 9.056935310363769531e-01 +5.471455097198486328e+00 -2.294329071044921875e+01 8.406127989292144775e-02 -2.180402576923370361e-01 -2.951793372631072998e-01 -2.176025211811065674e-01 9.044205546379089355e-01 +5.618889808654785156e+00 -2.296496009826660156e+01 6.493835151195526123e-02 -2.178272604942321777e-01 -3.003686070442199707e-01 -2.159234732389450073e-01 9.031649827957153320e-01 +5.766230106353759766e+00 -2.298657608032226562e+01 4.583679139614105225e-02 -2.176707684993743896e-01 -3.051361739635467529e-01 -2.145657837390899658e-01 9.019272923469543457e-01 +5.916031837463378906e+00 -2.300862312316894531e+01 2.632995508611202240e-02 -2.175770252943038940e-01 -3.095074892044067383e-01 -2.135170549154281616e-01 9.007084369659423828e-01 +6.068310260772705078e+00 -2.303104972839355469e+01 6.466064136475324631e-03 -2.175496369600296021e-01 -3.135075569152832031e-01 -2.127615511417388916e-01 8.995097279548645020e-01 +6.223081111907958984e+00 -2.305381202697753906e+01 -1.371154747903347015e-02 -2.175899446010589600e-01 -3.171609640121459961e-01 -2.122813165187835693e-01 8.983318805694580078e-01 +6.380347251892089844e+00 -2.307691383361816406e+01 -3.420227020978927612e-02 -2.176974266767501831e-01 -3.204920291900634766e-01 -2.120563983917236328e-01 8.971759676933288574e-01 +6.540111064910888672e+00 -2.310035514831542969e+01 -5.500915274024009705e-02 -2.178691923618316650e-01 -3.235246837139129639e-01 -2.120636552572250366e-01 8.960434198379516602e-01 +6.702379703521728516e+00 -2.312413978576660156e+01 -7.613097876310348511e-02 -2.181010395288467407e-01 -3.262832164764404297e-01 -2.122789770364761353e-01 8.949350714683532715e-01 +6.867156982421875000e+00 -2.314827537536621094e+01 -9.756835550069808960e-02 -2.183872163295745850e-01 -3.287917077541351318e-01 -2.126764357089996338e-01 8.938522338867187500e-01 +7.034446716308593750e+00 -2.317276382446289062e+01 -1.193243414163589478e-01 -2.187206745147705078e-01 -3.310744464397430420e-01 -2.132287174463272095e-01 8.927958011627197266e-01 +7.204215526580810547e+00 -2.319782638549804688e+01 -1.414691060781478882e-01 -2.190932780504226685e-01 -3.331558704376220703e-01 -2.139072418212890625e-01 8.917673230171203613e-01 +7.376455307006835938e+00 -2.322353553771972656e+01 -1.640246510505676270e-01 -2.194961309432983398e-01 -3.350614905357360840e-01 -2.146829664707183838e-01 8.907672762870788574e-01 +7.558326244354248047e+00 -2.325066757202148438e+01 -1.878265291452407837e-01 -2.199192792177200317e-01 -3.368162810802459717e-01 -2.155251652002334595e-01 8.897972106933593750e-01 +7.749835491180419922e+00 -2.327924728393554688e+01 -2.128747552633285522e-01 -2.203524261713027954e-01 -3.384456932544708252e-01 -2.164032459259033203e-01 8.888582587242126465e-01 +7.950988769531250000e+00 -2.330927276611328125e+01 -2.391711324453353882e-01 -2.207848131656646729e-01 -3.399763405323028564e-01 -2.172861248254776001e-01 8.879509568214416504e-01 +8.161792755126953125e+00 -2.334073638916015625e+01 -2.667163014411926270e-01 -2.212050259113311768e-01 -3.414342701435089111e-01 -2.181417942047119141e-01 8.870766758918762207e-01 +8.382266998291015625e+00 -2.337367630004882812e+01 -2.955285608768463135e-01 -2.215003967285156250e-01 -3.428717851638793945e-01 -2.188988626003265381e-01 8.862617015838623047e-01 +8.612287521362304688e+00 -2.340854835510253906e+01 -3.256640434265136719e-01 -2.219618260860443115e-01 -3.442403376102447510e-01 -2.196419537067413330e-01 8.854314684867858887e-01 +8.851962089538574219e+00 -2.344560432434082031e+01 -3.571130335330963135e-01 -2.221293747425079346e-01 -3.441322743892669678e-01 -2.200729548931121826e-01 8.853244185447692871e-01 +9.101294517517089844e+00 -2.348416900634765625e+01 -3.898266553878784180e-01 -2.222552895545959473e-01 -3.440509736537933350e-01 -2.203968763351440430e-01 8.852438330650329590e-01 +9.360280036926269531e+00 -2.352424240112304688e+01 -4.238024950027465820e-01 -2.223452627658843994e-01 -3.439927995204925537e-01 -2.206283807754516602e-01 8.851861357688903809e-01 +9.628916740417480469e+00 -2.356582069396972656e+01 -4.590429663658142090e-01 -2.224056422710418701e-01 -3.439537882804870605e-01 -2.207837700843811035e-01 8.851474523544311523e-01 +9.907197952270507812e+00 -2.360889053344726562e+01 -4.955468773841857910e-01 -2.224431037902832031e-01 -3.439295589923858643e-01 -2.208801507949829102e-01 8.851233720779418945e-01 +1.019474601745605469e+01 -2.365554618835449219e+01 -5.336694121360778809e-01 -2.224644124507904053e-01 -3.439157605171203613e-01 -2.209350764751434326e-01 8.851096630096435547e-01 +1.048197364807128906e+01 -2.370218658447265625e+01 -5.717553496360778809e-01 -2.224770784378051758e-01 -3.439075946807861328e-01 -2.209676057100296021e-01 8.851014971733093262e-01 +1.076888275146484375e+01 -2.374876976013183594e+01 -6.097985506057739258e-01 -2.224884331226348877e-01 -3.439002335071563721e-01 -2.209968268871307373e-01 8.850942254066467285e-01 +1.105547142028808594e+01 -2.379530143737792969e+01 -6.477990746498107910e-01 -2.225062996149063110e-01 -3.438886702060699463e-01 -2.210428118705749512e-01 8.850827813148498535e-01 +1.134161949157714844e+01 -2.384237670898437500e+01 -6.858483552932739258e-01 -2.225385308265686035e-01 -3.438678085803985596e-01 -2.211257815361022949e-01 8.850619792938232422e-01 +1.162697315216064453e+01 -2.389184570312500000e+01 -7.242211699485778809e-01 -2.225930988788604736e-01 -3.438324630260467529e-01 -2.212662696838378906e-01 8.850269317626953125e-01 +1.191199398040771484e+01 -2.394124984741210938e+01 -7.625512480735778809e-01 -2.226775139570236206e-01 -3.437778353691101074e-01 -2.214835584163665771e-01 8.849725723266601562e-01 +1.219667434692382812e+01 -2.399057579040527344e+01 -8.008385896682739258e-01 -2.227995544672012329e-01 -3.436987400054931641e-01 -2.217977046966552734e-01 8.848938941955566406e-01 +1.248101043701171875e+01 -2.403982925415039062e+01 -8.390832543373107910e-01 -2.229660153388977051e-01 -3.435907959938049316e-01 -2.222263514995574951e-01 8.847863674163818359e-01 +1.276442241668701172e+01 -2.409189414978027344e+01 -8.776794075965881348e-01 -2.231833934783935547e-01 -3.434496223926544189e-01 -2.227861881256103516e-01 8.846454620361328125e-01 +1.304715538024902344e+01 -2.414550781250000000e+01 -9.164562821388244629e-01 -2.234573364257812500e-01 -3.432714343070983887e-01 -2.234919369220733643e-01 8.844674825668334961e-01 +1.332954025268554688e+01 -2.419902801513671875e+01 -9.551879763603210449e-01 -2.237923741340637207e-01 -3.430531024932861328e-01 -2.243553698062896729e-01 8.842488527297973633e-01 +1.361156749725341797e+01 -2.425247001647949219e+01 -9.938769340515136719e-01 -2.241918444633483887e-01 -3.427921831607818604e-01 -2.253852337598800659e-01 8.839869499206542969e-01 +1.389249801635742188e+01 -2.430917930603027344e+01 -1.032952904701232910e+00 -2.246578484773635864e-01 -3.424869775772094727e-01 -2.265873253345489502e-01 8.836795687675476074e-01 +1.417225646972656250e+01 -2.436950111389160156e+01 -1.072458505630493164e+00 -2.251906096935272217e-01 -3.421368896961212158e-01 -2.279623448848724365e-01 8.833258748054504395e-01 +1.445251178741455078e+01 -2.443052101135253906e+01 -1.112601280212402344e+00 -2.207838743925094604e-01 -3.398961424827575684e-01 -2.274083197116851807e-01 8.854436874389648438e-01 +1.473253631591796875e+01 -2.449156761169433594e+01 -1.152830839157104492e+00 -2.156427800655364990e-01 -3.374349474906921387e-01 -2.267166227102279663e-01 8.878262639045715332e-01 +1.501059627532958984e+01 -2.455951690673828125e+01 -1.194051504135131836e+00 -2.098293602466583252e-01 -3.348003625869750977e-01 -2.259006351232528687e-01 8.904207348823547363e-01 +1.528816604614257812e+01 -2.462841796875000000e+01 -1.235473632812500000e+00 -2.034060060977935791e-01 -3.320398628711700439e-01 -2.249738425016403198e-01 8.931754231452941895e-01 +1.556547927856445312e+01 -2.469728469848632812e+01 -1.276966571807861328e+00 -1.964354664087295532e-01 -3.292009234428405762e-01 -2.239504456520080566e-01 8.960390686988830566e-01 +1.584055137634277344e+01 -2.477307510375976562e+01 -1.319479942321777344e+00 -1.889812648296356201e-01 -3.263326883316040039e-01 -2.228447943925857544e-01 8.989622592926025391e-01 +1.611485099792480469e+01 -2.485056114196777344e+01 -1.362290024757385254e+00 -1.811068356037139893e-01 -3.234843015670776367e-01 -2.216712534427642822e-01 9.018979668617248535e-01 +1.638828277587890625e+01 -2.492979431152343750e+01 -1.405413746833801270e+00 -1.728771626949310303e-01 -3.207059502601623535e-01 -2.204457521438598633e-01 9.048009514808654785e-01 +1.665892982482910156e+01 -2.501667404174804688e+01 -1.449704527854919434e+00 -1.643574535846710205e-01 -3.180485963821411133e-01 -2.191843688488006592e-01 9.076287150382995605e-01 +1.692925453186035156e+01 -2.510351562500000000e+01 -1.494035601615905762e+00 -1.556134819984436035e-01 -3.155647218227386475e-01 -2.179037779569625854e-01 9.103413224220275879e-01 +1.719555282592773438e+01 -2.520039939880371094e+01 -1.539997577667236328e+00 -1.467118263244628906e-01 -3.133070170879364014e-01 -2.166214287281036377e-01 9.129017591476440430e-01 +1.746067047119140625e+01 -2.529924201965332031e+01 -1.586348891258239746e+00 -1.377195268869400024e-01 -3.113292455673217773e-01 -2.153556346893310547e-01 9.152755737304687500e-01 +1.772199058532714844e+01 -2.540629768371582031e+01 -1.634212613105773926e+00 -1.287038028240203857e-01 -3.096866011619567871e-01 -2.141248285770416260e-01 9.174311757087707520e-01 +1.797966957092285156e+01 -2.552020454406738281e+01 -1.683673024177551270e+00 -1.197323352098464966e-01 -3.084343373775482178e-01 -2.129480689764022827e-01 9.193396568298339844e-01 +1.823372077941894531e+01 -2.564036560058593750e+01 -1.735097646713256836e+00 -1.108731925487518311e-01 -3.076283633708953857e-01 -2.118457108736038208e-01 9.209740757942199707e-01 +1.848494148254394531e+01 -2.576435089111328125e+01 -1.789418935775756836e+00 -1.021941900253295898e-01 -3.073254525661468506e-01 -2.108376473188400269e-01 9.223095774650573730e-01 +1.873287773132324219e+01 -2.589137077331542969e+01 -1.849500656127929688e+00 -9.376326948404312134e-02 -3.075828254222869873e-01 -2.099442481994628906e-01 9.233225584030151367e-01 +1.897032737731933594e+01 -2.602990150451660156e+01 -1.922786831855773926e+00 -8.564832061529159546e-02 -3.084577918052673340e-01 -2.091858983039855957e-01 9.239910244941711426e-01 +1.918661117553710938e+01 -2.619185066223144531e+01 -2.010993719100952148e+00 -7.791706919670104980e-02 -3.100074231624603271e-01 -2.085837125778198242e-01 9.242928028106689453e-01 +1.939688873291015625e+01 -2.636192321777343750e+01 -2.097397327423095703e+00 -7.063672691583633423e-02 -3.122891485691070557e-01 -2.081581056118011475e-01 9.242056608200073242e-01 +1.960333633422851562e+01 -2.653208923339843750e+01 -2.191108465194702148e+00 -6.386113911867141724e-02 -3.153225779533386230e-01 -2.079208791255950928e-01 9.237220287322998047e-01 +1.980067253112792969e+01 -2.670052719116210938e+01 -2.304293155670166016e+00 -5.759227648377418518e-02 -3.189783096313476562e-01 -2.078484743833541870e-01 9.228949546813964844e-01 +1.997805976867675781e+01 -2.686252403259277344e+01 -2.452465772628784180e+00 -5.181930959224700928e-02 -3.230887651443481445e-01 -2.079097777605056763e-01 9.217927455902099609e-01 +2.010663986206054688e+01 -2.700180625915527344e+01 -2.658095598220825195e+00 -4.653124511241912842e-02 -3.274874389171600342e-01 -2.080729454755783081e-01 9.204848408699035645e-01 +2.013336563110351562e+01 -2.708231353759765625e+01 -2.923445940017700195e+00 -4.171708226203918457e-02 -3.320077657699584961e-01 -2.083068042993545532e-01 9.190422892570495605e-01 +2.006044387817382812e+01 -2.710072135925292969e+01 -3.192740440368652344e+00 -3.736594691872596741e-02 -3.364843428134918213e-01 -2.085808515548706055e-01 9.175381064414978027e-01 +1.991547203063964844e+01 -2.707538032531738281e+01 -3.430675029754638672e+00 -3.346715122461318970e-02 -3.407529592514038086e-01 -2.088648378849029541e-01 9.160473942756652832e-01 +1.971638298034667969e+01 -2.702067375183105469e+01 -3.618968486785888672e+00 -3.000989928841590881e-02 -3.446498513221740723e-01 -2.091291546821594238e-01 9.146478772163391113e-01 +1.947625732421875000e+01 -2.694724464416503906e+01 -3.741216897964477539e+00 -2.698357030749320984e-02 -3.480124771595001221e-01 -2.093446254730224609e-01 9.134188890457153320e-01 +1.921686553955078125e+01 -2.686842155456542969e+01 -3.807093381881713867e+00 -2.437749505043029785e-02 -3.506780266761779785e-01 -2.094826698303222656e-01 9.124405384063720703e-01 +1.895020866394042969e+01 -2.679267120361328125e+01 -3.836425781250000000e+00 -2.218068391084671021e-02 -3.524843454360961914e-01 -2.095136344432830811e-01 9.117931723594665527e-01 +1.867999649047851562e+01 -2.672515487670898438e+01 -3.840672492980957031e+00 -2.038262039422988892e-02 -3.532688617706298828e-01 -2.094088792800903320e-01 9.115555882453918457e-01 +1.840722465515136719e+01 -2.667154693603515625e+01 -3.829312562942504883e+00 -1.897224783897399902e-02 -3.528676629066467285e-01 -2.091383486986160278e-01 9.118034839630126953e-01 +1.813268661499023438e+01 -2.663323211669921875e+01 -3.809109926223754883e+00 -1.793826371431350708e-02 -3.511150181293487549e-01 -2.086706757545471191e-01 9.126078486442565918e-01 +1.785753250122070312e+01 -2.660956573486328125e+01 -3.780355215072631836e+00 -1.726895570755004883e-02 -3.478419482707977295e-01 -2.079730629920959473e-01 9.140322804450988770e-01 +1.758689117431640625e+01 -2.659740638732910156e+01 -3.744694709777832031e+00 -1.695244759321212769e-02 -3.428765535354614258e-01 -2.070108056068420410e-01 9.161303043365478516e-01 +1.732136154174804688e+01 -2.659372901916503906e+01 -3.702745199203491211e+00 -1.697567105293273926e-02 -3.360415697097778320e-01 -2.057455033063888550e-01 9.189432263374328613e-01 +1.706144523620605469e+01 -2.659532737731933594e+01 -3.654067277908325195e+00 -1.732514798641204834e-02 -3.271546661853790283e-01 -2.041360139846801758e-01 9.224956631660461426e-01 +1.680853652954101562e+01 -2.660082435607910156e+01 -3.593966007232666016e+00 -1.798589155077934265e-02 -3.160273730754852295e-01 -2.021358907222747803e-01 9.267923831939697266e-01 +1.656593704223632812e+01 -2.660934448242187500e+01 -3.513918399810791016e+00 -1.894154399633407593e-02 -3.024637699127197266e-01 -1.996945291757583618e-01 9.318148493766784668e-01 +1.633611869812011719e+01 -2.661814308166503906e+01 -3.412678241729736328e+00 -2.016894891858100891e-02 -2.863315939903259277e-01 -1.967687010765075684e-01 9.374909400939941406e-01 +1.611628913879394531e+01 -2.662369537353515625e+01 -3.300189018249511719e+00 -2.162275835871696472e-02 -2.677738666534423828e-01 -1.933650076389312744e-01 9.436310529708862305e-01 +1.589969062805175781e+01 -2.662261199951171875e+01 -3.191188812255859375e+00 -2.325204573571681976e-02 -2.470081895589828491e-01 -1.895039975643157959e-01 9.500181674957275391e-01 +1.568132400512695312e+01 -2.661123466491699219e+01 -3.097897768020629883e+00 -2.500555105507373810e-02 -2.242593169212341309e-01 -1.852087676525115967e-01 9.564414024353027344e-01 +1.545940303802490234e+01 -2.658679199218750000e+01 -3.031638145446777344e+00 -2.683191560208797455e-02 -1.997609585523605347e-01 -1.805061548948287964e-01 9.627009630203247070e-01 +1.523797893524169922e+01 -2.655461883544921875e+01 -2.986737012863159180e+00 -2.867994084954261780e-02 -1.737575680017471313e-01 -1.754268705844879150e-01 9.686130285263061523e-01 +1.501963710784912109e+01 -2.652018547058105469e+01 -2.953201770782470703e+00 -3.049903176724910736e-02 -1.465035229921340942e-01 -1.700080633163452148e-01 9.740142822265625000e-01 +1.480522632598876953e+01 -2.648631858825683594e+01 -2.924599647521972656e+00 -3.223899379372596741e-02 -1.182626336812973022e-01 -1.642913967370986938e-01 9.787660837173461914e-01 +1.459505081176757812e+01 -2.645399284362792969e+01 -2.897641420364379883e+00 -3.385071828961372375e-02 -8.930751681327819824e-02 -1.583246886730194092e-01 9.827570915222167969e-01 +1.438920879364013672e+01 -2.642324638366699219e+01 -2.871393918991088867e+00 -3.528673201799392700e-02 -5.991753563284873962e-02 -1.521615684032440186e-01 9.859064817428588867e-01 +1.418772411346435547e+01 -2.639378929138183594e+01 -2.845865488052368164e+00 -3.650032728910446167e-02 -3.037654981017112732e-02 -1.458611339330673218e-01 9.881647229194641113e-01 +1.399059867858886719e+01 -2.636548233032226562e+01 -2.821068048477172852e+00 -3.744756802916526794e-02 -9.714961051940917969e-04 -1.394872367382049561e-01 9.895150661468505859e-01 +1.379781436920166016e+01 -2.633822631835937500e+01 -2.797016620635986328e+00 -3.808545321226119995e-02 2.801096439361572266e-02 -1.331087201833724976e-01 9.899731874465942383e-01 +1.360933780670166016e+01 -2.631202507019042969e+01 -2.773726701736450195e+00 -3.837392851710319519e-02 5.628693476319313049e-02 -1.267978847026824951e-01 9.895865917205810547e-01 +1.342513370513916016e+01 -2.628688812255859375e+01 -2.751210927963256836e+00 -3.827369213104248047e-02 8.357636630535125732e-02 -1.206306293606758118e-01 9.884322285652160645e-01 +1.324517345428466797e+01 -2.626273918151855469e+01 -2.729470252990722656e+00 -3.774780780076980591e-02 1.096056178212165833e-01 -1.146849542856216431e-01 9.866149425506591797e-01 +1.306941986083984375e+01 -2.623960304260253906e+01 -2.708507061004638672e+00 -3.676097095012664795e-02 1.341087967157363892e-01 -1.090409010648727417e-01 9.842630028724670410e-01 +1.289782524108886719e+01 -2.621754837036132812e+01 -2.688323974609375000e+00 -3.527792543172836304e-02 1.568278819322586060e-01 -1.037788391113281250e-01 9.815245866775512695e-01 +1.273034286499023438e+01 -2.619669914245605469e+01 -2.668940305709838867e+00 -3.326483443379402161e-02 1.775135546922683716e-01 -9.898018091917037964e-02 9.785629510879516602e-01 +1.256687068939208984e+01 -2.617734336853027344e+01 -2.650635957717895508e+00 -3.068697638809680939e-02 1.959243118762969971e-01 -9.472550451755523682e-02 9.755507111549377441e-01 +1.240734195709228516e+01 -2.615968132019042969e+01 -2.633720636367797852e+00 -2.752725780010223389e-02 2.118933647871017456e-01 -9.106374531984329224e-02 9.726514816284179688e-01 +1.225172710418701172e+01 -2.614393424987792969e+01 -2.618526458740234375e+00 -2.384060062468051910e-02 2.255300134420394897e-01 -8.791892975568771362e-02 9.699681401252746582e-01 +1.210001945495605469e+01 -2.613039398193359375e+01 -2.605453968048095703e+00 -1.969877257943153381e-02 2.370096743106842041e-01 -8.518087863922119141e-02 9.675652384757995605e-01 +1.195223331451416016e+01 -2.611929702758789062e+01 -2.594952344894409180e+00 -1.517291553318500519e-02 2.465046793222427368e-01 -8.273734152317047119e-02 9.654842019081115723e-01 +1.180842876434326172e+01 -2.611089324951171875e+01 -2.587496280670166016e+00 -1.033360138535499573e-02 2.541842758655548096e-01 -8.047319948673248291e-02 9.637466669082641602e-01 +1.166873264312744141e+01 -2.610503768920898438e+01 -2.583181142807006836e+00 -5.250874906778335571e-03 2.602048218250274658e-01 -7.827369868755340576e-02 9.623612165451049805e-01 +1.153323745727539062e+01 -2.610152244567871094e+01 -2.581868886947631836e+00 -4.532914608716964722e-04 2.597315609455108643e-01 -7.625352591276168823e-02 9.626653790473937988e-01 +1.140217590332031250e+01 -2.609998512268066406e+01 -2.583013772964477539e+00 4.624022170901298523e-03 2.592605948448181152e-01 -7.393597811460494995e-02 9.629621505737304688e-01 +1.127563953399658203e+01 -2.610012054443359375e+01 -2.586120605468750000e+00 9.884547442197799683e-03 2.588075399398803711e-01 -7.123043388128280640e-02 9.632481932640075684e-01 +1.115369224548339844e+01 -2.610171318054199219e+01 -2.590780019760131836e+00 1.523126568645238876e-02 2.583893537521362305e-01 -6.804589182138442993e-02 9.635209441184997559e-01 +1.103638744354248047e+01 -2.610457420349121094e+01 -2.596641778945922852e+00 2.056868188083171844e-02 2.580237686634063721e-01 -6.429013609886169434e-02 9.637777209281921387e-01 +1.092376804351806641e+01 -2.610856437683105469e+01 -2.603400707244873047e+00 2.580112963914871216e-02 2.577296495437622070e-01 -5.986779555678367615e-02 9.640153646469116211e-01 +1.081586933135986328e+01 -2.611361312866210938e+01 -2.610776424407958984e+00 3.083451092243194580e-02 2.575255334377288818e-01 -5.467998981475830078e-02 9.642302393913269043e-01 +1.070365047454833984e+01 -2.612030220031738281e+01 -2.619052648544311523e+00 3.557673841714859009e-02 2.574303746223449707e-01 -4.862414672970771790e-02 9.644167423248291016e-01 +1.058720302581787109e+01 -2.612927246093750000e+01 -2.628027200698852539e+00 3.993793204426765442e-02 2.574616968631744385e-01 -4.159193113446235657e-02 9.645665287971496582e-01 +1.046674633026123047e+01 -2.614217758178710938e+01 -2.637519359588623047e+00 4.383187368512153625e-02 2.576360106468200684e-01 -3.347089886665344238e-02 9.646668434143066406e-01 +1.034272193908691406e+01 -2.616141510009765625e+01 -2.647081136703491211e+00 4.717654734849929810e-02 2.579675316810607910e-01 -2.414281293749809265e-02 9.646990299224853516e-01 +1.021537590026855469e+01 -2.618688964843750000e+01 -2.656219482421875000e+00 4.989557713270187378e-02 2.584675848484039307e-01 -1.348417624831199646e-02 9.646362066268920898e-01 +1.008484077453613281e+01 -2.621813964843750000e+01 -2.664593458175659180e+00 5.191991105675697327e-02 2.591438591480255127e-01 -1.366918906569480896e-03 9.644412398338317871e-01 +9.950877189636230469e+00 -2.625335884094238281e+01 -2.672272920608520508e+00 5.318967998027801514e-02 2.599999010562896729e-01 1.234182342886924744e-02 9.640635251998901367e-01 +9.813652038574218750e+00 -2.629250335693359375e+01 -2.680364847183227539e+00 5.374157801270484924e-02 2.600106000900268555e-01 2.781768701970577240e-02 9.637076854705810547e-01 +9.673460960388183594e+00 -2.633624458312988281e+01 -2.690360069274902344e+00 5.356618016958236694e-02 2.605955302715301514e-01 4.487821832299232483e-02 9.629156589508056641e-01 +9.531424522399902344e+00 -2.638529205322265625e+01 -2.703675508499145508e+00 5.271744728088378906e-02 2.616814076900482178e-01 6.338652223348617554e-02 9.616267085075378418e-01 +9.388124465942382812e+00 -2.644035530090332031e+01 -2.721546649932861328e+00 5.124986916780471802e-02 2.631950974464416504e-01 8.320283889770507812e-02 9.597807526588439941e-01 +9.244585037231445312e+00 -2.650260734558105469e+01 -2.745594501495361328e+00 4.921869561076164246e-02 2.650635242462158203e-01 1.041846200823783875e-01 9.573215246200561523e-01 +9.102452278137207031e+00 -2.657352447509765625e+01 -2.777873516082763672e+00 4.668008908629417419e-02 2.672145068645477295e-01 1.261866539716720581e-01 9.541982412338256836e-01 +8.964381217956542969e+00 -2.665489768981933594e+01 -2.820977687835693359e+00 4.369113594293594360e-02 2.695775926113128662e-01 1.490615159273147583e-01 9.503681659698486328e-01 +8.832632064819335938e+00 -2.674715232849121094e+01 -2.876063108444213867e+00 4.040694609284400940e-02 2.716771364212036133e-01 1.727234572172164917e-01 9.458992481231689453e-01 +8.707996368408203125e+00 -2.684913444519042969e+01 -2.942261934280395508e+00 3.691590949892997742e-02 2.734744250774383545e-01 1.970320641994476318e-01 9.407589435577392578e-01 +8.590589523315429688e+00 -2.695952033996582031e+01 -3.018403291702270508e+00 3.319668024778366089e-02 2.753017246723175049e-01 2.217792868614196777e-01 9.348374009132385254e-01 +8.477613449096679688e+00 -2.707590675354003906e+01 -3.101557493209838867e+00 2.929470688104629517e-02 2.771500647068023682e-01 2.468045502901077271e-01 9.281256198883056641e-01 +8.368250846862792969e+00 -2.719570159912109375e+01 -3.189133167266845703e+00 2.524992823600769043e-02 2.790117561817169189e-01 2.719464898109436035e-01 9.206302165985107422e-01 +8.290827751159667969e+00 -2.728365135192871094e+01 -3.255115985870361328e+00 2.109719812870025635e-02 2.808790802955627441e-01 2.970450520515441895e-01 9.123739004135131836e-01 diff --git a/thirdparty/tartanair_tools/evaluation/tartanair_evaluator.py b/thirdparty/tartanair_tools/evaluation/tartanair_evaluator.py new file mode 100644 index 00000000..60018a38 --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/tartanair_evaluator.py @@ -0,0 +1,80 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. + +import numpy as np +from os.path import isdir, isfile + +from .evaluator_base import ATEEvaluator, RPEEvaluator, KittiEvaluator, transform_trajs, quats2SEs + +# from trajectory_transform import timestamp_associate + + +def plot_traj(gtposes, estposes, vis=False, savefigname=None, title=''): + import matplotlib.pyplot as plt + fig = plt.figure(figsize=(4,4)) + + + cm = plt.cm.get_cmap('Spectral') + + plt.subplot(111) + plt.plot(gtposes[:,2],gtposes[:,0], linestyle='dashed',c='k') + plt.plot(estposes[:, 2], estposes[:, 0],c='#ff7f0e') + plt.xlabel('x (m)') + plt.ylabel('y (m)') + plt.legend(['Ground Truth','Ours']) + plt.title(title) + + plt.axis('equal') + + if savefigname is not None: + plt.savefig(savefigname) + + if vis: + plt.show() + + plt.close(fig) + + +# + +class TartanAirEvaluator: + def __init__(self, scale = False, round=1): + self.ate_eval = ATEEvaluator() + self.rpe_eval = RPEEvaluator() + self.kitti_eval = KittiEvaluator() + + def evaluate_one_trajectory(self, gt_traj, est_traj, scale=False, title=''): + """ + scale = True: calculate a global scale + """ + + if gt_traj.shape[0] != est_traj.shape[0]: + raise Exception("POSEFILE_LENGTH_ILLEGAL") + + if gt_traj.shape[1] != 7 or est_traj.shape[1] != 7: + raise Exception("POSEFILE_FORMAT_ILLEGAL") + + gt_traj = gt_traj.astype(np.float64) + est_traj = est_traj.astype(np.float64) + + ate_score, gt_ate_aligned, est_ate_aligned = self.ate_eval.evaluate(gt_traj, est_traj, scale) + + plot_traj(np.matrix(gt_ate_aligned), np.matrix(est_ate_aligned), vis=False, savefigname="figures/%s.pdf"%title, title=title) + + est_ate_aligned = np.array(est_ate_aligned) + gt_SEs, est_SEs = quats2SEs(gt_ate_aligned, est_ate_aligned) + + + + rpe_score = self.rpe_eval.evaluate(gt_SEs, est_SEs) + kitti_score = self.kitti_eval.evaluate(gt_SEs, est_SEs) + + return {'ate_score': ate_score, 'rpe_score': rpe_score, 'kitti_score': kitti_score} + + +if __name__ == "__main__": + + # scale = True for monocular track, scale = False for stereo track + aicrowd_evaluator = TartanAirEvaluator() + result = aicrowd_evaluator.evaluate_one_trajectory('pose_gt.txt', 'pose_est.txt', scale=True) + print(result) diff --git a/thirdparty/tartanair_tools/evaluation/trajectory_transform.py b/thirdparty/tartanair_tools/evaluation/trajectory_transform.py new file mode 100644 index 00000000..4967bc43 --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/trajectory_transform.py @@ -0,0 +1,162 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. + +import numpy as np +from . import transformation as tf + +def shift0(traj): + ''' + Traj: a list of [t + quat] + Return: translate and rotate the traj + ''' + traj_ses = tf.pos_quats2SE_matrices(np.array(traj)) + traj_init = traj_ses[0] + traj_init_inv = np.linalg.inv(traj_init) + new_traj = [] + for tt in traj_ses: + ttt=traj_init_inv.dot(tt) + new_traj.append(tf.SE2pos_quat(ttt)) + return np.array(new_traj) + +def ned2cam(traj): + ''' + transfer a ned traj to camera frame traj + ''' + T = np.array([[0,1,0,0], + [0,0,1,0], + [1,0,0,0], + [0,0,0,1]], dtype=np.float32) + T_inv = np.linalg.inv(T) + new_traj = [] + traj_ses = tf.pos_quats2SE_matrices(np.array(traj)) + + for tt in traj_ses: + ttt=T.dot(tt).dot(T_inv) + new_traj.append(tf.SE2pos_quat(ttt)) + + return np.array(new_traj) + +def cam2ned(traj): + ''' + transfer a camera traj to ned frame traj + ''' + T = np.array([[0,0,1,0], + [1,0,0,0], + [0,1,0,0], + [0,0,0,1]], dtype=np.float32) + T_inv = np.linalg.inv(T) + new_traj = [] + traj_ses = tf.pos_quats2SE_matrices(np.array(traj)) + + for tt in traj_ses: + ttt=T.dot(tt).dot(T_inv) + new_traj.append(tf.SE2pos_quat(ttt)) + + return np.array(new_traj) + + +def trajectory_transform(gt_traj, est_traj): + ''' + 1. center the start frame to the axis origin + 2. align the GT frame (NED) with estimation frame (camera) + ''' + gt_traj_trans = shift0(gt_traj) + est_traj_trans = shift0(est_traj) + + # gt_traj_trans = ned2cam(gt_traj_trans) + # est_traj_trans = cam2ned(est_traj_trans) + + return gt_traj_trans, est_traj_trans + +def rescale_bk(poses_gt, poses): + motion_gt = tf.pose2motion(poses_gt) + motion = tf.pose2motion(poses) + + speed_square_gt = np.sum(motion_gt[:,0:3,3]*motion_gt[:,0:3,3],1) + speed_gt = np.sqrt(speed_square_gt) + speed_square = np.sum(motion[:,0:3,3]*motion[:,0:3,3],1) + speed = np.sqrt(speed_square) + # when the speed is small, the scale could become very large + # import ipdb;ipdb.set_trace() + mask = (speed_gt>0.0001) # * (speed>0.00001) + scale = np.mean((speed[mask])/speed_gt[mask]) + scale = 1.0/scale + motion[:,0:3,3] = motion[:,0:3,3]*scale + pose_update = tf.motion2pose(motion) + return pose_update, scale + +def pose2trans(pose_data): + data_size = len(pose_data) + trans = [] + for i in range(0,data_size-1): + tran = np.array(pose_data[i+1][:3]) - np.array(pose_data[i][:3]) # np.linalg.inv(data[i]).dot(data[i+1]) + trans.append(tran) + + return np.array(trans) # N x 3 + + +def rescale(poses_gt, poses): + ''' + similar to rescale + poses_gt/poses: N x 7 poselist in quaternion format + ''' + trans_gt = pose2trans(poses_gt) + trans = pose2trans(poses) + + speed_square_gt = np.sum(trans_gt*trans_gt,1) + speed_gt = np.sqrt(speed_square_gt) + speed_square = np.sum(trans*trans,1) + speed = np.sqrt(speed_square) + # when the speed is small, the scale could become very large + # import ipdb;ipdb.set_trace() + mask = (speed_gt>0.0001) # * (speed>0.00001) + scale = np.mean((speed[mask])/speed_gt[mask]) + scale = 1.0/scale + poses[:,0:3] = poses[:,0:3]*scale + return poses, scale + +def trajectory_scale(traj, scale): + for ttt in traj: + ttt[0:3,3] = ttt[0:3,3]*scale + return traj + +def timestamp_associate(first_list, second_list, max_difference): + """ + Associate two trajectory of [stamp,data]. As the time stamps never match exactly, we aim + to find the closest match for every input tuple. + + Input: + first_list -- first list of (stamp,data) + second_list -- second list of (stamp,data) + max_difference -- search radius for candidate generation + + Output: + first_res: matched data from the first list + second_res: matched data from the second list + + """ + first_dict = dict([(l[0],l[1:]) for l in first_list if len(l)>1]) + second_dict = dict([(l[0],l[1:]) for l in second_list if len(l)>1]) + + first_keys = first_dict.keys() + second_keys = second_dict.keys() + potential_matches = [(abs(a - b ), a, b) + for a in first_keys + for b in second_keys + if abs(a - b) < max_difference] + potential_matches.sort() + matches = [] + for diff, a, b in potential_matches: + if a in first_keys and b in second_keys: + first_keys.remove(a) + second_keys.remove(b) + matches.append((a, b)) + + matches.sort() + + first_res = [] + second_res = [] + for t1, t2 in matches: + first_res.append(first_dict[t1]) + second_res.append(second_dict[t2]) + return np.array(first_res), np.array(second_res) diff --git a/thirdparty/tartanair_tools/evaluation/transformation.py b/thirdparty/tartanair_tools/evaluation/transformation.py new file mode 100755 index 00000000..e692510d --- /dev/null +++ b/thirdparty/tartanair_tools/evaluation/transformation.py @@ -0,0 +1,164 @@ +# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang +# For License information please see the LICENSE file in the root directory. +# Cridit: Xiangwei Wang https://github.com/TimingSpace + +import numpy as np +from scipy.spatial.transform import Rotation as R + +def line2mat(line_data): + mat = np.eye(4) + mat[0:3,:] = line_data.reshape(3,4) + return np.matrix(mat) + +def motion2pose(data): + data_size = len(data) + all_pose = [] # np.zeros((data_size+1, 4, 4)) + all_pose.append(np.eye(4,4)) #[0,:] = np.eye(4,4) + pose = np.eye(4,4) + for i in range(0,data_size): + pose = pose.dot(data[i]) + all_pose.append(pose) + return all_pose + +def pose2motion(data): + data_size = len(data) + all_motion = [] + for i in range(0,data_size-1): + motion = np.linalg.inv(data[i]).dot(data[i+1]) + all_motion.append(motion) + + return np.array(all_motion) # N x 4 x 4 + +def SE2se(SE_data): + result = np.zeros((6)) + result[0:3] = np.array(SE_data[0:3,3].T) + result[3:6] = SO2so(SE_data[0:3,0:3]).T + return result + +def SO2so(SO_data): + return R.from_matrix(SO_data).as_rotvec() + +def so2SO(so_data): + return R.from_rotvec(so_data).as_matrix() + +def se2SE(se_data): + result_mat = np.matrix(np.eye(4)) + result_mat[0:3,0:3] = so2SO(se_data[3:6]) + result_mat[0:3,3] = np.matrix(se_data[0:3]).T + return result_mat +### can get wrong result +def se_mean(se_datas): + all_SE = np.matrix(np.eye(4)) + for i in range(se_datas.shape[0]): + se = se_datas[i,:] + SE = se2SE(se) + all_SE = all_SE*SE + all_se = SE2se(all_SE) + mean_se = all_se/se_datas.shape[0] + return mean_se + +def ses_mean(se_datas): + se_datas = np.array(se_datas) + se_datas = np.transpose(se_datas.reshape(se_datas.shape[0],se_datas.shape[1],se_datas.shape[2]*se_datas.shape[3]),(0,2,1)) + se_result = np.zeros((se_datas.shape[0],se_datas.shape[2])) + for i in range(0,se_datas.shape[0]): + mean_se = se_mean(se_datas[i,:,:]) + se_result[i,:] = mean_se + return se_result + +def ses2poses(data): + data_size = data.shape[0] + all_pose = np.zeros((data_size+1,12)) + temp = np.eye(4,4).reshape(1,16) + all_pose[0,:] = temp[0,0:12] + pose = np.matrix(np.eye(4,4)) + for i in range(0,data_size): + data_mat = se2SE(data[i,:]) + pose = pose*data_mat + pose_line = np.array(pose[0:3,:]).reshape(1,12) + all_pose[i+1,:] = pose_line + return all_pose + +def SEs2ses(motion_data): + data_size = motion_data.shape[0] + ses = np.zeros((data_size,6)) + for i in range(0,data_size): + SE = np.matrix(np.eye(4)) + SE[0:3,:] = motion_data[i,:].reshape(3,4) + ses[i,:] = SE2se(SE) + return ses + +def so2quat(so_data): + so_data = np.array(so_data) + theta = np.sqrt(np.sum(so_data*so_data)) + axis = so_data/theta + quat=np.zeros(4) + quat[0:3] = np.sin(theta/2)*axis + quat[3] = np.cos(theta/2) + return quat + +def quat2so(quat_data): + quat_data = np.array(quat_data) + sin_half_theta = np.sqrt(np.sum(quat_data[0:3]*quat_data[0:3])) + axis = quat_data[0:3]/sin_half_theta + cos_half_theta = quat_data[3] + theta = 2*np.arctan2(sin_half_theta,cos_half_theta) + so = theta*axis + return so + +# input so_datas batch*channel*height*width +# return quat_datas batch*numner*channel +def sos2quats(so_datas,mean_std=[[1],[1]]): + so_datas = np.array(so_datas) + so_datas = so_datas.reshape(so_datas.shape[0],so_datas.shape[1],so_datas.shape[2]*so_datas.shape[3]) + so_datas = np.transpose(so_datas,(0,2,1)) + quat_datas = np.zeros((so_datas.shape[0],so_datas.shape[1],4)) + for i_b in range(0,so_datas.shape[0]): + for i_p in range(0,so_datas.shape[1]): + so_data = so_datas[i_b,i_p,:] + quat_data = so2quat(so_data) + quat_datas[i_b,i_p,:] = quat_data + return quat_datas + +def SO2quat(SO_data): + rr = R.from_matrix(SO_data) + return rr.as_quat() + +def quat2SO(quat_data): + return R.from_quat(quat_data).as_matrix() + + +def pos_quat2SE(quat_data): + SO = R.from_quat(quat_data[3:7]).as_matrix() + SE = np.matrix(np.eye(4)) + SE[0:3,0:3] = np.matrix(SO) + SE[0:3,3] = np.matrix(quat_data[0:3]).T + SE = np.array(SE[0:3,:]).reshape(1,12) + return SE + + +def pos_quats2SEs(quat_datas): + data_len = quat_datas.shape[0] + SEs = np.zeros((data_len,12)) + for i_data in range(0,data_len): + SE = pos_quat2SE(quat_datas[i_data,:]) + SEs[i_data,:] = SE + return SEs + + +def pos_quats2SE_matrices(quat_datas): + data_len = quat_datas.shape[0] + SEs = [] + for quat in quat_datas: + SO = R.from_quat(quat[3:7]).as_matrix() + SE = np.eye(4) + SE[0:3,0:3] = SO + SE[0:3,3] = quat[0:3] + SEs.append(SE) + return SEs + +def SE2pos_quat(SE_data): + pos_quat = np.zeros(7) + pos_quat[3:] = SO2quat(SE_data[0:3,0:3]) + pos_quat[:3] = SE_data[0:3,3].T + return pos_quat \ No newline at end of file diff --git a/thirdparty/tartanair_tools/seg_rgbs.txt b/thirdparty/tartanair_tools/seg_rgbs.txt new file mode 100644 index 00000000..0417bccb --- /dev/null +++ b/thirdparty/tartanair_tools/seg_rgbs.txt @@ -0,0 +1,256 @@ +0 0 0 +153 108 6 +112 105 191 +89 121 72 +190 225 64 +206 190 59 +81 13 36 +115 176 195 +161 171 27 +135 169 180 +29 26 199 +102 16 239 +242 107 146 +156 198 23 +49 89 160 +68 218 116 +11 236 9 +196 30 8 +121 67 28 +0 53 65 +146 52 70 +226 149 143 +151 126 171 +194 39 7 +205 120 161 +212 51 60 +211 80 208 +189 135 188 +54 72 205 +103 252 157 +124 21 123 +19 132 69 +195 237 132 +94 253 175 +182 251 87 +90 162 242 +199 29 1 +254 12 229 +35 196 244 +220 163 49 +86 254 214 +152 3 129 +92 31 106 +207 229 90 +125 75 48 +98 55 74 +126 129 238 +222 153 109 +85 152 34 +173 69 31 +37 128 125 +58 19 33 +134 57 119 +218 124 115 +120 0 200 +225 131 92 +246 90 16 +51 155 241 +202 97 155 +184 145 182 +96 232 44 +133 244 133 +180 191 29 +1 222 192 +99 242 104 +91 168 219 +65 54 217 +148 66 130 +203 102 204 +216 78 75 +234 20 250 +109 206 24 +164 194 17 +157 23 236 +158 114 88 +245 22 110 +67 17 35 +181 213 93 +170 179 42 +52 187 148 +247 200 111 +25 62 174 +100 25 240 +191 195 144 +252 36 67 +241 77 149 +237 33 141 +119 230 85 +28 34 108 +78 98 254 +114 161 30 +75 50 243 +66 226 253 +46 104 76 +8 234 216 +15 241 102 +93 14 71 +192 255 193 +253 41 164 +24 175 120 +185 243 231 +169 233 97 +243 215 145 +72 137 21 +160 113 101 +214 92 13 +167 140 147 +101 109 181 +53 118 126 +3 177 32 +40 63 99 +186 139 153 +88 207 100 +71 146 227 +236 38 187 +215 4 215 +18 211 66 +113 49 134 +47 42 63 +219 103 127 +57 240 137 +227 133 211 +145 71 201 +217 173 183 +250 40 113 +208 125 68 +224 186 249 +69 148 46 +239 85 20 +108 116 224 +56 214 26 +179 147 43 +48 188 172 +221 83 47 +155 166 218 +62 217 189 +198 180 122 +201 144 169 +132 2 14 +128 189 114 +163 227 112 +45 157 177 +64 86 142 +118 193 163 +14 32 79 +200 45 170 +74 81 2 +59 37 212 +73 35 225 +95 224 39 +84 170 220 +159 58 173 +17 91 237 +31 95 84 +34 201 248 +63 73 209 +129 235 107 +231 115 40 +36 74 95 +238 228 154 +61 212 54 +13 94 165 +141 174 0 +140 167 255 +117 93 91 +183 10 186 +165 28 61 +144 238 194 +12 158 41 +76 110 234 +150 9 121 +142 1 246 +230 136 198 +5 60 233 +232 250 80 +143 112 56 +187 70 156 +2 185 62 +138 223 226 +122 183 222 +166 245 3 +175 6 140 +240 59 210 +248 44 10 +83 82 52 +223 248 167 +87 15 150 +111 178 117 +197 84 22 +235 208 124 +9 76 45 +176 24 50 +154 159 251 +149 111 207 +168 231 15 +209 247 202 +80 205 152 +178 221 213 +27 8 38 +244 117 51 +107 68 190 +23 199 139 +171 88 168 +136 202 58 +6 46 86 +105 127 176 +174 249 197 +172 172 138 +228 142 81 +7 204 185 +22 61 247 +233 100 78 +127 65 105 +33 87 158 +139 156 252 +42 7 136 +20 99 179 +79 150 223 +131 182 184 +110 123 37 +60 138 96 +210 96 94 +123 48 18 +137 197 162 +188 18 5 +39 219 151 +204 143 135 +249 79 73 +77 64 178 +41 246 77 +16 154 4 +116 134 19 +4 122 235 +177 106 230 +21 119 12 +104 5 98 +50 130 53 +30 192 25 +26 165 166 +10 160 82 +106 43 131 +44 216 103 +255 101 221 +32 151 196 +213 220 89 +70 209 228 +97 184 83 +82 239 232 +251 164 128 +193 11 245 +38 27 159 +229 141 203 +130 56 55 +147 210 11 +162 203 118 +255 255 255 \ No newline at end of file diff --git a/tools/download_sample_data.sh b/tools/download_sample_data.sh new file mode 100755 index 00000000..4b7a6707 --- /dev/null +++ b/tools/download_sample_data.sh @@ -0,0 +1,26 @@ +#!/bin/bash + +mkdir -p data && cd data + + +gdown https://drive.google.com/uc?id=1AlfhZnGmlsKWGcNHFB1i8i8Jzn4VHB15 +unzip abandonedfactory.zip +rm abandonedfactory.zip + +gdown https://drive.google.com/uc?id=0B-ePgl6HF260NzQySklGdXZyQzA +unzip Barn.zip +rm Barn.zip + +wget https://www.eth3d.net/data/slam/datasets/sfm_bench_mono.zip +unzip sfm_bench_mono.zip +rm sfm_bench_mono.zip + +wget https://vision.in.tum.de/rgbd/dataset/freiburg3/rgbd_dataset_freiburg3_cabinet.tgz +tar -zxvf rgbd_dataset_freiburg3_cabinet.tgz +rm rgbd_dataset_freiburg3_cabinet.tgz + +wget http://robotics.ethz.ch/~asl-datasets/ijrr_euroc_mav_dataset/machine_hall/MH_03_medium/MH_03_medium.zip +unzip MH_03_medium.zip +rm MH_03_medium.zip + +cd .. diff --git a/tools/evaluate_euroc.sh b/tools/evaluate_euroc.sh new file mode 100755 index 00000000..7b37f151 --- /dev/null +++ b/tools/evaluate_euroc.sh @@ -0,0 +1,23 @@ +#!/bin/bash + + +EUROC_PATH=datasets/EuRoC + +evalset=( + MH_01_easy + MH_02_easy + MH_03_medium + MH_04_difficult + MH_05_difficult + V1_01_easy + V1_02_medium + V1_03_difficult + V2_01_easy + V2_02_medium + V2_03_difficult +) + +for seq in ${evalset[@]}; do + python evaluation_scripts/test_euroc.py --datapath=$EUROC_PATH/$seq --gt=data/euroc_groundtruth/$seq.txt --weights=droid.pth --disable_vis +done + diff --git a/tools/evaluate_tum.sh b/tools/evaluate_tum.sh new file mode 100755 index 00000000..0d634713 --- /dev/null +++ b/tools/evaluate_tum.sh @@ -0,0 +1,21 @@ +#!/bin/bash + + +TUM_PATH=datasets/TUM-RGBD/$seq + +evalset=( + rgbd_dataset_freiburg1_360 + rgbd_dataset_freiburg1_desk + rgbd_dataset_freiburg1_desk2 + rgbd_dataset_freiburg1_floor + rgbd_dataset_freiburg1_plant + rgbd_dataset_freiburg1_room + rgbd_dataset_freiburg1_rpy + rgbd_dataset_freiburg1_teddy + rgbd_dataset_freiburg1_xyz +) + +for seq in ${evalset[@]}; do + python evaluation_scripts/test_tum.py --datapath=$TUM_PATH/$seq --weights=droid.pth --disable_vis +done + diff --git a/tools/validate_tartanair.sh b/tools/validate_tartanair.sh new file mode 100755 index 00000000..2ae4185e --- /dev/null +++ b/tools/validate_tartanair.sh @@ -0,0 +1,7 @@ +#!/bin/bash + + +TARTANAIR_PATH=datasets/TartanAir + +python evaluation_scripts/validate_tartanair.py --datapath=$TARTANAIR_PATH --weights=droid.pth --disable_vis --plot_curve + diff --git a/train.py b/train.py new file mode 100644 index 00000000..77a14d21 --- /dev/null +++ b/train.py @@ -0,0 +1,187 @@ +import sys +sys.path.append('droid_slam') + +import cv2 +import numpy as np +from collections import OrderedDict + +import torch +import torch.optim as optim +from torch.utils.data import DataLoader +from data_readers.factory import dataset_factory + +from lietorch import SO3, SE3, Sim3 +from geom import losses +from geom.losses import geodesic_loss, residual_loss, flow_loss +from geom.graph_utils import build_frame_graph + +# network +from droid_net import DroidNet +from logger import Logger + +# DDP training +import torch.multiprocessing as mp +import torch.distributed as dist +from torch.nn.parallel import DistributedDataParallel as DDP + + +def setup_ddp(gpu, args): + dist.init_process_group( + backend='nccl', + init_method='env://', + world_size=args.world_size, + rank=gpu) + + torch.manual_seed(0) + torch.cuda.set_device(gpu) + +def show_image(image): + image = image.permute(1, 2, 0).cpu().numpy() + cv2.imshow('image', image / 255.0) + cv2.waitKey() + +def train(gpu, args): + """ Test to make sure project transform correctly maps points """ + + # coordinate multiple GPUs + setup_ddp(gpu, args) + rng = np.random.default_rng(12345) + + N = args.n_frames + model = DroidNet() + model.cuda() + model.train() + + model = DDP(model, device_ids=[gpu], find_unused_parameters=False) + + if args.ckpt is not None: + model.load_state_dict(torch.load(args.ckpt)) + + # fetch dataloader + db = dataset_factory(['tartan'], datapath=args.datapath, n_frames=args.n_frames, fmin=args.fmin, fmax=args.fmax) + + train_sampler = torch.utils.data.distributed.DistributedSampler( + db, shuffle=True, num_replicas=args.world_size, rank=gpu) + + train_loader = DataLoader(db, batch_size=args.batch, sampler=train_sampler, num_workers=2) + + # fetch optimizer + optimizer = torch.optim.Adam(model.parameters(), lr=args.lr, weight_decay=1e-5) + scheduler = torch.optim.lr_scheduler.OneCycleLR(optimizer, + args.lr, args.steps, pct_start=0.01, cycle_momentum=False) + + logger = Logger(args.name, scheduler) + should_keep_training = True + total_steps = 0 + + while should_keep_training: + for i_batch, item in enumerate(train_loader): + optimizer.zero_grad() + + images, poses, disps, intrinsics = [x.to('cuda') for x in item] + + # convert poses w2c -> c2w + Ps = SE3(poses).inv() + Gs = SE3.IdentityLike(Ps) + + # randomize frame graph + if np.random.rand() < 0.5: + graph = build_frame_graph(poses, disps, intrinsics, num=args.edges) + + else: + graph = OrderedDict() + for i in range(N): + graph[i] = [j for j in range(N) if i!=j and abs(i-j) <= 2] + + # fix first to camera poses + Gs.data[:,0] = Ps.data[:,0].clone() + Gs.data[:,1:] = Ps.data[:,[1]].clone() + disp0 = torch.ones_like(disps[:,:,3::8,3::8]) + + # perform random restarts + r = 0 + while r < args.restart_prob: + r = rng.random() + + intrinsics0 = intrinsics / 8.0 + poses_est, disps_est, residuals = model(Gs, images, disp0, intrinsics0, + graph, num_steps=args.iters, fixedp=2) + + geo_loss, geo_metrics = losses.geodesic_loss(Ps, poses_est, graph, do_scale=False) + res_loss, res_metrics = losses.residual_loss(residuals) + flo_loss, flo_metrics = losses.flow_loss(Ps, disps, poses_est, disps_est, intrinsics, graph) + + loss = args.w1 * geo_loss + args.w2 * res_loss + args.w3 * flo_loss + loss.backward() + + Gs = poses_est[-1].detach() + disp0 = disps_est[-1][:,:,3::8,3::8].detach() + + metrics = {} + metrics.update(geo_metrics) + metrics.update(res_metrics) + metrics.update(flo_metrics) + + torch.nn.utils.clip_grad_norm_(model.parameters(), args.clip) + optimizer.step() + scheduler.step() + + total_steps += 1 + + if gpu == 0: + logger.push(metrics) + + if total_steps % 10000 == 0 and gpu == 0: + PATH = 'checkpoints/%s_%06d.pth' % (args.name, total_steps) + torch.save(model.state_dict(), PATH) + + if total_steps >= args.steps: + should_keep_training = False + break + + dist.destroy_process_group() + + +if __name__ == '__main__': + import argparse + parser = argparse.ArgumentParser() + parser.add_argument('--name', default='bla', help='name your experiment') + parser.add_argument('--ckpt', help='checkpoint to restore') + parser.add_argument('--datasets', nargs='+', help='lists of datasets for training') + parser.add_argument('--datapath', default='datasets/TartanAir', help="path to dataset directory") + parser.add_argument('--gpus', type=int, default=4) + + parser.add_argument('--batch', type=int, default=1) + parser.add_argument('--iters', type=int, default=15) + parser.add_argument('--steps', type=int, default=250000) + parser.add_argument('--lr', type=float, default=0.00025) + parser.add_argument('--clip', type=float, default=2.5) + parser.add_argument('--n_frames', type=int, default=7) + + parser.add_argument('--w1', type=float, default=10.0) + parser.add_argument('--w2', type=float, default=0.01) + parser.add_argument('--w3', type=float, default=0.05) + + parser.add_argument('--fmin', type=float, default=8.0) + parser.add_argument('--fmax', type=float, default=96.0) + parser.add_argument('--noise', action='store_true') + parser.add_argument('--scale', action='store_true') + parser.add_argument('--edges', type=int, default=24) + parser.add_argument('--restart_prob', type=float, default=0.2) + + args = parser.parse_args() + + args.world_size = args.gpus + print(args) + + import os + if not os.path.isdir('checkpoints'): + os.mkdir('checkpoints') + + args = parser.parse_args() + args.world_size = args.gpus + + os.environ['MASTER_ADDR'] = 'localhost' + os.environ['MASTER_PORT'] = '12356' + mp.spawn(train, nprocs=args.gpus, args=(args,)) +