From 8a9d961f0d7b0cf6371ab1fcd6d0d2ccb581d3d1 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Thu, 23 Apr 2020 22:38:09 +1000 Subject: [PATCH] EKF: Improve covariance prediction stability (#795) * EKF: Improve covariance prediction stability Eliminates collapse of vertical velocity state variance due to rounding errors that can occur under some operating conditions. * EKF: Fix typo * test: Fix initialisation test cases Provide sufficient time for variances to stabilise and fix calculation of reference quaternion for alignment. * test: Allow for accumulated rounding error in IMU sampling test * test: Allow sufficient time for quaternion variances to reduce after initial alignment * test: Increase allowance for tilt alignment delay and inertial nav errors * test: Increase allowance for tilt alignment delay and inertial nav errors * adpat reset velocity test * test: update change indication file * test: Adjust tests to handle alignment time and prediction errors * README.md: Add documentation for change indicator test --- EKF/covariance.cpp | 7 +- EKF/estimator_interface.h | 2 +- README.md | 23 + test/change_indication/iris_gps.csv | 700 ++++++++++++++-------------- test/test_EKF_externalVision.cpp | 16 +- test/test_EKF_flow.cpp | 2 +- test/test_EKF_fusionLogic.cpp | 4 +- test/test_EKF_imuSampling.cpp | 7 +- test/test_EKF_initialization.cpp | 12 +- 9 files changed, 404 insertions(+), 369 deletions(-) diff --git a/EKF/covariance.cpp b/EKF/covariance.cpp index 8d1bfd06cd..cb1d8eee91 100644 --- a/EKF/covariance.cpp +++ b/EKF/covariance.cpp @@ -135,7 +135,8 @@ void Ekf::predictCovariance() const float dvy_b = _state.delta_vel_bias(1); const float dvz_b = _state.delta_vel_bias(2); - const float dt = math::constrain(_imu_sample_delayed.delta_ang_dt, 0.5f * FILTER_UPDATE_PERIOD_S, 2.0f * FILTER_UPDATE_PERIOD_S); + // Use average update interval to reduce accumulated covariance prediction errors due to small single frame dt values + const float dt = FILTER_UPDATE_PERIOD_S; const float dt_inv = 1.0f / dt; // convert rate of change of rate gyro bias (rad/s**2) as specified by the parameter to an expected change in delta angle (rad) since the last update @@ -734,12 +735,12 @@ void Ekf::fixCovarianceErrors(bool force_symmetry) for (int i = 4; i <= 6; i++) { // NED velocity states - P(i,i) = math::constrain(P(i,i), 0.0f, P_lim[1]); + P(i,i) = math::constrain(P(i,i), 1E-6f, P_lim[1]); } for (int i = 7; i <= 9; i++) { // NED position states - P(i,i) = math::constrain(P(i,i), 0.0f, P_lim[2]); + P(i,i) = math::constrain(P(i,i), 1E-6f, P_lim[2]); } for (int i = 10; i <= 12; i++) { diff --git a/EKF/estimator_interface.h b/EKF/estimator_interface.h index 92c36eac3d..91f0c24ce5 100644 --- a/EKF/estimator_interface.h +++ b/EKF/estimator_interface.h @@ -391,7 +391,7 @@ public: void print_status(); - static constexpr unsigned FILTER_UPDATE_PERIOD_MS{8}; // ekf prediction period in milliseconds - this should ideally be an integer multiple of the IMU time delta + static constexpr unsigned FILTER_UPDATE_PERIOD_MS{10}; // ekf prediction period in milliseconds - this should ideally be an integer multiple of the IMU time delta static constexpr float FILTER_UPDATE_PERIOD_S{FILTER_UPDATE_PERIOD_MS * 0.001f}; // request the EKF reset the yaw to the estimate from the internal EKF-GSF filter diff --git a/README.md b/README.md index 5dc2b0aad3..4199a605bc 100644 --- a/README.md +++ b/README.md @@ -36,3 +36,26 @@ By following the steps you can run the unit tests ``` make test ``` +### Change Indicator / Unit Tests +Change indication is the concept of running the EKF on different data-sets and compare the state of the EKF to a previous version. If a contributor makes a functional change that is run during the change_indication tests, this will produce a different output of the EKF's state. As the tests are run in CI, this checks if a contributor forgot to run the checks themselves and add the [new EKF's state outputs](https://github.com/PX4/ecl/blob/master/test/change_indication/iris_gps.csv) to the pull request. + +The unit tests include a check to see if the pull request results in a difference to the [output data csv file](https://github.com/PX4/ecl/blob/master/test/change_indication/iris_gps.csv) when replaying the [sensor data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv). If a pull request results in an expected difference, then it is important that the output reference file be re-generated and included as part of the pull request. A non-functional pull request should not result in changes to this file, however the default test case does not exercise all sensor types so this test passing is a necessary, but not sufficient requirement for a non-functional pull request. + +The functionality that supports this test consists of: +* Python scripts that extract sensor data from ulog files and writes them to a sensor data csv file. The default [sensor data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv) used by the unit test was generated from a ulog created from an iris SITL flight. +* A [script file](https://github.com/PX4/ecl/blob/master/test/test_EKF_withReplayData.cpp) using functionality provided by the [sensor simulator](https://github.com/PX4/ecl/blob/master/test/sensor_simulator/sensor_simulator.cpp), that loads sensor data from the [sensor data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv) , replays the EKF with it and logs the EKF's state and covariance data to the [output data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv). +* CI action that checks if the logs of the test running with replay data is changing. This helps to see if there are functional changes. + +#### How to run the Change Indicator test during development on your own logs: + +* create sensor_data.csv file from ulog file 'cd test/sensor_simulator/ +python3 createSensorDataFile.py ../replay_data/.csv' +* Setup the test file to use the EKF with the created sensor data by copy&paste an existing test case in [test/test_EKF_withReplayData.cpp](https://github.com/PX4/ecl/blob/master/test/test_EKF_withReplayData.cpp) and adapt the paths to load the right sensor data and write it to the right place, eg +_sensor_simulator.loadSensorDataFromFile("../../../test/replay_data/.csv"); +_ekf_logger.setFilePath("../../../test/change_indication/.csv"); +* You can feed the EKF with the data in the csv file, by running '_sensor_simulator.runReplaySeconds(duration_in_seconds)'. Be aware that replay sensor data will only be available when the corresponding sensor simulation are running. By default only imu, baro and mag sensor simulators are running. You can start a sensor simulation by calling _sensor_simulator._.start(). Be also aware that you still have to setup the EKF yourself. This includes setting the bit mask (fusion_mode in common.h) according to what you intend to fuse. +* In between _sensor_simulator.runReplaySeconds(duration_in_seconds) calls, write the state and covariances to the change_indication file by including a _ekf_logger.writeStateToFile(); line. +* Run the EKF with your data and all the other tests by running 'make test' from the ecl directory. The [default output data csv file](https://github.com/PX4/ecl/blob/master/test/change_indication/iris_gps.csv) changes can then be included in the PR if differences are causing the CI test to fail. + +#### Known Issues +If compiler versions other than GCC 7.5 are used to generate the output data file, then is is possible that the file will cause CI failures due to small numerical differences to file generated by the CI test. diff --git a/test/change_indication/iris_gps.csv b/test/change_indication/iris_gps.csv index d4c00d4eed..39b0186468 100644 --- a/test/change_indication/iris_gps.csv +++ b/test/change_indication/iris_gps.csv @@ -1,351 +1,351 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -8000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -88000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -192000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -288000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -392000,0.982834,-0.007954,-0.0134175,0.183833,0.000493855,-0.000283937,-0.00241826,1.97542e-06,-1.13575e-06,-1.9725e-05,0,0,0,0,0,0,0.203491,1.11759e-08,0.43426,0,0,0,0,0,0.000169603,0.00247244,0.00247196,0.00483084,25.0001,25.0001,0.562526,0.250974,0.250974,4.00014,6.4e-07,6.4e-07,6.4e-07,2.56e-06,2.56e-06,2.56e-06,0,0,0,0,0,0,0,0 -488000,0.983237,-0.00798438,-0.0137631,0.181638,0.00110868,-0.000522823,-0.0193987,7.58213e-05,-5.08936e-05,0.0276484,3.10171e-08,7.03813e-11,1.30798e-06,9.88708e-10,-8.61862e-10,4.18262e-08,0.203491,1.11759e-08,0.43426,0,0,0,0,0,9.07318e-05,0.00250291,0.00250269,0.00257188,25.0112,25.0112,0.56249,0.5198,0.5198,0.801664,6.4e-07,6.4e-07,6.38957e-07,2.56001e-06,2.56001e-06,2.56001e-06,0,0,0,0,0,0,0,0 -592000,0.983276,-0.00801868,-0.0140021,0.181405,0.00068744,-0.000158829,-0.0369435,3.62418e-05,-2.13262e-05,0.0160397,4.30384e-08,9.07938e-12,1.81315e-06,3.65822e-09,-3.44532e-09,1.24343e-07,0.203491,1.11759e-08,0.43426,0,0,0,0,0,6.31954e-05,0.00258743,0.00258729,0.00178375,7.91695,7.91695,0.561206,0.210479,0.210479,0.45071,6.39996e-07,6.39999e-07,6.34828e-07,2.55998e-06,2.55998e-06,2.56e-06,0,0,0,0,0,0,0,0 -688000,0.983194,-0.00807139,-0.0143697,0.181816,0.00323877,-0.000530379,-0.0477349,0.000245381,-4.10186e-05,0.017733,4.75966e-09,-4.6012e-10,2.42576e-07,3.75332e-10,-6.24757e-10,-1.16492e-08,0.203491,1.11759e-08,0.43426,0,0,0,0,0,5.30946e-05,0.00271411,0.00271399,0.00149413,7.95517,7.95516,0.558895,0.441576,0.441576,0.348058,6.39993e-07,6.39999e-07,6.28838e-07,2.55999e-06,2.55999e-06,2.55996e-06,0,0,0,0,0,0,0,0 -792000,0.983148,-0.00805451,-0.014615,0.182046,0.00575464,0.00207042,-0.0592733,0.000629211,5.19098e-05,0.0143143,-3.0633e-08,-5.10887e-10,-1.18027e-06,-1.29548e-09,8.06943e-10,-8.05869e-08,0.203491,1.11759e-08,0.43426,0,0,0,0,0,4.49801e-05,0.00290335,0.00290324,0.00126117,8.02053,8.02053,0.551728,0.857921,0.857921,0.275196,6.39985e-07,6.39999e-07,6.16042e-07,2.55999e-06,2.55999e-06,2.55978e-06,0,0,0,0,0,0,0,0 -888000,0.983115,-0.00808491,-0.0149511,0.1822,0.00607733,0.00409994,-0.0743197,0.000573104,0.0002785,0.00366363,-8.03385e-08,-6.15489e-09,-3.07301e-06,1.60078e-08,-8.28136e-09,2.31536e-07,0.203491,1.11759e-08,0.43426,0,0,0,0,0,4.01915e-05,0.0031189,0.00311878,0.00112319,2.70232,2.70232,0.539085,0.311568,0.311568,0.235593,6.39921e-07,6.39947e-07,5.97168e-07,2.55975e-06,2.55975e-06,2.5593e-06,0,0,0,0,0,0,0,0 -992000,0.982949,-0.00802232,-0.0152528,0.18307,0.00927493,0.00704693,-0.0910266,0.0013844,0.000777652,-0.00913315,-3.06644e-07,-1.06683e-08,-1.19551e-05,2.93029e-08,-1.96426e-08,7.75945e-07,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.78678e-05,0.00341188,0.00341173,0.00105444,2.79631,2.79634,0.520989,0.50362,0.50362,0.216031,6.39905e-07,6.39948e-07,5.7211e-07,2.55975e-06,2.55975e-06,2.55827e-06,0,0,0,0,0,0,0,0 -1088000,0.983013,-0.00812394,-0.0154388,0.182703,0.0155354,0.00526201,-0.10627,0.00142513,0.000771492,-0.0228124,-1.88333e-07,-5.50272e-08,-7.64761e-06,1.03961e-07,-2.4591e-08,1.45274e-06,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.63271e-05,0.00370041,0.00370024,0.00100807,1.30756,1.3076,0.496864,0.235674,0.235675,0.203869,6.39375e-07,6.39439e-07,5.41404e-07,2.55891e-06,2.55891e-06,2.55639e-06,0,0,0,0,0,0,0,0 -1192000,0.983096,-0.00808171,-0.0157372,0.182237,0.0220566,0.00480347,-0.108038,0.00335611,0.0012893,-0.019894,-3.70017e-08,-4.31905e-08,-1.91251e-06,1.18851e-08,5.24949e-08,-2.21987e-06,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.59507e-05,0.00409574,0.0040955,0.000994299,1.43969,1.43976,0.468339,0.346677,0.346679,0.200061,6.39351e-07,6.39439e-07,5.06144e-07,2.55891e-06,2.55892e-06,2.55334e-06,0,0,0,0,0,0,0,0 -1288000,0.983276,-0.00800236,-0.0159855,0.181242,0.0257359,0.00430207,-0.121864,0.00324794,0.000817744,-0.0299464,3.09926e-07,-3.04288e-07,1.12404e-05,2.47389e-07,5.36701e-08,-2.5238e-06,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.70167e-05,0.00440951,0.00440919,0.00102383,0.899191,0.899265,0.445895,0.192334,0.192336,0.206496,6.36755e-07,6.36863e-07,4.77706e-07,2.5568e-06,2.5568e-06,2.55013e-06,0,0,0,0,0,0,0,0 -1392000,0.983367,-0.00801275,-0.0162327,0.180724,0.0349225,0.00525,-0.120987,0.00643697,0.00132661,-0.0263017,4.56161e-07,-2.78842e-07,1.65063e-05,9.26623e-08,1.81858e-07,-8.61093e-06,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.71223e-05,0.00490204,0.00490162,0.00102483,1.08002,1.08014,0.412489,0.271991,0.271996,0.206982,6.36726e-07,6.36863e-07,4.38089e-07,2.5568e-06,2.55681e-06,2.54437e-06,0,0,0,0,0,0,0,0 -1488000,0.983298,-0.00797385,-0.0162371,0.181101,0.0335704,0.00426553,-0.131496,0.00548229,0.000985135,-0.036932,1.05085e-07,-1.23855e-06,9.6534e-06,7.46588e-07,7.96659e-08,-9.11575e-06,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.66712e-05,0.00513213,0.00513169,0.00101134,0.831679,0.831802,0.377858,0.168555,0.168559,0.204407,6.27945e-07,6.28111e-07,3.98124e-07,2.55257e-06,2.55257e-06,2.53676e-06,0,0,0,0,0,0,0,0 -1592000,0.983297,-0.0080497,-0.0165743,0.181071,0.0415839,0.00471989,-0.142765,0.00940013,0.00139321,-0.0470266,9.59627e-08,-1.22597e-06,9.22595e-06,6.93446e-07,1.23063e-07,-1.11669e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.68609e-05,0.00570766,0.00570709,0.0010102,1.06745,1.06764,0.344571,0.238468,0.238479,0.204673,6.27915e-07,6.2811e-07,3.59141e-07,2.55257e-06,2.55257e-06,2.52719e-06,0,0,0,0,0,0,0,0 -1688000,0.983302,-0.00809787,-0.0164799,0.181055,0.0393023,0.00549178,-0.149375,0.00742378,0.0010842,-0.0523702,-4.02117e-07,-3.43862e-06,9.14775e-06,1.8276e-06,-6.218e-08,-1.57976e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.6215e-05,0.00567256,0.00567204,0.000991651,0.900171,0.900353,0.312531,0.158058,0.158064,0.201056,6.06115e-07,6.06332e-07,3.22118e-07,2.54577e-06,2.54578e-06,2.5156e-06,0,0,0,0,0,0,0,0 -1792000,0.983287,-0.00820575,-0.0167599,0.181102,0.0503195,0.00604146,-0.149728,0.0121627,0.0016697,-0.0542256,-4.45505e-07,-3.37862e-06,7.05306e-06,1.61963e-06,1.07131e-07,-2.38058e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.62095e-05,0.0063017,0.00630102,0.000983418,1.186,1.18628,0.2837,0.229229,0.229247,0.199805,6.06089e-07,6.06331e-07,2.87743e-07,2.54577e-06,2.54578e-06,2.50196e-06,0,0,0,0,0,0,0,0 -1888000,0.983396,-0.00814375,-0.0163208,0.180554,0.0440242,0.00698048,-0.152468,0.00907229,0.00127995,-0.0601208,-1.20673e-06,-7.36988e-06,1.34252e-05,3.32482e-06,-2.08456e-07,-2.93907e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.51381e-05,0.00582148,0.00582098,0.000958918,0.989765,0.989997,0.257162,0.155891,0.155901,0.194931,5.65241e-07,5.65492e-07,2.56327e-07,2.53727e-06,2.53728e-06,2.48623e-06,0,0,0,0,0,0,0,0 -1992000,0.983424,-0.00823228,-0.0166527,0.180368,0.0525925,0.0080017,-0.153894,0.0141523,0.00200772,-0.0623208,-1.15322e-06,-7.2924e-06,1.4745e-05,3.09531e-06,-1.69181e-08,-3.85304e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.4953e-05,0.00646001,0.00645934,0.000944397,1.30615,1.30649,0.234363,0.232404,0.232429,0.192399,5.65221e-07,5.65491e-07,2.28038e-07,2.53726e-06,2.53728e-06,2.46842e-06,0,0,0,0,0,0,0,0 -2088000,0.983344,-0.00825807,-0.0159689,0.180863,0.0422199,0.00563509,-0.153465,0.00968685,0.00135362,-0.0614483,-2.57865e-06,-1.27937e-05,8.11128e-06,4.87473e-06,-2.49674e-07,-5.00242e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.49088e-05,0.00551943,0.00551908,0.000956699,1.02972,1.02994,0.220728,0.156647,0.156659,0.196102,5.06659e-07,5.06917e-07,2.08745e-07,2.52925e-06,2.52926e-06,2.45358e-06,0,0,0,0,0,0,0,0 -2192000,0.983329,-0.00823573,-0.0163136,0.180915,0.0497313,0.00624449,-0.154829,0.0144914,0.00203064,-0.0650098,-2.6014e-06,-1.27089e-05,6.33637e-06,4.63808e-06,-5.17868e-08,-5.95875e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.45353e-05,0.00612261,0.00612207,0.000936581,1.34697,1.34729,0.203112,0.237138,0.237165,0.192571,5.06646e-07,5.06915e-07,1.85673e-07,2.52924e-06,2.52925e-06,2.43198e-06,0,0,0,0,0,0,0,0 -2288000,0.98349,-0.00827661,-0.0155619,0.180102,0.0370214,0.00462986,-0.149222,0.00924728,0.00128451,-0.0618825,-3.77539e-06,-1.87263e-05,1.50077e-05,6.0759e-06,-1.51744e-07,-7.42128e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.28558e-05,0.00491979,0.00491956,0.000904612,0.997305,0.997491,0.187365,0.156103,0.156114,0.186412,4.39776e-07,4.40024e-07,1.65258e-07,2.52364e-06,2.52365e-06,2.40812e-06,0,0,0,0,0,0,0,0 -2392000,0.983489,-0.00831532,-0.0157827,0.180089,0.0449226,0.00388733,-0.147752,0.0135671,0.00172302,-0.0590413,-3.7631e-06,-1.86022e-05,1.42828e-05,5.70253e-06,1.75203e-07,-9.01525e-05,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.23483e-05,0.00545995,0.0054596,0.000882694,1.29178,1.29204,0.174714,0.236435,0.23646,0.182729,4.39767e-07,4.40023e-07,1.47329e-07,2.52363e-06,2.52365e-06,2.38193e-06,0,0,0,0,0,0,0,0 -2488000,0.983634,-0.00818639,-0.0150677,0.179359,0.030296,0.00325497,-0.149488,0.00826939,0.000997642,-0.0617759,-4.9827e-06,-2.41904e-05,2.14745e-05,6.64414e-06,1.17851e-07,-0.000100992,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.06383e-05,0.00424727,0.00424714,0.000851198,0.918004,0.918144,0.163344,0.152803,0.152813,0.176869,3.74902e-07,3.7513e-07,1.31542e-07,2.52081e-06,2.52082e-06,2.3533e-06,0,0,0,0,0,0,0,0 -2592000,0.983662,-0.00832477,-0.0152108,0.179186,0.0341017,0.00147043,-0.153918,0.0116122,0.00127245,-0.0681563,-4.98102e-06,-2.41288e-05,2.08746e-05,6.43824e-06,3.03093e-07,-0.000110164,0.203491,1.11759e-08,0.43426,0,0,0,0,0,3.00258e-05,0.00471787,0.00471768,0.000829182,1.17783,1.17801,0.154541,0.229388,0.229409,0.173406,3.74896e-07,3.75128e-07,1.17724e-07,2.5208e-06,2.52082e-06,2.32213e-06,0,0,0,0,0,0,0,0 -2688000,0.983702,-0.00831168,-0.0146343,0.179019,0.022557,0.00115582,-0.155464,0.00683018,0.000663301,-0.0712644,-6.16219e-06,-2.85609e-05,2.19799e-05,6.73012e-06,4.04145e-07,-0.000122485,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.94514e-05,0.00364525,0.00364522,0.000830016,0.822365,0.822461,0.150668,0.147372,0.147379,0.175545,3.17477e-07,3.17681e-07,1.08441e-07,2.51991e-06,2.51993e-06,2.29699e-06,0,0,0,0,0,0,0,0 -2792000,0.983693,-0.00824723,-0.0148186,0.179054,0.0276388,0.000193475,-0.151665,0.00959555,0.000758327,-0.0659179,-6.16977e-06,-2.84275e-05,1.9973e-05,6.221e-06,8.69547e-07,-0.00014599,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.87963e-05,0.0040523,0.0040522,0.000807171,1.04779,1.04793,0.14445,0.218367,0.218383,0.172226,3.17473e-07,3.17679e-07,9.7439e-08,2.51989e-06,2.51992e-06,2.26114e-06,0,0,0,0,0,0,0,0 -2888000,0.983761,-0.00821955,-0.0143738,0.17872,0.0201793,-0.00109752,-0.152249,0.00570769,0.000321785,-0.0650697,-7.21366e-06,-3.18289e-05,2.12482e-05,5.97516e-06,1.18875e-06,-0.000163737,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.72735e-05,0.00315731,0.0031573,0.000777646,0.731836,0.731905,0.13857,0.140935,0.14094,0.167195,2.68479e-07,2.68659e-07,8.77379e-08,2.51982e-06,2.51984e-06,2.2225e-06,0,0,0,0,0,0,0,0 -2992000,0.983804,-0.00822596,-0.0144923,0.178472,0.0228735,-0.00183764,-0.155301,0.00806159,0.000184175,-0.0694656,-7.17568e-06,-3.17828e-05,2.23332e-05,5.68214e-06,1.47416e-06,-0.000177897,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.66655e-05,0.00351035,0.0035103,0.000756271,0.927537,0.927632,0.134465,0.205989,0.206001,0.16443,2.68476e-07,2.68658e-07,7.92223e-08,2.5198e-06,2.51983e-06,2.18102e-06,0,0,0,0,0,0,0,0 -3088000,0.983743,-0.00817253,-0.0142217,0.17883,0.0183276,-0.00326089,-0.156326,0.004902,-5.3218e-05,-0.0707192,-8.27907e-06,-3.44191e-05,1.96452e-05,5.16962e-06,1.87355e-06,-0.000195745,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.53909e-05,0.00277248,0.00277248,0.000729241,0.654034,0.654086,0.13034,0.134355,0.134359,0.160086,2.26866e-07,2.27024e-07,7.16859e-08,2.51968e-06,2.51971e-06,2.13667e-06,0,0,0,0,0,0,0,0 -3192000,0.983622,-0.00821139,-0.0143561,0.179482,0.0218349,-0.00543703,-0.162884,0.00699315,-0.000570752,-0.0826115,-8.38325e-06,-3.4344e-05,1.38304e-05,5.03901e-06,1.96301e-06,-0.000201761,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.48606e-05,0.00308008,0.00308006,0.000709526,0.825569,0.825638,0.127682,0.193888,0.193897,0.15788,2.26864e-07,2.27023e-07,6.50463e-08,2.51966e-06,2.51969e-06,2.08946e-06,0,0,0,0,0,0,0,0 -3288000,0.983612,-0.00823299,-0.0143512,0.179536,0.0240965,-0.00635163,-0.165897,0.00922335,-0.0011986,-0.0903289,-8.38372e-06,-3.42986e-05,1.30427e-05,4.81436e-06,2.17641e-06,-0.000212958,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.48992e-05,0.00338104,0.00338101,0.000707551,1.01311,1.0132,0.127878,0.270565,0.27058,0.160426,2.26862e-07,2.27022e-07,6.05715e-08,2.51965e-06,2.51968e-06,2.05225e-06,0,0,0,0,0,0,0,0 -3392000,0.98356,-0.00798106,-0.014049,0.179856,0.0172163,-0.00530365,-0.16723,0.00604118,-0.00111336,-0.0917313,-9.59546e-06,-3.63778e-05,9.75117e-06,4.06101e-06,2.76518e-06,-0.000235789,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.38875e-05,0.0027325,0.0027325,0.000688216,0.742661,0.742716,0.126037,0.18281,0.182817,0.158591,1.91241e-07,1.91378e-07,5.51712e-08,2.51894e-06,2.51898e-06,2.00017e-06,0,0,0,0,0,0,0,0 -3488000,0.983483,-0.00794048,-0.0140882,0.180275,0.0220416,-0.00340694,-0.163336,0.00804659,-0.00152453,-0.0885222,-9.63302e-06,-3.626e-05,6.04509e-06,3.51221e-06,3.28817e-06,-0.000264057,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.32078e-05,0.00299484,0.00299482,0.000664889,0.909352,0.90944,0.123719,0.252863,0.252875,0.155245,1.91239e-07,1.91377e-07,5.03868e-08,2.51893e-06,2.51896e-06,1.94546e-06,0,0,0,0,0,0,0,0 -3592000,0.98348,-0.00774641,-0.0137378,0.18033,0.0180845,-0.00323467,-0.169442,0.00558999,-0.00100296,-0.0963334,-1.07333e-05,-3.79994e-05,4.81397e-06,2.83671e-06,3.80331e-06,-0.000278504,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.23203e-05,0.00244025,0.00244027,0.000647343,0.67528,0.675337,0.122435,0.172988,0.172994,0.153893,1.60461e-07,1.60579e-07,4.61028e-08,2.51738e-06,2.51741e-06,1.88831e-06,0,0,0,0,0,0,0,0 -3688000,0.983554,-0.00779452,-0.0138022,0.179918,0.0196287,-0.00419477,-0.166633,0.00755635,-0.00136789,-0.0948662,-1.0656e-05,-3.7975e-05,7.44251e-06,2.29835e-06,4.34448e-06,-0.000306598,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.17135e-05,0.00266862,0.00266864,0.000626277,0.824891,0.824964,0.120503,0.237487,0.237498,0.151034,1.6046e-07,1.60578e-07,4.22907e-08,2.51736e-06,2.5174e-06,1.82892e-06,0,0,0,0,0,0,0,0 -3792000,0.98354,-0.00765258,-0.0136174,0.180013,0.013955,4.57865e-05,-0.166737,0.00509547,-0.000743393,-0.0966468,-1.16232e-05,-3.9531e-05,6.39531e-06,1.33993e-06,5.10923e-06,-0.000331898,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.09522e-05,0.00218351,0.00218355,0.000610378,0.618824,0.618878,0.119458,0.164326,0.164331,0.15007,1.33746e-07,1.33847e-07,3.88598e-08,2.51491e-06,2.51495e-06,1.76755e-06,0,0,0,0,0,0,0,0 -3888000,0.983566,-0.00762206,-0.0137068,0.179864,0.0148924,0.000486975,-0.16901,0.00656487,-0.000676531,-0.103455,-1.15893e-05,-3.95239e-05,7.58725e-06,1.05545e-06,5.39653e-06,-0.000346979,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.09588e-05,0.00238144,0.00238148,0.000607929,0.753698,0.753769,0.120517,0.224093,0.224103,0.153309,1.33745e-07,1.33846e-07,3.65325e-08,2.5149e-06,2.51494e-06,1.72056e-06,0,0,0,0,0,0,0,0 -3992000,0.983471,-0.00757985,-0.0135019,0.180404,0.012842,0.00128398,-0.170028,0.00444791,-0.000291522,-0.105182,-1.23101e-05,-4.08201e-05,4.38726e-06,6.09334e-08,6.13807e-06,-0.00037374,0.203491,1.11759e-08,0.43426,0,0,0,0,0,2.02747e-05,0.00195059,0.00195066,0.000592678,0.569988,0.570036,0.119465,0.156628,0.156633,0.15258,1.10615e-07,1.107e-07,3.36859e-08,2.51165e-06,2.51168e-06,1.65648e-06,0,0,0,0,0,0,0,0 -4088000,0.983404,-0.00754418,-0.0134528,0.180774,0.0151012,0.00112672,-0.159037,0.00597661,-0.000184476,-0.0939398,-1.23222e-05,-4.07319e-05,2.25126e-06,-7.64134e-07,6.98404e-06,-0.000419754,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.97485e-05,0.002121,0.00212107,0.000574579,0.691857,0.691919,0.117585,0.212295,0.212304,0.150263,1.10614e-07,1.107e-07,3.11324e-08,2.51163e-06,2.51167e-06,1.59131e-06,0,0,0,0,0,0,0,0 -4192000,0.983442,-0.00759554,-0.013188,0.180582,0.0116482,1.67883e-05,-0.159243,0.00411343,-6.0496e-05,-0.0977128,-1.27988e-05,-4.19587e-05,3.13747e-06,-1.70421e-06,7.61545e-06,-0.00044161,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.91205e-05,0.00173565,0.00173575,0.000560782,0.52568,0.525717,0.116402,0.149677,0.149682,0.149743,9.07436e-08,9.08148e-08,2.88135e-08,2.50775e-06,2.50779e-06,1.52543e-06,0,0,0,0,0,0,0,0 -4288000,0.983496,-0.00765224,-0.0132549,0.180279,0.0147913,0.000505228,-0.160715,0.0054613,-5.94361e-05,-0.10302,-1.27608e-05,-4.19645e-05,4.73926e-06,-2.02127e-06,7.94616e-06,-0.000459328,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.86334e-05,0.00188123,0.00188134,0.000544406,0.635764,0.635814,0.11437,0.201665,0.201672,0.147618,9.0743e-08,9.08143e-08,2.6725e-08,2.50773e-06,2.50777e-06,1.4592e-06,0,0,0,0,0,0,0,0 -4392000,0.983578,-0.00756888,-0.0131026,0.179849,0.0132502,-0.000690525,-0.153172,0.00398412,-8.63366e-05,-0.095125,-1.31349e-05,-4.30491e-05,6.80834e-06,-3.30884e-06,8.9376e-06,-0.000501434,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.80632e-05,0.00153689,0.00153699,0.0005319,0.484838,0.48487,0.112969,0.143289,0.143293,0.147215,7.38729e-08,7.39318e-08,2.482e-08,2.50346e-06,2.5035e-06,1.39301e-06,0,0,0,0,0,0,0,0 -4488000,0.983558,-0.00761651,-0.0130836,0.17996,0.0145386,0.00115556,-0.152281,0.00538318,-1.39926e-05,-0.0964669,-1.31353e-05,-4.3025e-05,6.31235e-06,-3.70339e-06,9.35462e-06,-0.000524501,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.76205e-05,0.00166029,0.00166041,0.000517016,0.58388,0.583925,0.11073,0.191897,0.191903,0.145198,7.38724e-08,7.39314e-08,2.30976e-08,2.50345e-06,2.50348e-06,1.32721e-06,0,0,0,0,0,0,0,0 -4592000,0.983487,-0.00755279,-0.0129828,0.180355,0.0125989,-0.000198164,-0.151651,0.00387034,7.57826e-06,-0.099917,-1.35432e-05,-4.39887e-05,4.33034e-06,-4.62226e-06,9.94927e-06,-0.000546061,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.7136e-05,0.00135438,0.00135449,0.00050561,0.446291,0.44632,0.109078,0.137329,0.137332,0.144836,5.97406e-08,5.97887e-08,2.15201e-08,2.49902e-06,2.49905e-06,1.26216e-06,0,0,0,0,0,0,0,0 -4688000,0.983576,-0.00751704,-0.0129662,0.179871,0.0131134,-0.000749645,-0.144994,0.00521032,8.8084e-06,-0.0966545,-1.34955e-05,-4.4005e-05,6.43924e-06,-5.13139e-06,1.04913e-05,-0.000576117,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.70813e-05,0.00145824,0.00145836,0.000503502,0.534761,0.534795,0.109255,0.182765,0.18277,0.148217,5.97403e-08,5.97885e-08,2.04332e-08,2.49901e-06,2.49904e-06,1.21393e-06,0,0,0,0,0,0,0,0 -4792000,0.983527,-0.00735351,-0.0128843,0.180152,0.00549486,-9.22914e-06,-0.143466,0.00340175,6.54992e-06,-0.0984896,-1.3846e-05,-4.48541e-05,5.19922e-06,-6.0306e-06,1.10927e-05,-0.000598637,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.66319e-05,0.00118887,0.00118897,0.000492609,0.409658,0.40968,0.107323,0.131694,0.131696,0.147809,4.80611e-08,4.81001e-08,1.90878e-08,2.49464e-06,2.49466e-06,1.15094e-06,0,0,0,0,0,0,0,0 -4888000,0.983542,-0.00731601,-0.0129231,0.180068,0.00590792,-0.00177202,-0.13695,0.00396777,-7.79055e-05,-0.0947775,-1.38292e-05,-4.48527e-05,5.76127e-06,-6.50298e-06,1.16037e-05,-0.000627552,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.62421e-05,0.00127576,0.00127587,0.000479708,0.48856,0.488583,0.104636,0.174131,0.174136,0.145749,4.80607e-08,4.80997e-08,1.78625e-08,2.49463e-06,2.49465e-06,1.08951e-06,0,0,0,0,0,0,0,0 -4992000,0.983542,-0.00724689,-0.0128006,0.180081,0.0044792,-0.000496051,-0.130345,0.00254907,-9.99713e-05,-0.090802,-1.40814e-05,-4.54253e-05,5.3059e-06,-7.36623e-06,1.22915e-05,-0.000657504,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.58153e-05,0.00104085,0.00104094,0.000469773,0.375063,0.375081,0.102493,0.126335,0.126338,0.145283,3.85255e-08,3.85568e-08,1.6733e-08,2.49046e-06,2.49048e-06,1.02986e-06,0,0,0,0,0,0,0,0 -5088000,0.983488,-0.0071065,-0.0127334,0.180384,0.00532131,-1.46725e-05,-0.125175,0.00305465,-0.000169569,-0.0865691,-1.4103e-05,-4.53931e-05,3.91241e-06,-7.78121e-06,1.27671e-05,-0.000684941,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.54513e-05,0.00111323,0.00111332,0.000457967,0.445252,0.445274,0.0996633,0.165929,0.165933,0.143194,3.85252e-08,3.85565e-08,1.57008e-08,2.49045e-06,2.49047e-06,9.72194e-07,0,0,0,0,0,0,0,0 -5192000,0.983492,-0.00697251,-0.0126983,0.180372,0.00106834,0.0029317,-0.12283,0.00192158,1.23866e-05,-0.0867284,-1.42648e-05,-4.58046e-05,4.12016e-06,-8.39901e-06,1.32462e-05,-0.000705937,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.50886e-05,0.000910179,0.000910253,0.000448845,0.342844,0.342861,0.0973586,0.121234,0.121236,0.142646,3.08188e-08,3.08438e-08,1.47463e-08,2.4866e-06,2.48661e-06,9.1666e-07,0,0,0,0,0,0,0,0 -5288000,0.983495,-0.00687601,-0.0126524,0.180362,0.00296255,0.00432334,-0.113384,0.00217544,0.00036217,-0.082855,-1.42585e-05,-4.58051e-05,4.32539e-06,-8.77269e-06,1.3663e-05,-0.000730306,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.50519e-05,0.000970283,0.000970363,0.000447033,0.404677,0.404699,0.0968191,0.158141,0.158144,0.145693,3.08186e-08,3.08436e-08,1.4083e-08,2.4866e-06,2.4866e-06,8.76454e-07,0,0,0,0,0,0,0,0 -5392000,0.983478,-0.00681537,-0.0125867,0.180459,-0.000360171,0.00661511,-0.109866,0.00133282,0.00053982,-0.0791108,-1.4281e-05,-4.6086e-05,3.71917e-06,-9.34448e-06,1.40818e-05,-0.000754355,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.47036e-05,0.000796154,0.000796217,0.000438313,0.312693,0.312709,0.0943549,0.116367,0.116369,0.145006,2.46397e-08,2.46595e-08,1.32551e-08,2.48312e-06,2.48312e-06,8.2492e-07,0,0,0,0,0,0,0,0 -5488000,0.983469,-0.00681156,-0.0126605,0.180504,0.000390504,0.00933496,-0.103531,0.00133447,0.00127797,-0.0748499,-1.42891e-05,-4.60759e-05,3.27761e-06,-9.66843e-06,1.44651e-05,-0.000776959,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.43743e-05,0.000845988,0.000846058,0.000427978,0.367529,0.367551,0.0913427,0.150747,0.15075,0.142735,2.46394e-08,2.46593e-08,1.24936e-08,2.48312e-06,2.48311e-06,7.75763e-07,0,0,0,0,0,0,0,0 -5592000,0.983463,-0.00685409,-0.0126382,0.180536,-0.000848678,0.0115006,-0.0962166,0.000811676,0.00141187,-0.0684492,-1.41235e-05,-4.62927e-05,2.676e-06,-1.0206e-05,1.47535e-05,-0.000802297,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.40504e-05,0.00069755,0.000697607,0.000419964,0.284951,0.284967,0.0888318,0.111742,0.111744,0.141953,1.97125e-08,1.97283e-08,1.1786e-08,2.48003e-06,2.48002e-06,7.29007e-07,0,0,0,0,0,0,0,0 -5688000,0.983445,-0.00681627,-0.0125627,0.180644,-0.000439419,0.0147604,-0.0934192,0.000704336,0.00260246,-0.0647364,-1.41419e-05,-4.62754e-05,1.79553e-06,-1.04609e-05,1.50782e-05,-0.000821409,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.37368e-05,0.000738859,0.000738924,0.00041044,0.333511,0.333534,0.0858442,0.143759,0.143762,0.13965,1.97123e-08,1.97281e-08,1.1133e-08,2.48003e-06,2.48002e-06,6.84657e-07,0,0,0,0,0,0,0,0 -5792000,0.983489,-0.00674758,-0.0125049,0.18041,-0.000707691,0.0149313,-0.0884845,0.000393647,0.00242715,-0.0604449,-1.37783e-05,-4.64894e-05,2.4089e-06,-1.09108e-05,1.51175e-05,-0.000841536,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.34425e-05,0.000612877,0.000612927,0.000403048,0.259722,0.259738,0.0833395,0.107356,0.107358,0.138783,1.57975e-08,1.58101e-08,1.05248e-08,2.47732e-06,2.47731e-06,6.42686e-07,0,0,0,0,0,0,0,0 -5888000,0.983481,-0.00671616,-0.0125711,0.180451,0.00150325,0.016302,-0.0870429,0.000426328,0.00397679,-0.0649805,-1.37813e-05,-4.64871e-05,2.2899e-06,-1.0982e-05,1.521e-05,-0.000847023,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.34086e-05,0.000647145,0.000647199,0.000401522,0.302396,0.302416,0.0824369,0.137176,0.137179,0.141333,1.57974e-08,1.581e-08,1.00989e-08,2.47732e-06,2.4773e-06,6.1277e-07,0,0,0,0,0,0,0,0 -5992000,0.983445,-0.00671868,-0.0127053,0.180637,0.00207571,0.0166291,-0.0809674,0.00063547,0.00569638,-0.0599446,-1.38015e-05,-4.64692e-05,1.40527e-06,-1.12167e-05,1.55359e-05,-0.000866186,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.31899e-05,0.000685551,0.00068561,0.000394438,0.354405,0.354427,0.0799136,0.178268,0.178273,0.140328,1.57973e-08,1.58098e-08,9.56572e-09,2.47732e-06,2.4773e-06,5.7486e-07,0,0,0,0,0,0,0,0 -6088000,0.983409,-0.00681044,-0.0126195,0.180837,0.00140601,0.0145387,-0.0758703,0.000498213,0.00461678,-0.055133,-1.33963e-05,-4.66632e-05,-3.20613e-07,-1.15977e-05,1.54411e-05,-0.000882924,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.28509e-05,0.000569011,0.000569061,0.000386,0.274317,0.274333,0.077027,0.130981,0.130984,0.137887,1.26923e-08,1.27023e-08,9.0674e-09,2.47498e-06,2.47494e-06,5.39175e-07,0,0,0,0,0,0,0,0 -6192000,0.983376,-0.00682959,-0.0126045,0.181016,0.00113994,0.0162831,-0.0732728,0.000713123,0.00623592,-0.0537234,-1.34137e-05,-4.66483e-05,-1.0719e-06,-1.17367e-05,1.56521e-05,-0.000895377,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.26497e-05,0.000600886,0.000600943,0.00037943,0.320135,0.320154,0.0745881,0.16904,0.169044,0.136825,1.26922e-08,1.27022e-08,8.60458e-09,2.47498e-06,2.47494e-06,5.05648e-07,0,0,0,0,0,0,0,0 -6288000,0.983361,-0.00691947,-0.0125945,0.181092,-0.00048506,0.0144272,-0.0752754,0.000429674,0.00491865,-0.058657,-1.29757e-05,-4.6872e-05,-1.2714e-06,-1.19713e-05,1.52995e-05,-0.00089835,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.23734e-05,0.000502664,0.000502709,0.000371567,0.249114,0.249127,0.0718368,0.125178,0.12518,0.1344,1.02303e-08,1.02383e-08,8.17113e-09,2.47295e-06,2.47291e-06,4.74181e-07,0,0,0,0,0,0,0,0 -6392000,0.983391,-0.00686996,-0.0125216,0.180938,0.000451835,0.0155153,-0.073821,0.000389893,0.00647856,-0.059446,-1.29684e-05,-4.68806e-05,-8.3145e-07,-1.20776e-05,1.54393e-05,-0.000907261,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.21779e-05,0.000529182,0.000529232,0.000365469,0.289492,0.289508,0.0695078,0.160459,0.160462,0.133298,1.02302e-08,1.02382e-08,7.7675e-09,2.47296e-06,2.47291e-06,4.44694e-07,0,0,0,0,0,0,0,0 -6488000,0.983391,-0.00693162,-0.0125241,0.180933,-0.0015135,0.0111854,-0.0707741,0.000173921,0.00486993,-0.0572578,-1.25509e-05,-4.70653e-05,-1.19772e-06,-1.23739e-05,1.5221e-05,-0.000918567,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.21047e-05,0.000446415,0.000446454,0.000364181,0.226447,0.226457,0.068541,0.119747,0.119749,0.135377,8.2763e-09,8.28267e-09,7.48102e-09,2.47122e-06,2.47117e-06,4.23853e-07,0,0,0,0,0,0,0,0 -6592000,0.983367,-0.00690264,-0.0124657,0.181068,-0.0023836,0.0122033,-0.0729342,-3.8322e-06,0.00600927,-0.0602087,-1.25679e-05,-4.70502e-05,-1.96888e-06,-1.24215e-05,1.53186e-05,-0.000924112,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.19139e-05,0.00046854,0.000468583,0.000358315,0.262175,0.262185,0.0662733,0.152491,0.152494,0.134174,8.2762e-09,8.28258e-09,7.12164e-09,2.47122e-06,2.47117e-06,3.97587e-07,0,0,0,0,0,0,0,0 -6688000,0.98335,-0.00693603,-0.0124281,0.181165,-0.00538792,0.0104073,-0.0731926,-0.000355397,0.00451334,-0.0582219,-1.22102e-05,-4.71739e-05,-2.47076e-06,-1.26505e-05,1.51305e-05,-0.000934855,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.1665e-05,0.00039875,0.000398782,0.000351297,0.206289,0.206296,0.0637685,0.114676,0.114677,0.131706,6.72244e-09,6.7275e-09,6.78392e-09,2.46973e-06,2.46967e-06,3.73024e-07,0,0,0,0,0,0,0,0 -6792000,0.983319,-0.00696208,-0.0123916,0.181335,-0.00309373,0.0123023,-0.0710562,-0.000806742,0.00567063,-0.0597774,-1.22276e-05,-4.71587e-05,-3.24779e-06,-1.27071e-05,1.52483e-05,-0.000941682,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.14911e-05,0.000417269,0.000417306,0.000345823,0.237789,0.237798,0.0616402,0.145111,0.145113,0.130494,6.72236e-09,6.72743e-09,6.46799e-09,2.46974e-06,2.46967e-06,3.5008e-07,0,0,0,0,0,0,0,0 -6888000,0.983307,-0.0068532,-0.0122729,0.181409,-0.00293761,0.00870453,-0.0655418,-0.000734184,0.00423203,-0.0560634,-1.19043e-05,-4.72236e-05,-3.63681e-06,-1.28807e-05,1.50934e-05,-0.000953258,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.12606e-05,0.000358336,0.000358361,0.000339271,0.187981,0.187986,0.0593059,0.109936,0.109937,0.128085,5.48348e-09,5.48748e-09,6.17058e-09,2.46846e-06,2.46839e-06,3.28647e-07,0,0,0,0,0,0,0,0 -6992000,0.983306,-0.00682296,-0.012215,0.18142,-0.00362043,0.0098211,-0.0627092,-0.00111285,0.00518682,-0.0550688,-1.19085e-05,-4.72215e-05,-3.76095e-06,-1.2954e-05,1.52248e-05,-0.000961684,0.203491,1.11759e-08,0.43426,0,0,0,0,0,1.10987e-05,0.000373892,0.00037392,0.000334155,0.215906,0.215912,0.0573203,0.138254,0.138256,0.126878,5.48342e-09,5.48742e-09,5.89176e-09,2.46846e-06,2.46839e-06,3.08645e-07,0,0,0,0,0,0,0,0 -7088000,0.9831,-0.00679114,-0.0121447,0.182541,-0.00374599,0.0112354,-0.0625641,-0.000991961,0.00410209,-0.0572127,-1.16226e-05,-4.72599e-05,-3.91456e-06,-1.30276e-05,1.49841e-05,-0.000965825,0.204748,1.44355e-08,0.43476,0,0,0,0,0,7.56093e-05,0.000319438,0.000319258,0.00219372,0.162812,0.162817,0.0551549,0.105416,0.105417,0.124537,4.49279e-09,4.49593e-09,5.75789e-09,2.46736e-06,2.46729e-06,2.89975e-07,0,0,0,0,0,0,0,0 -7192000,0.983041,-0.00672381,-0.012217,0.182853,-0.00442043,0.0122631,-0.059095,-0.00146287,0.00539751,-0.0557166,-1.16243e-05,-4.72604e-05,-3.91576e-06,-1.30946e-05,1.51091e-05,-0.000974104,0.204748,1.44355e-08,0.43476,0,0,0,0,0,5.39017e-05,0.000319728,0.000319606,0.00156335,0.165809,0.165815,0.0533112,0.13036,0.130362,0.123345,4.49285e-09,4.49599e-09,5.75775e-09,2.46737e-06,2.46729e-06,2.7256e-07,0,0,0,0,0,0,0,0 -7288000,0.983027,-0.00671881,-0.0121891,0.182932,-0.00283781,0.012951,-0.0564522,-0.00122955,0.00437323,-0.0533409,-1.1346e-05,-4.72858e-05,-3.92313e-06,-1.31726e-05,1.50207e-05,-0.000982229,0.204748,1.44355e-08,0.43476,0,0,0,0,0,4.43601e-05,0.000320006,0.000319914,0.00128657,0.123867,0.123871,0.0524743,0.0990724,0.0990733,0.124893,3.7244e-09,3.72687e-09,5.75694e-09,2.46694e-06,2.46686e-06,2.60248e-07,0,0,0,0,0,0,0,0 -7392000,0.983133,-0.00664277,-0.0121604,0.182367,-0.00413339,0.0149596,-0.0535805,-0.00157575,0.0058936,-0.0498268,-1.13471e-05,-4.72868e-05,-3.89618e-06,-1.32437e-05,1.51566e-05,-0.000991425,0.204748,1.44355e-08,0.43476,0,0,0,0,0,3.59031e-05,0.00032083,0.000320762,0.00104123,0.134331,0.134336,0.0507205,0.11973,0.119732,0.123648,3.72445e-09,3.72692e-09,5.75603e-09,2.46694e-06,2.46686e-06,2.44829e-07,0,0,0,0,0,0,0,0 -7488000,0.983215,-0.00665917,-0.0121512,0.181922,-0.00215375,0.0153869,-0.0469737,-0.00124471,0.00497028,-0.0427419,-1.10748e-05,-4.73178e-05,-3.84937e-06,-1.33157e-05,1.54358e-05,-0.00100307,0.204748,1.44355e-08,0.43476,0,0,0,0,0,3.01908e-05,0.000319927,0.000319876,0.00087484,0.111892,0.111896,0.0488251,0.0922028,0.0922037,0.121356,3.15365e-09,3.15563e-09,5.75412e-09,2.46685e-06,2.46677e-06,2.30443e-07,0,0,0,0,0,0,0,0 -7592000,0.983236,-0.00674809,-0.0120931,0.181813,-0.00187603,0.0166105,-0.0432337,-0.00145092,0.00659235,-0.0372017,-1.10762e-05,-4.73185e-05,-3.83331e-06,-1.33932e-05,1.55798e-05,-0.00101288,0.204748,1.44355e-08,0.43476,0,0,0,0,0,2.6067e-05,0.000320916,0.000320881,0.000754859,0.128826,0.128831,0.0472083,0.110204,0.110205,0.120144,3.1537e-09,3.15568e-09,5.7518e-09,2.46686e-06,2.46677e-06,2.17025e-07,0,0,0,0,0,0,0,0 -7688000,0.98323,-0.00678386,-0.0121456,0.181841,-0.00144002,0.0170539,-0.0425201,-0.00110466,0.00568952,-0.0322686,-1.08119e-05,-4.73623e-05,-3.85004e-06,-1.33453e-05,1.63599e-05,-0.00102132,0.204748,1.44355e-08,0.43476,0,0,0,0,0,2.29397e-05,0.00031666,0.000316633,0.00066422,0.117643,0.117647,0.0454653,0.0865958,0.0865966,0.117939,2.73547e-09,2.73708e-09,5.74832e-09,2.46431e-06,2.46422e-06,2.04504e-07,0,0,0,0,0,0,0,0 -7792000,0.98321,-0.00666984,-0.0121542,0.181952,-0.000345024,0.0178059,-0.0436474,-0.00122319,0.00742459,-0.0368946,-1.08122e-05,-4.7362e-05,-3.86643e-06,-1.33435e-05,1.63577e-05,-0.00102111,0.204748,1.44355e-08,0.43476,0,0,0,0,0,2.05203e-05,0.000317534,0.000317513,0.000593615,0.140042,0.140048,0.0439782,0.103578,0.103579,0.116762,2.73552e-09,2.73713e-09,5.7441e-09,2.46431e-06,2.46422e-06,1.9282e-07,0,0,0,0,0,0,0,0 -7888000,0.983187,-0.00674925,-0.0122011,0.182067,-0.00119988,0.0177557,-0.0435075,-0.000959428,0.00632363,-0.0390792,-1.05608e-05,-4.74157e-05,-3.87526e-06,-1.30466e-05,1.77915e-05,-0.00102285,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.90578e-05,0.000307637,0.000307619,0.000550529,0.13345,0.133456,0.04329,0.0830278,0.0830286,0.118057,2.43555e-09,2.43689e-09,5.74001e-09,2.45489e-06,2.45481e-06,1.84566e-07,0,0,0,0,0,0,0,0 -7992000,0.983199,-0.00671699,-0.0121096,0.182013,-0.00113421,0.0185723,-0.0406583,-0.00110237,0.00813719,-0.0381069,-1.05606e-05,-4.74165e-05,-3.83246e-06,-1.30922e-05,1.7858e-05,-0.00102755,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.74047e-05,0.000308201,0.000308189,0.000502131,0.160072,0.160079,0.0418857,0.100338,0.100339,0.116852,2.4356e-09,2.43694e-09,5.73372e-09,2.4549e-06,2.45481e-06,1.74208e-07,0,0,0,0,0,0,0,0 -8088000,0.983156,-0.00670238,-0.0120913,0.182245,0.000122234,0.0179084,-0.0388318,-0.000771923,0.00682105,-0.0369306,-1.03371e-05,-4.74714e-05,-3.94565e-06,-1.25444e-05,2.02039e-05,-0.00103179,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.60087e-05,0.000291068,0.000291058,0.000461938,0.152609,0.152616,0.0403778,0.0816085,0.0816094,0.114728,2.23126e-09,2.23242e-09,5.72596e-09,2.43409e-06,2.434e-06,1.64529e-07,0,0,0,0,0,0,0,0 -8192000,0.983132,-0.00677879,-0.0119967,0.18238,0.00031559,0.021944,-0.0341845,-0.000749536,0.0089346,-0.0305119,-1.03393e-05,-4.74697e-05,-4.00808e-06,-1.26448e-05,2.0333e-05,-0.00104042,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.48552e-05,0.000291235,0.000291231,0.000428415,0.181907,0.181916,0.0390898,0.100146,0.100147,0.113568,2.23131e-09,2.23247e-09,5.71689e-09,2.43409e-06,2.43401e-06,1.55493e-07,0,0,0,0,0,0,0,0 -8288000,0.983141,-0.00686592,-0.0119476,0.182331,0.00257313,0.0199633,-0.0319028,-0.000420208,0.00746257,-0.0295677,-1.01439e-05,-4.75316e-05,-4.00305e-06,-1.16414e-05,2.36151e-05,-0.00104368,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.38552e-05,0.000266949,0.000266947,0.000399763,0.169029,0.169037,0.0377074,0.0819086,0.0819096,0.111536,2.10487e-09,2.10592e-09,5.70617e-09,2.39935e-06,2.39926e-06,1.47035e-07,0,0,0,0,0,0,0,0 -8392000,0.983145,-0.00682623,-0.0119336,0.182313,-0.000212436,0.0199414,-0.0310215,-0.000303232,0.00949681,-0.0281183,-1.01437e-05,-4.75318e-05,-3.98153e-06,-1.16893e-05,2.36695e-05,-0.00104742,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.30191e-05,0.00026675,0.00026675,0.000375443,0.199132,0.19914,0.0365261,0.102011,0.102013,0.110422,2.10492e-09,2.10597e-09,5.69388e-09,2.39935e-06,2.39927e-06,1.39142e-07,0,0,0,0,0,0,0,0 -8488000,0.983165,-0.0067489,-0.0119133,0.182208,-0.00117332,0.0226401,-0.0308335,-0.000342163,0.0114938,-0.0310515,-1.01412e-05,-4.75343e-05,-3.86079e-06,-1.16881e-05,2.36639e-05,-0.00104744,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.24966e-05,0.000266726,0.000266727,0.000360062,0.229375,0.229385,0.0359767,0.125597,0.1256,0.111528,2.10497e-09,2.10601e-09,5.68354e-09,2.39935e-06,2.39927e-06,1.33563e-07,0,0,0,0,0,0,0,0 -8592000,0.983181,-0.00685436,-0.0119899,0.182109,-0.000341642,0.019544,-0.0248419,-0.000330086,0.00959499,-0.0253092,-9.99353e-06,-4.75854e-05,-3.82686e-06,-1.04137e-05,2.767e-05,-0.00105394,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.18347e-05,0.000237092,0.000237091,0.00034127,0.207112,0.20712,0.0348645,0.104554,0.104556,0.110399,2.03791e-09,2.0389e-09,5.66805e-09,2.35184e-06,2.35176e-06,1.26519e-07,0,0,0,0,0,0,0,0 -8688000,0.983206,-0.00690921,-0.0120352,0.181973,-0.00119619,0.019349,-0.026746,-0.000437936,0.0114462,-0.0273581,-9.99187e-06,-4.7587e-05,-3.74509e-06,-1.04149e-05,2.76704e-05,-0.00105422,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.12538e-05,0.000236844,0.000236844,0.000324595,0.235976,0.235985,0.0336729,0.129589,0.129592,0.108461,2.03795e-09,2.03894e-09,5.6507e-09,2.35184e-06,2.35176e-06,1.19946e-07,0,0,0,0,0,0,0,0 -8792000,0.983203,-0.00700568,-0.0119804,0.181988,-0.000337869,0.0152719,-0.0268194,-0.000434907,0.00896467,-0.0242826,-9.89757e-06,-4.76177e-05,-3.78803e-06,-9.0465e-06,3.19694e-05,-0.0010584,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.07484e-05,0.000206109,0.000206109,0.000310265,0.204596,0.204603,0.0326537,0.106469,0.106471,0.107382,2.01006e-09,2.01102e-09,5.63131e-09,2.29639e-06,2.2963e-06,1.13764e-07,0,0,0,0,0,0,0,0 -8888000,0.983239,-0.00709638,-0.0119756,0.181788,-0.00107545,0.0165886,-0.0225215,-0.000490339,0.0104999,-0.0177418,-9.89301e-06,-4.76214e-05,-3.57392e-06,-9.15645e-06,3.20602e-05,-0.00106474,0.204748,1.44355e-08,0.43476,0,0,0,0,0,1.0302e-05,0.000205814,0.000205816,0.000297342,0.230582,0.230589,0.0315614,0.132103,0.132105,0.105532,2.0101e-09,2.01106e-09,5.60987e-09,2.29639e-06,2.29631e-06,1.07999e-07,0,0,0,0,0,0,0,0 -8992000,0.983281,-0.00714044,-0.0118672,0.181568,-0.0024694,0.0133851,-0.0200297,-0.000541679,0.00799755,-0.0185715,-9.84106e-06,-4.76426e-05,-3.25702e-06,-7.85457e-06,3.60231e-05,-0.00106561,0.204748,1.44355e-08,0.43476,0,0,0,0,0,9.91499e-06,0.000177579,0.000177579,0.00028625,0.192844,0.192849,0.0306271,0.106949,0.10695,0.104502,2.00271e-09,2.00366e-09,5.58628e-09,2.23938e-06,2.2393e-06,1.02566e-07,0,0,0,0,0,0,0,0 -9088000,0.983324,-0.00715471,-0.0119317,0.181329,-0.00222525,0.0147393,-0.0223033,-0.000770496,0.00930853,-0.0213934,-9.83607e-06,-4.76477e-05,-3.0146e-06,-7.83676e-06,3.60034e-05,-0.00106507,0.204748,1.44355e-08,0.43476,0,0,0,0,0,9.68133e-06,0.000177414,0.000177413,0.000279657,0.215259,0.215266,0.0301941,0.132235,0.132237,0.105464,2.00275e-09,2.0037e-09,5.56719e-09,2.23938e-06,2.2393e-06,9.87429e-08,0,0,0,0,0,0,0,0 -9192000,0.983362,-0.0072165,-0.0119614,0.181117,0.000780427,0.0106369,-0.0202654,-0.000539376,0.00704868,-0.0207888,-9.82063e-06,-4.76555e-05,-2.75413e-06,-6.8654e-06,3.95025e-05,-0.00106688,0.204748,1.44355e-08,0.43476,0,0,0,0,0,9.36526e-06,0.00015396,0.000153957,0.000270785,0.175287,0.175292,0.0293151,0.105795,0.105796,0.104428,2.00236e-09,2.00332e-09,5.5397e-09,2.18623e-06,2.18615e-06,9.38842e-08,0,0,0,0,0,0,0,0 -9288000,0.98339,-0.00711484,-0.0118077,0.180983,0.00200496,0.0107766,-0.0175024,-0.000359606,0.00803309,-0.0167811,-9.81549e-06,-4.76597e-05,-2.52409e-06,-6.94239e-06,3.95605e-05,-0.00107065,0.204748,1.44355e-08,0.43476,0,0,0,0,0,9.08127e-06,0.000154055,0.000154053,0.000262537,0.193903,0.193907,0.0283728,0.129965,0.129966,0.102672,2.0024e-09,2.00335e-09,5.50993e-09,2.18623e-06,2.18615e-06,8.93517e-08,0,0,0,0,0,0,0,0 -9392000,0.98338,-0.00707733,-0.0118266,0.181033,0.00194962,0.00696059,-0.0162489,-2.91125e-05,0.0058886,-0.0172093,-9.8284e-06,-4.7654e-05,-2.60592e-06,-6.00556e-06,4.23238e-05,-0.00107145,0.204748,1.44355e-08,0.43476,0,0,0,0,0,8.8353e-06,0.000136096,0.000136092,0.000255593,0.155153,0.155156,0.0275667,0.103248,0.103249,0.101684,2.00166e-09,2.00261e-09,5.47783e-09,2.14006e-06,2.13998e-06,8.50697e-08,0,0,0,0,0,0,0,0 -9488000,0.983412,-0.00712247,-0.0119086,0.180855,0.00140065,0.00645902,-0.0136375,0.000119798,0.00650773,-0.0137922,-9.8235e-06,-4.76579e-05,-2.38939e-06,-6.07342e-06,4.23729e-05,-0.00107447,0.204748,1.44355e-08,0.43476,0,0,0,0,0,8.60311e-06,0.000136538,0.000136534,0.000249025,0.170269,0.170271,0.0267013,0.125804,0.125805,0.100009,2.00169e-09,2.00265e-09,5.44338e-09,2.14006e-06,2.13998e-06,8.10715e-08,0,0,0,0,0,0,0,0 -9592000,0.98337,-0.00723743,-0.0118929,0.181081,0.00102456,0.00264919,-0.0126527,9.20216e-05,0.00451462,-0.0145697,-9.84888e-06,-4.76443e-05,-2.67564e-06,-5.28271e-06,4.43601e-05,-0.00107477,0.204748,1.44355e-08,0.43476,0,0,0,0,0,8.41676e-06,0.000123695,0.000123691,0.000243583,0.134959,0.134961,0.0259615,0.0997268,0.0997275,0.099068,1.99803e-09,1.99898e-09,5.40657e-09,2.10189e-06,2.10181e-06,7.72914e-08,0,0,0,0,0,0,0,0 -9688000,0.983382,-0.00723798,-0.0118239,0.18102,0.000552483,0.00146553,-0.00949142,0.000245994,0.00479337,-0.0124804,-9.84841e-06,-4.7644e-05,-2.66914e-06,-5.33406e-06,4.43993e-05,-0.00107669,0.204748,1.44355e-08,0.43476,0,0,0,0,0,8.22899e-06,0.000124521,0.000124518,0.000238332,0.147056,0.147057,0.0251663,0.12043,0.120431,0.0974698,1.99806e-09,1.99901e-09,5.36739e-09,2.1019e-06,2.10182e-06,7.37573e-08,0,0,0,0,0,0,0,0 -9792000,0.983356,-0.00723882,-0.011775,0.181163,0.00106326,-0.000191512,-0.00974566,0.000238006,0.00318446,-0.0120308,-9.87315e-06,-4.76292e-05,-2.98396e-06,-4.79704e-06,4.56888e-05,-0.00107759,0.204748,1.44355e-08,0.43476,0,0,0,0,0,8.07732e-06,0.000115916,0.000115912,0.000234095,0.116209,0.11621,0.0244869,0.0956393,0.0956396,0.0965734,1.99162e-09,1.99257e-09,5.32585e-09,2.07135e-06,2.07127e-06,7.0414e-08,0,0,0,0,0,0,0,0 -9888000,0.983373,-0.00723202,-0.0117536,0.18107,0.00209535,-0.00138986,-0.00871594,0.000351116,0.00301697,-0.0137486,-9.86766e-06,-4.76347e-05,-2.71584e-06,-4.77815e-06,4.56684e-05,-0.00107711,0.204748,1.44355e-08,0.43476,0,0,0,0,0,8.01856e-06,0.000117137,0.000117133,0.000232343,0.125855,0.125856,0.0241733,0.114446,0.114447,0.0973775,1.99166e-09,1.9926e-09,5.29312e-09,2.07136e-06,2.07128e-06,6.80469e-08,0,0,0,0,0,0,0,0 -9992000,0.983343,-0.00727715,-0.0118113,0.181232,0.00328353,-0.00382457,-0.00774245,0.000441956,0.00173885,-0.0148189,-9.88455e-06,-4.76228e-05,-2.97524e-06,-4.40691e-06,4.63012e-05,-0.00107701,0.204748,1.44355e-08,0.43476,0,0,0,0,0,7.90353e-06,0.000111809,0.000111805,0.000228989,0.0996043,0.0996052,0.0235337,0.0913073,0.0913076,0.0964816,1.98371e-09,1.98464e-09,5.24751e-09,2.04746e-06,2.04737e-06,6.50401e-08,0,0,0,0,0,0,0,0 -10088000,0.983327,-0.00723117,-0.0119424,0.181309,0.00184801,-0.00683329,-0.00665995,0.000701081,0.00117931,-0.0126147,-9.89011e-06,-4.76166e-05,-3.25992e-06,-4.46112e-06,4.63478e-05,-0.00107862,0.204748,1.44355e-08,0.43476,0,0,0,0,0,7.78017e-06,0.000113417,0.000113411,0.000225554,0.107328,0.107328,0.0228446,0.108292,0.108292,0.0949688,1.98373e-09,1.98467e-09,5.1996e-09,2.04746e-06,2.04738e-06,6.22203e-08,0,0,0,0,0,0,0,0 -10192000,0.983296,-0.00722046,-0.0118555,0.181483,-0.00068218,-0.00716568,-0.00529454,0.000509345,0.000245868,-0.0133777,-9.89973e-06,-4.76046e-05,-3.63699e-06,-4.24839e-06,4.64431e-05,-0.00107857,0.204748,1.44355e-08,0.43476,0,0,0,0,0,7.68997e-06,0.000110529,0.000110523,0.000222992,0.0853811,0.0853814,0.0222565,0.086955,0.0869551,0.0941162,1.97568e-09,1.97661e-09,5.14946e-09,2.02905e-06,2.02897e-06,5.95509e-08,0,0,0,0,0,0,0,0 -10288000,0.983328,-0.00725904,-0.0117772,0.181314,-0.000140646,-0.00772389,-0.00574423,0.000445843,-0.00051915,-0.0118324,-9.89369e-06,-4.76097e-05,-3.36106e-06,-4.28124e-06,4.64585e-05,-0.00107967,0.204748,1.44355e-08,0.43476,0,0,0,0,0,7.58952e-06,0.000112508,0.000112503,0.000220245,0.0916372,0.0916377,0.0216216,0.102259,0.102259,0.092672,1.97571e-09,1.97664e-09,5.09715e-09,2.02905e-06,2.02897e-06,5.70435e-08,0,0,0,0,0,0,0,0 -10392000,0.982994,-0.00724183,-0.0116976,0.183121,0.00691907,0.00130545,-0.00247622,0.000810475,-1.26166e-05,-0.010229,-9.89339e-06,-4.76094e-05,-3.35877e-06,-4.31255e-06,4.64797e-05,-0.00108059,0.205039,0.000821555,0.434373,0,0,0,0,0,6.19791e-05,0.000113329,0.000113189,0.00177558,0.0350672,0.0350672,0.0374384,0.125319,0.125319,0.085676,1.97576e-09,1.9767e-09,5.09716e-09,2.02905e-06,2.02897e-06,5.48327e-08,0,0,0,0,0,0,0,0 -10488000,0.982895,-0.00715067,-0.0116477,0.183658,0.00730255,-0.000692935,-0.00135946,0.00148421,-3.80128e-06,-0.00765561,-9.89316e-06,-4.76087e-05,-3.36751e-06,-4.36246e-06,4.65137e-05,-0.00108204,0.205039,0.000821555,0.434373,0,0,0,0,0,4.97779e-05,0.000113511,0.000113401,0.00142649,0.0370056,0.0370056,0.0375232,0.12629,0.12629,0.0815567,1.97581e-09,1.97674e-09,5.09704e-09,2.02906e-06,2.02898e-06,5.34067e-08,0,0,0,0,0,0,0,0 -10592000,0.983025,-0.00711547,-0.0115704,0.182966,0.00479634,-0.00217594,-0.000192218,0.00112096,-0.00375276,-0.00397274,-9.8854e-06,-4.75921e-05,-3.33553e-06,-1.67679e-06,4.54738e-05,-0.00108391,0.205039,0.000821555,0.434373,0,0,0,0,0,3.94958e-05,0.000113312,0.000113229,0.00113048,0.0353711,0.0353711,0.0352268,0.0849825,0.0849825,0.0770606,1.97559e-09,1.97652e-09,5.09657e-09,2.02148e-06,2.0214e-06,5.1744e-08,0,0,0,0,0,0,0,0 -10688000,0.983045,-0.00707203,-0.0115877,0.182862,0.00585968,-0.00469892,-0.000224791,0.00165523,-0.00406956,-0.00283772,-9.88524e-06,-4.75918e-05,-3.33575e-06,-1.69752e-06,4.54874e-05,-0.00108449,0.205039,0.000821555,0.434373,0,0,0,0,0,3.27099e-05,0.000113819,0.000113751,0.000936584,0.0397889,0.0397887,0.0352034,0.0867792,0.0867792,0.0737234,1.97564e-09,1.97657e-09,5.09566e-09,2.02148e-06,2.0214e-06,5.0316e-08,0,0,0,0,0,0,0,0 -10792000,0.983059,-0.00707775,-0.0117064,0.182776,0.00572264,-0.00687288,0.000186615,0.00150485,-0.00380801,-0.000250152,-9.88843e-06,-4.75789e-05,-3.32922e-06,6.19337e-07,4.62304e-05,-0.00108578,0.205039,0.000821555,0.434373,0,0,0,0,0,2.7931e-05,0.000112414,0.000112355,0.000799933,0.039463,0.0394628,0.0330585,0.0660561,0.0660561,0.0711521,1.9749e-09,1.97583e-09,5.09419e-09,1.99334e-06,1.99327e-06,5.00004e-08,0,0,0,0,0,0,0,0 -10888000,0.983165,-0.00705348,-0.011732,0.182206,0.0056261,-0.00750871,-0.000523923,0.0020201,-0.00454021,-0.00147128,-9.88657e-06,-4.75811e-05,-3.23109e-06,6.38162e-07,4.62153e-05,-0.00108521,0.205039,0.000821555,0.434373,0,0,0,0,0,2.44138e-05,0.000113245,0.000113194,0.000698401,0.0458773,0.0458771,0.032893,0.0686696,0.0686696,0.0694352,1.97494e-09,1.97588e-09,5.09206e-09,1.99335e-06,1.99327e-06,5e-08,0,0,0,0,0,0,0,0 -10992000,0.983135,-0.00702377,-0.01182,0.182366,0.00372381,-0.0023611,0.0022348,0.00174288,-0.00361644,0.00344486,-9.8692e-06,-4.75754e-05,-3.26907e-06,1.44195e-06,4.23025e-05,-0.00108718,0.205039,0.000821555,0.434373,0,0,0,0,0,2.16836e-05,0.000110237,0.000110191,0.000620286,0.0451808,0.0451809,0.030867,0.0559893,0.0559893,0.0679688,1.97398e-09,1.97492e-09,5.08918e-09,1.94016e-06,1.94009e-06,5e-08,0,0,0,0,0,0,0,0 -11088000,0.983059,-0.00714137,-0.0117902,0.182768,0.00391917,-0.000352093,0.00411294,0.00207126,-0.00381221,0.00644588,-9.87071e-06,-4.75731e-05,-3.35966e-06,1.4007e-06,4.23301e-05,-0.00108833,0.205039,0.000821555,0.434373,0,0,0,0,0,2.00386e-05,0.000111395,0.000111355,0.000572931,0.0529824,0.0529829,0.0306788,0.0594925,0.0594925,0.0684158,1.97403e-09,1.97497e-09,5.08648e-09,1.94016e-06,1.94009e-06,5.00008e-08,0,0,0,0,0,0,0,0 -11192000,0.983008,-0.00717103,-0.0117806,0.183046,0.00404397,0.00197317,0.00752938,0.00263251,-0.00299789,0.00944308,-9.87323e-06,-4.75787e-05,-3.46363e-06,-1.28995e-06,4.27626e-05,-0.00108891,0.205039,0.000821555,0.434373,0,0,0,0,0,1.81764e-05,0.000107033,0.000106999,0.000520196,0.0506109,0.0506115,0.0287777,0.0505381,0.0505381,0.0675465,1.9733e-09,1.97423e-09,5.08205e-09,1.86633e-06,1.86625e-06,5.00008e-08,0,0,0,0,0,0,0,0 -11288000,0.982991,-0.00718269,-0.0118103,0.183131,0.00342573,0.001008,0.00784805,0.00296661,-0.00280513,0.0100188,-9.87366e-06,-4.75783e-05,-3.48354e-06,-1.28711e-06,4.2762e-05,-0.00108886,0.205039,0.000821555,0.434373,0,0,0,0,0,1.66657e-05,0.000108514,0.000108483,0.000476663,0.059154,0.0591548,0.0283726,0.0549469,0.0549469,0.0674521,1.97335e-09,1.97428e-09,5.07661e-09,1.86633e-06,1.86626e-06,5.00004e-08,0,0,0,0,0,0,0,0 -11392000,0.983002,-0.00706943,-0.0118039,0.183077,0.00150892,0.00153351,0.00608984,0.00234038,-0.00224161,0.00715266,-9.87126e-06,-4.75749e-05,-3.46754e-06,9.00545e-07,4.199e-05,-0.00108755,0.205039,0.000821555,0.434373,0,0,0,0,0,1.53983e-05,0.00010347,0.000103441,0.000440495,0.0545146,0.0545152,0.0265919,0.0477357,0.0477358,0.0669264,1.97305e-09,1.97399e-09,5.07006e-09,1.78206e-06,1.78199e-06,5.00004e-08,0,0,0,0,0,0,0,0 -11488000,0.983021,-0.00704128,-0.0117786,0.182978,-0.000545596,-0.000283806,0.00809933,0.00232145,-0.00214454,0.0108546,-9.87064e-06,-4.75746e-05,-3.45501e-06,8.56454e-07,4.2013e-05,-0.00108859,0.205039,0.000821555,0.434373,0,0,0,0,0,1.43159e-05,0.000105265,0.000105239,0.000409738,0.0632077,0.0632084,0.0260951,0.0529701,0.0529702,0.0671875,1.9731e-09,1.97403e-09,5.06233e-09,1.78207e-06,1.782e-06,5e-08,0,0,0,0,0,0,0,0 -11592000,0.98301,-0.0070966,-0.0117748,0.183039,0.00123247,2.32839e-05,0.00845421,0.00199917,-0.00175913,0.0112184,-9.8701e-06,-4.75737e-05,-3.49594e-06,9.33521e-07,4.16093e-05,-0.00108891,0.205039,0.000821555,0.434373,0,0,0,0,0,1.34028e-05,0.000100264,0.00010024,0.000383646,0.056412,0.0564127,0.024446,0.0464623,0.0464624,0.0668169,1.97306e-09,1.974e-09,5.05332e-09,1.69829e-06,1.69823e-06,5e-08,0,0,0,0,0,0,0,0 -11688000,0.983006,-0.0070382,-0.0117549,0.18306,0.0014185,0.000802582,0.0102585,0.00214093,-0.00173827,0.0119023,-9.86956e-06,-4.75743e-05,-3.46842e-06,9.36352e-07,4.16069e-05,-0.00108882,0.205039,0.000821555,0.434373,0,0,0,0,0,1.28322e-05,0.00010236,0.000102338,0.000367035,0.0648224,0.0648235,0.0240685,0.0523661,0.0523662,0.0684011,1.97311e-09,1.97404e-09,5.0457e-09,1.69829e-06,1.69823e-06,5.00012e-08,0,0,0,0,0,0,0,0 -11792000,0.983046,-0.00711998,-0.0117367,0.182843,0.000164609,0.000698394,0.0111993,0.00166343,-0.00266288,0.0132191,-9.85532e-06,-4.75818e-05,-3.29907e-06,3.58014e-06,4.59026e-05,-0.00108886,0.205039,0.000821555,0.434373,0,0,0,0,0,1.21318e-05,9.79376e-05,9.7917e-05,0.000346898,0.0565029,0.0565038,0.0225569,0.0460258,0.0460259,0.0680605,1.97281e-09,1.97374e-09,5.03426e-09,1.62277e-06,1.62271e-06,5.00012e-08,0,0,0,0,0,0,0,0 -11888000,0.983046,-0.00719671,-0.0116704,0.182848,0.00163308,0.00125707,0.0103302,0.00172318,-0.00259784,0.0140942,-9.8561e-06,-4.75811e-05,-3.33582e-06,3.58291e-06,4.59021e-05,-0.0010888,0.205039,0.000821555,0.434373,0,0,0,0,0,1.15062e-05,0.000100316,0.000100298,0.000329102,0.0644046,0.0644059,0.0219833,0.0524146,0.0524147,0.0685508,1.97285e-09,1.97379e-09,5.02133e-09,1.62277e-06,1.62271e-06,5.00008e-08,0,0,0,0,0,0,0,0 -11992000,0.983043,-0.00722295,-0.0117489,0.182858,0.00370756,0.00395249,0.0104995,0.00269898,-0.00264725,0.0143062,-9.8686e-06,-4.75582e-05,-3.36278e-06,-8.81963e-08,4.51572e-05,-0.00108871,0.205039,0.000821555,0.434373,0,0,0,0,0,1.09666e-05,9.67227e-05,9.67064e-05,0.000313751,0.055279,0.0552801,0.0206144,0.0460032,0.0460033,0.0681862,1.97157e-09,1.97251e-09,5.00684e-09,1.55928e-06,1.55922e-06,5.00008e-08,0,0,0,0,0,0,0,0 -12088000,0.983017,-0.00714486,-0.0118008,0.182998,0.0044491,0.00353192,0.0129508,0.0030822,-0.0023181,0.0185462,-9.86986e-06,-4.7556e-05,-3.43886e-06,-1.26495e-07,4.51762e-05,-0.00108946,0.205039,0.000821555,0.434373,0,0,0,0,0,1.0493e-05,9.9367e-05,9.93512e-05,0.000299951,0.0625501,0.0625515,0.020037,0.0527016,0.0527018,0.0686346,1.97161e-09,1.97255e-09,4.99071e-09,1.55928e-06,1.55922e-06,5.00004e-08,0,0,0,0,0,0,0,0 -12192000,0.982999,-0.00702303,-0.0118002,0.183099,0.00473572,0.00395834,0.0123347,0.00247346,-0.000612456,0.0207811,-9.89853e-06,-4.75578e-05,-3.60215e-06,8.44707e-07,4.15803e-05,-0.00108978,0.205039,0.000821555,0.434373,0,0,0,0,0,1.00697e-05,9.66514e-05,9.66359e-05,0.000288047,0.053245,0.0532461,0.018812,0.0461497,0.0461498,0.068213,1.96855e-09,1.96949e-09,4.9729e-09,1.50845e-06,1.5084e-06,5.00004e-08,0,0,0,0,0,0,0,0 -12288000,0.982979,-0.00706975,-0.0117765,0.183202,0.00229211,0.0031295,0.0111966,0.00282271,-0.000258239,0.0215819,-9.90143e-06,-4.75552e-05,-3.74005e-06,8.49025e-07,4.15816e-05,-0.00108971,0.205039,0.000821555,0.434373,0,0,0,0,0,9.68939e-06,9.95443e-05,9.95306e-05,0.000277188,0.059908,0.0599092,0.0182528,0.0530122,0.0530124,0.0685717,1.96859e-09,1.96953e-09,4.95335e-09,1.50846e-06,1.5084e-06,5e-08,0,0,0,0,0,0,0,0 -12392000,0.982973,-0.00710607,-0.0117256,0.18324,0.00125852,0.00133699,0.0111795,0.00229414,-0.000374551,0.0195278,-9.89487e-06,-4.75659e-05,-3.84295e-06,2.17129e-06,4.20542e-05,-0.00108913,0.205039,0.000821555,0.434373,0,0,0,0,0,9.35773e-06,9.76159e-05,9.76034e-05,0.000267846,0.0508211,0.0508219,0.0171686,0.0463308,0.0463309,0.0680814,1.96291e-09,1.96384e-09,4.932e-09,1.46928e-06,1.46923e-06,5e-08,0,0,0,0,0,0,0,0 -12488000,0.982951,-0.00711278,-0.0117216,0.183354,0.00144432,0.00201304,0.014493,0.00242248,-0.000233502,0.0208246,-9.89569e-06,-4.75651e-05,-3.88257e-06,2.17089e-06,4.20552e-05,-0.00108914,0.205039,0.000821555,0.434373,0,0,0,0,0,9.17417e-06,0.000100743,0.000100731,0.000262321,0.0569022,0.0569033,0.0168163,0.0532464,0.0532465,0.0695225,1.96295e-09,1.96388e-09,4.91477e-09,1.46928e-06,1.46923e-06,5.00008e-08,0,0,0,0,0,0,0,0 -12592000,0.982923,-0.00715319,-0.0116616,0.18351,0.0047268,-0.0019112,0.0158837,0.0035587,-0.00183878,0.0234291,-9.81959e-06,-4.75375e-05,-4.01299e-06,1.22125e-06,4.58677e-05,-0.00108922,0.205039,0.000821555,0.434373,0,0,0,0,0,8.91569e-06,9.94724e-05,9.94619e-05,0.000254758,0.0483012,0.048302,0.0158577,0.0464805,0.0464806,0.0689455,1.95381e-09,1.95474e-09,4.89019e-09,1.43994e-06,1.4399e-06,5.00008e-08,0,0,0,0,0,0,0,0 -12688000,0.982918,-0.00710375,-0.011668,0.183538,0.00486069,-0.00328238,0.0158572,0.00397605,-0.00208992,0.0251243,-9.82082e-06,-4.75363e-05,-4.07334e-06,1.21903e-06,4.58698e-05,-0.00108925,0.205039,0.000821555,0.434373,0,0,0,0,0,8.66712e-06,0.000102818,0.000102808,0.000247664,0.0539173,0.0539183,0.0153791,0.0533719,0.0533721,0.0690854,1.95385e-09,1.95478e-09,4.86372e-09,1.43995e-06,1.4399e-06,5.00004e-08,0,0,0,0,0,0,0,0 -12792000,0.982965,-0.0072084,-0.0115662,0.183289,0.00590228,-0.00544433,0.017113,0.00408505,-0.00445593,0.0275284,-9.67705e-06,-4.74924e-05,-3.75337e-06,1.14943e-06,4.96538e-05,-0.00108927,0.205039,0.000821555,0.434373,0,0,0,0,0,8.45329e-06,0.000102038,0.00010203,0.000241693,0.0459071,0.0459081,0.0145463,0.0465708,0.0465709,0.0684483,1.94035e-09,1.94128e-09,4.83533e-09,1.41863e-06,1.41859e-06,5.00004e-08,0,0,0,0,0,0,0,0 -12888000,0.982998,-0.00722554,-0.0114972,0.183114,0.00568788,-0.00650662,0.0176306,0.00468083,-0.00501818,0.0296823,-9.67277e-06,-4.74963e-05,-3.54945e-06,1.14461e-06,4.96509e-05,-0.00108934,0.205039,0.000821555,0.434373,0,0,0,0,0,8.24915e-06,0.000105585,0.000105578,0.000235986,0.0511322,0.0511333,0.0141193,0.0533879,0.053388,0.0684715,1.94039e-09,1.94132e-09,4.80502e-09,1.41864e-06,1.41859e-06,5e-08,0,0,0,0,0,0,0,0 -12992000,0.983033,-0.0072182,-0.0115063,0.182923,0.00563186,-0.00393141,0.0182836,0.00367173,-0.00385136,0.0320828,-9.73354e-06,-4.75249e-05,-3.33888e-06,2.00295e-06,4.74005e-05,-0.00108946,0.205039,0.000821555,0.434373,0,0,0,0,0,8.07727e-06,0.00010514,0.000105133,0.000231271,0.0437443,0.0437454,0.0134028,0.0465957,0.0465959,0.0677874,1.92165e-09,1.92257e-09,4.77277e-09,1.40363e-06,1.40359e-06,5e-08,0,0,0,0,0,0,0,0 -13088000,0.983044,-0.00721234,-0.0114054,0.182871,0.00642508,-0.00387125,0.0165825,0.00423407,-0.00418052,0.0315556,-9.72958e-06,-4.75294e-05,-3.1355e-06,2.02518e-06,4.73869e-05,-0.00108911,0.205039,0.000821555,0.434373,0,0,0,0,0,8.00452e-06,0.000108872,0.000108866,0.000229047,0.048673,0.0486743,0.0131747,0.0533094,0.0533096,0.068879,1.92169e-09,1.92261e-09,4.74732e-09,1.40364e-06,1.40359e-06,5.00008e-08,0,0,0,0,0,0,0,0 -13192000,0.983052,-0.00721712,-0.011349,0.182832,0.00318966,-0.00464107,0.0161108,0.00137842,-0.00475156,0.033321,-9.70622e-06,-4.76209e-05,-2.92611e-06,4.70704e-06,4.67307e-05,-0.00108916,0.205039,0.000821555,0.434373,0,0,0,0,0,7.87725e-06,0.000108602,0.000108597,0.00022525,0.0418834,0.0418846,0.0125559,0.0465601,0.0465602,0.0681372,1.8968e-09,1.8977e-09,4.71169e-09,1.39348e-06,1.39343e-06,5.00008e-08,0,0,0,0,0,0,0,0 -13288000,0.98305,-0.00724722,-0.0113375,0.182846,0.00317102,-0.00539329,0.0135816,0.0016283,-0.00520108,0.0324872,-9.70836e-06,-4.76198e-05,-3.01508e-06,4.73093e-06,4.67242e-05,-0.00108884,0.205039,0.000821555,0.434373,0,0,0,0,0,7.74207e-06,0.000112498,0.000112494,0.000221454,0.0465944,0.0465958,0.0122381,0.0531576,0.0531578,0.0679689,1.89683e-09,1.89774e-09,4.67416e-09,1.39348e-06,1.39344e-06,5.00004e-08,0,0,0,0,0,0,0,0 -13392000,0.983035,-0.00718643,-0.0114329,0.182922,0.00169803,-0.00347296,0.012866,0.00117573,-0.00400348,0.0332248,-9.78434e-06,-4.76256e-05,-3.24056e-06,4.81352e-06,4.54902e-05,-0.00108873,0.205039,0.000821555,0.434373,0,0,0,0,0,7.63548e-06,0.000112255,0.00011225,0.000218499,0.040345,0.0403462,0.0117154,0.0464745,0.0464746,0.0672077,1.86496e-09,1.86585e-09,4.63473e-09,1.38691e-06,1.38687e-06,5.00004e-08,0,0,0,0,0,0,0,0 -13488000,0.983034,-0.0071551,-0.0114069,0.182928,0.00112441,-0.00192631,0.0129642,0.00129952,-0.00419792,0.0307006,-9.78404e-06,-4.76275e-05,-3.20183e-06,4.8518e-06,4.54754e-05,-0.00108821,0.205039,0.000821555,0.434373,0,0,0,0,0,7.53038e-06,0.000116292,0.000116288,0.000215429,0.0448905,0.0448922,0.0114524,0.0529542,0.0529545,0.0669663,1.86499e-09,1.86588e-09,4.59346e-09,1.38692e-06,1.38688e-06,5e-08,0,0,0,0,0,0,0,0 -13592000,0.983008,-0.00713672,-0.0114468,0.183066,0.00490991,-0.00236169,0.0140159,0.00393894,-0.00343849,0.0296512,-9.7361e-06,-4.74111e-05,-3.3658e-06,3.54396e-06,4.54233e-05,-0.0010878,0.205039,0.000821555,0.434373,0,0,0,0,0,7.45472e-06,0.000115939,0.000115935,0.000213142,0.0391081,0.0391096,0.0110155,0.0463519,0.0463521,0.0661989,1.82549e-09,1.82637e-09,4.55036e-09,1.38287e-06,1.38284e-06,5e-08,0,0,0,0,0,0,0,0 -13688000,0.983036,-0.00706815,-0.0113567,0.182924,0.00447998,-0.00378945,0.0142454,0.00439589,-0.00371812,0.0329119,-9.73228e-06,-4.74139e-05,-3.19359e-06,3.52329e-06,4.5426e-05,-0.00108805,0.205039,0.000821555,0.434373,0,0,0,0,0,7.43446e-06,0.000120091,0.000120087,0.000212737,0.0435661,0.0435677,0.0109213,0.0527202,0.0527204,0.0670121,1.82553e-09,1.82641e-09,4.5169e-09,1.38288e-06,1.38284e-06,5.00008e-08,0,0,0,0,0,0,0,0 -13792000,0.983019,-0.00702345,-0.0114661,0.183011,0.0104053,-0.000995691,0.0150292,0.007732,-0.00156753,0.0318608,-9.79726e-06,-4.70602e-05,-3.38713e-06,2.74621e-06,4.48577e-05,-0.00108756,0.205039,0.000821555,0.434373,0,0,0,0,0,7.37189e-06,0.000119496,0.000119493,0.000210969,0.0381863,0.0381878,0.0105545,0.0462059,0.0462061,0.0662243,1.77794e-09,1.77879e-09,4.47073e-09,1.38048e-06,1.38044e-06,5.00008e-08,0,0,0,0,0,0,0,0 -13888000,0.983028,-0.00694944,-0.0114358,0.182966,0.0109603,-0.000447999,0.0156141,0.00872992,-0.00161892,0.033582,-9.79227e-06,-4.70648e-05,-3.14894e-06,2.73967e-06,4.48525e-05,-0.00108759,0.205039,0.000821555,0.434373,0,0,0,0,0,7.30513e-06,0.000123733,0.00012373,0.000208931,0.0425923,0.0425943,0.0103917,0.0524758,0.052476,0.0658835,1.77797e-09,1.77882e-09,4.42291e-09,1.38048e-06,1.38045e-06,5.00004e-08,0,0,0,0,0,0,0,0 -13992000,0.983039,-0.00698006,-0.0112237,0.182921,0.0107833,0.000650884,0.0147057,0.00699742,-0.00259076,0.0331824,-9.72108e-06,-4.72732e-05,-2.88322e-06,3.37269e-06,4.45376e-05,-0.00108733,0.205039,0.000821555,0.434373,0,0,0,0,0,7.26215e-06,0.000122774,0.000122771,0.000207611,0.037547,0.037549,0.0100927,0.04605,0.0460502,0.0651116,1.72206e-09,1.72288e-09,4.37347e-09,1.37898e-06,1.37895e-06,5.00004e-08,0,0,0,0,0,0,0,0 -14088000,0.982971,-0.00699369,-0.0111726,0.18329,0.0083693,-0.00326511,0.0159177,0.00799619,-0.00274375,0.0305559,-9.73871e-06,-4.72584e-05,-3.70506e-06,3.42857e-06,4.45423e-05,-0.00108679,0.205039,0.000821555,0.434373,0,0,0,0,0,7.20821e-06,0.000127063,0.000127062,0.000205963,0.0419324,0.0419344,0.00997589,0.0522377,0.052238,0.0647466,1.72208e-09,1.72291e-09,4.32251e-09,1.37899e-06,1.37896e-06,5e-08,0,0,0,0,0,0,0,0 -14192000,0.98293,-0.0069674,-0.0111069,0.183514,0.00558676,-0.00167393,0.0157067,0.00753482,-0.00208516,0.0306613,-9.8056e-06,-4.72257e-05,-4.13712e-06,3.93771e-06,4.42836e-05,-0.00108626,0.205039,0.000821555,0.434373,0,0,0,0,0,7.17783e-06,0.000125637,0.000125636,0.000205005,0.0371357,0.0371374,0.00973609,0.0458956,0.0458958,0.0639991,1.658e-09,1.6588e-09,4.27007e-09,1.37777e-06,1.37774e-06,5e-08,0,0,0,0,0,0,0,0 -14288000,0.982921,-0.00690674,-0.0110895,0.183562,0.00706047,-0.00190925,0.0144726,0.00803957,-0.00229532,0.0343064,-9.80545e-06,-4.72248e-05,-4.14791e-06,3.9134e-06,4.4292e-05,-0.00108658,0.205039,0.000821555,0.434373,0,0,0,0,0,7.20232e-06,0.000129945,0.000129944,0.000205599,0.041555,0.0415571,0.00975719,0.0520193,0.0520196,0.0646571,1.65804e-09,1.65883e-09,4.22991e-09,1.37778e-06,1.37775e-06,5.00012e-08,0,0,0,0,0,0,0,0 -14392000,0.982924,-0.00699576,-0.0110481,0.183547,0.00824093,-0.00414665,0.0145659,0.00787321,-0.00326379,0.0374984,-9.68436e-06,-4.72526e-05,-3.95313e-06,4.22053e-06,4.36075e-05,-0.0010867,0.205039,0.000821555,0.434373,0,0,0,0,0,7.18186e-06,0.000127954,0.000127954,0.000204913,0.0369392,0.036941,0.00956474,0.045752,0.0457522,0.0639172,1.58618e-09,1.58693e-09,4.17512e-09,1.37634e-06,1.37631e-06,5.00012e-08,0,0,0,0,0,0,0,0 -14488000,0.982901,-0.00709352,-0.0109664,0.18367,0.00623168,-0.00400248,0.0183471,0.00852407,-0.00365915,0.0401386,-9.69207e-06,-4.72448e-05,-4.33708e-06,4.21289e-06,4.36201e-05,-0.00108688,0.205039,0.000821555,0.434373,0,0,0,0,0,7.14205e-06,0.000132244,0.000132245,0.000203807,0.0413586,0.0413608,0.00952713,0.0518299,0.0518303,0.0635361,1.5862e-09,1.58696e-09,4.11914e-09,1.37634e-06,1.37631e-06,5.00008e-08,0,0,0,0,0,0,0,0 -14592000,0.982883,-0.00717131,-0.0108135,0.183775,0.00473147,-0.00396429,0.0164281,0.00560637,-0.00425705,0.0367407,-9.71912e-06,-4.75448e-05,-4.52466e-06,3.23123e-06,4.33479e-05,-0.00108603,0.205039,0.000821555,0.434373,0,0,0,0,0,7.12778e-06,0.000129648,0.00012965,0.000203349,0.0368634,0.0368653,0.00937955,0.0456267,0.0456269,0.0628338,1.5076e-09,1.50831e-09,4.06199e-09,1.3743e-06,1.37428e-06,5.00008e-08,0,0,0,0,0,0,0,0 -14688000,0.98289,-0.00715664,-0.0108627,0.183731,0.00407902,-0.00422189,0.0168046,0.005997,-0.00462442,0.0370937,-9.71699e-06,-4.75474e-05,-4.4084e-06,3.24597e-06,4.33406e-05,-0.00108581,0.205039,0.000821555,0.434373,0,0,0,0,0,7.09644e-06,0.000133886,0.000133888,0.000202432,0.0413284,0.0413306,0.00937634,0.0516756,0.051676,0.0624644,1.50762e-09,1.50834e-09,4.00386e-09,1.37431e-06,1.37428e-06,5.00004e-08,0,0,0,0,0,0,0,0 -14792000,0.982922,-0.00711922,-0.0108655,0.183564,0.00601272,0.00267774,0.0157837,0.00498834,0.000330117,0.0399652,-1.02795e-05,-4.74267e-05,-3.94493e-06,4.14628e-06,4.63603e-05,-0.00108625,0.205039,0.000821555,0.434373,0,0,0,0,0,7.08515e-06,0.00013065,0.000130653,0.000202148,0.0369004,0.0369025,0.00926702,0.045524,0.0455243,0.0618037,1.42339e-09,1.42407e-09,3.94475e-09,1.37139e-06,1.37136e-06,5.00004e-08,0,0,0,0,0,0,0,0 -14888000,0.982955,-0.0070189,-0.0108012,0.183397,0.00450758,0.000771418,0.0178835,0.00545813,0.000492455,0.0403451,-1.0271e-05,-4.74352e-05,-3.51843e-06,4.15913e-06,4.63465e-05,-0.001086,0.205039,0.000821555,0.434373,0,0,0,0,0,7.05687e-06,0.000134801,0.000134805,0.000201374,0.041385,0.0413871,0.00929428,0.0515591,0.0515596,0.0614544,1.42342e-09,1.42409e-09,3.88484e-09,1.3714e-06,1.37137e-06,5e-08,0,0,0,0,0,0,0,0 -14992000,0.982957,-0.00714253,-0.0106831,0.183385,0.00283002,0.000141058,0.0201754,0.00439041,-0.000873375,0.0421557,-1.01359e-05,-4.75992e-05,-3.35226e-06,3.34036e-06,4.53556e-05,-0.00108543,0.205039,0.000821555,0.434373,0,0,0,0,0,7.05308e-06,0.000130937,0.000130941,0.000201212,0.0369538,0.0369557,0.00921705,0.0454456,0.045446,0.0608379,1.3351e-09,1.33572e-09,3.82416e-09,1.36744e-06,1.36742e-06,5e-08,0,0,0,0,0,0,0,0 -15088000,0.982948,-0.0071102,-0.0107693,0.183431,0.00193418,0.000147479,0.0223263,0.00462357,-0.000893426,0.0435546,-1.01379e-05,-4.75977e-05,-3.44309e-06,3.34966e-06,4.53547e-05,-0.00108531,0.205039,0.000821555,0.434373,0,0,0,0,0,7.0962e-06,0.000134971,0.000134975,0.000202407,0.0414551,0.0414573,0.00935108,0.0514772,0.0514777,0.0614495,1.33513e-09,1.33575e-09,3.77823e-09,1.36745e-06,1.36742e-06,5.00008e-08,0,0,0,0,0,0,0,0 -15192000,0.982932,-0.00723352,-0.0108452,0.183505,5.38446e-05,-0.000583063,0.0230491,0.00375483,-0.00084704,0.0452476,-1.01573e-05,-4.76438e-05,-3.62377e-06,3.16051e-06,4.53627e-05,-0.001085,0.205039,0.000821555,0.434373,0,0,0,0,0,7.09317e-06,0.000130527,0.000130531,0.000202331,0.0370227,0.0370244,0.00929809,0.0453906,0.0453909,0.0608612,1.24442e-09,1.245e-09,3.71651e-09,1.36242e-06,1.36239e-06,5.00008e-08,0,0,0,0,0,0,0,0 -15288000,0.982947,-0.00732049,-0.0108867,0.183423,5.94309e-06,-0.0016145,0.0222833,0.00380057,-0.000929499,0.0423871,-1.01505e-05,-4.76525e-05,-3.23795e-06,3.22894e-06,4.53345e-05,-0.00108398,0.205039,0.000821555,0.434373,0,0,0,0,0,7.07606e-06,0.000134417,0.000134422,0.00020171,0.0415362,0.0415381,0.00937534,0.0514276,0.0514281,0.0605661,1.24444e-09,1.24502e-09,3.65435e-09,1.36242e-06,1.3624e-06,5.00004e-08,0,0,0,0,0,0,0,0 -15392000,0.982926,-0.00736507,-0.0109197,0.18353,0.000805728,0.00122639,0.02209,0.00316496,-0.000614651,0.0424914,-1.01942e-05,-4.76657e-05,-3.32737e-06,3.28453e-06,4.55816e-05,-0.00108317,0.205039,0.000821555,0.434373,0,0,0,0,0,7.07944e-06,0.000129452,0.000129457,0.000201684,0.0370706,0.0370725,0.00934404,0.0453571,0.0453575,0.0600257,1.15297e-09,1.1535e-09,3.59181e-09,1.35633e-06,1.35631e-06,5.00004e-08,0,0,0,0,0,0,0,0 -15488000,0.982922,-0.0074039,-0.0108985,0.183548,0.000550093,-0.00120091,0.0227298,0.00321011,-0.00059336,0.0431025,-1.01933e-05,-4.76672e-05,-3.26942e-06,3.30659e-06,4.55736e-05,-0.00108284,0.205039,0.000821555,0.434373,0,0,0,0,0,7.06223e-06,0.000133176,0.000133182,0.000201104,0.0415671,0.041569,0.00944107,0.0514048,0.0514054,0.0597673,1.15299e-09,1.15352e-09,3.52902e-09,1.35634e-06,1.35632e-06,5e-08,0,0,0,0,0,0,0,0 -15592000,0.982917,-0.00756513,-0.0109631,0.183565,0.00416404,-0.00497189,0.02237,0.00537578,-0.00437624,0.0414593,-9.63305e-06,-4.75629e-05,-3.05394e-06,4.44932e-06,4.04037e-05,-0.00108186,0.205039,0.000821555,0.434373,0,0,0,0,0,7.06667e-06,0.000127778,0.000127779,0.000201102,0.0370542,0.037056,0.00942666,0.0453412,0.0453416,0.0592745,1.06235e-09,1.06279e-09,3.46602e-09,1.34927e-06,1.34926e-06,5e-08,0,0,0,0,0,0,0,0 -15688000,0.982932,-0.00753286,-0.0109796,0.183487,0.00663846,-0.00760214,0.0230755,0.00587238,-0.00498119,0.0428399,-9.63031e-06,-4.757e-05,-2.80296e-06,4.37966e-06,4.04776e-05,-0.00108167,0.205039,0.000821555,0.434373,0,0,0,0,0,7.11254e-06,0.000131321,0.000131319,0.00020241,0.0415163,0.0415184,0.00961684,0.0514009,0.0514016,0.0599446,1.06239e-09,1.0628e-09,3.41873e-09,1.34927e-06,1.34926e-06,5.00008e-08,0,0,0,0,0,0,0,0 -15792000,0.982958,-0.00754448,-0.0108892,0.183354,0.00394549,-0.00662674,0.0233257,0.00462894,-0.00399206,0.0426656,-9.81988e-06,-4.7655e-05,-2.4021e-06,3.74277e-06,4.22152e-05,-0.0010806,0.205039,0.000821555,0.434373,0,0,0,0,0,7.11073e-06,0.00012559,0.000125588,0.000202421,0.0369576,0.0369592,0.00961358,0.0453383,0.0453387,0.0594845,9.74006e-10,9.74364e-10,3.35566e-09,1.3414e-06,1.34139e-06,5.00008e-08,0,0,0,0,0,0,0,0 -15888000,0.98293,-0.00761095,-0.0109235,0.183497,0.00352636,-0.00521334,0.0239507,0.00494369,-0.00457596,0.0435583,-9.82375e-06,-4.76477e-05,-2.69318e-06,3.85225e-06,4.21229e-05,-0.00108028,0.205039,0.000821555,0.434373,0,0,0,0,0,7.0933e-06,0.000128939,0.000128934,0.000201845,0.0413636,0.0413659,0.00974151,0.0514085,0.0514092,0.0593047,9.74045e-10,9.74368e-10,3.29268e-09,1.3414e-06,1.34139e-06,5.00004e-08,0,0,0,0,0,0,0,0 -15992000,0.982934,-0.00741537,-0.0108898,0.183488,0.0018,-0.00438333,0.0212061,0.00399173,-0.00360726,0.0424381,-9.95781e-06,-4.76884e-05,-2.73576e-06,3.58152e-06,4.33004e-05,-0.00107849,0.205039,0.000821555,0.434373,0,0,0,0,0,7.08839e-06,0.000122984,0.000122976,0.000201845,0.0367828,0.0367846,0.00974698,0.0453432,0.0453437,0.0588904,8.89126e-10,8.89399e-10,3.22984e-09,1.33289e-06,1.33288e-06,5.00004e-08,0,0,0,0,0,0,0,0 -16088000,0.982938,-0.00733798,-0.0108904,0.183469,0.00107548,-0.00530718,0.0189979,0.00409948,-0.00406709,0.0422678,-9.96327e-06,-4.76846e-05,-2.97566e-06,3.60263e-06,4.33033e-05,-0.00107799,0.205039,0.000821555,0.434373,0,0,0,0,0,7.05985e-06,0.000126131,0.000126123,0.000201265,0.0411319,0.041134,0.00988543,0.0514212,0.0514219,0.0587526,8.89148e-10,8.89429e-10,3.16726e-09,1.3329e-06,1.33288e-06,5e-08,0,0,0,0,0,0,0,0 -16192000,0.982919,-0.00723734,-0.0107925,0.183579,-0.00217743,-0.00275982,0.0175741,0.00198275,-0.00309672,0.0383317,-1.01516e-05,-4.7825e-05,-3.29144e-06,2.16025e-06,4.51101e-05,-0.00107607,0.205039,0.000821555,0.434373,0,0,0,0,0,7.05654e-06,0.00012004,0.000120033,0.000201236,0.036513,0.0365146,0.00989588,0.0453514,0.0453518,0.0583811,8.08542e-10,8.08791e-10,3.10496e-09,1.32391e-06,1.3239e-06,5e-08,0,0,0,0,0,0,0,0 -16288000,0.98291,-0.00724577,-0.010706,0.183635,-0.00121739,-0.00411896,0.0170149,0.00179235,-0.00346337,0.0398504,-1.01505e-05,-4.7826e-05,-3.23793e-06,2.16471e-06,4.51064e-05,-0.00107603,0.205039,0.000821555,0.434373,0,0,0,0,0,7.10587e-06,0.000122984,0.000122978,0.000202486,0.0407655,0.0407674,0.01012,0.051431,0.0514317,0.0591505,8.0857e-10,8.08826e-10,3.05852e-09,1.32391e-06,1.3239e-06,5.00008e-08,0,0,0,0,0,0,0,0 -16392000,0.982923,-0.0071794,-0.0107165,0.183564,0.00125127,-0.00296286,0.0174883,0.00291523,-0.00271723,0.0396999,-1.0162e-05,-4.76595e-05,-2.85082e-06,4.24504e-06,4.51842e-05,-0.00107522,0.205039,0.000821555,0.434373,0,0,0,0,0,7.10615e-06,0.000116867,0.00011686,0.000202412,0.0361389,0.0361404,0.0101315,0.045358,0.0453585,0.0588088,7.3301e-10,7.33236e-10,2.99693e-09,1.31465e-06,1.31464e-06,5.00008e-08,0,0,0,0,0,0,0,0 -16488000,0.982912,-0.0072908,-0.010745,0.183618,0.0034506,-0.00458731,0.0198345,0.0031325,-0.00311827,0.0439311,-1.01649e-05,-4.76562e-05,-3.0105e-06,4.20152e-06,4.5207e-05,-0.00107589,0.205039,0.000821555,0.434373,0,0,0,0,0,7.08306e-06,0.00011961,0.000119604,0.00020175,0.0402738,0.0402756,0.0102846,0.0514315,0.0514322,0.0587541,7.33033e-10,7.33266e-10,2.93585e-09,1.31465e-06,1.31465e-06,5.00004e-08,0,0,0,0,0,0,0,0 -16592000,0.982909,-0.00724206,-0.0107707,0.183634,0.00652138,-0.00467924,0.0231868,0.00274374,-0.00248647,0.0440815,-1.02726e-05,-4.76813e-05,-3.02025e-06,3.9834e-06,4.63754e-05,-0.0010751,0.205039,0.000821555,0.434373,0,0,0,0,0,7.07801e-06,0.000113555,0.000113549,0.000201633,0.0356535,0.035655,0.0102951,0.0453585,0.0453589,0.0584492,6.62936e-10,6.63141e-10,2.87531e-09,1.30531e-06,1.3053e-06,5.00004e-08,0,0,0,0,0,0,0,0 -16688000,0.982916,-0.00726544,-0.0107219,0.183596,0.00800456,-0.00796329,0.0230295,0.00344775,-0.0030862,0.0445589,-1.02689e-05,-4.76851e-05,-2.82597e-06,4.01704e-06,4.63554e-05,-0.0010746,0.205039,0.000821555,0.434373,0,0,0,0,0,7.05561e-06,0.000116103,0.000116098,0.000200926,0.0396771,0.0396787,0.010451,0.0514175,0.0514181,0.0584327,6.6296e-10,6.6317e-10,2.81538e-09,1.30531e-06,1.30531e-06,5e-08,0,0,0,0,0,0,0,0 -16792000,0.982939,-0.00710053,-0.0106236,0.18349,0.0095044,-0.00805663,0.021316,0.0027921,-0.00240394,0.0437904,-1.04424e-05,-4.77622e-05,-2.61751e-06,3.21674e-06,4.84364e-05,-0.00107316,0.205039,0.000821555,0.434373,0,0,0,0,0,7.04486e-06,0.000110184,0.000110178,0.000200761,0.0351244,0.0351256,0.0104579,0.0453504,0.0453509,0.0581604,5.98504e-10,5.98686e-10,2.7561e-09,1.29604e-06,1.29604e-06,5e-08,0,0,0,0,0,0,0,0 -16888000,0.982964,-0.00709859,-0.0107154,0.183351,0.00870731,-0.008271,0.0235426,0.00365287,-0.00317527,0.0446355,-1.04358e-05,-4.77684e-05,-2.28322e-06,3.24775e-06,4.8413e-05,-0.00107274,0.205039,0.000821555,0.434373,0,0,0,0,0,7.08211e-06,0.000112545,0.000112539,0.000201874,0.0390107,0.039012,0.0106972,0.0513879,0.0513885,0.059042,5.98534e-10,5.98721e-10,2.71215e-09,1.29605e-06,1.29605e-06,5.00012e-08,0,0,0,0,0,0,0,0 -16992000,0.982955,-0.00715529,-0.0107466,0.183392,0.0093842,-0.00749788,0.0235701,0.00353637,-0.00242647,0.0431495,-1.05323e-05,-4.76633e-05,-2.16906e-06,5.00463e-06,4.94688e-05,-0.00107147,0.205039,0.000821555,0.434373,0,0,0,0,0,7.07828e-06,0.00010681,0.000106804,0.00020164,0.0345083,0.0345094,0.0106978,0.0453311,0.0453314,0.0587905,5.39655e-10,5.39815e-10,2.65413e-09,1.28695e-06,1.28695e-06,5.00012e-08,0,0,0,0,0,0,0,0 -17088000,0.982955,-0.00723318,-0.0107024,0.183391,0.0121961,-0.00980393,0.0237369,0.00458565,-0.00329114,0.0424097,-1.05334e-05,-4.76633e-05,-2.19571e-06,5.05017e-06,4.94514e-05,-0.00107052,0.205039,0.000821555,0.434373,0,0,0,0,0,7.04876e-06,0.000108992,0.000108987,0.000200833,0.038271,0.0382722,0.0108556,0.0513387,0.0513393,0.0588463,5.3968e-10,5.39846e-10,2.59689e-09,1.28695e-06,1.28696e-06,5.00008e-08,0,0,0,0,0,0,0,0 -17192000,0.982903,-0.00733644,-0.0105934,0.183675,0.01065,-0.0146966,0.0245322,0.00291752,-0.00702246,0.0443193,-1.04286e-05,-4.7822e-05,-2.73269e-06,3.23313e-06,4.78753e-05,-0.00106993,0.205039,0.000821555,0.434373,0,0,0,0,0,7.04329e-06,0.000103481,0.000103474,0.000200541,0.0338466,0.0338474,0.0108488,0.0452986,0.045299,0.0586188,4.86218e-10,4.86349e-10,2.54045e-09,1.27812e-06,1.27812e-06,5.00008e-08,0,0,0,0,0,0,0,0 -17288000,0.982874,-0.00729804,-0.0105997,0.183827,0.0118405,-0.0144385,0.0239624,0.00399668,-0.00836616,0.0441777,-1.04342e-05,-4.78143e-05,-3.08443e-06,3.36628e-06,4.77654e-05,-0.00106916,0.205039,0.000821555,0.434373,0,0,0,0,0,7.01458e-06,0.000105496,0.000105487,0.000199682,0.0374781,0.0374792,0.0110036,0.0512699,0.0512705,0.058703,4.86255e-10,4.86369e-10,2.48486e-09,1.27812e-06,1.27812e-06,5.00004e-08,0,0,0,0,0,0,0,0 -17392000,0.982915,-0.00718588,-0.0106052,0.183612,0.00842242,-0.0138276,0.0239067,0.0053833,-0.00536411,0.0438704,-1.07174e-05,-4.76337e-05,-2.74759e-06,6.02621e-06,5.15574e-05,-0.00106777,0.205039,0.000821555,0.434373,0,0,0,0,0,6.99381e-06,0.000100238,0.000100229,0.000199348,0.0331465,0.0331468,0.010988,0.045253,0.0452534,0.0584948,4.37941e-10,4.38038e-10,2.43013e-09,1.26962e-06,1.26963e-06,5.00004e-08,0,0,0,0,0,0,0,0 -17488000,0.982896,-0.00718895,-0.0106448,0.183713,0.00715858,-0.0141684,0.0242604,0.00608455,-0.00668056,0.0451272,-1.07218e-05,-4.76302e-05,-2.96142e-06,6.03023e-06,5.15632e-05,-0.00106742,0.205039,0.000821555,0.434373,0,0,0,0,0,6.96398e-06,0.000102095,0.000102087,0.000198443,0.036639,0.0366394,0.0111383,0.0511809,0.0511814,0.058603,4.37968e-10,4.3807e-10,2.3763e-09,1.26962e-06,1.26963e-06,5e-08,0,0,0,0,0,0,0,0 -17592000,0.982893,-0.00713296,-0.0105312,0.183736,0.00315581,-0.0107673,0.023641,0.00230958,-0.00511154,0.0449181,-1.1019e-05,-4.78703e-05,-2.92833e-06,2.71135e-06,5.56203e-05,-0.00106612,0.205039,0.000821555,0.434373,0,0,0,0,0,6.95114e-06,9.71089e-05,9.70998e-05,0.000198043,0.0324147,0.032415,0.0111131,0.0451936,0.0451939,0.0584093,3.94487e-10,3.94571e-10,2.32337e-09,1.26151e-06,1.26152e-06,5e-08,0,0,0,0,0,0,0,0 -17688000,0.982919,-0.0072317,-0.0104616,0.183599,0.00265801,-0.0112201,0.0239622,0.00262512,-0.00617286,0.0452564,-1.10181e-05,-4.78722e-05,-2.84781e-06,2.71769e-06,5.56315e-05,-0.00106544,0.205039,0.000821555,0.434373,0,0,0,0,0,6.9727e-06,9.88208e-05,9.88115e-05,0.000198912,0.0357696,0.0357699,0.0113485,0.0510722,0.0510726,0.0594109,3.94525e-10,3.94603e-10,2.28428e-09,1.26151e-06,1.26152e-06,5.00008e-08,0,0,0,0,0,0,0,0 -17792000,0.982958,-0.00719249,-0.010445,0.183394,0.00508653,-0.0097418,0.0248142,0.00343598,-0.00544733,0.0505683,-1.1175e-05,-4.77412e-05,-2.75877e-06,4.67836e-06,5.80653e-05,-0.00106631,0.205039,0.000821555,0.434373,0,0,0,0,0,6.94175e-06,9.41147e-05,9.41036e-05,0.000198465,0.0316609,0.0316612,0.0113124,0.0451202,0.0451206,0.0592218,3.55514e-10,3.55566e-10,2.23299e-09,1.25381e-06,1.25382e-06,5.00008e-08,0,0,0,0,0,0,0,0 -17888000,0.982966,-0.00714163,-0.0105395,0.183345,0.00633164,-0.0120125,0.0239169,0.00403911,-0.00650223,0.0545101,-1.11722e-05,-4.77443e-05,-2.6054e-06,4.6238e-06,5.81067e-05,-0.00106685,0.205039,0.000821555,0.434373,0,0,0,0,0,6.90745e-06,9.5692e-05,9.56799e-05,0.000197462,0.0348916,0.034892,0.0114535,0.0509443,0.0509447,0.0593736,3.55544e-10,3.55598e-10,2.18265e-09,1.25382e-06,1.25383e-06,5.00004e-08,0,0,0,0,0,0,0,0 -17992000,0.982964,-0.00694535,-0.010511,0.183367,0.00548188,-0.00570587,0.0237636,0.00320136,-0.00121383,0.0554318,-1.1619e-05,-4.76614e-05,-2.62371e-06,5.90311e-06,6.47049e-05,-0.00106633,0.205039,0.000821555,0.434373,0,0,0,0,0,6.88907e-06,9.12639e-05,9.12514e-05,0.00019695,0.0309005,0.0309007,0.0114068,0.0450335,0.0450338,0.0591907,3.20605e-10,3.20648e-10,2.13327e-09,1.24654e-06,1.24655e-06,5.00004e-08,0,0,0,0,0,0,0,0 -18088000,0.982966,-0.00702665,-0.0104789,0.183352,0.00554704,-0.00564168,0.0225301,0.00376337,-0.00180263,0.0536721,-1.16177e-05,-4.76634e-05,-2.53074e-06,5.9605e-06,6.46821e-05,-0.00106492,0.205039,0.000821555,0.434373,0,0,0,0,0,6.85418e-06,9.27163e-05,9.27046e-05,0.000195908,0.0339927,0.033993,0.0115406,0.0507991,0.0507995,0.0593537,3.20634e-10,3.20683e-10,2.08486e-09,1.24654e-06,1.24656e-06,5e-08,0,0,0,0,0,0,0,0 -18192000,0.983007,-0.00705271,-0.0105142,0.183132,0.00546669,-0.00483396,0.0231392,0.0042084,-0.00137268,0.0514685,-1.16566e-05,-4.7626e-05,-2.06336e-06,6.80644e-06,6.53225e-05,-0.00106303,0.205039,0.000821555,0.434373,0,0,0,0,0,6.83038e-06,8.8566e-05,8.85542e-05,0.000195354,0.0301199,0.0301202,0.0114834,0.0449339,0.0449342,0.0591731,2.89409e-10,2.89449e-10,2.03742e-09,1.2397e-06,1.23971e-06,5e-08,0,0,0,0,0,0,0,0 -18288000,0.983,-0.00710349,-0.0104758,0.183169,0.00597566,-0.00543201,0.0222788,0.00470341,-0.00186812,0.0504342,-1.16562e-05,-4.76269e-05,-2.02274e-06,6.84951e-06,6.53072e-05,-0.00106185,0.205039,0.000821555,0.434373,0,0,0,0,0,6.85748e-06,8.99046e-05,8.98934e-05,0.000196031,0.0330824,0.0330826,0.0117071,0.0506358,0.0506362,0.0602417,2.89445e-10,2.89488e-10,2.00249e-09,1.2397e-06,1.23972e-06,5.00008e-08,0,0,0,0,0,0,0,0 -18392000,0.98297,-0.00702117,-0.0105058,0.18333,0.00621319,-0.00527107,0.0221624,0.00618029,-0.0014898,0.0506205,-1.16749e-05,-4.7513e-05,-2.18064e-06,8.68798e-06,6.54981e-05,-0.00106109,0.205039,0.000821555,0.434373,0,0,0,0,0,6.8419e-06,8.60269e-05,8.6015e-05,0.000195413,0.0293467,0.0293468,0.0116387,0.0448218,0.044822,0.0600546,2.61578e-10,2.61613e-10,1.95675e-09,1.2333e-06,1.23331e-06,5.00008e-08,0,0,0,0,0,0,0,0 -18488000,0.98298,-0.00708871,-0.0105082,0.183277,0.0086866,-0.00543257,0.0218275,0.00696734,-0.00202536,0.0519776,-1.16709e-05,-4.75166e-05,-1.97182e-06,8.70909e-06,6.54838e-05,-0.00106084,0.205039,0.000821555,0.434373,0,0,0,0,0,6.80465e-06,8.72611e-05,8.72499e-05,0.000194289,0.0321858,0.032186,0.0117602,0.050458,0.0504583,0.0602381,2.61609e-10,2.61649e-10,1.91198e-09,1.2333e-06,1.23332e-06,5.00004e-08,0,0,0,0,0,0,0,0 -18592000,0.982943,-0.00692276,-0.0103742,0.183488,0.00701506,-0.00548571,0.0218456,0.00560722,-0.00164116,0.0542893,-1.17636e-05,-4.75893e-05,-2.21603e-06,7.53012e-06,6.68617e-05,-0.00106044,0.205039,0.000821555,0.434373,0,0,0,0,0,6.78841e-06,8.3643e-05,8.36314e-05,0.00019363,0.0285817,0.0285817,0.011682,0.0446985,0.0446987,0.0600471,2.36752e-10,2.36785e-10,1.86818e-09,1.22732e-06,1.22733e-06,5.00004e-08,0,0,0,0,0,0,0,0 -18688000,0.982968,-0.00690282,-0.0103235,0.183355,0.00666074,-0.00437976,0.0206439,0.00627468,-0.0021037,0.0531817,-1.17586e-05,-4.75943e-05,-1.93838e-06,7.58062e-06,6.68372e-05,-0.00105927,0.205039,0.000821555,0.434373,0,0,0,0,0,6.74634e-06,8.47819e-05,8.47709e-05,0.000192484,0.0313012,0.0313014,0.0117956,0.050266,0.0502662,0.0602306,2.36784e-10,2.36821e-10,1.82534e-09,1.22732e-06,1.22734e-06,5e-08,0,0,0,0,0,0,0,0 -18792000,0.982965,-0.00687323,-0.0102081,0.183378,0.00598604,-0.00528283,0.0196555,0.00621987,-0.00179543,0.0501054,-1.18012e-05,-4.75826e-05,-1.94213e-06,7.90159e-06,6.74663e-05,-0.00105648,0.205039,0.000821555,0.434373,0,0,0,0,0,6.72217e-06,8.14105e-05,8.14001e-05,0.000191795,0.0278234,0.0278234,0.0117084,0.0445646,0.0445648,0.0600334,2.14617e-10,2.14648e-10,1.78346e-09,1.22174e-06,1.22176e-06,5e-08,0,0,0,0,0,0,0,0 -18888000,0.982954,-0.00682923,-0.0102423,0.18344,0.00509693,-0.00474746,0.0189183,0.00672252,-0.00232147,0.0485748,-1.18042e-05,-4.75805e-05,-2.07627e-06,7.92955e-06,6.74645e-05,-0.0010552,0.205039,0.000821555,0.434373,0,0,0,0,0,6.74042e-06,8.24631e-05,8.24524e-05,0.000192315,0.030426,0.0304261,0.0119175,0.0500612,0.0500614,0.0611389,2.14655e-10,2.14688e-10,1.75268e-09,1.22174e-06,1.22176e-06,5.00008e-08,0,0,0,0,0,0,0,0 -18992000,0.98294,-0.00678535,-0.010238,0.183517,0.00316006,-0.00594342,0.0195346,0.00550926,-0.00192227,0.0510553,-1.18684e-05,-4.76239e-05,-2.05297e-06,7.26506e-06,6.85065e-05,-0.00105484,0.205039,0.000821555,0.434373,0,0,0,0,0,6.71993e-06,7.93283e-05,7.93174e-05,0.000191576,0.0270796,0.0270795,0.0118209,0.044421,0.0444211,0.0609274,1.94892e-10,1.94919e-10,1.71244e-09,1.21655e-06,1.21657e-06,5.00008e-08,0,0,0,0,0,0,0,0 -19088000,0.982947,-0.00688275,-0.0102505,0.183473,0.0010003,-0.00617209,0.0204456,0.00575408,-0.00247326,0.0471066,-1.1865e-05,-4.76278e-05,-1.84352e-06,7.33162e-06,6.84842e-05,-0.00105265,0.205039,0.000821555,0.434373,0,0,0,0,0,6.68053e-06,8.03012e-05,8.02911e-05,0.000190367,0.0295641,0.029564,0.0119222,0.0498455,0.0498457,0.0611123,1.94926e-10,1.94957e-10,1.67314e-09,1.21656e-06,1.21658e-06,5.00004e-08,0,0,0,0,0,0,0,0 -19192000,0.982913,-0.00678395,-0.0103651,0.183654,-0.000981517,-0.00599811,0.0203524,0.00473762,-0.00202602,0.0468428,-1.19338e-05,-4.76276e-05,-2.2703e-06,7.26362e-06,6.94857e-05,-0.00105176,0.205039,0.000821555,0.434373,0,0,0,0,0,6.65314e-06,7.73898e-05,7.73787e-05,0.000189605,0.0263463,0.0263462,0.0118182,0.0442687,0.0442688,0.0608911,1.77304e-10,1.77329e-10,1.63475e-09,1.21175e-06,1.21177e-06,5.00004e-08,0,0,0,0,0,0,0,0 -19288000,0.982918,-0.00674229,-0.0103418,0.183631,-0.00178315,-0.0058768,0.0205781,0.00463409,-0.00259786,0.0462605,-1.19346e-05,-4.76272e-05,-2.29958e-06,7.2842e-06,6.94833e-05,-0.00105081,0.205039,0.000821555,0.434373,0,0,0,0,0,6.60769e-06,7.82906e-05,7.82798e-05,0.000188387,0.0287323,0.0287322,0.0119127,0.04962,0.0496201,0.0610679,1.77339e-10,1.77367e-10,1.59726e-09,1.21175e-06,1.21177e-06,5e-08,0,0,0,0,0,0,0,0 -19392000,0.982909,-0.00684142,-0.0102422,0.18368,-0.00231692,-0.00286588,0.0214882,0.00391832,-0.000799575,0.0444096,-1.20424e-05,-4.75921e-05,-2.43581e-06,7.9307e-06,7.12856e-05,-0.0010489,0.205039,0.000821555,0.434373,0,0,0,0,0,6.57847e-06,7.55853e-05,7.55756e-05,0.000187602,0.0256333,0.0256332,0.0118023,0.0441083,0.0441084,0.0608363,1.61614e-10,1.61636e-10,1.56067e-09,1.20729e-06,1.20732e-06,5e-08,0,0,0,0,0,0,0,0 -19488000,0.982872,-0.00687454,-0.0101397,0.18388,-0.00303573,-0.00280373,0.0218689,0.003647,-0.00104858,0.045237,-1.20467e-05,-4.75885e-05,-2.64946e-06,7.92995e-06,7.12939e-05,-0.0010484,0.205039,0.000821555,0.434373,0,0,0,0,0,6.59934e-06,7.64204e-05,7.64116e-05,0.000187978,0.0279208,0.0279208,0.0119978,0.0493854,0.0493855,0.0619533,1.61653e-10,1.61677e-10,1.53383e-09,1.2073e-06,1.20732e-06,5.00012e-08,0,0,0,0,0,0,0,0 -19592000,0.982855,-0.00682358,-0.0102534,0.183967,-0.00416759,-0.00587013,0.0236876,0.00413107,-0.00210478,0.0461728,-1.19879e-05,-4.75372e-05,-2.71205e-06,8.86882e-06,7.0198e-05,-0.00104757,0.205039,0.000821555,0.434373,0,0,0,0,0,6.57428e-06,7.39093e-05,7.38995e-05,0.000187152,0.0249431,0.024943,0.0118806,0.0439409,0.043941,0.0617032,1.4761e-10,1.4763e-10,1.49876e-09,1.20317e-06,1.20319e-06,5.00012e-08,0,0,0,0,0,0,0,0 -19688000,0.98287,-0.00683088,-0.0102719,0.183887,-0.00566872,-0.00456686,0.0230337,0.0036706,-0.00260531,0.0468152,-1.19848e-05,-4.75402e-05,-2.54283e-06,8.89029e-06,7.01893e-05,-0.00104695,0.205039,0.000821555,0.434373,0,0,0,0,0,6.52968e-06,7.46849e-05,7.46755e-05,0.000185895,0.0271393,0.0271392,0.0119654,0.0491443,0.0491443,0.0618692,1.47646e-10,1.47669e-10,1.46455e-09,1.20318e-06,1.2032e-06,5.00008e-08,0,0,0,0,0,0,0,0 -19792000,0.982849,-0.00690266,-0.0103447,0.183993,-0.00543157,-0.00307033,0.0205563,0.00604947,-0.0020877,0.0415861,-1.19791e-05,-4.74168e-05,-2.74876e-06,1.10455e-05,7.0014e-05,-0.00104385,0.205039,0.000821555,0.434373,0,0,0,0,0,6.50079e-06,7.23523e-05,7.23431e-05,0.000185056,0.0242841,0.024284,0.0118439,0.0437678,0.0437679,0.061608,1.35094e-10,1.35112e-10,1.43118e-09,1.19935e-06,1.19938e-06,5.00008e-08,0,0,0,0,0,0,0,0 -19888000,0.982832,-0.00693422,-0.0104238,0.184077,-0.00515582,-0.00284257,0.0209034,0.00547948,-0.00233392,0.0405431,-1.1981e-05,-4.74155e-05,-2.83292e-06,1.10628e-05,7.00167e-05,-0.00104272,0.205039,0.000821555,0.434373,0,0,0,0,0,6.4601e-06,7.30737e-05,7.30646e-05,0.00018379,0.0263873,0.0263873,0.0119235,0.0488982,0.0488983,0.0617617,1.35131e-10,1.35152e-10,1.39863e-09,1.19936e-06,1.19938e-06,5.00004e-08,0,0,0,0,0,0,0,0 -19992000,0.98285,-0.00693998,-0.0105962,0.183972,-0.00464226,-0.00275814,0.0179725,0.00576191,-0.000818078,0.0372013,-1.20295e-05,-4.73295e-05,-2.75373e-06,1.27654e-05,7.09049e-05,-0.00103988,0.205039,0.000821555,0.434373,0,0,0,0,0,6.42502e-06,7.09076e-05,7.08979e-05,0.000182942,0.0236462,0.0236461,0.0117987,0.0435903,0.0435903,0.0614897,1.239e-10,1.23917e-10,1.36689e-09,1.19582e-06,1.19585e-06,5.00004e-08,0,0,0,0,0,0,0,0 -20088000,0.982859,-0.00692897,-0.0105921,0.183922,-0.00413845,-0.00463,0.0173988,0.00533189,-0.00117996,0.0393889,-1.20296e-05,-4.73294e-05,-2.75974e-06,1.27618e-05,7.09053e-05,-0.00104005,0.205039,0.000821555,0.434373,0,0,0,0,0,6.37718e-06,7.15792e-05,7.15699e-05,0.000181682,0.0256715,0.0256713,0.0118737,0.0486483,0.0486483,0.0616306,1.23937e-10,1.23956e-10,1.33593e-09,1.19583e-06,1.19585e-06,5e-08,0,0,0,0,0,0,0,0 -20192000,0.982834,-0.00690891,-0.0106864,0.184055,-0.00313479,-0.00260452,0.0184721,0.00628838,-0.000914442,0.0405082,-1.20474e-05,-4.72772e-05,-3.04501e-06,1.35908e-05,7.11625e-05,-0.00103951,0.205039,0.000821555,0.434373,0,0,0,0,0,6.34683e-06,6.95633e-05,6.95533e-05,0.000180818,0.02303,0.0230298,0.0117466,0.0434086,0.0434086,0.0613484,1.13872e-10,1.13887e-10,1.30576e-09,1.19254e-06,1.19257e-06,5e-08,0,0,0,0,0,0,0,0 -20288000,0.982839,-0.00690346,-0.0107247,0.184024,-0.0064324,-0.00347506,0.0188144,0.00586309,-0.00116405,0.0418159,-1.20475e-05,-4.72771e-05,-3.04854e-06,1.35936e-05,7.11629e-05,-0.00103935,0.205039,0.000821555,0.434373,0,0,0,0,0,6.35305e-06,7.01901e-05,7.01802e-05,0.000181056,0.0249725,0.0249722,0.0119268,0.0483948,0.0483948,0.0624412,1.13913e-10,1.13929e-10,1.28363e-09,1.19255e-06,1.19257e-06,5.00008e-08,0,0,0,0,0,0,0,0 -20392000,0.982833,-0.00685103,-0.0107088,0.184057,-0.00703619,-0.00240032,0.0181939,0.00668082,-0.000900536,0.0407806,-1.2047e-05,-4.72282e-05,-2.84639e-06,1.45844e-05,7.12368e-05,-0.00103751,0.205039,0.000821555,0.434373,0,0,0,0,0,6.33004e-06,6.83153e-05,6.83051e-05,0.000180162,0.0224356,0.0224353,0.0117961,0.0432237,0.0432237,0.0621405,1.04885e-10,1.04898e-10,1.25476e-09,1.18951e-06,1.18953e-06,5.00008e-08,0,0,0,0,0,0,0,0 -20488000,0.982851,-0.0068716,-0.0106813,0.183963,-0.00967195,-0.00313539,0.0182803,0.00585633,-0.0011249,0.039183,-1.20469e-05,-4.72286e-05,-2.83192e-06,1.46054e-05,7.12388e-05,-0.00103625,0.205039,0.000821555,0.434373,0,0,0,0,0,6.27943e-06,6.89005e-05,6.88909e-05,0.000178892,0.0243013,0.0243009,0.011866,0.0481386,0.0481386,0.0622644,1.04923e-10,1.04938e-10,1.22663e-09,1.18951e-06,1.18953e-06,5.00004e-08,0,0,0,0,0,0,0,0 -20592000,0.982882,-0.00685485,-0.0107032,0.183799,-0.00885324,-0.00447536,0.0180753,0.00673487,-0.00098339,0.0374762,-1.20354e-05,-4.71696e-05,-2.51211e-06,1.58611e-05,7.11345e-05,-0.00103447,0.205039,0.000821555,0.434373,0,0,0,0,0,6.24655e-06,6.71569e-05,6.71472e-05,0.000178002,0.0218619,0.0218614,0.0117346,0.0430358,0.0430358,0.0619551,9.6816e-11,9.68276e-11,1.19921e-09,1.1867e-06,1.18672e-06,5.00004e-08,0,0,0,0,0,0,0,0 -20688000,0.982875,-0.00678174,-0.0106993,0.183836,-0.0108371,-0.00400718,0.0188875,0.00583966,-0.00134528,0.0375585,-1.20382e-05,-4.71672e-05,-2.6531e-06,1.58643e-05,7.11424e-05,-0.00103384,0.205039,0.000821555,0.434373,0,0,0,0,0,6.20012e-06,6.77047e-05,6.76951e-05,0.000176734,0.0236564,0.0236559,0.0118017,0.0478805,0.0478805,0.0620662,9.68551e-11,9.68687e-11,1.17249e-09,1.1867e-06,1.18673e-06,5e-08,0,0,0,0,0,0,0,0 -20792000,0.9829,-0.00618301,-0.0105906,0.183729,-0.0136217,-0.00140106,0.00442353,0.00476204,-0.0010957,0.0366264,-1.20459e-05,-4.71365e-05,-2.5457e-06,1.65673e-05,7.13108e-05,-0.00103256,0.205039,0.000821555,0.434373,0,0,0,0,0,6.16391e-06,6.6082e-05,6.60703e-05,0.000175846,0.0213432,0.0213427,0.0116702,0.0428458,0.0428458,0.0617493,8.95647e-11,8.95748e-11,1.14645e-09,1.1841e-06,1.18412e-06,5e-08,0,0,0,0,0,0,0,0 -20888000,0.982956,0.00261654,-0.00689238,0.183692,-0.0198639,0.0102274,-0.106543,0.00309746,-0.0006567,0.0319796,-1.2045e-05,-4.71373e-05,-2.49463e-06,1.65807e-05,7.13091e-05,-0.0010324,0.205039,0.000821555,0.434373,0,0,0,0,0,6.16234e-06,6.65881e-05,6.6569e-05,0.000176031,0.0233377,0.0233375,0.011845,0.0476334,0.0476333,0.0628246,8.96066e-11,8.96174e-11,1.12736e-09,1.1841e-06,1.18413e-06,5.00008e-08,0,0,0,0,0,0,0,0 -20992000,0.982946,0.00632192,-0.00323587,0.183756,-0.031148,0.0286004,-0.252858,0.00213809,0.000252224,0.0170335,-1.19785e-05,-4.70847e-05,-2.48458e-06,1.76937e-05,6.98145e-05,-0.00103584,0.205039,0.000821555,0.434373,0,0,0,0,0,6.13392e-06,6.49912e-05,6.49807e-05,0.000175125,0.0213554,0.0213553,0.011712,0.0426767,0.0426767,0.0624912,8.29665e-11,8.29736e-11,1.10247e-09,1.18133e-06,1.18136e-06,5.00008e-08,0,0,0,0,0,0,0,0 -21088000,0.982889,0.00482334,-0.00355418,0.184104,-0.0436714,0.0435192,-0.365327,-0.00144518,0.00375629,-0.0120811,-1.19789e-05,-4.70843e-05,-2.51166e-06,1.76805e-05,6.97912e-05,-0.001036,0.205039,0.000821555,0.434373,0,0,0,0,0,6.11033e-06,6.54746e-05,6.54625e-05,0.000173828,0.02332,0.0233199,0.0117772,0.0474489,0.0474489,0.0625864,8.3007e-11,8.30137e-11,1.07822e-09,1.18133e-06,1.18136e-06,5.00004e-08,0,0,0,0,0,0,0,0 -21192000,0.982834,0.00183669,-0.00523056,0.184408,-0.0476235,0.0488394,-0.494459,-0.00146234,0.00341569,-0.0448325,-1.17439e-05,-4.69881e-05,-2.41066e-06,2.00626e-05,6.37501e-05,-0.00104612,0.205039,0.000821555,0.434373,0,0,0,0,0,6.10101e-06,6.3854e-05,6.38397e-05,0.000172887,0.0212907,0.0212904,0.0116454,0.0425418,0.0425418,0.0622475,7.69007e-11,7.69078e-11,1.05458e-09,1.17802e-06,1.17805e-06,5.00004e-08,0,0,0,0,0,0,0,0 -21288000,0.982778,-0.000263937,-0.00653125,0.184677,-0.0478553,0.0526064,-0.618906,-0.00605771,0.00831336,-0.100673,-1.17497e-05,-4.69827e-05,-2.69897e-06,2.01471e-05,6.37701e-05,-0.00104526,0.205039,0.000821555,0.434373,0,0,0,0,0,6.06554e-06,6.43074e-05,6.42924e-05,0.000171613,0.0232403,0.0232398,0.0117094,0.0472945,0.0472946,0.0623316,7.69411e-11,7.69487e-11,1.03155e-09,1.17802e-06,1.17805e-06,5e-08,0,0,0,0,0,0,0,0 -21392000,0.98274,-0.00183654,-0.00727609,0.184838,-0.0434484,0.0493557,-0.748057,-0.00524486,0.0110286,-0.164554,-1.16308e-05,-4.68708e-05,-2.60123e-06,2.31494e-05,6.04334e-05,-0.00105254,0.205039,0.000821555,0.434373,0,0,0,0,0,6.04771e-06,6.26552e-05,6.26418e-05,0.000170687,0.0211924,0.0211919,0.0115792,0.0424291,0.0424291,0.0619887,7.13429e-11,7.13526e-11,1.00911e-09,1.17416e-06,1.17418e-06,5e-08,0,0,0,0,0,0,0,0 -21488000,0.982708,-0.00263873,-0.007714,0.18498,-0.0391284,0.0471727,-0.877632,-0.00928806,0.015705,-0.245033,-1.16291e-05,-4.68726e-05,-2.50751e-06,2.31481e-05,6.04382e-05,-0.00105159,0.205039,0.000821555,0.434373,0,0,0,0,0,6.06363e-06,6.30758e-05,6.3063e-05,0.000170761,0.0231097,0.023109,0.0117523,0.0471604,0.0471605,0.063046,7.13857e-11,7.13961e-11,9.92675e-10,1.17417e-06,1.17419e-06,5.00008e-08,0,0,0,0,0,0,0,0 -21592000,0.982716,-0.00311368,-0.00772595,0.184932,-0.0308505,0.0429524,-1.00536,-0.00808998,0.0164913,-0.334073,-1.15444e-05,-4.68267e-05,-2.30339e-06,2.42859e-05,5.83517e-05,-0.00106058,0.205039,0.000821555,0.434373,0,0,0,0,0,6.03435e-06,6.14021e-05,6.13914e-05,0.000169841,0.0210534,0.0210528,0.0116217,0.0423304,0.0423304,0.0626891,6.62675e-11,6.62794e-11,9.71233e-10,1.16977e-06,1.16979e-06,5.00008e-08,0,0,0,0,0,0,0,0 -21688000,0.982712,-0.00342375,-0.00760248,0.184953,-0.0291378,0.0394374,-1.1329,-0.0109569,0.0204537,-0.442878,-1.15408e-05,-4.68304e-05,-2.10758e-06,2.42906e-05,5.8376e-05,-0.00105829,0.205039,0.000821555,0.434373,0,0,0,0,0,5.99753e-06,6.17918e-05,6.17827e-05,0.000168587,0.022915,0.0229143,0.0116863,0.0470379,0.0470379,0.0627612,6.63086e-11,6.63215e-11,9.50342e-10,1.16978e-06,1.16979e-06,5.00004e-08,0,0,0,0,0,0,0,0 -21792000,0.982727,-0.00380315,-0.00780917,0.184855,-0.0212397,0.03245,-1.2664,-0.00399327,0.0178831,-0.562815,-1.14191e-05,-4.67036e-05,-1.84045e-06,2.81988e-05,5.59064e-05,-0.00106537,0.205039,0.000821555,0.434373,0,0,0,0,0,5.96733e-06,6.01141e-05,6.01063e-05,0.000167675,0.0208696,0.020869,0.0115577,0.0422394,0.0422394,0.0624023,6.1645e-11,6.16584e-11,9.29987e-10,1.16492e-06,1.16492e-06,5.00004e-08,0,0,0,0,0,0,0,0 -21888000,0.982719,-0.00409436,-0.00793191,0.184889,-0.0177257,0.0285178,-1.38123,-0.00586586,0.0208395,-0.696615,-1.14214e-05,-4.67019e-05,-1.94422e-06,2.82156e-05,5.59657e-05,-0.00106306,0.205039,0.000821555,0.434373,0,0,0,0,0,5.92233e-06,6.04764e-05,6.04692e-05,0.000166445,0.0226498,0.0226489,0.0116221,0.0469199,0.0469199,0.0624658,6.16865e-11,6.17008e-11,9.10151e-10,1.16492e-06,1.16493e-06,5e-08,0,0,0,0,0,0,0,0 -21992000,0.982734,-0.00478737,-0.00822559,0.184779,-0.0139708,0.0218253,-1.36594,-0.000380554,0.0165016,-0.83607,-1.13581e-05,-4.66914e-05,-1.79108e-06,2.73205e-05,5.61346e-05,-0.00106866,0.205039,0.000821555,0.434373,0,0,0,0,0,5.88833e-06,5.88135e-05,5.88081e-05,0.000165543,0.0202882,0.0202874,0.0114954,0.042141,0.042141,0.0621061,5.74519e-11,5.74657e-11,8.90825e-10,1.15972e-06,1.15972e-06,5e-08,0,0,0,0,0,0,0,0 -22088000,0.982728,-0.00551364,-0.00898373,0.184756,-0.0114363,0.0181825,-1.34885,-0.00164958,0.0183694,-0.971639,-1.13547e-05,-4.66949e-05,-1.60621e-06,2.73223e-05,5.61914e-05,-0.00106654,0.205039,0.000821555,0.434373,0,0,0,0,0,5.89525e-06,5.9151e-05,5.91453e-05,0.000165575,0.0216954,0.0216944,0.0116685,0.0467473,0.0467472,0.0631484,5.74956e-11,5.75101e-11,8.76669e-10,1.15973e-06,1.15972e-06,5.00012e-08,0,0,0,0,0,0,0,0 -22192000,0.982755,-0.00595154,-0.00927967,0.184583,-0.00291633,0.0120925,-1.36396,0.00611704,0.0126225,-1.11873,-1.12901e-05,-4.66547e-05,-1.3657e-06,2.76611e-05,5.67004e-05,-0.00106404,0.205039,0.000821555,0.434373,0,0,0,0,0,5.85979e-06,5.76523e-05,5.76477e-05,0.000164671,0.0195309,0.01953,0.0115418,0.0420058,0.0420058,0.0627772,5.37298e-11,5.3743e-11,8.58198e-10,1.15529e-06,1.15527e-06,5.00012e-08,0,0,0,0,0,0,0,0 -22288000,0.98274,-0.00665235,-0.00952934,0.184629,0.00223892,0.00689997,-1.3617,0.0060675,0.0135542,-1.25548,-1.12917e-05,-4.66535e-05,-1.44114e-06,2.7646e-05,5.67875e-05,-0.00106192,0.205039,0.000821555,0.434373,0,0,0,0,0,5.81737e-06,5.79646e-05,5.79617e-05,0.000163455,0.0209094,0.0209083,0.0116077,0.0465325,0.0465323,0.062833,5.37723e-11,5.3786e-11,8.40194e-10,1.15529e-06,1.15528e-06,5.00008e-08,0,0,0,0,0,0,0,0 -22392000,0.982938,-0.007048,-0.00969204,0.183548,0.00807337,-0.003152,-1.36455,0.0133809,0.00373248,-1.40779,-1.11944e-05,-4.6686e-05,-1.54751e-06,2.52311e-05,5.5575e-05,-0.00105679,0.203917,0.000817041,0.434574,0,0,0,0,0,7.97766e-05,5.67661e-05,5.6663e-05,0.00230586,0.0185469,0.0185459,0.011483,0.0418374,0.0418372,0.0624628,5.04055e-11,5.04163e-11,8.27002e-10,1.1514e-06,1.15138e-06,5.00008e-08,0,0,0,0,0,0,0,0 -22488000,0.982729,-0.00722568,-0.0101128,0.184633,0.0124283,-0.00951979,-1.3693,0.0143674,0.00310946,-1.54308,-1.11945e-05,-4.66861e-05,-1.54761e-06,2.5215e-05,5.56486e-05,-0.0010553,0.203917,0.000817041,0.434574,0,0,0,0,0,5.60319e-05,5.67607e-05,5.66728e-05,0.00161912,0.0185482,0.018547,0.0115479,0.0461792,0.0461789,0.0625124,5.04546e-11,5.04654e-11,8.27049e-10,1.15141e-06,1.15138e-06,5.00004e-08,0,0,0,0,0,0,0,0 -22592000,0.982857,-0.00704626,-0.0107023,0.183924,0.0214323,-0.0186863,-1.36855,0.0264187,-0.00621062,-1.69164,-1.11182e-05,-4.66112e-05,-1.54418e-06,2.78574e-05,5.10609e-05,-0.00105242,0.203917,0.000817041,0.434574,0,0,0,0,0,4.3235e-05,5.67144e-05,5.6627e-05,0.00124758,0.0164836,0.0164823,0.0114252,0.0414715,0.0414713,0.0621436,4.76559e-11,4.76641e-11,8.27091e-10,1.15011e-06,1.15007e-06,5.00004e-08,0,0,0,0,0,0,0,0 -22688000,0.98273,-0.00697263,-0.0109141,0.184591,0.0237241,-0.0225653,-1.37212,0.0286092,-0.00822842,-1.82884,-1.11184e-05,-4.66114e-05,-1.54916e-06,2.7827e-05,5.11743e-05,-0.00105038,0.203917,0.000817041,0.434574,0,0,0,0,0,3.52175e-05,5.67385e-05,5.66634e-05,0.00101477,0.0180466,0.0180451,0.0114909,0.0454479,0.0454476,0.0621875,4.7705e-11,4.77132e-11,8.27121e-10,1.15011e-06,1.15008e-06,5e-08,0,0,0,0,0,0,0,0 -22792000,0.982668,-0.00683361,-0.0112612,0.184904,0.0295173,-0.0293436,-1.3763,0.0394573,-0.0186586,-1.9828,-1.10602e-05,-4.65977e-05,-1.55464e-06,3.50398e-05,3.92891e-05,-0.00104562,0.203917,0.000817041,0.434574,0,0,0,0,0,2.96231e-05,5.62943e-05,5.62228e-05,0.000855349,0.0178442,0.0178428,0.0113712,0.0408835,0.0408833,0.061821,4.54824e-11,4.54885e-11,8.2714e-10,1.1473e-06,1.14726e-06,5e-08,0,0,0,0,0,0,0,0 -22888000,0.982828,-0.00701331,-0.0115756,0.184025,0.0326759,-0.0337919,-1.37768,0.0424387,-0.0216312,-2.12049,-1.10602e-05,-4.6598e-05,-1.54214e-06,3.50026e-05,3.94119e-05,-0.00104363,0.203917,0.000817041,0.434574,0,0,0,0,0,2.64221e-05,5.63335e-05,5.62667e-05,0.00076534,0.0208318,0.0208301,0.0115447,0.0446445,0.0446441,0.0628371,4.55316e-11,4.55376e-11,8.27154e-10,1.1473e-06,1.14726e-06,5.00008e-08,0,0,0,0,0,0,0,0 -22992000,0.982976,-0.00685504,-0.0118328,0.183226,0.035997,-0.0379747,-1.38243,0.053058,-0.0326019,-2.27843,-1.09985e-05,-4.65875e-05,-1.52676e-06,4.75566e-05,2.10894e-05,-0.00103779,0.203917,0.000817041,0.434574,0,0,0,0,0,2.30941e-05,5.52055e-05,5.51405e-05,0.000671209,0.0217311,0.0217298,0.0114256,0.0402851,0.0402848,0.0624618,4.37834e-11,4.37878e-11,8.27142e-10,1.13732e-06,1.13728e-06,5.00008e-08,0,0,0,0,0,0,0,0 -23088000,0.983019,-0.00682841,-0.012149,0.182974,0.0400759,-0.041353,-1.38054,0.0567283,-0.0364364,-2.41487,-1.09987e-05,-4.65876e-05,-1.52888e-06,4.75298e-05,2.11809e-05,-0.00103639,0.203917,0.000817041,0.434574,0,0,0,0,0,2.0495e-05,5.52387e-05,5.51766e-05,0.000597784,0.0259462,0.0259451,0.0114948,0.0440353,0.0440348,0.0625034,4.38325e-11,4.38369e-11,8.27108e-10,1.13733e-06,1.13728e-06,5.00004e-08,0,0,0,0,0,0,0,0 -23192000,0.983006,-0.00671867,-0.0122445,0.183044,0.0426942,-0.0405515,-1.38341,0.0683816,-0.046635,-2.56706,-1.09241e-05,-4.65492e-05,-1.54118e-06,6.17394e-05,3.51628e-06,-0.0010325,0.203917,0.000817041,0.434574,0,0,0,0,0,1.84238e-05,5.32992e-05,5.32407e-05,0.000538935,0.0270834,0.0270834,0.0113783,0.0398888,0.0398885,0.0621316,4.24981e-11,4.25011e-11,8.27053e-10,1.11661e-06,1.11656e-06,5.00004e-08,0,0,0,0,0,0,0,0 -23288000,0.983041,-0.00718764,-0.0123517,0.18283,0.0461036,-0.0442842,-1.37964,0.0726075,-0.050742,-2.70576,-1.09243e-05,-4.65495e-05,-1.53683e-06,6.16913e-05,3.66662e-06,-0.00103028,0.203917,0.000817041,0.434574,0,0,0,0,0,1.67504e-05,5.33243e-05,5.32744e-05,0.000490683,0.0322473,0.0322474,0.0114483,0.0438416,0.0438412,0.0621698,4.25472e-11,4.25502e-11,8.2697e-10,1.11662e-06,1.11656e-06,5e-08,0,0,0,0,0,0,0,0 -23392000,0.983001,-0.00698672,-0.012376,0.183048,0.0465766,-0.0416929,-1.38171,0.0832359,-0.0559341,-2.85277,-1.08947e-05,-4.64921e-05,-1.5642e-06,6.91229e-05,-2.47337e-05,-0.00102904,0.203917,0.000817041,0.434574,0,0,0,0,0,1.53444e-05,5.065e-05,5.06037e-05,0.000450479,0.0327352,0.0327354,0.0113344,0.0398409,0.0398406,0.061802,4.15714e-11,4.15734e-11,8.2686e-10,1.0845e-06,1.08444e-06,5e-08,0,0,0,0,0,0,0,0 -23488000,0.983031,-0.00708861,-0.0126813,0.182866,0.0490261,-0.0423862,-1.38294,0.0878178,-0.0600016,-2.98953,-1.08947e-05,-4.64924e-05,-1.55256e-06,6.90852e-05,-2.46354e-05,-0.00102754,0.203917,0.000817041,0.434574,0,0,0,0,0,1.44581e-05,5.06736e-05,5.06276e-05,0.000424525,0.0385326,0.0385332,0.0115115,0.0441671,0.0441667,0.0628137,4.16205e-11,4.16225e-11,8.26769e-10,1.0845e-06,1.08444e-06,5.00008e-08,0,0,0,0,0,0,0,0 -23592000,0.983051,-0.00730379,-0.0125063,0.182758,0.0456542,-0.0433063,-1.38215,0.0946942,-0.0697471,-3.14077,-1.08244e-05,-4.64746e-05,-1.54499e-06,8.81278e-05,-3.80127e-05,-0.00102515,0.203917,0.000817041,0.434574,0,0,0,0,0,1.34213e-05,4.75119e-05,4.74719e-05,0.000394243,0.0376529,0.0376537,0.0113978,0.0401758,0.0401755,0.0624388,4.09379e-11,4.09393e-11,8.26604e-10,1.04326e-06,1.04319e-06,5.00008e-08,0,0,0,0,0,0,0,0 -23688000,0.983065,-0.00792692,-0.0130192,0.182622,0.0424523,-0.0439475,-1.28619,0.0989393,-0.0739769,-3.27479,-1.08243e-05,-4.6475e-05,-1.52554e-06,8.8085e-05,-3.79114e-05,-0.00102352,0.203917,0.000817041,0.434574,0,0,0,0,0,1.25396e-05,4.75315e-05,4.74937e-05,0.000368031,0.0433448,0.0433453,0.0114707,0.0449617,0.0449614,0.0624784,4.09869e-11,4.09884e-11,8.26401e-10,1.04326e-06,1.04319e-06,5.00004e-08,0,0,0,0,0,0,0,0 -23792000,0.983029,-0.00972913,-0.0158717,0.182503,0.035418,-0.0365088,-0.950864,0.108278,-0.0780531,-3.40169,-1.07722e-05,-4.64265e-05,-1.50821e-06,8.89225e-05,-5.74741e-05,-0.00101897,0.203917,0.000817041,0.434574,0,0,0,0,0,1.1773e-05,4.43073e-05,4.42557e-05,0.000345174,0.0398078,0.0398081,0.0113584,0.0407985,0.0407983,0.0621082,4.05233e-11,4.05243e-11,8.26163e-10,9.96764e-07,9.9669e-07,5.00004e-08,0,0,0,0,0,0,0,0 -23888000,0.982934,-0.0129741,-0.0198288,0.182429,0.0294333,-0.0352362,-0.537368,0.1114,-0.0814557,-3.47611,-1.07725e-05,-4.64265e-05,-1.5133e-06,8.89094e-05,-5.74013e-05,-0.00101789,0.203917,0.000817041,0.434574,0,0,0,0,0,1.10859e-05,4.43593e-05,4.42911e-05,0.000325023,0.0442864,0.044287,0.0114309,0.0459524,0.0459521,0.062146,4.05723e-11,4.05733e-11,8.25882e-10,9.96768e-07,9.96692e-07,5e-08,0,0,0,0,0,0,0,0 -23992000,0.982863,-0.0151855,-0.0223615,0.182342,0.0311866,-0.0317038,-0.142905,0.120179,-0.0837135,-3.54686,-1.07401e-05,-4.63898e-05,-1.5147e-06,8.40297e-05,-6.71865e-05,-0.00099165,0.203917,0.000817041,0.434574,0,0,0,0,0,1.04676e-05,4.163e-05,4.15546e-05,0.000307235,0.0398069,0.0398082,0.0113203,0.0415252,0.041525,0.0617806,4.0257e-11,4.02577e-11,8.25561e-10,9.47348e-07,9.47269e-07,5e-08,0,0,0,0,0,0,0,0 -24088000,0.98289,-0.0147527,-0.0213417,0.182355,0.0354357,-0.0381835,0.0841377,0.123352,-0.0870467,-3.55029,-1.07406e-05,-4.63897e-05,-1.53293e-06,8.4043e-05,-6.71484e-05,-0.000990787,0.203917,0.000817041,0.434574,0,0,0,0,0,1.00493e-05,4.16326e-05,4.15683e-05,0.000295344,0.0446102,0.0446122,0.0115,0.0469583,0.0469581,0.0627924,4.0306e-11,4.03068e-11,8.25301e-10,9.47353e-07,9.47272e-07,5.00008e-08,0,0,0,0,0,0,0,0 -24192000,0.982982,-0.0118242,-0.0175463,0.182482,0.0466005,-0.0429649,0.0714938,0.131877,-0.0920648,-3.56739,-1.07188e-05,-4.63663e-05,-1.52548e-06,8.31799e-05,-6.81424e-05,-0.000969936,0.203917,0.000817041,0.434574,0,0,0,0,0,9.55531e-06,3.92999e-05,3.92561e-05,0.000280829,0.0405725,0.0405747,0.0113903,0.0422688,0.0422688,0.0624205,4.00839e-11,4.00846e-11,8.24899e-10,8.98182e-07,8.981e-07,5.00008e-08,0,0,0,0,0,0,0,0 -24288000,0.983063,-0.00950144,-0.0142638,0.182463,0.0480741,-0.0440403,0.0492307,0.1365,-0.0962872,-3.56496,-1.07189e-05,-4.63664e-05,-1.52322e-06,8.31773e-05,-6.80914e-05,-0.000968926,0.203917,0.000817041,0.434574,0,0,0,0,0,9.10239e-06,3.92944e-05,3.92677e-05,0.00026771,0.0457612,0.0457638,0.011467,0.0480125,0.0480126,0.062462,4.01329e-11,4.01336e-11,8.24445e-10,8.98187e-07,8.98104e-07,5.00004e-08,0,0,0,0,0,0,0,0 -24392000,0.983128,-0.0085673,-0.013213,0.182241,0.0430449,-0.0358409,0.0660737,0.1445,-0.0968577,-3.55961,-1.06995e-05,-4.63592e-05,-1.48337e-06,7.57715e-05,-7.81777e-05,-0.000968719,0.203917,0.000817041,0.434574,0,0,0,0,0,8.69562e-06,3.72302e-05,3.72082e-05,0.000255876,0.0407331,0.040735,0.0113588,0.0430023,0.0430023,0.0620956,3.99634e-11,3.9964e-11,8.23942e-10,8.53665e-07,8.53579e-07,5.00004e-08,0,0,0,0,0,0,0,0 -24488000,0.983154,-0.00879774,-0.0132822,0.182082,0.036485,-0.0307447,0.0638378,0.148315,-0.100048,-3.55275,-1.06984e-05,-4.636e-05,-1.42812e-06,7.57397e-05,-7.82077e-05,-0.000968924,0.203917,0.000817041,0.434574,0,0,0,0,0,8.33745e-06,3.72568e-05,3.72369e-05,0.000245055,0.0454613,0.0454636,0.0114356,0.0489723,0.0489724,0.0621363,4.00123e-11,4.0013e-11,8.23382e-10,8.53669e-07,8.53583e-07,5e-08,0,0,0,0,0,0,0,0 -24592000,0.983107,-0.00948661,-0.0134589,0.182292,0.0355029,-0.0235254,0.0590858,0.154263,-0.0971531,-3.54795,-1.06964e-05,-4.63763e-05,-1.4383e-06,6.44642e-05,-8.66436e-05,-0.000967627,0.203917,0.000817041,0.434574,0,0,0,0,0,8.02038e-06,3.55048e-05,3.54886e-05,0.000235242,0.0399489,0.0399506,0.011329,0.0436602,0.0436603,0.0617752,3.98707e-11,3.98714e-11,8.22768e-10,8.14908e-07,8.14822e-07,5e-08,0,0,0,0,0,0,0,0 -24688000,0.983085,-0.00996026,-0.0132424,0.182398,0.0312029,-0.0209023,0.0590935,0.157503,-0.0992174,-3.5402,-1.06964e-05,-4.63761e-05,-1.44557e-06,6.44656e-05,-8.66734e-05,-0.000968352,0.203917,0.000817041,0.434574,0,0,0,0,0,7.80211e-06,3.5538e-05,3.55256e-05,0.000228596,0.0442244,0.0442262,0.0115121,0.0497636,0.0497638,0.0627909,3.99197e-11,3.99204e-11,8.2228e-10,8.14911e-07,8.14826e-07,5.00012e-08,0,0,0,0,0,0,0,0 -24792000,0.983097,-0.0100603,-0.0126178,0.182374,0.0289644,-0.0181478,0.0507914,0.161484,-0.0962875,-3.53809,-1.07032e-05,-4.63803e-05,-1.45095e-06,5.99163e-05,-9.14984e-05,-0.000967673,0.203917,0.000817041,0.434574,0,0,0,0,0,7.51265e-06,3.40829e-05,3.40745e-05,0.000220227,0.0385095,0.0385109,0.0114048,0.0441986,0.0441987,0.0624237,3.97934e-11,3.97941e-11,8.21563e-10,7.82181e-07,7.82098e-07,5.00012e-08,0,0,0,0,0,0,0,0 -24888000,0.983092,-0.00987111,-0.0121509,0.182441,0.0247848,-0.01857,0.0412024,0.164108,-0.098047,-3.53478,-1.0703e-05,-4.63805e-05,-1.43617e-06,5.99049e-05,-9.14794e-05,-0.000967278,0.203917,0.000817041,0.434574,0,0,0,0,0,7.2575e-06,3.41235e-05,3.41164e-05,0.000212458,0.0423535,0.0423549,0.0114839,0.0503508,0.0503511,0.0624699,3.98423e-11,3.9843e-11,8.20779e-10,7.82185e-07,7.82102e-07,5.00008e-08,0,0,0,0,0,0,0,0 -24992000,0.98307,-0.00963336,-0.011945,0.182587,0.0189265,-0.0110193,0.0330489,0.166373,-0.0902603,-3.53314,-1.07152e-05,-4.64013e-05,-1.44051e-06,5.19513e-05,-9.98738e-05,-0.00096681,0.203917,0.000817041,0.434574,0,0,0,0,0,7.02605e-06,3.29425e-05,3.29352e-05,0.000205365,0.0366779,0.0366791,0.0113776,0.0445994,0.0445997,0.0621081,3.97261e-11,3.97268e-11,8.19933e-10,7.55119e-07,7.55039e-07,5.00008e-08,0,0,0,0,0,0,0,0 -25088000,0.983055,-0.00998859,-0.0119813,0.182644,0.0142807,-0.00802917,0.0302009,0.16792,-0.0912276,-3.53406,-1.07157e-05,-4.64011e-05,-1.4612e-06,5.20061e-05,-9.98565e-05,-0.000965389,0.203917,0.000817041,0.434574,0,0,0,0,0,6.80099e-06,3.29938e-05,3.29876e-05,0.000198751,0.0400819,0.0400833,0.0114567,0.05073,0.0507304,0.0621539,3.97749e-11,3.97757e-11,8.19018e-10,7.55123e-07,7.55043e-07,5.00004e-08,0,0,0,0,0,0,0,0 -25192000,0.982998,-0.0102557,-0.0118577,0.182948,0.012465,-0.00330798,0.0292246,0.171343,-0.0856633,-3.53302,-1.07498e-05,-4.64287e-05,-1.50589e-06,4.31432e-05,-9.96572e-05,-0.000963814,0.203917,0.000817041,0.434574,0,0,0,0,0,6.60826e-06,3.20502e-05,3.20455e-05,0.000192689,0.0346111,0.0346123,0.0113514,0.0448611,0.0448614,0.0617973,3.96678e-11,3.96686e-11,8.18036e-10,7.32983e-07,7.32906e-07,5.00004e-08,0,0,0,0,0,0,0,0 -25288000,0.982942,-0.010363,-0.0112196,0.183283,0.00616237,-0.00280242,0.0237157,0.172231,-0.0859418,-3.53102,-1.07513e-05,-4.64275e-05,-1.58335e-06,4.32177e-05,-9.96877e-05,-0.000963659,0.203917,0.000817041,0.434574,0,0,0,0,0,6.42427e-06,3.21076e-05,3.21062e-05,0.000187,0.0376321,0.0376337,0.0114303,0.0509146,0.0509149,0.0618427,3.97166e-11,3.97175e-11,8.16981e-10,7.32987e-07,7.32911e-07,5e-08,0,0,0,0,0,0,0,0 -25392000,0.982938,-0.0105189,-0.0110497,0.183303,-8.12404e-06,0.00396623,0.0219942,0.170443,-0.076852,-3.53147,-1.07695e-05,-4.64533e-05,-1.58673e-06,3.8268e-05,-0.00010528,-0.000961927,0.203917,0.000817041,0.434574,0,0,0,0,0,6.2471e-06,3.13626e-05,3.13623e-05,0.000181798,0.0324822,0.0324836,0.0113259,0.0449921,0.0449923,0.061491,3.96195e-11,3.96203e-11,8.15855e-10,7.14994e-07,7.14921e-07,5e-08,0,0,0,0,0,0,0,0 -25488000,0.98294,-0.0105468,-0.0107457,0.183311,-0.0065164,0.00647757,0.0218009,0.170104,-0.0763616,-3.53045,-1.07695e-05,-4.64532e-05,-1.58855e-06,3.82823e-05,-0.000105279,-0.000961546,0.203917,0.000817041,0.434574,0,0,0,0,0,6.12905e-06,3.14304e-05,3.14313e-05,0.000178332,0.0351485,0.0351502,0.0115097,0.0509289,0.0509292,0.0625027,3.96683e-11,3.96692e-11,8.14971e-10,7.14998e-07,7.14926e-07,5.00008e-08,0,0,0,0,0,0,0,0 -25592000,0.982906,-0.010779,-0.0105729,0.183491,-0.00929355,0.00620163,0.022643,0.168974,-0.0724453,-3.52949,-1.08185e-05,-4.64724e-05,-1.6515e-06,3.48021e-05,-0.000101072,-0.000960863,0.203917,0.000817041,0.434574,0,0,0,0,0,5.97587e-06,3.08486e-05,3.08505e-05,0.000173755,0.0303679,0.0303694,0.0114039,0.0450065,0.0450067,0.0621449,3.95826e-11,3.95835e-11,8.13714e-10,7.00409e-07,7.0034e-07,5.00008e-08,0,0,0,0,0,0,0,0 -25688000,0.982911,-0.0102507,-0.0102811,0.183508,-0.0109508,0.00916703,0.0115186,0.16803,-0.071729,-3.52992,-1.08185e-05,-4.64724e-05,-1.64936e-06,3.48315e-05,-0.000101078,-0.000960089,0.203917,0.000817041,0.434574,0,0,0,0,0,5.82827e-06,3.09253e-05,3.09259e-05,0.000169408,0.0327427,0.0327442,0.011484,0.0507991,0.0507994,0.062196,3.96313e-11,3.96322e-11,8.12376e-10,7.00413e-07,7.00344e-07,5.00004e-08,0,0,0,0,0,0,0,0 -25792000,0.982922,-0.0100563,-0.00957279,0.1835,-0.0200221,0.0147467,0.0108644,0.163341,-0.0658377,-3.53236,-1.08521e-05,-4.64984e-05,-1.66997e-06,3.23413e-05,-0.000100553,-0.000958454,0.203917,0.000817041,0.434574,0,0,0,0,0,5.68896e-06,3.04726e-05,3.04748e-05,0.000165439,0.0283463,0.0283478,0.0113789,0.04492,0.0449202,0.061843,3.95585e-11,3.95594e-11,8.10961e-10,6.88624e-07,6.88557e-07,5.00004e-08,0,0,0,0,0,0,0,0 -25888000,0.982883,-0.0101117,-0.00963422,0.183701,-0.0264389,0.0187379,0.0129143,0.161057,-0.0642095,-3.53155,-1.08539e-05,-4.64967e-05,-1.77478e-06,3.24089e-05,-0.000100586,-0.00095833,0.203917,0.000817041,0.434574,0,0,0,0,0,5.56023e-06,3.05585e-05,3.05604e-05,0.000161635,0.0304416,0.0304433,0.0114586,0.0505505,0.0505507,0.0618935,3.96072e-11,3.96081e-11,8.09463e-10,6.88627e-07,6.88561e-07,5e-08,0,0,0,0,0,0,0,0 -25992000,0.982886,-0.0102076,-0.00979342,0.183673,-0.0352733,0.0218147,0.0058778,0.151077,-0.0592053,-3.53065,-1.08878e-05,-4.65e-05,-1.78069e-06,3.53483e-05,-9.96725e-05,-0.000957798,0.203917,0.000817041,0.434574,0,0,0,0,0,5.44e-06,3.02148e-05,3.02159e-05,0.000158167,0.0264328,0.0264343,0.0113538,0.044748,0.0447481,0.061545,3.95482e-11,3.95491e-11,8.07885e-10,6.79075e-07,6.7901e-07,5e-08,0,0,0,0,0,0,0,0 -26088000,0.982909,-0.00995655,-0.00975234,0.183565,-0.0410796,0.0241461,0.0049855,0.147394,-0.0570088,-3.53109,-1.08871e-05,-4.65007e-05,-1.74005e-06,3.53441e-05,-9.96688e-05,-0.000957434,0.203917,0.000817041,0.434574,0,0,0,0,0,5.36184e-06,3.03087e-05,3.03089e-05,0.000155941,0.0283023,0.0283039,0.0115386,0.050206,0.0502063,0.0625633,3.9597e-11,3.95979e-11,8.06657e-10,6.79079e-07,6.79014e-07,5.00008e-08,0,0,0,0,0,0,0,0 -26192000,0.9829,-0.00995925,-0.0102863,0.183583,-0.0456974,0.0250935,7.61077e-05,0.139797,-0.0554241,-3.5348,-1.0938e-05,-4.6522e-05,-1.70799e-06,3.47055e-05,-9.36941e-05,-0.000955729,0.203917,0.000817041,0.434574,0,0,0,0,0,5.26135e-06,3.00503e-05,3.0048e-05,0.000152855,0.0246496,0.0246509,0.0114322,0.0445045,0.0445047,0.0622082,3.95527e-11,3.95535e-11,8.0493e-10,6.71354e-07,6.71289e-07,5.00008e-08,0,0,0,0,0,0,0,0 -26288000,0.98289,-0.00998174,-0.0105685,0.183616,-0.0491023,0.0279305,-0.00522843,0.135247,-0.052911,-3.5356,-1.0939e-05,-4.65211e-05,-1.7664e-06,3.47393e-05,-9.37198e-05,-0.000955553,0.203917,0.000817041,0.434574,0,0,0,0,0,5.15701e-06,3.01527e-05,3.01493e-05,0.000149874,0.0263262,0.0263275,0.0115127,0.0497849,0.0497851,0.0622639,3.96013e-11,3.96021e-11,8.03117e-10,6.71358e-07,6.71294e-07,5.00004e-08,0,0,0,0,0,0,0,0 -26392000,0.982907,-0.00945602,-0.0105449,0.183559,-0.0544723,0.0303619,-0.00116195,0.123128,-0.0499437,-3.53647,-1.09794e-05,-4.65202e-05,-1.82531e-06,3.78459e-05,-9.03282e-05,-0.000955467,0.203917,0.000817041,0.434574,0,0,0,0,0,5.05737e-06,2.99604e-05,2.99549e-05,0.000147181,0.0230018,0.0230027,0.0114066,0.0442025,0.0442027,0.0619131,3.95719e-11,3.95725e-11,8.01216e-10,6.65112e-07,6.65046e-07,5.00004e-08,0,0,0,0,0,0,0,0 -26488000,0.982912,-0.00923423,-0.0104389,0.183549,-0.0589233,0.0344793,0.00857946,0.117664,-0.0468558,-3.5342,-1.09798e-05,-4.65197e-05,-1.84851e-06,3.7819e-05,-9.03097e-05,-0.000956186,0.203917,0.000817041,0.434574,0,0,0,0,0,4.96565e-06,3.00694e-05,3.00635e-05,0.000144548,0.0244977,0.0244985,0.0114863,0.0493031,0.0493034,0.0619678,3.96204e-11,3.96211e-11,7.99228e-10,6.65115e-07,6.6505e-07,5e-08,0,0,0,0,0,0,0,0 -26592000,0.982891,-0.00871593,-0.0107128,0.18367,-0.0578633,0.0380051,0.00875352,0.110052,-0.0447083,-3.53494,-1.10238e-05,-4.65342e-05,-1.91511e-06,3.69663e-05,-8.5099e-05,-0.000954503,0.203917,0.000817041,0.434574,0,0,0,0,0,4.88703e-06,2.9934e-05,2.99254e-05,0.000142173,0.0214867,0.0214868,0.0113804,0.0438526,0.0438528,0.0616209,3.96054e-11,3.96059e-11,7.9715e-10,6.60027e-07,6.59959e-07,5e-08,0,0,0,0,0,0,0,0 -26688000,0.982878,-0.00860128,-0.0103935,0.183764,-0.0603075,0.0431873,0.00757857,0.104351,-0.0408083,-3.53306,-1.10255e-05,-4.65325e-05,-2.01257e-06,3.69766e-05,-8.51175e-05,-0.00095491,0.203917,0.000817041,0.434574,0,0,0,0,0,4.83718e-06,3.00497e-05,3.00419e-05,0.000140748,0.0228465,0.0228463,0.0115655,0.0487757,0.0487758,0.0626456,3.9654e-11,3.96546e-11,7.95546e-10,6.60031e-07,6.59963e-07,5.00008e-08,0,0,0,0,0,0,0,0 -26792000,0.982891,-0.00843233,-0.00986036,0.18373,-0.0650299,0.0420143,0.00636414,0.0938371,-0.0406082,-3.53592,-1.10674e-05,-4.65365e-05,-2.03685e-06,3.86117e-05,-7.93334e-05,-0.000953104,0.203917,0.000817041,0.434574,0,0,0,0,0,4.76218e-06,2.99558e-05,2.99494e-05,0.000138638,0.0201162,0.0201159,0.0114577,0.0434651,0.0434652,0.0622917,3.96529e-11,3.96532e-11,7.93309e-10,6.55906e-07,6.55834e-07,5.00008e-08,0,0,0,0,0,0,0,0 -26888000,0.982904,-0.00781325,-0.00995883,0.183684,-0.0712217,0.0463641,0.00108408,0.0872784,-0.0363535,-3.53671,-1.10667e-05,-4.65373e-05,-1.99314e-06,3.86226e-05,-7.93401e-05,-0.000952668,0.203917,0.000817041,0.434574,0,0,0,0,0,4.69171e-06,3.00801e-05,3.00718e-05,0.000136542,0.0213554,0.0213551,0.0115379,0.0482153,0.0482154,0.0623508,3.97013e-11,3.97017e-11,7.90983e-10,6.55909e-07,6.55837e-07,5.00004e-08,0,0,0,0,0,0,0,0 -26992000,0.982892,-0.00726917,-0.0104404,0.183743,-0.0762194,0.0494825,0.000253946,0.0764943,-0.0343771,-3.54019,-1.10955e-05,-4.65421e-05,-2.02231e-06,3.94003e-05,-7.5353e-05,-0.000950831,0.203917,0.000817041,0.434574,0,0,0,0,0,4.63061e-06,3.00248e-05,3.00135e-05,0.00013468,0.0188778,0.0188772,0.0114305,0.0430492,0.0430492,0.0620006,3.97131e-11,3.97132e-11,7.88563e-10,6.52571e-07,6.52493e-07,5.00004e-08,0,0,0,0,0,0,0,0 -27088000,0.982891,-0.0071143,-0.0107604,0.183736,-0.0786232,0.056994,0.0036823,0.0690232,-0.0292722,-3.5449,-1.10957e-05,-4.65419e-05,-2.03455e-06,3.94999e-05,-7.54702e-05,-0.000948984,0.203917,0.000817041,0.434574,0,0,0,0,0,4.56702e-06,3.01563e-05,3.01438e-05,0.000132818,0.0200065,0.0200054,0.0115098,0.0476322,0.0476322,0.0620583,3.97614e-11,3.97617e-11,7.86052e-10,6.52574e-07,6.52495e-07,5e-08,0,0,0,0,0,0,0,0 -27192000,0.982895,-0.00716686,-0.0106784,0.183716,-0.0835555,0.058298,0.00552197,0.0600221,-0.0271302,-3.54818,-1.11189e-05,-4.65456e-05,-2.06511e-06,3.95269e-05,-7.13093e-05,-0.000947458,0.203917,0.000817041,0.434574,0,0,0,0,0,4.5096e-06,3.01282e-05,3.01165e-05,0.000131184,0.0177558,0.0177547,0.0114025,0.042612,0.042612,0.0617116,3.97844e-11,3.97847e-11,7.83446e-10,6.49866e-07,6.49781e-07,5e-08,0,0,0,0,0,0,0,0 -27288000,0.982896,-0.00729877,-0.0116222,0.183649,-0.0903589,0.0648034,0.110527,0.0517103,-0.0212203,-3.54372,-1.11189e-05,-4.65456e-05,-2.06404e-06,3.95182e-05,-7.12978e-05,-0.000947634,0.203917,0.000817041,0.434574,0,0,0,0,0,4.47824e-06,3.02683e-05,3.02537e-05,0.000130305,0.0187359,0.0187346,0.0115872,0.0470328,0.0470328,0.0627417,3.98329e-11,3.98334e-11,7.81446e-10,6.4987e-07,6.49784e-07,5.00012e-08,0,0,0,0,0,0,0,0 -27392000,0.982846,-0.00875006,-0.0142207,0.183668,-0.0926574,0.0677668,0.442062,0.0446639,-0.0172045,-3.5239,-1.11335e-05,-4.65566e-05,-2.05367e-06,3.73215e-05,-6.80125e-05,-0.000942375,0.203917,0.000817041,0.434574,0,0,0,0,0,4.43356e-06,3.02798e-05,3.02583e-05,0.000128836,0.0165328,0.0165315,0.0114774,0.0421511,0.042151,0.0623874,3.98647e-11,3.98653e-11,7.78677e-10,6.47566e-07,6.47473e-07,5.00012e-08,0,0,0,0,0,0,0,0 -27488000,0.982793,-0.0100704,-0.0160346,0.183737,-0.0960976,0.0738145,0.74483,0.0355809,-0.0103828,-3.46805,-1.11352e-05,-4.65552e-05,-2.14604e-06,3.73098e-05,-6.80527e-05,-0.000941586,0.203917,0.000817041,0.434574,0,0,0,0,0,4.38503e-06,3.04292e-05,3.04035e-05,0.000127339,0.0173495,0.0173479,0.0115565,0.0463885,0.0463884,0.0624486,3.99129e-11,3.99137e-11,7.75818e-10,6.47568e-07,6.47475e-07,5.00008e-08,0,0,0,0,0,0,0,0 -27592000,0.982813,-0.0100092,-0.0148826,0.183731,-0.0890873,0.0735606,0.844981,0.0291553,-0.00958783,-3.40564,-1.11514e-05,-4.65611e-05,-2.14592e-06,3.58811e-05,-6.24364e-05,-0.000924512,0.203917,0.000817041,0.434574,0,0,0,0,0,4.34041e-06,3.0483e-05,3.04634e-05,0.000126066,0.0154995,0.0154975,0.0114475,0.0416585,0.0416583,0.0620975,3.9949e-11,3.995e-11,7.72863e-10,6.45028e-07,6.44928e-07,5.00008e-08,0,0,0,0,0,0,0,0 -27688000,0.982874,-0.00888062,-0.0120774,0.183669,-0.0857245,0.0707623,0.750412,0.0207971,-0.00260857,-3.33189,-1.11509e-05,-4.65616e-05,-2.11938e-06,3.59444e-05,-6.25266e-05,-0.000923228,0.203917,0.000817041,0.434574,0,0,0,0,0,4.29161e-06,3.06248e-05,3.06138e-05,0.000124754,0.016421,0.0164189,0.011526,0.0457419,0.0457417,0.0621567,3.99972e-11,3.99982e-11,7.69819e-10,6.45031e-07,6.44928e-07,5.00004e-08,0,0,0,0,0,0,0,0 -27792000,0.982899,-0.00747727,-0.0104765,0.183696,-0.0835054,0.0658115,0.741828,0.0163806,-0.0031342,-3.25464,-1.11607e-05,-4.65644e-05,-2.08415e-06,3.37606e-05,-5.53066e-05,-0.000925146,0.203917,0.000817041,0.434574,0,0,0,0,0,4.25586e-06,3.06951e-05,3.06868e-05,0.000123638,0.0147768,0.014775,0.0114171,0.0411675,0.0411673,0.0618089,4.00402e-11,4.0041e-11,7.66681e-10,6.42913e-07,6.42801e-07,5.00004e-08,0,0,0,0,0,0,0,0 -27888000,0.982891,-0.00713456,-0.0105685,0.183744,-0.0897597,0.0722526,0.779997,0.00807476,0.0034422,-3.18398,-1.11605e-05,-4.65645e-05,-2.08057e-06,3.38208e-05,-5.54019e-05,-0.000924044,0.203917,0.000817041,0.434574,0,0,0,0,0,4.21902e-06,3.08521e-05,3.0843e-05,0.000122456,0.0156004,0.0155982,0.0114947,0.04512,0.0451196,0.0618661,4.00882e-11,4.00892e-11,7.63453e-10,6.42916e-07,6.42802e-07,5e-08,0,0,0,0,0,0,0,0 -27992000,0.982884,-0.00760269,-0.0109502,0.183742,-0.088481,0.0720447,0.767281,0.00439611,0.00256413,-3.10862,-1.11616e-05,-4.65637e-05,-2.05754e-06,3.15918e-05,-4.90043e-05,-0.00092005,0.203917,0.000817041,0.434574,0,0,0,0,0,4.18794e-06,3.09395e-05,3.09305e-05,0.000121474,0.0141004,0.0140983,0.0113863,0.0406875,0.0406872,0.0615214,4.01348e-11,4.01359e-11,7.60131e-10,6.41137e-07,6.41014e-07,5e-08,0,0,0,0,0,0,0,0 -28088000,0.982895,-0.00789085,-0.0109559,0.183671,-0.0926149,0.073103,0.773641,-0.00427819,0.00954793,-3.03454,-1.11601e-05,-4.65652e-05,-1.97428e-06,3.15752e-05,-4.8965e-05,-0.000920126,0.203917,0.000817041,0.434574,0,0,0,0,0,4.17647e-06,3.11023e-05,3.10939e-05,0.000121095,0.0148987,0.0148966,0.0115689,0.0445161,0.0445156,0.0625444,4.01832e-11,4.01843e-11,7.57593e-10,6.41141e-07,6.41016e-07,5.00008e-08,0,0,0,0,0,0,0,0 -28192000,0.982896,-0.00734387,-0.0112597,0.183668,-0.0919024,0.0681575,0.779776,-0.00970878,0.00774088,-2.95722,-1.11524e-05,-4.65606e-05,-1.95545e-06,3.05567e-05,-4.33291e-05,-0.000917825,0.203917,0.000817041,0.434574,0,0,0,0,0,4.1488e-06,3.11976e-05,3.11873e-05,0.00012023,0.013518,0.0135162,0.0114585,0.0402194,0.0402189,0.0621919,4.02302e-11,4.02315e-11,7.54112e-10,6.39689e-07,6.39554e-07,5.00008e-08,0,0,0,0,0,0,0,0 -28288000,0.982914,-0.00684932,-0.0115026,0.18358,-0.0978034,0.0716192,0.779808,-0.0187816,0.0144994,-2.88489,-1.11502e-05,-4.65625e-05,-1.84327e-06,3.06509e-05,-4.34361e-05,-0.000916871,0.203917,0.000817041,0.434574,0,0,0,0,0,4.11803e-06,3.13673e-05,3.13555e-05,0.000119285,0.0142889,0.0142872,0.0115363,0.0439333,0.0439328,0.0622516,4.02781e-11,4.02797e-11,7.50546e-10,6.39692e-07,6.39554e-07,5.00004e-08,0,0,0,0,0,0,0,0 -28392000,0.982897,-0.00687467,-0.012137,0.183628,-0.0974977,0.0726489,0.780512,-0.0223575,0.0157516,-2.80916,-1.11324e-05,-4.65516e-05,-1.75517e-06,2.83897e-05,-3.93832e-05,-0.000914401,0.203917,0.000817041,0.434574,0,0,0,0,0,4.09948e-06,3.1468e-05,3.14547e-05,0.000118527,0.0130242,0.0130226,0.0114265,0.0397656,0.0397651,0.0619021,4.03219e-11,4.03239e-11,7.46887e-10,6.38511e-07,6.38365e-07,5.00004e-08,0,0,0,0,0,0,0,0 -28488000,0.982895,-0.00715709,-0.0126367,0.183592,-0.0988952,0.0765113,0.781588,-0.0317483,0.0229007,-2.73798,-1.11318e-05,-4.65521e-05,-1.72971e-06,2.84737e-05,-3.95203e-05,-0.00091302,0.203917,0.000817041,0.434574,0,0,0,0,0,4.07161e-06,3.16438e-05,3.16297e-05,0.000117686,0.0137724,0.0137706,0.0115033,0.0433752,0.0433746,0.0619595,4.03697e-11,4.0372e-11,7.43146e-10,6.38514e-07,6.38364e-07,5e-08,0,0,0,0,0,0,0,0 -28592000,0.982922,-0.00720878,-0.0126088,0.18345,-0.0914821,0.0710455,0.780264,-0.0341216,0.0188889,-2.65776,-1.11001e-05,-4.65399e-05,-1.67778e-06,2.70718e-05,-3.39577e-05,-0.000912169,0.203917,0.000817041,0.434574,0,0,0,0,0,4.04625e-06,3.17447e-05,3.17314e-05,0.00011704,0.01261,0.0126082,0.0113935,0.0393294,0.0393289,0.061613,4.04062e-11,4.0409e-11,7.39313e-10,6.37569e-07,6.3741e-07,5e-08,0,0,0,0,0,0,0,0 -28688000,0.982911,-0.00699628,-0.0119699,0.183558,-0.0919222,0.072481,0.78085,-0.0429338,0.0258093,-2.58498,-1.11003e-05,-4.65397e-05,-1.69221e-06,2.71089e-05,-3.40353e-05,-0.000911366,0.203917,0.000817041,0.434574,0,0,0,0,0,4.04696e-06,3.19235e-05,3.19124e-05,0.000116916,0.0133431,0.0133413,0.0115757,0.0428447,0.042844,0.0626388,4.04543e-11,4.04573e-11,7.36399e-10,6.37572e-07,6.37411e-07,5.00008e-08,0,0,0,0,0,0,0,0 -28792000,0.98293,-0.00630349,-0.0117617,0.183498,-0.0874386,0.0718689,0.778516,-0.0446706,0.0263266,-2.5113,-1.10674e-05,-4.65181e-05,-1.58436e-06,2.55907e-05,-3.12726e-05,-0.000907391,0.203917,0.000817041,0.434574,0,0,0,0,0,4.02938e-06,3.20231e-05,3.20123e-05,0.00011635,0.0122693,0.0122676,0.0114644,0.0389136,0.038913,0.0622842,4.04789e-11,4.04825e-11,7.32419e-10,6.3683e-07,6.3666e-07,5.00008e-08,0,0,0,0,0,0,0,0 -28888000,0.982955,-0.00615498,-0.0114987,0.183386,-0.0912624,0.0734329,0.777184,-0.0532144,0.0332864,-2.43989,-1.10652e-05,-4.652e-05,-1.47266e-06,2.56908e-05,-3.14094e-05,-0.000906176,0.203917,0.000817041,0.434574,0,0,0,0,0,4.00602e-06,3.22085e-05,3.21986e-05,0.00011568,0.0129937,0.012992,0.0115413,0.0423445,0.0423437,0.0623437,4.05266e-11,4.05305e-11,7.28363e-10,6.36833e-07,6.3666e-07,5.00004e-08,0,0,0,0,0,0,0,0 -28992000,0.982934,-0.00589678,-0.0117089,0.183488,-0.087101,0.0691898,0.77624,-0.0520138,0.0312173,-2.36638,-1.10171e-05,-4.64935e-05,-1.45959e-06,2.40454e-05,-2.83007e-05,-0.000902296,0.203917,0.000817041,0.434574,0,0,0,0,0,3.99548e-06,3.23053e-05,3.2295e-05,0.00011519,0.0119975,0.0119961,0.0114303,0.0385208,0.0385202,0.061992,4.05345e-11,4.05391e-11,7.24221e-10,6.3626e-07,6.36078e-07,5.00004e-08,0,0,0,0,0,0,0,0 -29088000,0.982936,-0.00576262,-0.0117772,0.183482,-0.0901153,0.0711923,0.776417,-0.0605703,0.0379166,-2.29316,-1.10164e-05,-4.64941e-05,-1.4273e-06,2.4081e-05,-2.83555e-05,-0.000901794,0.203917,0.000817041,0.434574,0,0,0,0,0,3.97679e-06,3.24968e-05,3.24864e-05,0.000114591,0.012717,0.0127156,0.0115064,0.0418774,0.0418766,0.0620489,4.05822e-11,4.0587e-11,7.20006e-10,6.36263e-07,6.36078e-07,5e-08,0,0,0,0,0,0,0,0 -29192000,0.982961,-0.00569794,-0.0119645,0.183334,-0.0855632,0.0685837,0.771123,-0.0577815,0.0361723,-2.22058,-1.09586e-05,-4.64569e-05,-1.30182e-06,2.25616e-05,-2.5985e-05,-0.000897397,0.203917,0.000817041,0.434574,0,0,0,0,0,3.96141e-06,3.2587e-05,3.25766e-05,0.000114181,0.0117918,0.0117907,0.011396,0.0381538,0.0381532,0.0617002,4.05685e-11,4.0574e-11,7.15708e-10,6.35829e-07,6.35635e-07,5e-08,0,0,0,0,0,0,0,0 -29288000,0.982941,-0.00595028,-0.0119883,0.183435,-0.0873775,0.0746405,0.773463,-0.0660496,0.0430877,-2.14613,-1.09582e-05,-4.64573e-05,-1.28075e-06,2.2561e-05,-2.59741e-05,-0.000897527,0.203917,0.000817041,0.434574,0,0,0,0,0,3.96989e-06,3.27835e-05,3.27738e-05,0.000114241,0.0125108,0.0125094,0.011578,0.0414463,0.0414455,0.0627282,4.06165e-11,4.06222e-11,7.12452e-10,6.35832e-07,6.35636e-07,5.00008e-08,0,0,0,0,0,0,0,0 -29392000,0.982946,-0.00639792,-0.0114459,0.183428,-0.0824222,0.072103,0.775492,-0.0638987,0.0430685,-2.06826,-1.0899e-05,-4.64222e-05,-1.19701e-06,2.13449e-05,-2.43029e-05,-0.000895866,0.203917,0.000817041,0.434574,0,0,0,0,0,3.96086e-06,3.28626e-05,3.2856e-05,0.000113887,0.0116417,0.0116406,0.011466,0.0378152,0.0378145,0.0623714,4.0576e-11,4.05825e-11,7.08023e-10,6.35509e-07,6.35306e-07,5.00008e-08,0,0,0,0,0,0,0,0 -29488000,0.982962,-0.00640027,-0.011351,0.183348,-0.0854019,0.0729383,0.77686,-0.0719226,0.0500607,-1.99403,-1.08956e-05,-4.64252e-05,-1.01992e-06,2.14059e-05,-2.43317e-05,-0.000895763,0.203917,0.000817041,0.434574,0,0,0,0,0,3.94732e-06,3.30636e-05,3.30577e-05,0.000113406,0.0123646,0.0123636,0.0115425,0.041053,0.0410522,0.0624301,4.06235e-11,4.06303e-11,7.03529e-10,6.35512e-07,6.35305e-07,5.00004e-08,0,0,0,0,0,0,0,0 -29592000,0.982983,-0.00629262,-0.0113348,0.183239,-0.080484,0.0699358,0.77847,-0.0690017,0.0483842,-1.91431,-1.08201e-05,-4.63877e-05,-8.63046e-07,2.04798e-05,-2.29015e-05,-0.000895432,0.203917,0.000817041,0.434574,0,0,0,0,0,3.93826e-06,3.31325e-05,3.3127e-05,0.000113111,0.0115469,0.0115462,0.011431,0.0375068,0.0375061,0.0620763,4.05512e-11,4.05588e-11,6.98958e-10,6.35274e-07,6.35061e-07,5.00004e-08,0,0,0,0,0,0,0,0 -29688000,0.983001,-0.00637949,-0.0111456,0.183148,-0.0846613,0.0695001,0.773564,-0.0768996,0.055111,-1.84336,-1.08172e-05,-4.63902e-05,-7.18661e-07,2.05895e-05,-2.30456e-05,-0.000894114,0.203917,0.000817041,0.434574,0,0,0,0,0,3.9247e-06,3.33379e-05,3.33334e-05,0.000112684,0.0122806,0.0122801,0.0115068,0.0406999,0.0406991,0.0621325,4.05986e-11,4.06065e-11,6.94326e-10,6.35277e-07,6.35061e-07,5e-08,0,0,0,0,0,0,0,0 -29792000,0.983009,-0.00618086,-0.0116277,0.183085,-0.0800328,0.0616463,0.770395,-0.0718892,0.0516279,-1.76739,-1.07361e-05,-4.63419e-05,-5.43605e-07,1.99326e-05,-2.19455e-05,-0.000891587,0.203917,0.000817041,0.434574,0,0,0,0,0,3.91999e-06,3.33929e-05,3.33871e-05,0.000112436,0.0115071,0.011507,0.0113958,0.037231,0.0372304,0.0617817,4.04891e-11,4.04977e-11,6.89622e-10,6.35101e-07,6.34879e-07,5e-08,0,0,0,0,0,0,0,0 -29888000,0.983009,-0.00570923,-0.0119792,0.183077,-0.0811548,0.0623774,0.76695,-0.079562,0.0575513,-1.69695,-1.0734e-05,-4.63438e-05,-4.38396e-07,2.00224e-05,-2.20722e-05,-0.000890376,0.203917,0.000817041,0.434574,0,0,0,0,0,3.93062e-06,3.36038e-05,3.35964e-05,0.000112632,0.0122505,0.0122505,0.0115776,0.0403892,0.0403885,0.0628114,4.05369e-11,4.05458e-11,6.86072e-10,6.35105e-07,6.3488e-07,5.00012e-08,0,0,0,0,0,0,0,0 -29992000,0.983007,-0.0057987,-0.0120381,0.183079,-0.0752452,0.0571084,0.764243,-0.0748108,0.0523162,-1.62456,-1.06362e-05,-4.6301e-05,-3.70481e-07,1.96654e-05,-2.17236e-05,-0.000886439,0.203917,0.000817041,0.434574,0,0,0,0,0,3.92653e-06,3.36396e-05,3.36327e-05,0.000112427,0.0115102,0.0115103,0.0114653,0.0369894,0.0369889,0.0624525,4.03852e-11,4.03947e-11,6.81259e-10,6.34968e-07,6.34739e-07,5.00012e-08,0,0,0,0,0,0,0,0 -30088000,0.982999,-0.00590914,-0.0121641,0.183114,-0.0756583,0.0585564,0.762464,-0.0820824,0.0578812,-1.55358,-1.06388e-05,-4.62985e-05,-5.14052e-07,1.96701e-05,-2.17916e-05,-0.000885581,0.203917,0.000817041,0.434574,0,0,0,0,0,3.91276e-06,3.38534e-05,3.38468e-05,0.000112084,0.0122653,0.0122654,0.0115415,0.0401217,0.0401211,0.0625104,4.04326e-11,4.04424e-11,6.76394e-10,6.34971e-07,6.34739e-07,5.00008e-08,0,0,0,0,0,0,0,0 -30192000,0.982965,-0.00587279,-0.0121477,0.183299,-0.0691472,0.0545061,0.762218,-0.0752575,0.0552692,-1.47899,-1.0572e-05,-4.62326e-05,-6.54924e-07,1.94476e-05,-2.13927e-05,-0.000883169,0.203917,0.000817041,0.434574,0,0,0,0,0,3.9116e-06,3.38686e-05,3.38625e-05,0.000111917,0.0115505,0.0115508,0.0114298,0.0367828,0.0367824,0.0621546,4.02343e-11,4.02447e-11,6.71466e-10,6.34855e-07,6.34619e-07,5.00008e-08,0,0,0,0,0,0,0,0 -30288000,0.98295,-0.00588997,-0.0121447,0.183376,-0.0680339,0.055015,0.761288,-0.0817989,0.060545,-1.41235,-1.05706e-05,-4.62336e-05,-5.97141e-07,1.95792e-05,-2.1612e-05,-0.000880776,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90647e-06,3.40854e-05,3.40798e-05,0.000111602,0.012318,0.0123184,0.0115052,0.0398976,0.0398972,0.0622099,4.02816e-11,4.02923e-11,6.66489e-10,6.34858e-07,6.3462e-07,5.00004e-08,0,0,0,0,0,0,0,0 -30392000,0.982947,-0.00586582,-0.0120366,0.183403,-0.0605731,0.0497444,0.758541,-0.0734262,0.0567656,-1.34209,-1.04775e-05,-4.6159e-05,-3.87231e-07,2.00885e-05,-2.19933e-05,-0.000876399,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90962e-06,3.40778e-05,3.40729e-05,0.000111465,0.0116236,0.0116241,0.0113942,0.0366116,0.0366113,0.0618573,4.0033e-11,4.00443e-11,6.61456e-10,6.34745e-07,6.34504e-07,5.00004e-08,0,0,0,0,0,0,0,0 -30488000,0.982972,-0.0058571,-0.0121708,0.18326,-0.0641488,0.0498861,0.759938,-0.0793972,0.0615846,-1.27245,-1.04744e-05,-4.61618e-05,-2.31001e-07,2.01859e-05,-2.21097e-05,-0.00087516,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89897e-06,3.42977e-05,3.42928e-05,0.000111186,0.0124055,0.0124062,0.0114691,0.039717,0.0397167,0.0619101,4.00803e-11,4.00918e-11,6.56378e-10,6.34748e-07,6.34505e-07,5e-08,0,0,0,0,0,0,0,0 -30592000,0.98298,-0.00617975,-0.0124488,0.183186,-0.0590838,0.0457823,0.759554,-0.0720296,0.0569247,-1.1981,-1.03748e-05,-4.60951e-05,-1.10411e-07,2.07387e-05,-2.28224e-05,-0.000872659,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89666e-06,3.4266e-05,3.42613e-05,0.000111083,0.0117234,0.0117241,0.0113588,0.0364755,0.0364753,0.0615606,3.97784e-11,3.97903e-11,6.51248e-10,6.34624e-07,6.34378e-07,5e-08,0,0,0,0,0,0,0,0 -30688000,0.982997,-0.00653566,-0.0126437,0.18307,-0.0571527,0.0445538,0.75907,-0.0776719,0.0612798,-1.12829,-1.03738e-05,-4.6096e-05,-6.37684e-08,2.08054e-05,-2.29186e-05,-0.00087151,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90485e-06,3.44883e-05,3.44841e-05,0.000111399,0.0125233,0.0125241,0.0115389,0.039579,0.0395788,0.06258,3.98261e-11,3.98382e-11,6.47386e-10,6.34627e-07,6.34381e-07,5.00008e-08,0,0,0,0,0,0,0,0 -30792000,0.983027,-0.00624074,-0.012307,0.182942,-0.0492168,0.0381428,0.756985,-0.0700112,0.0589878,-1.05481,-1.03244e-05,-4.60275e-05,-9.87064e-09,2.14544e-05,-2.28719e-05,-0.000868762,0.203917,0.000817041,0.434574,0,0,0,0,0,3.8983e-06,3.44286e-05,3.44253e-05,0.000111327,0.0118489,0.0118498,0.0114272,0.036374,0.0363739,0.0622226,3.94684e-11,3.94808e-11,6.42182e-10,6.34477e-07,6.3423e-07,5.00008e-08,0,0,0,0,0,0,0,0 -30888000,0.983009,-0.00558326,-0.0122133,0.183066,-0.0489934,0.0355721,0.755422,-0.0746519,0.062546,-0.987017,-1.03259e-05,-4.6026e-05,-9.48227e-08,2.15151e-05,-2.29969e-05,-0.00086702,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89326e-06,3.46523e-05,3.46484e-05,0.00011109,0.0126662,0.0126672,0.0115027,0.0394824,0.0394824,0.0622773,3.95156e-11,3.95282e-11,6.36942e-10,6.34481e-07,6.34232e-07,5.00004e-08,0,0,0,0,0,0,0,0 -30992000,0.983003,-0.00574656,-0.0121461,0.183097,-0.0407963,0.0295519,0.757259,-0.0643057,0.0549653,-0.91463,-1.02128e-05,-4.59532e-05,-8.02141e-08,2.23623e-05,-2.43736e-05,-0.000864152,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89348e-06,3.45643e-05,3.45612e-05,0.000111032,0.0119886,0.0119895,0.0113917,0.0363058,0.0363058,0.0619232,3.91009e-11,3.91134e-11,6.31661e-10,6.34294e-07,6.34045e-07,5.00004e-08,0,0,0,0,0,0,0,0 -31088000,0.982968,-0.00589937,-0.0122432,0.183273,-0.0396467,0.0272475,0.756102,-0.068111,0.0576203,-0.845024,-1.02131e-05,-4.59529e-05,-9.69e-08,2.24098e-05,-2.44485e-05,-0.000863029,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89348e-06,3.47893e-05,3.47867e-05,0.000110807,0.0128229,0.0128238,0.0114666,0.0394248,0.039425,0.0619754,3.9148e-11,3.91608e-11,6.2635e-10,6.34298e-07,6.34048e-07,5e-08,0,0,0,0,0,0,0,0 -31192000,0.982979,-0.00608658,-0.0123527,0.183199,-0.0347243,0.0227813,0.759039,-0.0591499,0.0518966,-0.770426,-1.01334e-05,-4.58908e-05,9.58553e-08,2.33138e-05,-2.52567e-05,-0.000861411,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89484e-06,3.46724e-05,3.46701e-05,0.000110765,0.0121404,0.0121413,0.0113564,0.0362688,0.036269,0.0616246,3.86762e-11,3.86887e-11,6.21003e-10,6.34069e-07,6.3382e-07,5e-08,0,0,0,0,0,0,0,0 -31288000,0.982996,-0.00634475,-0.0124469,0.183094,-0.0319667,0.0210408,0.762112,-0.0623134,0.0540535,-0.700874,-1.01314e-05,-4.58927e-05,1.96249e-07,2.33937e-05,-2.53434e-05,-0.000860147,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90645e-06,3.48981e-05,3.48963e-05,0.000111129,0.0129865,0.0129874,0.0115367,0.0394035,0.0394038,0.0626455,3.87238e-11,3.87365e-11,6.16988e-10,6.34073e-07,6.33823e-07,5.00008e-08,0,0,0,0,0,0,0,0 -31392000,0.983011,-0.00609527,-0.0122267,0.183036,-0.0250981,0.0136137,0.760978,-0.0529142,0.0477469,-0.624735,-1.0057e-05,-4.58402e-05,1.50173e-07,2.39618e-05,-2.62436e-05,-0.000858037,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90191e-06,3.47516e-05,3.475e-05,0.000111108,0.0122992,0.0122998,0.0114252,0.0362606,0.0362609,0.062287,3.81962e-11,3.82085e-11,6.11593e-10,6.33799e-07,6.3355e-07,5.00008e-08,0,0,0,0,0,0,0,0 -31488000,0.982988,-0.00586185,-0.0125593,0.183149,-0.025438,0.0110686,0.756931,-0.0553629,0.0488789,-0.5555,-1.00575e-05,-4.58397e-05,1.22756e-07,2.40126e-05,-2.63157e-05,-0.000856736,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89987e-06,3.4978e-05,3.49753e-05,0.000110911,0.0131684,0.013169,0.0115008,0.0394154,0.0394158,0.0623413,3.82433e-11,3.82558e-11,6.06175e-10,6.33803e-07,6.33554e-07,5.00004e-08,0,0,0,0,0,0,0,0 -31592000,0.983008,-0.00575062,-0.0130178,0.183011,-0.0212747,0.00781487,0.760383,-0.0439522,0.0438063,-0.480517,-9.99468e-06,-4.57574e-05,2.77883e-07,2.55452e-05,-2.70488e-05,-0.000854555,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89838e-06,3.48021e-05,3.4798e-05,0.000110897,0.0124622,0.0124626,0.0113901,0.0362788,0.0362792,0.0619861,3.76612e-11,3.76729e-11,6.00734e-10,6.33474e-07,6.33227e-07,5.00004e-08,0,0,0,0,0,0,0,0 -31688000,0.983036,-0.00573764,-0.0135228,0.182821,-0.0235485,0.00687105,0.756683,-0.0461227,0.0444593,-0.413631,-9.9908e-06,-4.5761e-05,4.73934e-07,2.56796e-05,-2.71696e-05,-0.000852321,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89009e-06,3.50283e-05,3.50229e-05,0.000110715,0.0133449,0.0133453,0.0114652,0.0394567,0.0394573,0.0620381,3.77083e-11,3.77202e-11,5.95275e-10,6.33478e-07,6.3323e-07,5e-08,0,0,0,0,0,0,0,0 -31792000,0.983052,-0.00600462,-0.0141939,0.182678,-0.0132969,0.00433754,0.756373,-0.0340716,0.0419736,-0.339613,-9.97112e-06,-4.5657e-05,6.36214e-07,2.79098e-05,-2.69316e-05,-0.000850034,0.203917,0.000817041,0.434574,0,0,0,0,0,3.88901e-06,3.48233e-05,3.48166e-05,0.000110707,0.0126255,0.0126257,0.0113552,0.0363199,0.0363204,0.0616863,3.70754e-11,3.70862e-11,5.89796e-10,6.33097e-07,6.32852e-07,5e-08,0,0,0,0,0,0,0,0 -31888000,0.98305,-0.00572232,-0.0139664,0.182713,-0.00946419,0.00273662,0.755058,-0.0351576,0.0422573,-0.272883,-9.96945e-06,-4.56586e-05,7.18824e-07,2.80172e-05,-2.70272e-05,-0.000847899,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90618e-06,3.50469e-05,3.50406e-05,0.000111094,0.0135193,0.0135193,0.0115358,0.0395238,0.0395244,0.062709,3.7123e-11,3.7134e-11,5.85692e-10,6.33101e-07,6.32856e-07,5.00008e-08,0,0,0,0,0,0,0,0 -31992000,0.983029,-0.00598033,-0.0135318,0.182852,-0.000464563,0.00173506,0.75277,-0.0226,0.038574,-0.203211,-9.94023e-06,-4.55717e-05,6.53425e-07,2.98095e-05,-2.72824e-05,-0.000844008,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90984e-06,3.48107e-05,3.48065e-05,0.000111089,0.0127808,0.0127807,0.0114245,0.0363808,0.0363813,0.0623496,3.6443e-11,3.64528e-11,5.80191e-10,6.32668e-07,6.32426e-07,5.00008e-08,0,0,0,0,0,0,0,0 -32088000,0.983045,-0.00635561,-0.0131984,0.182779,0.000231437,-0.00176415,0.754653,-0.0226326,0.0386284,-0.135303,-9.93918e-06,-4.55727e-05,7.05673e-07,2.9888e-05,-2.73434e-05,-0.000842368,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90209e-06,3.50323e-05,3.50302e-05,0.000110917,0.0136834,0.0136831,0.0115003,0.0396119,0.0396125,0.0624038,3.64901e-11,3.65001e-11,5.74681e-10,6.32672e-07,6.3243e-07,5.00004e-08,0,0,0,0,0,0,0,0 -32192000,0.983038,-0.00655582,-0.0134502,0.18279,0.00503725,-0.00623488,0.755383,-0.0108509,0.0365702,-0.0646635,-9.95317e-06,-4.54961e-05,6.80672e-07,3.15368e-05,-2.6464e-05,-0.000838595,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90219e-06,3.4771e-05,3.47688e-05,0.000110919,0.0129205,0.0129199,0.0113898,0.0364573,0.0364578,0.0620479,3.57683e-11,3.57769e-11,5.69162e-10,6.32191e-07,6.31953e-07,5.00004e-08,0,0,0,0,0,0,0,0 -32288000,0.983059,-0.00652513,-0.0137085,0.182659,0.00608101,-0.0095672,0.752944,-0.0103353,0.0357918,0.00164638,-9.95063e-06,-4.54985e-05,8.10728e-07,3.16587e-05,-2.65362e-05,-0.000836325,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89459e-06,3.49919e-05,3.49891e-05,0.000110749,0.0138375,0.0138367,0.011465,0.0397159,0.0397164,0.0620999,3.58154e-11,3.58242e-11,5.63639e-10,6.32195e-07,6.31958e-07,5e-08,0,0,0,0,0,0,0,0 -32392000,0.98304,-0.0066334,-0.013839,0.182746,0.0123682,-0.0116394,0.751776,0.00150492,0.032672,0.0770869,-9.9526e-06,-4.54346e-05,7.68891e-07,3.29671e-05,-2.59665e-05,-0.000833971,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89737e-06,3.47057e-05,3.47028e-05,0.00011075,0.0130554,0.0130545,0.0113552,0.0365459,0.0365463,0.0617475,3.50574e-11,3.50645e-11,5.58112e-10,6.31672e-07,6.31438e-07,5e-08,0,0,0,0,0,0,0,0 -32488000,0.983048,-0.00873446,-0.0122745,0.182726,0.0343281,-0.0583651,0.0448742,0.00422957,0.0278177,0.0941336,-9.95337e-06,-4.54338e-05,7.26488e-07,3.29671e-05,-2.59665e-05,-0.000833971,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90872e-06,3.492e-05,3.49266e-05,0.000111149,0.0152373,0.0152337,0.0112397,0.0398877,0.0398881,0.0627591,3.51052e-11,3.5112e-11,5.5398e-10,0,0,0,0,0,0,0,0,0,0,0 -32592000,0.983055,-0.00872543,-0.0122374,0.182695,0.0361787,-0.0599159,0.0395115,0.0169882,0.0236614,0.0870135,-1.00316e-05,-4.5374e-05,8.21744e-07,3.29671e-05,-2.59665e-05,-0.000833971,0.203917,0.000817041,0.434574,0,0,0,0,0,3.9096e-06,3.43744e-05,3.43802e-05,0.00011115,0.0149583,0.0149545,0.0107247,0.0367248,0.0367251,0.0623467,3.42395e-11,3.42425e-11,5.48452e-10,0,0,0,0,0,0,0,0,0,0,0 -32688000,0.983055,-0.00869789,-0.0121289,0.1827,0.03311,-0.0645244,0.0378103,0.0203215,0.0176748,0.0856733,-1.0032e-05,-4.53737e-05,8.02165e-07,3.29671e-05,-2.59665e-05,-0.000833971,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90315e-06,3.45874e-05,3.4593e-05,0.000110979,0.0167574,0.016753,0.010427,0.0401693,0.0401695,0.0622879,3.42868e-11,3.42895e-11,5.42928e-10,0,0,0,0,0,0,0,0,0,0,0 -32792000,0.983058,-0.00856209,-0.0121583,0.182691,0.0336862,-0.063615,0.0330912,0.0307667,0.0150061,0.0789916,-1.01355e-05,-4.5318e-05,9.19051e-07,3.29671e-05,-2.59665e-05,-0.000833971,0.203917,0.000817041,0.434574,0,0,0,0,0,3.90532e-06,3.36647e-05,3.36687e-05,0.000110977,0.0166236,0.0166193,0.0099667,0.0369723,0.0369723,0.0618183,3.33581e-11,3.33568e-11,5.37409e-10,0,0,0,0,0,0,0,0,0,0,0 -32888000,0.983072,-0.00852925,-0.0122448,0.182612,0.034107,-0.0690431,0.0309787,0.0340611,0.00865124,0.0761155,-1.01348e-05,-4.5319e-05,9.6448e-07,3.29671e-05,-2.59665e-05,-0.000833971,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89714e-06,3.38704e-05,3.38739e-05,0.000110805,0.0187697,0.0187648,0.00969502,0.0405396,0.0405394,0.0616708,3.34054e-11,3.34039e-11,5.31898e-10,6.31674e-07,6.3144e-07,5.00021e-08,0,0,0,0,0,0,0,0 -32992000,0.983086,-0.00842349,-0.0122156,0.182543,0.0326156,-0.0674505,0.0290711,0.0424683,0.00423935,0.0715265,-1.02175e-05,-4.5287e-05,1.11037e-06,3.30587e-05,-2.67111e-05,-0.000833957,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89736e-06,3.25341e-05,3.25358e-05,0.000110801,0.0187629,0.0187584,0.00929709,0.0372971,0.0372969,0.0611586,3.24383e-11,3.24329e-11,5.26396e-10,6.31655e-07,6.31421e-07,5.00073e-08,0,0,0,0,0,0,0,0 -33088000,0.98308,-0.00837418,-0.0122071,0.182575,0.0300375,-0.071215,0.0302882,0.0454965,-0.00239541,0.0752843,-1.02185e-05,-4.52861e-05,1.06143e-06,3.30579e-05,-2.67104e-05,-0.00083396,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89119e-06,3.27294e-05,3.27312e-05,0.000110624,0.021509,0.021504,0.00907659,0.041032,0.0410315,0.060938,3.24853e-11,3.24804e-11,5.20906e-10,6.3166e-07,6.31426e-07,5.00122e-08,0,0,0,0,0,0,0,0 -33192000,0.98308,-0.00824082,-0.0121192,0.182588,0.0277184,-0.069824,0.0280058,0.0521746,-0.00585968,0.0747502,-1.03042e-05,-4.52541e-05,1.0104e-06,3.33799e-05,-3.12404e-05,-0.000833883,0.203917,0.000817041,0.434574,0,0,0,0,0,3.88934e-06,3.09967e-05,3.09969e-05,0.000110618,0.0216101,0.0216056,0.00875473,0.0377236,0.0377231,0.0603969,3.15135e-11,3.15051e-11,5.1543e-10,6.30456e-07,6.30223e-07,5.00138e-08,0,0,0,0,0,0,0,0 -33288000,0.983104,-0.00830783,-0.012105,0.182461,0.0254315,-0.0707345,0.0270644,0.0546742,-0.012606,0.0768624,-1.03011e-05,-4.52569e-05,1.16733e-06,3.338e-05,-3.12408e-05,-0.000833879,0.203917,0.000817041,0.434574,0,0,0,0,0,3.9016e-06,3.11801e-05,3.11805e-05,0.000111003,0.0249017,0.024897,0.00866639,0.0416823,0.0416814,0.0610416,3.1561e-11,3.15529e-11,5.11344e-10,6.30461e-07,6.30228e-07,5.00187e-08,0,0,0,0,0,0,0,0 -33392000,0.983116,-0.00809081,-0.0121434,0.182402,0.0214906,-0.0618321,0.0260524,0.0581851,-0.00989569,0.0734807,-1.04487e-05,-4.52161e-05,1.235e-06,3.21451e-05,-4.2307e-05,-0.000833551,0.203917,0.000817041,0.434574,0,0,0,0,0,3.8996e-06,2.91278e-05,2.91261e-05,0.000110991,0.0247596,0.0247558,0.00840907,0.038273,0.0382722,0.0604676,3.06251e-11,3.06138e-11,5.05895e-10,6.26673e-07,6.26442e-07,5.00113e-08,0,0,0,0,0,0,0,0 -33488000,0.983113,-0.00810403,-0.0121304,0.182416,0.0189819,-0.0628903,0.0253271,0.0600919,-0.0158444,0.0718407,-1.04481e-05,-4.52168e-05,1.27036e-06,3.21584e-05,-4.23181e-05,-0.000833504,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89453e-06,2.92982e-05,2.92967e-05,0.000110802,0.0284479,0.0284441,0.00829068,0.0425065,0.0425053,0.0601448,3.06721e-11,3.06612e-11,5.00467e-10,6.26678e-07,6.26447e-07,5.00156e-08,0,0,0,0,0,0,0,0 -33592000,0.983138,-0.0079001,-0.0120811,0.182297,0.0155988,-0.0581745,0.0249794,0.0627119,-0.0140589,0.0694087,-1.05492e-05,-4.51887e-05,1.4043e-06,3.10227e-05,-5.28736e-05,-0.000833283,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89148e-06,2.70544e-05,2.7051e-05,0.000110785,0.0277706,0.0277676,0.00809502,0.0389443,0.0389433,0.0595674,2.98129e-11,2.97993e-11,4.95058e-10,6.19561e-07,6.19335e-07,5.00039e-08,0,0,0,0,0,0,0,0 -33688000,0.983148,-0.00789451,-0.0120634,0.182244,0.0119365,-0.0601467,0.0214906,0.0640843,-0.0197606,0.0674003,-1.05482e-05,-4.51897e-05,1.4566e-06,3.10523e-05,-5.28977e-05,-0.000833177,0.203917,0.000817041,0.434574,0,0,0,0,0,3.88377e-06,2.72117e-05,2.72085e-05,0.000110593,0.031712,0.0317089,0.00802375,0.0434825,0.0434811,0.0592193,2.98599e-11,2.98468e-11,4.89671e-10,6.19566e-07,6.1934e-07,5.00068e-08,0,0,0,0,0,0,0,0 -33792000,0.983162,-0.00771505,-0.0120322,0.182177,0.00798503,-0.0536316,0.0234155,0.0676008,-0.016879,0.0644036,-1.06388e-05,-4.51438e-05,1.42228e-06,2.81708e-05,-6.47726e-05,-0.000832787,0.203917,0.000817041,0.434574,0,0,0,0,0,3.87812e-06,2.49256e-05,2.49204e-05,0.000110572,0.0302961,0.0302938,0.00788255,0.0397089,0.0397078,0.0586497,2.91092e-11,2.90937e-11,4.84308e-10,6.09063e-07,6.08844e-07,5.00021e-08,0,0,0,0,0,0,0,0 -33888000,0.983172,-0.00775135,-0.0119982,0.182126,0.0044865,-0.0525029,0.0223843,0.0681416,-0.0220042,0.0643243,-1.06369e-05,-4.51456e-05,1.5232e-06,2.81935e-05,-6.47897e-05,-0.000832702,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89126e-06,2.50708e-05,2.50659e-05,0.000110936,0.0343258,0.0343237,0.00792027,0.0445517,0.0445503,0.0591571,2.91567e-11,2.91417e-11,4.80314e-10,6.09067e-07,6.08849e-07,5.00037e-08,0,0,0,0,0,0,0,0 -33992000,0.983163,-0.00754593,-0.0121209,0.182171,0.00311212,-0.0420776,0.0221989,0.0705329,-0.01614,0.0634188,-1.07317e-05,-4.50919e-05,1.49239e-06,2.09276e-05,-7.9583e-05,-0.000832274,0.203917,0.000817041,0.434574,0,0,0,0,0,3.89021e-06,2.28819e-05,2.28749e-05,0.000110902,0.0321261,0.0321248,0.0078243,0.0405171,0.0405161,0.0585886,2.85318e-11,2.8515e-11,4.74996e-10,5.95683e-07,5.95474e-07,5.00008e-08,0,0,0,0,0,0,0,0 -34088000,0.983161,-0.0075343,-0.0121301,0.182183,0.000811702,-0.0442881,0.0223576,0.0707499,-0.0203071,0.0645711,-1.07324e-05,-4.50913e-05,1.45879e-06,2.0943e-05,-7.95954e-05,-0.00083222,0.203917,0.000817041,0.434574,0,0,0,0,0,3.88239e-06,2.30166e-05,2.30098e-05,0.000110695,0.0361165,0.0361152,0.00783519,0.0456364,0.0456351,0.058226,2.85788e-11,2.85625e-11,4.69707e-10,5.95687e-07,5.95478e-07,5.00004e-08,0,0,0,0,0,0,0,0 -34192000,0.983158,-0.00742722,-0.012157,0.182203,-0.00258845,-0.0354318,0.0212063,0.0733098,-0.015496,0.0629352,-1.07937e-05,-4.50511e-05,1.54239e-06,1.56488e-05,-9.18921e-05,-0.000831215,0.203917,0.000817041,0.434574,0,0,0,0,0,3.88317e-06,2.10271e-05,2.10189e-05,0.00011065,0.0331895,0.033189,0.00778104,0.0413125,0.0413115,0.0576841,2.80815e-11,2.8064e-11,4.64446e-10,5.80255e-07,5.80056e-07,5.00004e-08,0,0,0,0,0,0,0,0 -34288000,0.98316,-0.0073052,-0.0122161,0.182193,-0.00345633,-0.036496,0.0199994,0.0730461,-0.0189525,0.0608257,-1.07925e-05,-4.50522e-05,1.60411e-06,1.5724e-05,-9.19453e-05,-0.000830941,0.203917,0.000817041,0.434574,0,0,0,0,0,3.87675e-06,2.11535e-05,2.1145e-05,0.000110434,0.0370423,0.0370419,0.00782768,0.0466587,0.0466575,0.057336,2.81285e-11,2.81115e-11,4.59216e-10,5.80259e-07,5.8006e-07,5e-08,0,0,0,0,0,0,0,0 -34392000,0.983178,-0.00719756,-0.0122232,0.1821,-0.00577775,-0.0278576,0.0210002,0.0737819,-0.014043,0.0586651,-1.08424e-05,-4.50259e-05,1.62485e-06,1.04826e-05,-0.000102828,-0.000830624,0.203917,0.000817041,0.434574,0,0,0,0,0,3.87085e-06,1.9423e-05,1.94133e-05,0.000110388,0.0335301,0.0335302,0.0078092,0.042045,0.0420441,0.0568276,2.77491e-11,2.77312e-11,4.54019e-10,5.6369e-07,5.63503e-07,5e-08,0,0,0,0,0,0,0,0 -34488000,0.983175,-0.0072727,-0.0121745,0.182118,-0.00776572,-0.0286296,0.0207991,0.073157,-0.016789,0.059062,-1.08406e-05,-4.50276e-05,1.71772e-06,1.05176e-05,-0.00010285,-0.000830491,0.203917,0.000817041,0.434574,0,0,0,0,0,3.88577e-06,1.95429e-05,1.95334e-05,0.000110725,0.0371733,0.0371737,0.00794642,0.0475572,0.0475562,0.0573171,2.77966e-11,2.77791e-11,4.50155e-10,5.63694e-07,5.63508e-07,5.00008e-08,0,0,0,0,0,0,0,0 -34592000,0.983179,-0.00717297,-0.0119614,0.18211,-0.00718042,-0.0230348,0.81281,0.074005,-0.0135666,0.0894318,-1.08688e-05,-4.50069e-05,1.71829e-06,5.87629e-06,-0.000109521,-0.000829883,0.203917,0.000817041,0.434574,0,0,0,0,0,3.88257e-06,1.80907e-05,1.80809e-05,0.000110666,0.0318372,0.031838,0.00795435,0.0426362,0.0426354,0.056834,2.75183e-11,2.75004e-11,4.45016e-10,5.46799e-07,5.46625e-07,5.00008e-08,0,0,0,0,0,0,0,0 -34688000,0.983185,-0.00716083,-0.0116842,0.1821,-0.00800334,-0.0217027,1.76166,0.0732708,-0.0156936,0.20365,-1.08687e-05,-4.50069e-05,1.71875e-06,6.13259e-06,-0.000109701,-0.000828915,0.203917,0.000817041,0.434574,0,0,0,0,0,3.87369e-06,1.82057e-05,1.81967e-05,0.000110436,0.0334861,0.0334873,0.00805857,0.04805,0.0480491,0.0565376,2.75653e-11,2.7548e-11,4.39911e-10,5.46802e-07,5.46629e-07,5.00004e-08,0,0,0,0,0,0,0,0 -34792000,0.983194,-0.00709955,-0.0114349,0.182066,-0.0085172,-0.0154833,2.76147,0.0737615,-0.0122843,0.372385,-1.088e-05,-4.49858e-05,1.77706e-06,1.01466e-05,-0.000121588,-0.000794126,0.203917,0.000817041,0.434574,0,0,0,0,0,3.87014e-06,1.72175e-05,1.72085e-05,0.00011037,0.0288114,0.028813,0.00809059,0.0429654,0.0429648,0.0560982,2.73901e-11,2.73726e-11,4.34844e-10,5.28096e-07,5.27937e-07,5.00004e-08,0,0,0,0,0,0,0,0 -34888000,0.9832,-0.00708668,-0.01116,0.182052,-0.00951845,-0.0139647,3.70402,0.0728641,-0.0136266,0.651715,-1.08793e-05,-4.49858e-05,1.78555e-06,1.11418e-05,-0.000122278,-0.000790243,0.203917,0.000817041,0.434574,0,0,0,0,0,3.86098e-06,1.73308e-05,1.73226e-05,0.000110132,0.0305399,0.0305419,0.00821916,0.0481625,0.0481618,0.0558413,2.74371e-11,2.74202e-11,4.29813e-10,5.28098e-07,5.27941e-07,5e-08,0,0,0,0,0,0,0,0 +12000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +60000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +156000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +264000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +360000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +456000,0.983119,-0.00753939,-0.0133676,0.182322,0.000682994,2.38496e-05,-0.0161989,4.28855e-05,1.50768e-05,0.0380912,2.24563e-08,5.36074e-11,9.69814e-07,8.23652e-11,-6.98798e-11,3.5566e-09,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,0.000102289,0.00248762,0.00248735,0.00290692,25.0072,25.0072,0.562642,0.371881,0.371881,1.00102,1e-06,1e-06,9.99412e-07,4.00001e-06,4.00001e-06,4.00001e-06,0,0,0,0,0,0,0,0 +564000,0.983173,-0.00757457,-0.0136319,0.182008,6.97579e-05,0.000895459,-0.0339974,0.000119613,5.79026e-05,0.0219429,3.40817e-08,1.1906e-10,1.46666e-06,-3.02146e-10,2.5136e-10,-1.26802e-08,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,6.78821e-05,0.00254378,0.00254362,0.00192027,25.0378,25.0378,0.562141,0.889586,0.889586,0.504176,9.99998e-07,1e-06,9.95701e-07,4.00002e-06,4.00002e-06,4.00001e-06,0,0,0,0,0,0,0,0 +660000,0.983089,-0.00762057,-0.0139585,0.182436,0.00108318,0.00124637,-0.0458162,5.71916e-05,0.000106632,0.0108311,-2.00795e-08,-7.59152e-10,-7.91859e-07,-3.66934e-10,8.86414e-10,-3.97895e-08,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,5.17202e-05,0.00262719,0.00262708,0.00145718,10.2725,10.2725,0.559747,0.370921,0.370921,0.341709,9.99992e-07,1e-06,9.87422e-07,4e-06,4e-06,3.99998e-06,0,0,0,0,0,0,0,0 +756000,0.983022,-0.00758964,-0.0142058,0.182781,0.00184741,0.00335976,-0.0577735,0.00016852,0.000311625,0.00918085,-8.26426e-08,-9.95708e-10,-3.34976e-06,-9.53962e-10,1.38832e-09,-6.54921e-08,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,4.27841e-05,0.00274317,0.00274307,0.00119989,10.329,10.329,0.554634,0.691099,0.691099,0.264019,9.99984e-07,1e-06,9.73454e-07,4.00001e-06,4.00001e-06,3.99985e-06,0,0,0,0,0,0,0,0 +864000,0.98303,-0.00763433,-0.0146045,0.182703,0.00367379,0.00552016,-0.0731847,0.000268229,0.00046696,-0.0017796,-7.1361e-08,-3.61185e-09,-2.93653e-06,1.73792e-08,-5.28855e-09,4.85345e-07,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.77881e-05,0.00290666,0.00290656,0.001055,3.79521,3.79522,0.545681,0.29662,0.29662,0.222867,9.99931e-07,9.9996e-07,9.51897e-07,3.99981e-06,3.99981e-06,3.99947e-06,0,0,0,0,0,0,0,0 +960000,0.98288,-0.00761993,-0.0148213,0.183493,0.00599332,0.00798198,-0.0876367,0.000691105,0.00110942,-0.00939528,-3.13195e-07,-8.23429e-09,-1.26138e-05,1.75332e-08,-5.50178e-09,4.96127e-07,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.60549e-05,0.00309054,0.00309042,0.00100429,3.87598,3.876,0.536857,0.464503,0.464504,0.207917,9.99918e-07,9.9996e-07,9.31125e-07,3.99981e-06,3.99981e-06,3.99893e-06,0,0,0,0,0,0,0,0 +1056000,0.982913,-0.00762172,-0.0151135,0.18329,0.00919886,0.00902321,-0.101915,0.000757959,0.00104357,-0.0217426,-2.06945e-07,-3.61543e-08,-9.2621e-06,7.25462e-08,7.30519e-09,1.23158e-06,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.38671e-05,0.00328743,0.00328729,0.000939164,1.80112,1.80114,0.52003,0.225115,0.225115,0.191138,9.99529e-07,9.99593e-07,8.96758e-07,3.99916e-06,3.99916e-06,3.99762e-06,0,0,0,0,0,0,0,0 +1176000,0.98294,-0.00765045,-0.015409,0.183117,0.0169117,0.00857008,-0.106224,0.00239717,0.00203407,-0.0214095,-1.5823e-07,-2.81208e-08,-7.27655e-06,-1.46569e-08,7.82653e-08,-2.30782e-06,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.22845e-05,0.0036014,0.00360122,0.000890993,1.9397,1.93976,0.492595,0.350072,0.350073,0.179272,9.99494e-07,9.99593e-07,8.43954e-07,3.99917e-06,3.99917e-06,3.99465e-06,0,0,0,0,0,0,0,0 +1280000,0.983154,-0.00757575,-0.0156814,0.181948,0.0213601,0.00697666,-0.116847,0.00252484,0.00133578,-0.0272312,4.31271e-07,-2.26734e-07,1.27493e-05,1.2816e-07,1.80697e-07,-4.49888e-06,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.2612e-05,0.00389703,0.00389679,0.000898366,1.11423,1.1143,0.466406,0.201291,0.201292,0.180545,9.97206e-07,9.97339e-07,7.93821e-07,3.99728e-06,3.99728e-06,3.99058e-06,0,0,0,0,0,0,0,0 +1380000,0.983224,-0.00756967,-0.0159274,0.18155,0.0294883,0.00858067,-0.117204,0.00506294,0.00214483,-0.0257876,5.52035e-07,-2.02886e-07,1.73216e-05,-1.84935e-08,2.98505e-07,-1.03407e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.31327e-05,0.00430697,0.00430665,0.000911542,1.27183,1.27194,0.435597,0.290904,0.290908,0.18344,9.97165e-07,9.97339e-07,7.36871e-07,3.99729e-06,3.99729e-06,3.9843e-06,0,0,0,0,0,0,0,0 +1480000,0.983157,-0.00757056,-0.0159818,0.181905,0.0284755,0.00738887,-0.12906,0.00430365,0.00153679,-0.037926,3.50263e-07,-1.04424e-06,9.40485e-06,5.70402e-07,3.13364e-07,-1.06202e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.50429e-05,0.0045626,0.00456224,0.000965802,0.874671,0.87477,0.411975,0.175886,0.175889,0.19563,9.88117e-07,9.88324e-07,6.91032e-07,3.99275e-06,3.99275e-06,3.9778e-06,0,0,0,0,0,0,0,0 +1580000,0.983152,-0.00762424,-0.0163116,0.1819,0.0353916,0.00811123,-0.141558,0.00746983,0.00227541,-0.0488718,3.33359e-07,-1.03485e-06,8.76258e-06,5.29086e-07,3.46003e-07,-1.2226e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.55629e-05,0.00505843,0.00505797,0.000975109,1.07415,1.07431,0.376921,0.247333,0.247341,0.197853,9.8807e-07,9.88323e-07,6.27911e-07,3.99275e-06,3.99275e-06,3.96643e-06,0,0,0,0,0,0,0,0 +1680000,0.983181,-0.0077306,-0.0163272,0.181738,0.0343459,0.00898089,-0.14876,0.005953,0.00171292,-0.0547659,2.32162e-07,-3.00255e-06,1.09002e-05,1.57299e-06,3.53251e-07,-1.73164e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.57555e-05,0.00515023,0.00514979,0.000979729,0.853339,0.853489,0.342852,0.159579,0.159584,0.199067,9.64617e-07,9.64911e-07,5.66253e-07,3.98469e-06,3.98469e-06,3.95229e-06,0,0,0,0,0,0,0,0 +1780000,0.98314,-0.00787282,-0.0166146,0.18193,0.0445701,0.00978183,-0.149302,0.00991318,0.00265646,-0.0574721,1.01834e-07,-2.9512e-06,5.99307e-06,1.3647e-06,5.17407e-07,-2.53482e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.59121e-05,0.0057117,0.00571113,0.000976858,1.09559,1.09582,0.310044,0.225614,0.225627,0.198568,9.64571e-07,9.6491e-07,5.06616e-07,3.98469e-06,3.9847e-06,3.9347e-06,0,0,0,0,0,0,0,0 +1880000,0.98325,-0.00786567,-0.0163555,0.181358,0.0406201,0.0104369,-0.150794,0.00760539,0.00198028,-0.0621617,-8.05234e-08,-6.81326e-06,1.52166e-05,3.10426e-06,4.48838e-07,-3.26701e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.55205e-05,0.00547784,0.00547736,0.000968362,0.910471,0.91067,0.280122,0.151763,0.151771,0.1969,9.17145e-07,9.1751e-07,4.51305e-07,3.97333e-06,3.97334e-06,3.91414e-06,0,0,0,0,0,0,0,0 +1980000,0.983274,-0.00793682,-0.0166791,0.181196,0.0490684,0.0122235,-0.148077,0.0121044,0.00306201,-0.06116,-2.38189e-08,-6.71211e-06,1.68713e-05,2.79084e-06,7.01636e-07,-4.50655e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.53568e-05,0.00607136,0.00607072,0.000955262,1.18627,1.18657,0.25346,0.2191,0.219119,0.194267,9.17108e-07,9.17508e-07,4.00988e-07,3.97332e-06,3.97334e-06,3.89058e-06,0,0,0,0,0,0,0,0 +2080000,0.983232,-0.00805202,-0.0161604,0.181465,0.0413455,0.0085858,-0.151115,0.00863001,0.00210527,-0.063194,-8.89123e-07,-1.26412e-05,1.15845e-05,4.95246e-06,6.26967e-07,-5.60768e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.5887e-05,0.00541741,0.00541702,0.000979688,0.961496,0.9617,0.237463,0.148934,0.148943,0.200317,8.41437e-07,8.41833e-07,3.66258e-07,3.96086e-06,3.96088e-06,3.87053e-06,0,0,0,0,0,0,0,0 +2180000,0.983192,-0.00804591,-0.0165026,0.181651,0.0488976,0.0103049,-0.152125,0.0131245,0.00311238,-0.0666007,-9.84174e-07,-1.25553e-05,7.34749e-06,4.69556e-06,8.32879e-07,-6.61814e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.54405e-05,0.00600184,0.00600127,0.000957669,1.25018,1.25048,0.216471,0.219185,0.219207,0.195966,8.4141e-07,8.41832e-07,3.24723e-07,3.96085e-06,3.96088e-06,3.84138e-06,0,0,0,0,0,0,0,0 +2280000,0.98336,-0.00816146,-0.0158436,0.180789,0.0379788,0.00762841,-0.145048,0.00868435,0.00198688,-0.0611816,-1.70926e-06,-1.98055e-05,1.89355e-05,6.6757e-06,8.89938e-07,-8.54888e-05,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.41171e-05,0.00500771,0.00500742,0.00093281,0.958998,0.959184,0.198386,0.147166,0.147176,0.191188,7.44913e-07,7.45314e-07,2.87839e-07,3.95045e-06,3.95047e-06,3.8087e-06,0,0,0,0,0,0,0,0 +2380000,0.983378,-0.00823225,-0.0160962,0.180666,0.0457792,0.00725635,-0.14326,0.0129224,0.00271031,-0.0590548,-1.67134e-06,-1.96759e-05,1.97469e-05,6.27999e-06,1.23089e-06,-0.000102164,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.34747e-05,0.00554882,0.00554842,0.000906669,1.23772,1.23798,0.183037,0.218295,0.218317,0.186215,7.44895e-07,7.45312e-07,2.55415e-07,3.95044e-06,3.95047e-06,3.77249e-06,0,0,0,0,0,0,0,0 +2480000,0.98352,-0.00817932,-0.015373,0.179958,0.0325139,0.00472705,-0.145947,0.00810068,0.00158544,-0.0620351,-2.72939e-06,-2.70214e-05,2.87025e-05,7.87649e-06,1.16787e-06,-0.000114389,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.19758e-05,0.0044227,0.00442252,0.000879865,0.905051,0.905197,0.170177,0.14401,0.144019,0.181325,6.42458e-07,6.42837e-07,2.2703e-07,3.94396e-06,3.94398e-06,3.73285e-06,0,0,0,0,0,0,0,0 +2580000,0.98356,-0.00829116,-0.015569,0.179719,0.0363071,0.00373564,-0.148184,0.0115725,0.00205954,-0.0658602,-2.71355e-06,-2.69412e-05,2.88247e-05,7.59602e-06,1.41779e-06,-0.000126649,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,3.12058e-05,0.0049036,0.00490335,0.000853076,1.15796,1.15815,0.159428,0.213012,0.21303,0.176501,6.42446e-07,6.42835e-07,2.02221e-07,3.94394e-06,3.94398e-06,3.68926e-06,0,0,0,0,0,0,0,0 +2680000,0.983624,-0.00836102,-0.0149184,0.179422,0.0250011,0.00229466,-0.14817,0.00692241,0.00110639,-0.0648263,-3.96979e-06,-3.3188e-05,3.14741e-05,8.25495e-06,1.59304e-06,-0.000146442,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.97067e-05,0.00383096,0.00383089,0.000826477,0.822951,0.823054,0.150561,0.139083,0.13909,0.171942,5.46251e-07,5.46597e-07,1.80541e-07,3.94109e-06,3.94112e-06,3.64201e-06,0,0,0,0,0,0,0,0 +2780000,0.983663,-0.00834216,-0.0151067,0.17919,0.0308159,0.00151732,-0.148276,0.0098107,0.00131167,-0.0651535,-3.9304e-06,-3.30853e-05,3.22836e-05,7.83835e-06,1.98001e-06,-0.000165506,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.99909e-05,0.00425021,0.00425008,0.000831425,1.04541,1.04555,0.14735,0.203799,0.203814,0.17502,5.46245e-07,5.46596e-07,1.66109e-07,3.94108e-06,3.94111e-06,3.6037e-06,0,0,0,0,0,0,0,0 +2880000,0.983684,-0.00836849,-0.0152839,0.179057,0.0359343,0.000609532,-0.147277,0.0131822,0.00138136,-0.061984,-3.92234e-06,-3.29278e-05,3.09255e-05,7.30357e-06,2.46505e-06,-0.000189876,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.92039e-05,0.00469678,0.00469657,0.000804132,1.31111,1.3113,0.141011,0.296986,0.297013,0.170531,5.46238e-07,5.46593e-07,1.48928e-07,3.94106e-06,3.9411e-06,3.54836e-06,0,0,0,0,0,0,0,0 +2980000,0.983771,-0.00836188,-0.0147434,0.178624,0.0259164,-0.0015924,-0.151195,0.00837872,0.000521132,-0.0663024,-5.21055e-06,-3.79801e-05,3.39614e-05,7.44401e-06,2.65407e-06,-0.000204964,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.7722e-05,0.00368158,0.00368152,0.000778068,0.929853,0.929953,0.135939,0.192603,0.192614,0.166534,4.61558e-07,4.61869e-07,1.33918e-07,3.94038e-06,3.94042e-06,3.48945e-06,0,0,0,0,0,0,0,0 +3080000,0.983726,-0.00840471,-0.0149389,0.178855,0.0313613,-0.00331621,-0.15482,0.011277,0.000227467,-0.0710814,-5.23483e-06,-3.78853e-05,3.16154e-05,7.10051e-06,2.96604e-06,-0.000221042,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.70576e-05,0.00406835,0.00406824,0.000752812,1.16067,1.1608,0.13174,0.277515,0.277536,0.162729,4.61553e-07,4.61867e-07,1.20719e-07,3.94036e-06,3.9404e-06,3.42508e-06,0,0,0,0,0,0,0,0 +3180000,0.983604,-0.00836253,-0.0145452,0.179558,0.0237355,-0.00616647,-0.158178,0.00726182,-0.000378837,-0.0764853,-6.87826e-06,-4.18361e-05,2.3074e-05,6.76867e-06,3.24088e-06,-0.000236948,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.57668e-05,0.00321568,0.00321566,0.000728629,0.826203,0.826273,0.128356,0.181093,0.181101,0.159311,3.88813e-07,3.89085e-07,1.09095e-07,3.94034e-06,3.94038e-06,3.35648e-06,0,0,0,0,0,0,0,0 +3280000,0.983617,-0.00841694,-0.0145616,0.179486,0.0266492,-0.00705178,-0.161473,0.00984379,-0.00109671,-0.0850811,-6.85919e-06,-4.17881e-05,2.31474e-05,6.5143e-06,3.48612e-06,-0.00024946,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.51275e-05,0.00355097,0.00355093,0.00070586,1.02725,1.02735,0.125665,0.258071,0.258086,0.156261,3.8881e-07,3.89084e-07,9.89038e-08,3.94032e-06,3.94037e-06,3.28355e-06,0,0,0,0,0,0,0,0 +3380000,0.983589,-0.00813608,-0.0141736,0.179684,0.0195173,-0.00674476,-0.165149,0.00627082,-0.00106894,-0.0894642,-8.60164e-06,-4.49088e-05,1.96553e-05,5.82375e-06,4.02294e-06,-0.000270576,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.4699e-05,0.00283604,0.00283604,0.000706062,0.73899,0.739044,0.126455,0.170201,0.170207,0.159595,3.26517e-07,3.26751e-07,9.19798e-08,3.93988e-06,3.93993e-06,3.22518e-06,0,0,0,0,0,0,0,0 +3480000,0.983525,-0.00813291,-0.0142424,0.180025,0.0243972,-0.00521284,-0.161684,0.00854706,-0.0016423,-0.0860427,-8.63593e-06,-4.47567e-05,1.53578e-05,5.11543e-06,4.69094e-06,-0.000306171,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.40653e-05,0.00312702,0.003127,0.000684076,0.916663,0.91675,0.124557,0.240173,0.240185,0.15694,3.26514e-07,3.2675e-07,8.3751e-08,3.93985e-06,3.93991e-06,3.14421e-06,0,0,0,0,0,0,0,0 +3580000,0.983505,-0.00795744,-0.0138211,0.180176,0.0194421,-0.00471573,-0.167528,0.0057095,-0.00113268,-0.0924431,-1.03071e-05,-4.73271e-05,1.25593e-05,4.30526e-06,5.31949e-06,-0.000325012,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.30113e-05,0.00251875,0.00251877,0.000662957,0.667376,0.667431,0.122909,0.160341,0.160346,0.154522,2.72954e-07,2.73155e-07,7.64026e-08,3.93834e-06,3.9384e-06,3.05853e-06,0,0,0,0,0,0,0,0 +3680000,0.983616,-0.00799862,-0.0138891,0.179562,0.0222004,-0.00538987,-0.165718,0.00792131,-0.00166631,-0.0916503,-1.01773e-05,-4.73033e-05,1.73967e-05,3.63307e-06,5.99986e-06,-0.000359464,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.24358e-05,0.00277101,0.00277102,0.00064296,0.825697,0.825771,0.121464,0.224325,0.224335,0.152332,2.72951e-07,2.73153e-07,6.98846e-08,3.93832e-06,3.93837e-06,2.96856e-06,0,0,0,0,0,0,0,0 +3780000,0.983587,-0.00782831,-0.0136844,0.179743,0.0149477,-0.00212809,-0.168189,0.00516373,-0.00103087,-0.0976437,-1.16905e-05,-4.95524e-05,1.51316e-05,2.65864e-06,6.76634e-06,-0.000380604,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.15385e-05,0.0022435,0.00224354,0.000623946,0.607165,0.607215,0.120172,0.151538,0.151542,0.150411,2.2675e-07,2.2692e-07,6.40508e-08,3.93545e-06,3.93552e-06,2.87528e-06,0,0,0,0,0,0,0,0 +3880000,0.983633,-0.0078266,-0.0137618,0.179484,0.0163845,-0.00160705,-0.167571,0.00685046,-0.00116509,-0.0998387,-1.16242e-05,-4.95271e-05,1.72284e-05,2.09546e-06,7.33445e-06,-0.000410019,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.10284e-05,0.00246135,0.00246139,0.000605925,0.748897,0.748967,0.118932,0.210386,0.210395,0.148657,2.26748e-07,2.26919e-07,5.88511e-08,3.93543e-06,3.93549e-06,2.77839e-06,0,0,0,0,0,0,0,0 +3980000,0.983529,-0.00775831,-0.0135484,0.180074,0.0139167,-0.000748894,-0.168161,0.00448403,-0.000694907,-0.100258,-1.28175e-05,-5.13559e-05,1.23419e-05,8.32763e-07,8.34022e-06,-0.000444805,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.02459e-05,0.00199725,0.00199731,0.000588769,0.55571,0.555755,0.117735,0.143682,0.143686,0.14712,1.86983e-07,1.87127e-07,5.41717e-08,3.93123e-06,3.93129e-06,2.67921e-06,0,0,0,0,0,0,0,0 +4080000,0.983484,-0.00773807,-0.0134888,0.180324,0.0160178,-0.00139537,-0.161429,0.00613951,-0.000796346,-0.0951101,-1.2818e-05,-5.12627e-05,1.03412e-05,-1.05861e-08,9.20038e-06,-0.000490926,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,2.02889e-05,0.00218428,0.00218434,0.000588065,0.683015,0.683074,0.119284,0.198092,0.1981,0.151279,1.86982e-07,1.87126e-07,5.09894e-08,3.93122e-06,3.93128e-06,2.6031e-06,0,0,0,0,0,0,0,0 +4180000,0.983512,-0.00777263,-0.0132434,0.180192,0.0126562,-0.00165759,-0.161164,0.00408549,-0.000523978,-0.0976966,-1.37008e-05,-5.29364e-05,1.06665e-05,-1.21156e-06,1.01059e-05,-0.000519762,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.95476e-05,0.00177259,0.00177269,0.000571622,0.509682,0.509719,0.117881,0.136607,0.13661,0.149833,1.52986e-07,1.53106e-07,4.70867e-08,3.92588e-06,3.92593e-06,2.49938e-06,0,0,0,0,0,0,0,0 +4280000,0.983577,-0.00782383,-0.0132683,0.179832,0.0154959,-0.00227627,-0.164334,0.00553263,-0.00075403,-0.104696,-1.3646e-05,-5.29474e-05,1.30037e-05,-1.58226e-06,1.04926e-05,-0.000539901,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.90904e-05,0.001932,0.00193211,0.000556255,0.624204,0.624254,0.116488,0.187075,0.187081,0.148613,1.52985e-07,1.53105e-07,4.35972e-08,3.92585e-06,3.92591e-06,2.39567e-06,0,0,0,0,0,0,0,0 +4380000,0.983658,-0.00773269,-0.0131458,0.179401,0.0136788,-0.00292501,-0.155918,0.003847,-0.00057014,-0.0960261,-1.43997e-05,-5.4413e-05,1.53171e-05,-3.23292e-06,1.18862e-05,-0.000593829,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.84224e-05,0.00156658,0.00156669,0.000541426,0.467938,0.467969,0.114884,0.130158,0.130161,0.147354,1.24235e-07,1.24334e-07,4.04113e-08,3.91969e-06,3.91974e-06,2.29025e-06,0,0,0,0,0,0,0,0 +4480000,0.983656,-0.00781322,-0.0130894,0.179412,0.015166,-0.00136736,-0.153566,0.00534498,-0.000750543,-0.0955509,-1.43837e-05,-5.43822e-05,1.51526e-05,-3.84412e-06,1.25299e-05,-0.000628736,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.80022e-05,0.00170144,0.00170157,0.000527418,0.570523,0.570568,0.113196,0.177059,0.177065,0.146198,1.24234e-07,1.24333e-07,3.75435e-08,3.91967e-06,3.91972e-06,2.18537e-06,0,0,0,0,0,0,0,0 +4580000,0.983594,-0.00773331,-0.0129654,0.179761,0.0125644,-0.00251092,-0.154042,0.00367225,-0.000515359,-0.0992454,-1.51458e-05,-5.5667e-05,1.27688e-05,-4.98098e-06,1.33809e-05,-0.000654585,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.74344e-05,0.00137843,0.00137855,0.000514051,0.429164,0.429191,0.111399,0.124208,0.124211,0.145114,1.00222e-07,1.00303e-07,3.49266e-08,3.91303e-06,3.91308e-06,2.08147e-06,0,0,0,0,0,0,0,0 +4680000,0.983676,-0.00769787,-0.0129476,0.179317,0.0137121,-0.00345566,-0.150454,0.00506793,-0.0007489,-0.101074,-1.50921e-05,-5.56826e-05,1.50321e-05,-5.48657e-06,1.39193e-05,-0.00068379,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.74189e-05,0.00149172,0.00149186,0.000513157,0.520511,0.520543,0.112105,0.167816,0.167821,0.149394,1.00222e-07,1.00302e-07,3.3124e-08,3.91302e-06,3.91306e-06,2.00363e-06,0,0,0,0,0,0,0,0 +4780000,0.983635,-0.00750526,-0.0128577,0.179555,0.00542575,-0.00190172,-0.146518,0.00329636,-0.0005402,-0.0991975,-1.57566e-05,-5.67515e-05,1.32801e-05,-6.72791e-06,1.49434e-05,-0.000719652,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.68859e-05,0.00120841,0.00120852,0.00050044,0.392683,0.392702,0.109997,0.118662,0.118664,0.14826,8.04291e-08,8.04939e-08,3.09e-08,3.90626e-06,3.90629e-06,1.90205e-06,0,0,0,0,0,0,0,0 +4880000,0.983654,-0.00746872,-0.0128783,0.179451,0.00609739,-0.00386875,-0.140961,0.00388712,-0.000839066,-0.097211,-1.57304e-05,-5.67489e-05,1.40308e-05,-7.31394e-06,1.5576e-05,-0.000754735,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.65212e-05,0.00130304,0.00130316,0.000488319,0.473958,0.473979,0.107742,0.159201,0.159205,0.147079,8.04285e-08,8.04934e-08,2.88774e-08,3.90624e-06,3.90627e-06,1.80222e-06,0,0,0,0,0,0,0,0 +4980000,0.983643,-0.00743305,-0.0128885,0.179514,0.00705737,-0.00324722,-0.134945,0.00461483,-0.00121397,-0.0936029,-1.57346e-05,-5.67127e-05,1.29801e-05,-7.90427e-06,1.62328e-05,-0.000791743,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.61556e-05,0.00140169,0.00140181,0.000476738,0.567397,0.567425,0.105354,0.212865,0.212871,0.145851,8.0428e-08,8.04929e-08,2.70248e-08,3.90622e-06,3.90625e-06,1.70472e-06,0,0,0,0,0,0,0,0 +5080000,0.983604,-0.00723892,-0.0127213,0.179746,0.00534492,-0.00266009,-0.129835,0.00297491,-0.000933176,-0.0900393,-1.6278e-05,-5.74018e-05,1.13067e-05,-8.91707e-06,1.71899e-05,-0.000826961,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.56815e-05,0.00113535,0.00113545,0.000465643,0.430693,0.430712,0.102896,0.151124,0.151127,0.144635,6.43052e-08,6.43569e-08,2.53186e-08,3.89962e-06,3.89963e-06,1.61045e-06,0,0,0,0,0,0,0,0 +5180000,0.983592,-0.00713826,-0.0127484,0.179817,0.00417989,-0.000182232,-0.126407,0.0034691,-0.00107682,-0.0880395,-1.62736e-05,-5.73867e-05,1.102e-05,-9.4003e-06,1.77305e-05,-0.000857831,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.5366e-05,0.00121724,0.00121735,0.000455045,0.51327,0.513297,0.100334,0.200701,0.200705,0.143356,6.43048e-08,6.43565e-08,2.37593e-08,3.8996e-06,3.89961e-06,1.51917e-06,0,0,0,0,0,0,0,0 +5280000,0.983603,-0.00701315,-0.0126357,0.179766,0.00316996,0.00167651,-0.115628,0.00214292,-0.000463577,-0.0818786,-1.66413e-05,-5.78757e-05,1.12104e-05,-1.03267e-05,1.86478e-05,-0.000895349,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.49463e-05,0.000988128,0.000988216,0.000444895,0.390479,0.390499,0.0977362,0.143546,0.143549,0.142085,5.13039e-08,5.13448e-08,2.23186e-08,3.89335e-06,3.89336e-06,1.43168e-06,0,0,0,0,0,0,0,0 +5380000,0.983584,-0.00691427,-0.0126172,0.179878,0.00118862,0.00410179,-0.115159,0.00240035,-0.000210521,-0.0842677,-1.6657e-05,-5.78522e-05,1.01637e-05,-1.05864e-05,1.89635e-05,-0.00091349,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.49312e-05,0.00105591,0.00105601,0.000444119,0.463097,0.463123,0.09747,0.189299,0.189303,0.14595,5.13037e-08,5.13445e-08,2.1318e-08,3.89335e-06,3.89335e-06,1.36831e-06,0,0,0,0,0,0,0,0 +5480000,0.98357,-0.00692219,-0.0126388,0.179952,0.000137022,0.00690929,-0.107479,0.00134479,0.000356372,-0.0775303,-1.68074e-05,-5.81756e-05,9.50656e-06,-1.13576e-05,1.96791e-05,-0.000948714,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.45436e-05,0.000860287,0.000860362,0.000434373,0.353746,0.353767,0.0946637,0.136427,0.136429,0.144442,4.09037e-08,4.09359e-08,2.00658e-08,3.88758e-06,3.88757e-06,1.28669e-06,0,0,0,0,0,0,0,0 +5580000,0.983572,-0.00695274,-0.0126568,0.179938,0.000615611,0.0104341,-0.0994047,0.00146677,0.00121401,-0.0699568,-1.68151e-05,-5.81601e-05,8.88643e-06,-1.1856e-05,2.02737e-05,-0.000983201,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.42418e-05,0.000916307,0.00091639,0.000425158,0.41746,0.417488,0.0919106,0.17865,0.178654,0.143008,4.09034e-08,4.09356e-08,1.89183e-08,3.88758e-06,3.88756e-06,1.20963e-06,0,0,0,0,0,0,0,0 +5680000,0.983546,-0.00693278,-0.0125462,0.18009,-0.000620809,0.0116199,-0.0978795,0.000743511,0.00152633,-0.0693865,-1.67091e-05,-5.8391e-05,7.23255e-06,-1.23216e-05,2.05084e-05,-0.00100289,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.3874e-05,0.000750251,0.000750315,0.000416221,0.320259,0.320281,0.0890876,0.12976,0.129762,0.141439,3.26314e-08,3.26569e-08,1.78486e-08,3.88237e-06,3.88234e-06,1.13581e-06,0,0,0,0,0,0,0,0 +5780000,0.983599,-0.00680097,-0.0125292,0.179805,-0.000357041,0.0146003,-0.0923961,0.00072707,0.00284773,-0.0632266,-1.66915e-05,-5.84051e-05,8.08523e-06,-1.27438e-05,2.10011e-05,-0.00103199,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.35898e-05,0.000796537,0.000796604,0.0004077,0.376288,0.376315,0.0863023,0.168727,0.16873,0.139882,3.26312e-08,3.26566e-08,1.68633e-08,3.88236e-06,3.88233e-06,1.06615e-06,0,0,0,0,0,0,0,0 +5880000,0.983584,-0.00682901,-0.0125408,0.179886,0.00119246,0.0139473,-0.0888092,0.000445317,0.00276424,-0.0647416,-1.63258e-05,-5.86335e-05,7.59838e-06,-1.31217e-05,2.09196e-05,-0.00104565,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.32807e-05,0.000656153,0.000656203,0.000399488,0.289792,0.289811,0.0835582,0.123525,0.123527,0.13833,2.6075e-08,2.60951e-08,1.59459e-08,3.87771e-06,3.87767e-06,1.00047e-06,0,0,0,0,0,0,0,0 +5980000,0.983562,-0.00680793,-0.0126526,0.179998,0.00198155,0.0138726,-0.0837503,0.000635387,0.00416652,-0.0602042,-1.63438e-05,-5.86163e-05,6.74689e-06,-1.3418e-05,2.1323e-05,-0.00106906,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.32674e-05,0.000694426,0.000694478,0.000398771,0.338917,0.33894,0.0828291,0.159493,0.159497,0.141568,2.60748e-08,2.6095e-08,1.53023e-08,3.87771e-06,3.87766e-06,9.53369e-07,0,0,0,0,0,0,0,0 +6080000,0.983518,-0.00691988,-0.0125931,0.180238,0.00114989,0.01214,-0.0786678,0.000474931,0.00335565,-0.0574933,-1.59099e-05,-5.88403e-05,4.36473e-06,-1.38585e-05,2.12262e-05,-0.00108779,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.29491e-05,0.000576112,0.000576154,0.00039093,0.262338,0.262353,0.0800776,0.1177,0.117702,0.139869,2.08895e-08,2.09055e-08,1.44951e-08,3.87361e-06,3.87355e-06,8.94118e-07,0,0,0,0,0,0,0,0 +6180000,0.983476,-0.00692724,-0.012548,0.180471,0.00174517,0.0133025,-0.0768325,0.000669226,0.00464791,-0.0565966,-1.59412e-05,-5.88116e-05,2.88093e-06,-1.40214e-05,2.14901e-05,-0.00110284,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.27095e-05,0.000607812,0.000607861,0.000383368,0.305517,0.305535,0.0773604,0.150927,0.15093,0.138124,2.08893e-08,2.09053e-08,1.37458e-08,3.87361e-06,3.87354e-06,8.38282e-07,0,0,0,0,0,0,0,0 +6280000,0.983453,-0.00702604,-0.0125814,0.180591,-0.000240297,0.01219,-0.0778786,0.000411317,0.00362781,-0.0603281,-1.54665e-05,-5.90615e-05,2.37965e-06,-1.43347e-05,2.11484e-05,-0.00110947,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.24521e-05,0.000508235,0.000508271,0.000376045,0.23779,0.237802,0.07469,0.112271,0.112273,0.136348,1.67893e-08,1.6802e-08,1.30443e-08,3.87001e-06,3.86993e-06,7.85781e-07,0,0,0,0,0,0,0,0 +6380000,0.983481,-0.00697096,-0.0124993,0.180442,0.00018207,0.0131752,-0.0772193,0.000345678,0.00487047,-0.0616449,-1.54564e-05,-5.90722e-05,2.93142e-06,-1.44651e-05,2.13145e-05,-0.00111987,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.22291e-05,0.000534555,0.000534596,0.000369036,0.275767,0.275782,0.0721026,0.142999,0.143002,0.134599,1.67891e-08,1.68019e-08,1.23925e-08,3.87002e-06,3.86993e-06,7.36716e-07,0,0,0,0,0,0,0,0 +6480000,0.983481,-0.0070129,-0.012496,0.180443,-0.00176779,0.00855623,-0.0726348,0.000165942,0.0036266,-0.0583635,-1.50047e-05,-5.92672e-05,2.18698e-06,-1.48485e-05,2.11383e-05,-0.0011369,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.19694e-05,0.000450778,0.000450807,0.000362266,0.215747,0.215756,0.0695715,0.107218,0.107219,0.132824,1.35444e-08,1.35546e-08,1.1781e-08,3.86688e-06,3.86678e-06,6.90681e-07,0,0,0,0,0,0,0,0 +6580000,0.983459,-0.00700322,-0.0124363,0.180568,-0.00182791,0.00876344,-0.0742613,-2.02884e-05,0.0044812,-0.0602043,-1.50261e-05,-5.92482e-05,1.2028e-06,-1.49259e-05,2.12888e-05,-0.00114549,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.17578e-05,0.000472695,0.000472729,0.000355756,0.249276,0.249286,0.0671313,0.13567,0.135673,0.131086,1.35443e-08,1.35545e-08,1.12114e-08,3.86688e-06,3.86678e-06,6.47761e-07,0,0,0,0,0,0,0,0 +6680000,0.983462,-0.00701082,-0.0124074,0.180553,-0.00534942,0.00798853,-0.0767233,-0.000276065,0.00331411,-0.0621064,-1.46285e-05,-5.93661e-05,9.15991e-07,-1.51343e-05,2.10106e-05,-0.00115407,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.1715e-05,0.000402159,0.000402181,0.00035517,0.1962,0.196207,0.0663186,0.102516,0.102517,0.133703,1.09716e-08,1.09797e-08,1.08063e-08,3.86415e-06,3.86404e-06,6.17368e-07,0,0,0,0,0,0,0,0 +6780000,0.983421,-0.00703643,-0.0123641,0.18078,-0.00339216,0.00959268,-0.0721667,-0.00074375,0.00418175,-0.0594671,-1.46573e-05,-5.93414e-05,-3.72178e-07,-1.52647e-05,2.12635e-05,-0.00116893,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.15151e-05,0.00042047,0.000420497,0.000348876,0.225702,0.225711,0.063933,0.128907,0.128909,0.131817,1.09714e-08,1.09796e-08,1.02971e-08,3.86415e-06,3.86404e-06,5.7904e-07,0,0,0,0,0,0,0,0 +6880000,0.983402,-0.00695128,-0.0122553,0.180895,-0.00266487,0.00644484,-0.0683943,-0.000658399,0.00308724,-0.0582223,-1.43113e-05,-5.93838e-05,-1.07194e-06,-1.54265e-05,2.10679e-05,-0.00118083,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.13026e-05,0.000361007,0.000361023,0.000342827,0.178498,0.178504,0.061667,0.098142,0.098143,0.130025,8.92619e-09,8.93274e-09,9.81936e-09,3.86177e-06,3.86164e-06,5.43521e-07,0,0,0,0,0,0,0,0 +6980000,0.983405,-0.00690416,-0.0121945,0.180884,-0.00394377,0.007365,-0.0638094,-0.00102351,0.0037803,-0.0553241,-1.43147e-05,-5.93832e-05,-1.14327e-06,-1.55502e-05,2.12754e-05,-0.00119417,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.11172e-05,0.000376362,0.00037638,0.000336955,0.204587,0.204594,0.0594481,0.122647,0.122648,0.12818,8.92609e-09,8.93266e-09,9.37087e-09,3.86177e-06,3.86164e-06,5.10166e-07,0,0,0,0,0,0,0,0 +7080000,0.98338,-0.00682897,-0.0121147,0.181023,-0.00453475,0.0109391,-0.0634827,-0.00144137,0.00478684,-0.0562042,-1.43259e-05,-5.93739e-05,-1.62341e-06,-1.56081e-05,2.13985e-05,-0.00120169,0.203712,-8.84756e-09,0.434376,0,0,0,0,0,1.0946e-05,0.000392163,0.000392183,0.000331285,0.233461,0.233471,0.0573249,0.152829,0.152831,0.126385,8.92601e-09,8.93258e-09,8.94968e-09,3.86178e-06,3.86165e-06,4.79152e-07,0,0,0,0,0,0,0,0 +7180000,0.983027,-0.00678312,-0.0122118,0.182928,-0.00459184,0.0106489,-0.0616555,-0.00133628,0.00395932,-0.0578706,-1.40048e-05,-5.93964e-05,-1.63229e-06,-1.56813e-05,2.11275e-05,-0.0012079,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,6.27357e-05,0.0003291,0.000328946,0.00182664,0.167859,0.167867,0.0552917,0.116458,0.11646,0.124636,7.29544e-09,7.30071e-09,8.94872e-09,3.8597e-06,3.85956e-06,4.50292e-07,0,0,0,0,0,0,0,0 +7280000,0.982971,-0.0067779,-0.0121754,0.183234,-0.00339382,0.0123202,-0.0587849,-0.00179437,0.00508359,-0.0558505,-1.40066e-05,-5.93968e-05,-1.64251e-06,-1.57667e-05,2.1285e-05,-0.00121834,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,5.01245e-05,0.000329573,0.000329458,0.00145949,0.172239,0.172247,0.0545418,0.142249,0.142251,0.126787,7.29554e-09,7.30081e-09,8.94849e-09,3.85971e-06,3.85957e-06,4.2983e-07,0,0,0,0,0,0,0,0 +7380000,0.983162,-0.00676693,-0.0121361,0.182209,-0.00405748,0.0128086,-0.0536552,-0.00143802,0.00436459,-0.049305,-1.36895e-05,-5.94073e-05,-1.60465e-06,-1.58929e-05,2.12413e-05,-0.00123385,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,3.95231e-05,0.000329945,0.000329862,0.00115136,0.130152,0.130158,0.052607,0.10791,0.107911,0.124984,6.03384e-09,6.0381e-09,8.94682e-09,3.8588e-06,3.85865e-06,4.04284e-07,0,0,0,0,0,0,0,0 +7480000,0.983232,-0.00672209,-0.0121367,0.181828,-0.0026942,0.014822,-0.0494248,-0.00178771,0.00571857,-0.0459981,-1.36902e-05,-5.94088e-05,-1.55541e-06,-1.59768e-05,2.13954e-05,-0.00124445,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,3.26762e-05,0.000330898,0.000330834,0.000951066,0.141817,0.141824,0.0507418,0.129168,0.12917,0.123191,6.03394e-09,6.0382e-09,8.94503e-09,3.85881e-06,3.85865e-06,3.80426e-07,0,0,0,0,0,0,0,0 +7580000,0.983275,-0.00681726,-0.0120822,0.181596,-0.0018678,0.0142326,-0.0453835,-0.00135019,0.00492816,-0.0396244,-1.33772e-05,-5.94313e-05,-1.53363e-06,-1.60712e-05,2.16752e-05,-0.00125795,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,2.7857e-05,0.000329928,0.000329883,0.000810605,0.120053,0.120059,0.048947,0.0994945,0.0994956,0.121412,5.10117e-09,5.10469e-09,8.94156e-09,3.85875e-06,3.85859e-06,3.5815e-07,0,0,0,0,0,0,0,0 +7680000,0.983273,-0.00684031,-0.012136,0.181603,-0.00249545,0.0170158,-0.0433533,-0.00155724,0.00650382,-0.0329126,-1.33792e-05,-5.94318e-05,-1.537e-06,-1.61788e-05,2.18672e-05,-0.00127114,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,2.42947e-05,0.00033102,0.000330985,0.000706778,0.138086,0.138094,0.0472355,0.118082,0.118084,0.119688,5.10127e-09,5.10479e-09,8.93742e-09,3.85876e-06,3.8586e-06,3.37432e-07,0,0,0,0,0,0,0,0 +7780000,0.983254,-0.00676317,-0.012145,0.181711,-0.000743091,0.0143639,-0.0445981,-0.00116209,0.00560647,-0.0369823,-1.30704e-05,-5.9474e-05,-1.56849e-06,-1.60715e-05,2.2584e-05,-0.00127141,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,2.1564e-05,0.000326391,0.000326362,0.000627015,0.127798,0.127804,0.0455893,0.0930333,0.0930344,0.11798,4.42159e-09,4.42458e-09,8.93135e-09,3.85515e-06,3.85499e-06,3.18079e-07,0,0,0,0,0,0,0,0 +7880000,0.983232,-0.00676964,-0.0122071,0.181826,-0.0024208,0.017458,-0.0444286,-0.00134687,0.00721752,-0.0396816,-1.30708e-05,-5.94739e-05,-1.57432e-06,-1.60889e-05,2.26123e-05,-0.00127336,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.94246e-05,0.000327344,0.000327321,0.000563913,0.151086,0.151094,0.0440214,0.110711,0.110713,0.116326,4.42168e-09,4.42467e-09,8.92411e-09,3.85516e-06,3.855e-06,3.00075e-07,0,0,0,0,0,0,0,0 +7980000,0.983241,-0.00679518,-0.0121114,0.181783,-0.000772091,0.0149153,-0.0438972,-0.00104691,0.00619429,-0.0417795,-1.27801e-05,-5.95286e-05,-1.53426e-06,-1.58073e-05,2.42137e-05,-0.00127591,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.8112e-05,0.000316634,0.000316616,0.000525242,0.145274,0.145282,0.0434299,0.0891612,0.0891624,0.118111,3.93752e-09,3.94012e-09,8.91717e-09,3.84098e-06,3.84082e-06,2.87349e-07,0,0,0,0,0,0,0,0 +8080000,0.983198,-0.00671693,-0.0120756,0.182022,-0.000951838,0.0182666,-0.0404283,-0.00109868,0.00784746,-0.038336,-1.27838e-05,-5.95257e-05,-1.67392e-06,-1.58888e-05,2.43378e-05,-0.00128413,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.65916e-05,0.000317261,0.000317246,0.000481224,0.172601,0.172611,0.041937,0.107313,0.107315,0.116397,3.93762e-09,3.94022e-09,8.90647e-09,3.84099e-06,3.84083e-06,2.71322e-07,0,0,0,0,0,0,0,0 +8180000,0.983177,-0.00685793,-0.0119865,0.182132,0.000185421,0.0187371,-0.036611,-0.000750162,0.00682643,-0.0335226,-1.25235e-05,-5.95875e-05,-1.74062e-06,-1.53437e-05,2.70624e-05,-0.00129334,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.53305e-05,0.000298835,0.000298827,0.000444542,0.165384,0.165394,0.0405276,0.087779,0.0877803,0.114773,3.611e-09,3.61333e-09,8.89356e-09,3.80903e-06,3.80887e-06,2.56443e-07,0,0,0,0,0,0,0,0 +8280000,0.983181,-0.0068624,-0.0119428,0.182112,0.00219992,0.0200679,-0.0337818,-0.000658476,0.00879046,-0.0320565,-1.25244e-05,-5.95869e-05,-1.76315e-06,-1.54011e-05,2.71351e-05,-0.00129838,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.42602e-05,0.000299055,0.000299051,0.000413593,0.195118,0.19513,0.0391626,0.107268,0.10727,0.113138,3.61109e-09,3.61343e-09,8.87839e-09,3.80903e-06,3.80888e-06,2.42481e-07,0,0,0,0,0,0,0,0 +8380000,0.983183,-0.00692692,-0.0119234,0.182102,-0.000161009,0.0170623,-0.0318672,-0.000364039,0.00735269,-0.0283247,-1.23e-05,-5.96577e-05,-1.75019e-06,-1.42997e-05,3.09147e-05,-0.00130536,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.3351e-05,0.000273124,0.000273123,0.00038719,0.181732,0.181741,0.0378632,0.0882158,0.0882173,0.111558,3.41198e-09,3.41415e-09,8.86065e-09,3.75529e-06,3.75514e-06,2.29449e-07,0,0,0,0,0,0,0,0 +8480000,0.983218,-0.00682535,-0.0118891,0.181919,-0.0014373,0.0191398,-0.0321219,-0.000420023,0.00914437,-0.0324007,-1.22963e-05,-5.96615e-05,-1.57205e-06,-1.42864e-05,3.08932e-05,-0.00130446,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.25754e-05,0.000272977,0.000272978,0.000364483,0.211984,0.211995,0.0366258,0.109293,0.109296,0.110029,3.41207e-09,3.41424e-09,8.84049e-09,3.7553e-06,3.75515e-06,2.17315e-07,0,0,0,0,0,0,0,0 +8580000,0.983232,-0.00692993,-0.0119613,0.181832,-0.0010825,0.0173402,-0.0268801,-0.000377431,0.0074448,-0.0273119,-1.21268e-05,-5.97158e-05,-1.55774e-06,-1.29127e-05,3.55151e-05,-0.0013121,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.20751e-05,0.000242053,0.000242053,0.000350366,0.189678,0.189686,0.0361486,0.0894403,0.0894418,0.111549,3.30896e-09,3.31105e-09,8.82336e-09,3.68181e-06,3.68166e-06,2.08661e-07,0,0,0,0,0,0,0,0 +8680000,0.983254,-0.00698125,-0.012025,0.181708,-0.00131153,0.0165755,-0.0266439,-0.000505585,0.0091205,-0.0264609,-1.21253e-05,-5.97171e-05,-1.48159e-06,-1.29611e-05,3.5559e-05,-0.00131536,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.14628e-05,0.00024168,0.000241682,0.000332681,0.218595,0.218603,0.0349839,0.11177,0.111772,0.110011,3.30905e-09,3.31113e-09,8.7982e-09,3.68181e-06,3.68167e-06,1.97864e-07,0,0,0,0,0,0,0,0 +8780000,0.983249,-0.00704674,-0.0119868,0.181734,-0.00136686,0.0127705,-0.0266044,-0.000459079,0.00700252,-0.0252452,-1.20219e-05,-5.97473e-05,-1.55264e-06,-1.15339e-05,4.03788e-05,-0.00131893,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.09204e-05,0.000209739,0.000209741,0.000317203,0.187828,0.187833,0.0338653,0.0904226,0.090424,0.108495,3.26791e-09,3.26995e-09,8.76989e-09,3.59636e-06,3.59622e-06,1.87699e-07,0,0,0,0,0,0,0,0 +8880000,0.983288,-0.0071518,-0.0119358,0.181524,-0.00101003,0.0136888,-0.0239003,-0.000538533,0.00834996,-0.0194407,-1.20171e-05,-5.97514e-05,-1.31979e-06,-1.16606e-05,4.04816e-05,-0.00132649,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.04505e-05,0.000209334,0.000209339,0.000303604,0.213914,0.21392,0.0327923,0.113294,0.113296,0.107005,3.268e-09,3.27004e-09,8.7384e-09,3.59636e-06,3.59623e-06,1.78212e-07,0,0,0,0,0,0,0,0 +8980000,0.983327,-0.00718164,-0.0118926,0.181314,-0.00293946,0.0111905,-0.0214891,-0.000501701,0.00623279,-0.0211545,-1.19627e-05,-5.97717e-05,-9.90016e-07,-1.0353e-05,4.49116e-05,-0.00132686,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,1.00334e-05,0.000180156,0.000180159,0.000291608,0.177394,0.177397,0.03177,0.0904903,0.0904914,0.105565,3.2581e-09,3.26013e-09,8.70372e-09,3.50901e-06,3.50888e-06,1.69297e-07,0,0,0,0,0,0,0,0 +9080000,0.98338,-0.00722603,-0.0118964,0.181025,-0.00210516,0.0125259,-0.0226805,-0.000753211,0.00738439,-0.0208375,-1.19548e-05,-5.97792e-05,-6.12118e-07,-1.03851e-05,4.49284e-05,-0.00132899,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,9.6652e-06,0.000179908,0.000179913,0.000281007,0.199869,0.199873,0.030789,0.113087,0.113088,0.104149,3.25818e-09,3.26022e-09,8.66561e-09,3.50902e-06,3.50889e-06,1.60975e-07,0,0,0,0,0,0,0,0 +9180000,0.983422,-0.0072029,-0.0119589,0.180795,0.000412634,0.0120296,-0.0207466,-0.000886921,0.00868128,-0.0206231,-1.19477e-05,-5.97859e-05,-2.7153e-07,-1.04212e-05,4.49455e-05,-0.00133098,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,9.34032e-06,0.000179824,0.000179829,0.000271614,0.223588,0.223592,0.0298545,0.140961,0.140963,0.10278,3.25827e-09,3.2603e-09,8.62416e-09,3.50903e-06,3.5089e-06,1.53189e-07,0,0,0,0,0,0,0,0 +9280000,0.983449,-0.00716757,-0.0117857,0.18066,0.00178229,0.00851023,-0.0187776,-0.000404536,0.00634105,-0.0185754,-1.19362e-05,-5.97909e-05,-9.00912e-08,-9.4351e-06,4.88499e-05,-0.00133424,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,9.15319e-06,0.000155859,0.000155862,0.000266502,0.180155,0.180157,0.029503,0.111079,0.11108,0.104097,3.25805e-09,3.26008e-09,8.59074e-09,3.4281e-06,3.42798e-06,1.47618e-07,0,0,0,0,0,0,0,0 +9380000,0.983432,-0.00709732,-0.011822,0.180754,0.00200198,0.00861939,-0.01706,-0.000193244,0.00722921,-0.0176052,-1.19389e-05,-5.97878e-05,-2.31228e-07,-9.48641e-06,4.88927e-05,-0.00133644,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,8.89481e-06,0.000156073,0.000156077,0.0002589,0.19975,0.199751,0.0286167,0.13747,0.137471,0.102704,3.25813e-09,3.26016e-09,8.54283e-09,3.42811e-06,3.42799e-06,1.40624e-07,0,0,0,0,0,0,0,0 +9480000,0.983459,-0.00717498,-0.0118668,0.180599,0.00108102,0.00430427,-0.0139739,8.16814e-06,0.00509362,-0.0134892,-1.19497e-05,-5.97853e-05,-4.56655e-08,-8.53358e-06,5.18971e-05,-0.00134089,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,8.65213e-06,0.00013793,0.000137933,0.000252156,0.158318,0.158318,0.0277781,0.107636,0.107636,0.101381,3.25636e-09,3.2584e-09,8.49163e-09,3.35827e-06,3.35815e-06,1.34052e-07,0,0,0,0,0,0,0,0 +9580000,0.983432,-0.00724554,-0.0118662,0.180742,-0.000308551,0.00334454,-0.014162,1.38464e-05,0.00548158,-0.0163806,-1.19553e-05,-5.97802e-05,-3.08287e-07,-8.50435e-06,5.18853e-05,-0.00133965,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,8.44838e-06,0.000138528,0.000138532,0.000246142,0.174139,0.174138,0.0269665,0.132051,0.132052,0.100058,3.25644e-09,3.25847e-09,8.43648e-09,3.35828e-06,3.35816e-06,1.27886e-07,0,0,0,0,0,0,0,0 +9680000,0.983438,-0.00727553,-0.0118285,0.180712,0.000442874,0.000485672,-0.0109177,0.000137161,0.00370259,-0.0137357,-1.19779e-05,-5.97701e-05,-3.56951e-07,-7.80132e-06,5.39372e-05,-0.00134261,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,8.25634e-06,0.000125696,0.000125699,0.000240803,0.136872,0.136871,0.0261928,0.103264,0.103264,0.0987798,3.24963e-09,3.25166e-09,8.37779e-09,3.30089e-06,3.30077e-06,1.22069e-07,0,0,0,0,0,0,0,0 +9780000,0.983419,-0.00730296,-0.0117593,0.180818,0.000866226,0.000527242,-0.011295,0.000205525,0.00373907,-0.0139772,-1.19858e-05,-5.97623e-05,-7.40456e-07,-7.82478e-06,5.39644e-05,-0.00134327,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,8.08871e-06,0.000126716,0.000126721,0.00023606,0.149501,0.149499,0.0254548,0.125502,0.125503,0.0975445,3.2497e-09,3.25174e-09,8.31557e-09,3.3009e-06,3.30078e-06,1.16639e-07,0,0,0,0,0,0,0,0 +9880000,0.983438,-0.00730252,-0.0117203,0.180717,0.00167986,-0.00233078,-0.0090982,0.000211182,0.002232,-0.0137991,-1.19974e-05,-5.976e-05,-4.24395e-07,-7.30424e-06,5.51343e-05,-0.00134411,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,8.02795e-06,0.000118216,0.00011822,0.000234332,0.117278,0.117275,0.0251802,0.09842,0.0984201,0.0987072,3.23855e-09,3.24059e-09,8.26632e-09,3.25525e-06,3.25513e-06,1.12737e-07,0,0,0,0,0,0,0,0 +9980000,0.983409,-0.0073101,-0.0117983,0.180873,0.00270468,-0.00366411,-0.00887546,0.00043385,0.00187813,-0.0147779,-1.20042e-05,-5.97534e-05,-7.52731e-07,-7.30691e-06,5.51458e-05,-0.00134406,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,7.8997e-06,0.000119666,0.00011967,0.000230503,0.127311,0.127308,0.0244852,0.118486,0.118486,0.0974751,3.23862e-09,3.24066e-09,8.19771e-09,3.25525e-06,3.25513e-06,1.07851e-07,0,0,0,0,0,0,0,0 +10080000,0.983396,-0.00728885,-0.0119147,0.180936,0.00189141,-0.00787699,-0.00707664,0.000501552,0.000715626,-0.0132862,-1.20194e-05,-5.97391e-05,-1.11062e-06,-7.01386e-06,5.56022e-05,-0.00134566,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,7.77587e-06,0.000114476,0.000114479,0.000227112,0.100151,0.100148,0.0238166,0.0934398,0.0934396,0.0962639,3.22538e-09,3.22741e-09,8.12542e-09,3.21975e-06,3.21963e-06,1.0322e-07,0,0,0,0,0,0,0,0 +10180000,0.983359,-0.0072617,-0.0118489,0.181139,-0.000523819,-0.00747649,-0.00633653,0.000569514,-3.62415e-05,-0.0133017,-1.20313e-05,-5.97275e-05,-1.68507e-06,-7.03335e-06,5.56331e-05,-0.00134614,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,7.67278e-06,0.000116343,0.000116347,0.000224104,0.10817,0.108167,0.0231741,0.111458,0.111457,0.0950749,3.22544e-09,3.22747e-09,8.04955e-09,3.21975e-06,3.21963e-06,9.88717e-08,0,0,0,0,0,0,0,0 +10280000,0.983391,-0.00729233,-0.0117698,0.180971,-0.000696234,-0.00820414,-0.00675687,0.000318692,-0.000705407,-0.0131771,-1.20199e-05,-5.97325e-05,-1.33962e-06,-6.96639e-06,5.5444e-05,-0.00134661,0.204529,-4.65661e-10,0.434659,0,0,0,0,0,7.57596e-06,0.000113592,0.000113596,0.000221451,0.0856372,0.0856345,0.0225604,0.0885472,0.0885469,0.0939251,3.21245e-09,3.21448e-09,7.97037e-09,3.19259e-06,3.19247e-06,9.4762e-08,0,0,0,0,0,0,0,0 +10380000,0.983077,-0.00728949,-0.0116813,0.182673,0.00725269,0.000359604,-0.00259491,0.0008051,-4.14566e-05,-0.0113067,-1.20194e-05,-5.97322e-05,-1.32778e-06,-7.01079e-06,5.54705e-05,-0.00134794,0.204984,0.000821313,0.434268,0,0,0,0,0,6.18887e-05,0.000114347,0.000114219,0.00177608,0.0350735,0.0350736,0.037455,0.12528,0.12528,0.0868236,3.21255e-09,3.21458e-09,7.97041e-09,3.1926e-06,3.19248e-06,9.11288e-08,0,0,0,0,0,0,0,0 +10480000,0.982938,-0.00720127,-0.0116694,0.183425,0.00672815,-0.00111686,-0.00157053,0.00150637,-4.79662e-05,-0.00660893,-1.20191e-05,-5.97308e-05,-1.34231e-06,-7.11972e-06,5.55368e-05,-0.0013512,0.204984,0.000821313,0.434268,0,0,0,0,0,4.6636e-05,0.000114549,0.000114457,0.00133899,0.0371479,0.0371478,0.0375577,0.126265,0.126265,0.080918,3.21265e-09,3.21468e-09,7.97012e-09,3.1926e-06,3.19249e-06,8.80706e-08,0,0,0,0,0,0,0,0 +10580000,0.983014,-0.00716033,-0.0115641,0.183024,0.00553452,-0.00191133,-0.000724941,0.00113409,-0.00378911,-0.00405095,-1.20091e-05,-5.97094e-05,-1.31664e-06,-3.8548e-06,5.41672e-05,-0.00135282,0.204984,0.000821313,0.434268,0,0,0,0,0,3.94135e-05,0.000114341,0.000114268,0.00113075,0.0354038,0.0354036,0.0352945,0.0848977,0.0848977,0.0778592,3.21224e-09,3.21427e-09,7.96956e-09,3.18013e-06,3.18002e-06,8.60692e-08,0,0,0,0,0,0,0,0 +10680000,0.98307,-0.0071263,-0.0115693,0.182727,0.00596045,-0.00462202,-0.000738993,0.0016869,-0.00412982,-0.00476322,-1.20088e-05,-5.97099e-05,-1.29956e-06,-3.84086e-06,5.41585e-05,-0.0013524,0.204984,0.000821313,0.434268,0,0,0,0,0,3.2645e-05,0.000114905,0.000114848,0.000936825,0.0400692,0.0400687,0.0353057,0.0867458,0.0867458,0.0744855,3.21234e-09,3.21436e-09,7.96812e-09,3.18014e-06,3.18003e-06,8.37353e-08,0,0,0,0,0,0,0,0 +10780000,0.983065,-0.007122,-0.0116672,0.182745,0.00531839,-0.00670165,-0.000781603,0.00151571,-0.00384105,-0.00187039,-1.20125e-05,-5.96932e-05,-1.30556e-06,-1.06281e-06,5.49482e-05,-0.00135424,0.204984,0.000821313,0.434268,0,0,0,0,0,2.78739e-05,0.00011344,0.000113391,0.000800102,0.0395091,0.0395084,0.0331768,0.0659342,0.0659342,0.0717,3.21103e-09,3.21305e-09,7.96588e-09,3.13492e-06,3.13481e-06,8.16797e-08,0,0,0,0,0,0,0,0 +10880000,0.983166,-0.00712823,-0.0117177,0.1822,0.00490027,-0.00823362,-0.000968318,0.00205822,-0.00463995,-0.00133614,-1.20101e-05,-5.96952e-05,-1.19455e-06,-1.0778e-06,5.49534e-05,-0.00135457,0.204984,0.000821313,0.434268,0,0,0,0,0,2.43577e-05,0.000114356,0.000114316,0.000698609,0.046256,0.046255,0.0330471,0.0686351,0.068635,0.070031,3.21112e-09,3.21315e-09,7.96254e-09,3.13493e-06,3.13482e-06,7.99138e-08,0,0,0,0,0,0,0,0 +10980000,0.983163,-0.00706229,-0.0117973,0.18221,0.0037859,-0.00293282,0.00159928,0.00171926,-0.00371141,0.00142712,-1.19849e-05,-5.96886e-05,-1.21445e-06,1.30277e-07,4.95218e-05,-0.00135588,0.204984,0.000821313,0.434268,0,0,0,0,0,2.1626e-05,0.000111264,0.000111227,0.000620426,0.0452109,0.0452103,0.0310301,0.0558307,0.0558307,0.0683485,3.20945e-09,3.21148e-09,7.95805e-09,3.0503e-06,3.05019e-06,7.83105e-08,0,0,0,0,0,0,0,0 +11080000,0.98307,-0.00719642,-0.0117785,0.182709,0.00302156,-0.0012207,0.00282396,0.00205083,-0.0039839,0.00398161,-1.19878e-05,-5.9685e-05,-1.36596e-06,9.01645e-08,4.9549e-05,-0.00135714,0.204984,0.000821313,0.434268,0,0,0,0,0,1.94732e-05,0.000112532,0.000112504,0.000558423,0.053398,0.0533974,0.0307622,0.0594575,0.0594574,0.0677523,3.20955e-09,3.21157e-09,7.95227e-09,3.05031e-06,3.0502e-06,7.6952e-08,0,0,0,0,0,0,0,0 +11180000,0.983026,-0.00719386,-0.0117678,0.182949,0.00443493,0.00103988,0.00614775,0.00261984,-0.00316789,0.00823858,-1.199e-05,-5.96934e-05,-1.48638e-06,-3.63556e-06,4.98663e-05,-0.00135858,0.204984,0.000821313,0.434268,0,0,0,0,0,1.81283e-05,0.000108083,0.000108058,0.000520322,0.0506048,0.0506044,0.0289798,0.0503405,0.0503405,0.067826,3.20829e-09,3.21031e-09,7.94694e-09,2.93363e-06,2.93353e-06,7.59675e-08,0,0,0,0,0,0,0,0 +11280000,0.983021,-0.00721963,-0.0117996,0.18297,0.0036146,0.000878337,0.0083596,0.00297212,-0.00301893,0.0106565,-1.19902e-05,-5.96927e-05,-1.50051e-06,-3.66733e-06,4.98831e-05,-0.00135939,0.204984,0.000821313,0.434268,0,0,0,0,0,1.66198e-05,0.000109704,0.000109683,0.000476881,0.0595428,0.0595423,0.0286094,0.054907,0.0549069,0.0678859,3.20839e-09,3.21041e-09,7.93848e-09,2.93364e-06,2.93354e-06,7.48808e-08,0,0,0,0,0,0,0,0 +11380000,0.983022,-0.00714549,-0.0117762,0.18297,0.00198752,0.00095322,0.00633501,0.00237024,-0.00243709,0.00638393,-1.1987e-05,-5.96887e-05,-1.50974e-06,-1.23438e-06,4.87113e-05,-0.00135707,0.204984,0.000821313,0.434268,0,0,0,0,0,1.53537e-05,0.000104581,0.000104561,0.000440617,0.0544468,0.0544465,0.0268266,0.0474979,0.0474978,0.0671354,3.20789e-09,3.20991e-09,7.92826e-09,2.80125e-06,2.80114e-06,7.3838e-08,0,0,0,0,0,0,0,0 +11480000,0.983055,-0.00709615,-0.0117736,0.182795,-0.000861527,-0.000174979,0.00734418,0.00236956,-0.00237847,0.00943476,-1.19858e-05,-5.9689e-05,-1.46259e-06,-1.27783e-06,4.87316e-05,-0.0013581,0.204984,0.000821313,0.434268,0,0,0,0,0,1.4275e-05,0.000106543,0.000106526,0.000409965,0.0635393,0.0635387,0.0263578,0.0529187,0.0529186,0.067573,3.20798e-09,3.21e-09,7.91614e-09,2.80126e-06,2.80115e-06,7.29933e-08,0,0,0,0,0,0,0,0 +11580000,0.983051,-0.00716595,-0.0117377,0.182814,0.000938859,-0.000903223,0.00781874,0.00205042,-0.00191573,0.0107176,-1.19842e-05,-5.96883e-05,-1.48634e-06,-1.56595e-06,4.78025e-05,-0.00135892,0.204984,0.000821313,0.434268,0,0,0,0,0,1.3361e-05,0.000101478,0.000101462,0.000383766,0.0563021,0.0563017,0.0247022,0.0461862,0.0461861,0.0669786,3.20793e-09,3.20995e-09,7.90208e-09,2.67027e-06,2.67017e-06,7.21657e-08,0,0,0,0,0,0,0,0 +11680000,0.983057,-0.00709155,-0.0117478,0.182785,0.00165342,-7.87842e-05,0.00978313,0.0021903,-0.00195435,0.0107904,-1.19833e-05,-5.96894e-05,-1.44087e-06,-1.55269e-06,4.77948e-05,-0.00135858,0.204984,0.000821313,0.434268,0,0,0,0,0,1.25789e-05,0.000103766,0.000103752,0.000361181,0.0650864,0.0650862,0.0241704,0.0522984,0.0522983,0.0676025,3.20802e-09,3.21004e-09,7.88585e-09,2.67028e-06,2.67018e-06,7.15088e-08,0,0,0,0,0,0,0,0 +11780000,0.983089,-0.00715804,-0.0117149,0.182614,0.00017605,0.000456647,0.0103038,0.00168937,-0.00279153,0.0135195,-1.19661e-05,-5.96977e-05,-1.24913e-06,1.57773e-06,5.25491e-05,-0.00135916,0.204984,0.000821313,0.434268,0,0,0,0,0,1.19017e-05,9.92906e-05,9.92775e-05,0.00034157,0.0563676,0.0563677,0.0226516,0.0457164,0.0457164,0.0670523,3.20752e-09,3.20954e-09,7.86744e-09,2.55269e-06,2.55258e-06,7.08556e-08,0,0,0,0,0,0,0,0 +11880000,0.98309,-0.00723187,-0.0116637,0.182608,0.00202049,0.000492042,0.0103166,0.00172916,-0.00276325,0.01345,-1.19668e-05,-5.96975e-05,-1.27807e-06,1.59718e-06,5.25413e-05,-0.00135876,0.204984,0.000821313,0.434268,0,0,0,0,0,1.14734e-05,0.000101885,0.000101874,0.000329365,0.0646145,0.0646147,0.0222734,0.0523289,0.0523288,0.0689047,3.20761e-09,3.20964e-09,7.8521e-09,2.5527e-06,2.55259e-06,7.0469e-08,0,0,0,0,0,0,0,0 +11980000,0.983088,-0.00728524,-0.011727,0.18261,0.00308657,0.00351666,0.0099567,0.00271698,-0.00269277,0.0122132,-1.19871e-05,-5.96655e-05,-1.36068e-06,-3.30569e-06,5.1045e-05,-0.00135824,0.204984,0.000821313,0.434268,0,0,0,0,0,1.09245e-05,9.82412e-05,9.82321e-05,0.00031388,0.055132,0.0551324,0.020887,0.0456678,0.0456677,0.0683065,3.20544e-09,3.20746e-09,7.82933e-09,2.4542e-06,2.4541e-06,6.99407e-08,0,0,0,0,0,0,0,0 +12080000,0.983059,-0.00722227,-0.01179,0.182767,0.00434552,0.00322981,0.0126855,0.00310049,-0.00236669,0.0189906,-1.1989e-05,-5.96616e-05,-1.4761e-06,-3.39033e-06,5.10837e-05,-0.00135995,0.204984,0.000821313,0.434268,0,0,0,0,0,1.04588e-05,0.000101123,0.000101115,0.000300236,0.0627342,0.0627346,0.0203272,0.0525997,0.0525997,0.0689813,3.20553e-09,3.20755e-09,7.80424e-09,2.45421e-06,2.45411e-06,6.95301e-08,0,0,0,0,0,0,0,0 +12180000,0.983038,-0.00709529,-0.0117858,0.182888,0.00528998,0.0040884,0.0121953,0.002477,-0.00074461,0.0206793,-1.20252e-05,-5.96633e-05,-1.72449e-06,-2.20313e-06,4.68099e-05,-0.0013602,0.204984,0.000821313,0.434268,0,0,0,0,0,1.0031e-05,9.83505e-05,9.83423e-05,0.00028818,0.0531135,0.0531139,0.0190822,0.0457955,0.0457955,0.0683316,3.20034e-09,3.20236e-09,7.7763e-09,2.37566e-06,2.37556e-06,6.91148e-08,0,0,0,0,0,0,0,0 +12280000,0.983024,-0.00710731,-0.0117554,0.18296,0.00241467,0.00315863,0.0114928,0.00286368,-0.000402956,0.0213515,-1.20284e-05,-5.96604e-05,-1.87728e-06,-2.19464e-06,4.68099e-05,-0.00136006,0.204984,0.000821313,0.434268,0,0,0,0,0,9.65675e-06,0.000101501,0.000101495,0.000277488,0.0600813,0.0600816,0.0185342,0.0528971,0.0528971,0.0689098,3.20043e-09,3.20244e-09,7.74573e-09,2.37567e-06,2.37557e-06,6.8793e-08,0,0,0,0,0,0,0,0 +12380000,0.983027,-0.0071337,-0.011691,0.182947,0.00135733,0.00109806,0.0109846,0.00225777,-0.00049872,0.0184929,-1.20214e-05,-5.96768e-05,-1.99346e-06,-4.15829e-07,4.72146e-05,-0.00135917,0.204984,0.000821313,0.434268,0,0,0,0,0,9.31701e-06,9.95046e-05,9.94995e-05,0.000267992,0.0507171,0.0507173,0.0174304,0.0459648,0.0459647,0.0682076,3.19078e-09,3.19279e-09,7.71243e-09,2.31538e-06,2.31527e-06,6.84647e-08,0,0,0,0,0,0,0,0 +12480000,0.983008,-0.00715674,-0.0117181,0.183049,0.00186315,0.00141121,0.0135922,0.00237843,-0.000399204,0.0192773,-1.2022e-05,-5.96763e-05,-2.02335e-06,-4.09536e-07,4.72127e-05,-0.00135906,0.204984,0.000821313,0.434268,0,0,0,0,0,9.14106e-06,0.000102908,0.000102904,0.000262649,0.0570913,0.0570917,0.0170869,0.0531222,0.0531222,0.0698714,3.19087e-09,3.19288e-09,7.68546e-09,2.31539e-06,2.31528e-06,6.82737e-08,0,0,0,0,0,0,0,0 +12580000,0.982982,-0.00720778,-0.0116527,0.183192,0.0042641,-0.00265124,0.0158904,0.00337055,-0.00196557,0.0217429,-1.19264e-05,-5.96445e-05,-2.17663e-06,-1.39787e-06,5.1725e-05,-0.00135916,0.204984,0.000821313,0.434268,0,0,0,0,0,8.87734e-06,0.000101554,0.000101551,0.000254911,0.0482349,0.048235,0.0161058,0.0461085,0.0461085,0.0690828,3.17538e-09,3.17738e-09,7.64708e-09,2.27045e-06,2.27034e-06,6.80028e-08,0,0,0,0,0,0,0,0 +12680000,0.982961,-0.00718266,-0.0116224,0.183306,0.00423568,-0.0036681,0.0153083,0.00377397,-0.00226816,0.0245709,-1.19312e-05,-5.96395e-05,-2.41306e-06,-1.41362e-06,5.17369e-05,-0.00135944,0.204984,0.000821313,0.434268,0,0,0,0,0,8.63724e-06,0.000105193,0.000105191,0.00024801,0.0541345,0.0541347,0.0156314,0.0532425,0.0532425,0.0694367,3.17547e-09,3.17746e-09,7.60569e-09,2.27045e-06,2.27035e-06,6.77937e-08,0,0,0,0,0,0,0,0 +12780000,0.983016,-0.00729209,-0.0115699,0.183011,0.00597171,-0.00548833,0.0165333,0.00391061,-0.00458423,0.0261105,-1.17459e-05,-5.95792e-05,-1.95145e-06,-1.65009e-06,5.62963e-05,-0.0013593,0.204984,0.000821313,0.434268,0,0,0,0,0,8.41683e-06,0.000104312,0.000104311,0.000241849,0.0458906,0.0458909,0.0147726,0.0461974,0.0461974,0.0685874,3.15262e-09,3.1546e-09,7.56123e-09,2.238e-06,2.23789e-06,6.757e-08,0,0,0,0,0,0,0,0 +12880000,0.983051,-0.00729337,-0.0114708,0.182827,0.00571544,-0.00744692,0.0173199,0.00450662,-0.00520778,0.0293449,-1.17409e-05,-5.95832e-05,-1.71951e-06,-1.67094e-06,5.62982e-05,-0.00135959,0.204984,0.000821313,0.434268,0,0,0,0,0,8.21944e-06,0.000108168,0.000108169,0.000236351,0.051389,0.0513893,0.0143474,0.0532569,0.053257,0.0688185,3.1527e-09,3.15468e-09,7.51387e-09,2.238e-06,2.2379e-06,6.73996e-08,0,0,0,0,0,0,0,0 +12980000,0.983087,-0.0072874,-0.0114571,0.182638,0.00475954,-0.00434551,0.0174674,0.00348667,-0.00393668,0.0308295,-1.18293e-05,-5.96152e-05,-1.51385e-06,-7.37308e-07,5.33344e-05,-0.00135962,0.204984,0.000821313,0.434268,0,0,0,0,0,8.03974e-06,0.000107598,0.000107599,0.000231436,0.0437808,0.0437812,0.0136036,0.0462246,0.0462247,0.0679308,3.12102e-09,3.12297e-09,7.46339e-09,2.21533e-06,2.21522e-06,6.72076e-08,0,0,0,0,0,0,0,0 +13080000,0.983103,-0.00729084,-0.0113871,0.182553,0.00596238,-0.00405141,0.0160645,0.00403561,-0.00433109,0.0307064,-1.18229e-05,-5.96221e-05,-1.19269e-06,-7.15461e-07,5.33185e-05,-0.00135926,0.204984,0.000821313,0.434268,0,0,0,0,0,7.89236e-06,0.000111652,0.000111655,0.000227039,0.0489789,0.0489795,0.0132315,0.0531799,0.05318,0.0680503,3.1211e-09,3.12305e-09,7.41003e-09,2.21534e-06,2.21523e-06,6.70653e-08,0,0,0,0,0,0,0,0 +13180000,0.983121,-0.0072824,-0.0113751,0.182458,0.00373222,-0.00478251,0.0145828,0.00125885,-0.00488227,0.0317895,-1.17922e-05,-5.97335e-05,-9.19108e-07,2.43527e-06,5.24904e-05,-0.00135923,0.204984,0.000821313,0.434268,0,0,0,0,0,7.8374e-06,0.000111232,0.000111235,0.000225431,0.0419775,0.0419779,0.0127299,0.046194,0.046194,0.0682923,3.0791e-09,3.08102e-09,7.36799e-09,2.20013e-06,2.20002e-06,6.69262e-08,0,0,0,0,0,0,0,0 +13280000,0.98311,-0.00728921,-0.0112984,0.182522,0.00242733,-0.00566856,0.0138937,0.00151312,-0.0053955,0.0321682,-1.17959e-05,-5.97305e-05,-1.09541e-06,2.45146e-06,5.24896e-05,-0.00135905,0.204984,0.000821313,0.434268,0,0,0,0,0,7.71309e-06,0.000115462,0.000115466,0.000221856,0.0469531,0.0469536,0.012408,0.0530324,0.0530325,0.0683082,3.07917e-09,3.0811e-09,7.30916e-09,2.20014e-06,2.20003e-06,6.68017e-08,0,0,0,0,0,0,0,0 +13380000,0.983097,-0.00723792,-0.0114118,0.182588,0.00181673,-0.00393931,0.0122071,0.00107974,-0.00414409,0.0320604,-1.18988e-05,-5.97344e-05,-1.3284e-06,2.48839e-06,5.09187e-05,-0.00135883,0.204984,0.000821313,0.434268,0,0,0,0,0,7.60072e-06,0.000115036,0.00011504,0.000218681,0.0404923,0.0404928,0.0118565,0.0461153,0.0461154,0.0673612,3.02549e-09,3.02737e-09,7.24765e-09,2.19044e-06,2.19033e-06,6.66343e-08,0,0,0,0,0,0,0,0 +13480000,0.983095,-0.00723405,-0.0114042,0.182599,0.000819997,-0.00230352,0.0123741,0.00120048,-0.00441922,0.030696,-1.19002e-05,-5.97344e-05,-1.37594e-06,2.52228e-06,5.09089e-05,-0.00135841,0.204984,0.000821313,0.434268,0,0,0,0,0,7.50238e-06,0.000119415,0.00011942,0.000215847,0.0453127,0.0453134,0.011588,0.0528357,0.0528358,0.0672953,3.02556e-09,3.02744e-09,7.183e-09,2.19045e-06,2.19034e-06,6.65238e-08,0,0,0,0,0,0,0,0 +13580000,0.983066,-0.00720297,-0.0114586,0.182752,0.00457513,-0.00242749,0.0133122,0.00379509,-0.00358534,0.028807,-1.18485e-05,-5.94524e-05,-1.61442e-06,9.84098e-07,5.07567e-05,-0.00135785,0.204984,0.000821313,0.434268,0,0,0,0,0,7.41988e-06,0.000118845,0.00011885,0.000213327,0.0393112,0.0393118,0.0111201,0.0460012,0.0460013,0.0663423,2.95917e-09,2.961e-09,7.11559e-09,2.18456e-06,2.18446e-06,6.63554e-08,0,0,0,0,0,0,0,0 +13680000,0.98309,-0.00716257,-0.0113577,0.18263,0.00424584,-0.0037744,0.0139268,0.00425367,-0.00392165,0.0310755,-1.18447e-05,-5.94555e-05,-1.43918e-06,9.71094e-07,5.07561e-05,-0.00135798,0.204984,0.000821313,0.434268,0,0,0,0,0,7.33796e-06,0.000123344,0.00012335,0.000211105,0.044044,0.0440447,0.0109044,0.0526101,0.0526103,0.0662195,2.95924e-09,2.96107e-09,7.04557e-09,2.18457e-06,2.18447e-06,6.62539e-08,0,0,0,0,0,0,0,0 +13780000,0.983084,-0.00709851,-0.0114539,0.18266,0.0101229,-0.00169557,0.0137345,0.00763533,-0.00172239,0.0295691,-1.19318e-05,-5.89844e-05,-1.65541e-06,1.21229e-07,5.00706e-05,-0.00135743,0.204984,0.000821313,0.434268,0,0,0,0,0,7.33537e-06,0.000122495,0.0001225,0.000211164,0.038443,0.0384436,0.0106216,0.0458645,0.0458646,0.0663619,2.87944e-09,2.8812e-09,6.99109e-09,2.18112e-06,2.18101e-06,6.61033e-08,0,0,0,0,0,0,0,0 +13880000,0.983089,-0.00702807,-0.0114366,0.182638,0.0109804,-0.000817373,0.014946,0.00866458,-0.0018461,0.0323284,-1.19288e-05,-5.89865e-05,-1.51838e-06,1.00558e-07,5.00725e-05,-0.00135763,0.204984,0.000821313,0.434268,0,0,0,0,0,7.2762e-06,0.000127081,0.000127087,0.000209387,0.0431314,0.0431323,0.0104518,0.0523757,0.0523759,0.0661858,2.8795e-09,2.88127e-09,6.9164e-09,2.18112e-06,2.18102e-06,6.60063e-08,0,0,0,0,0,0,0,0 +13980000,0.983109,-0.00706338,-0.0112269,0.182538,0.0107636,0.000614945,0.0144567,0.00683391,-0.00270666,0.0332801,-1.18558e-05,-5.92545e-05,-1.03338e-06,7.50592e-07,4.96324e-05,-0.00135755,0.204984,0.000821313,0.434268,0,0,0,0,0,7.22485e-06,0.00012583,0.000125837,0.000207814,0.0378521,0.0378531,0.0101194,0.0457185,0.0457186,0.0652361,2.78603e-09,2.78773e-09,6.83908e-09,2.17892e-06,2.17882e-06,6.58127e-08,0,0,0,0,0,0,0,0 +14080000,0.983046,-0.00705946,-0.0111403,0.182884,0.00845154,-0.0037306,0.0154184,0.00788689,-0.00287143,0.0316747,-1.18766e-05,-5.92364e-05,-2.02037e-06,8.1033e-07,4.96436e-05,-0.00135712,0.204984,0.000821313,0.434268,0,0,0,0,0,7.17989e-06,0.000130467,0.000130475,0.000206428,0.0425297,0.0425304,0.00999377,0.0521491,0.0521493,0.0650202,2.7861e-09,2.7878e-09,6.75932e-09,2.17893e-06,2.17883e-06,6.57164e-08,0,0,0,0,0,0,0,0 +14180000,0.982998,-0.00706761,-0.0110951,0.183145,0.0060079,-0.00206711,0.0147555,0.0074199,-0.0022375,0.0294195,-1.19669e-05,-5.91923e-05,-2.69881e-06,1.47579e-06,4.93459e-05,-0.00135625,0.204984,0.000821313,0.434268,0,0,0,0,0,7.1409e-06,0.000128709,0.000128718,0.000205211,0.0374855,0.0374861,0.00971997,0.0455742,0.0455743,0.0641008,2.67928e-09,2.6809e-09,6.67737e-09,2.17701e-06,2.17691e-06,6.55015e-08,0,0,0,0,0,0,0,0 +14280000,0.982988,-0.00698722,-0.011068,0.183203,0.00611815,-0.00290372,0.0140566,0.00793328,-0.0025074,0.0330184,-1.19675e-05,-5.91906e-05,-2.74357e-06,1.44618e-06,4.93557e-05,-0.00135659,0.204984,0.000821313,0.434268,0,0,0,0,0,7.1082e-06,0.000133361,0.000133369,0.000204141,0.0421973,0.042198,0.00963577,0.0519426,0.0519428,0.0638661,2.67935e-09,2.68097e-09,6.59323e-09,2.17702e-06,2.17692e-06,6.54029e-08,0,0,0,0,0,0,0,0 +14380000,0.982996,-0.00707307,-0.0110136,0.183162,0.00821303,-0.00473989,0.0142063,0.00773922,-0.00339309,0.0365609,-1.18256e-05,-5.92175e-05,-2.53903e-06,1.82173e-06,4.8491e-05,-0.00135682,0.204984,0.000821313,0.434268,0,0,0,0,0,7.07679e-06,0.000131006,0.000131014,0.000203207,0.0373239,0.0373245,0.00941294,0.0454407,0.0454408,0.0629829,2.56002e-09,2.56154e-09,6.50715e-09,2.17459e-06,2.1745e-06,6.51614e-08,0,0,0,0,0,0,0,0 +14480000,0.982974,-0.0071487,-0.0109657,0.183279,0.00646647,-0.00490447,0.0178509,0.00843022,-0.00386732,0.0390663,-1.1834e-05,-5.92091e-05,-2.95416e-06,1.81418e-06,4.85042e-05,-0.00135699,0.204984,0.000821313,0.434268,0,0,0,0,0,7.115e-06,0.000135632,0.000135641,0.000204297,0.0420428,0.0420435,0.00945613,0.0517659,0.0517661,0.0637476,2.56009e-09,2.56162e-09,6.44138e-09,2.1746e-06,2.17451e-06,6.50867e-08,0,0,0,0,0,0,0,0 +14580000,0.982949,-0.00723438,-0.010777,0.183418,0.00411598,-0.00469567,0.0165862,0.00548425,-0.00435937,0.0365025,-1.1891e-05,-5.9582e-05,-3.36197e-06,4.71939e-07,4.82672e-05,-0.00135624,0.204984,0.000821313,0.434268,0,0,0,0,0,7.09027e-06,0.00013264,0.00013265,0.000203561,0.0372744,0.037275,0.00927204,0.0453249,0.045325,0.0628718,2.43e-09,2.43142e-09,6.35188e-09,2.1711e-06,2.17101e-06,6.48132e-08,0,0,0,0,0,0,0,0 +14680000,0.982959,-0.00720926,-0.0108269,0.183362,0.00399875,-0.00453049,0.0163829,0.00587978,-0.00480085,0.0369153,-1.18873e-05,-5.95861e-05,-3.1693e-06,4.88715e-07,4.82582e-05,-0.00135602,0.204984,0.000821313,0.434268,0,0,0,0,0,7.06969e-06,0.000137202,0.000137212,0.000202928,0.0420445,0.0420454,0.00925869,0.0516236,0.0516238,0.062633,2.43006e-09,2.43149e-09,6.26114e-09,2.17111e-06,2.17102e-06,6.47039e-08,0,0,0,0,0,0,0,0 +14780000,0.982993,-0.00713124,-0.0108327,0.183184,0.0051733,0.00233893,0.0149258,0.00480433,0.000231863,0.038833,-1.26309e-05,-5.94249e-05,-2.74677e-06,1.66889e-06,5.23754e-05,-0.0013563,0.204984,0.000821313,0.434268,0,0,0,0,0,7.04494e-06,0.000133549,0.000133559,0.000202366,0.0373347,0.0373356,0.00911259,0.045231,0.0452311,0.0618026,2.29121e-09,2.29254e-09,6.16861e-09,2.16611e-06,2.16602e-06,6.4395e-08,0,0,0,0,0,0,0,0 +14880000,0.983017,-0.00708955,-0.0107749,0.183063,0.00417647,0.000678833,0.0171077,0.00528705,0.000372189,0.0395369,-1.26213e-05,-5.94344e-05,-2.26974e-06,1.67952e-06,5.23614e-05,-0.00135611,0.204984,0.000821313,0.434268,0,0,0,0,0,7.0297e-06,0.000138012,0.000138022,0.000201871,0.0421223,0.0421231,0.00912854,0.0515184,0.0515186,0.0615711,2.29127e-09,2.2926e-09,6.07495e-09,2.16612e-06,2.16603e-06,6.4275e-08,0,0,0,0,0,0,0,0 +14980000,0.983022,-0.00721542,-0.0106511,0.183039,0.00256276,-0.000298599,0.0192476,0.00425063,-0.000992734,0.0407317,-1.24535e-05,-5.96344e-05,-2.06253e-06,6.58134e-07,5.11021e-05,-0.00135546,0.204984,0.000821313,0.434268,0,0,0,0,0,7.01587e-06,0.000133715,0.000133725,0.000201432,0.0373975,0.0373982,0.00901524,0.0451603,0.0451604,0.0607938,2.14623e-09,2.14745e-09,5.98021e-09,2.1594e-06,2.15932e-06,6.3928e-08,0,0,0,0,0,0,0,0 +15080000,0.983018,-0.00716242,-0.0107512,0.183052,0.00207498,-0.000599383,0.0220322,0.0044815,-0.00106764,0.0433248,-1.24549e-05,-5.96328e-05,-2.13909e-06,6.50049e-07,5.11057e-05,-0.00135556,0.204984,0.000821313,0.434268,0,0,0,0,0,7.06766e-06,0.000138046,0.000138055,0.000202918,0.0421987,0.0421996,0.00913557,0.0514464,0.0514466,0.0615143,2.1463e-09,2.14752e-09,5.90837e-09,2.15941e-06,2.15933e-06,6.38314e-08,0,0,0,0,0,0,0,0 +15180000,0.982998,-0.0072729,-0.0108118,0.183156,0.000286748,-0.00149185,0.0230393,0.00362054,-0.000924703,0.0443496,-1.25009e-05,-5.96816e-05,-2.51227e-06,4.50919e-07,5.12624e-05,-0.00135515,0.204984,0.000821313,0.434268,0,0,0,0,0,7.0545e-06,0.000133168,0.000133176,0.000202559,0.0374637,0.0374644,0.00904604,0.0451118,0.0451119,0.0607627,1.99795e-09,1.99906e-09,5.81195e-09,2.15095e-06,2.15087e-06,6.34436e-08,0,0,0,0,0,0,0,0 +15280000,0.983025,-0.00738345,-0.0108775,0.182997,-0.000215837,-0.00236646,0.0220565,0.00365119,-0.00105306,0.0424615,-1.24882e-05,-5.96955e-05,-1.85065e-06,5.21876e-07,5.12317e-05,-0.00135429,0.204984,0.000821313,0.434268,0,0,0,0,0,7.04629e-06,0.000137337,0.000137347,0.000202227,0.0422787,0.0422795,0.00911107,0.0514052,0.0514054,0.0605721,1.99801e-09,1.99912e-09,5.7148e-09,2.15096e-06,2.15088e-06,6.32984e-08,0,0,0,0,0,0,0,0 +15380000,0.982989,-0.00740424,-0.0109072,0.183188,0.000925194,0.000325083,0.0213869,0.0030966,-0.000732431,0.041471,-1.25535e-05,-5.96884e-05,-2.24159e-06,7.58452e-07,5.15924e-05,-0.00135329,0.204984,0.000821313,0.434268,0,0,0,0,0,7.04051e-06,0.000131943,0.000131952,0.00020191,0.0375093,0.0375103,0.00904273,0.0450833,0.0450834,0.0598654,1.84896e-09,1.84996e-09,5.61694e-09,2.1408e-06,2.14073e-06,6.28662e-08,0,0,0,0,0,0,0,0 +15480000,0.982986,-0.00746173,-0.0108764,0.183205,8.88305e-06,-0.00142498,0.022688,0.00314857,-0.000739983,0.0419906,-1.255e-05,-5.9688e-05,-2.16782e-06,8.71259e-07,5.15013e-05,-0.00135292,0.204984,0.000821313,0.434268,0,0,0,0,0,7.03384e-06,0.00013593,0.000135939,0.000201617,0.0422953,0.0422964,0.00912754,0.0513886,0.0513889,0.0597064,1.84903e-09,1.85002e-09,5.51883e-09,2.1408e-06,2.14073e-06,6.27037e-08,0,0,0,0,0,0,0,0 +15580000,0.982986,-0.0076278,-0.010935,0.183195,0.0039468,-0.00511521,0.0218027,0.00535076,-0.00448527,0.0408403,-1.18463e-05,-5.95421e-05,-1.90539e-06,2.44991e-06,4.49625e-05,-0.00135209,0.204984,0.000821313,0.434268,0,0,0,0,0,7.02666e-06,0.000130117,0.000130121,0.000201327,0.0374811,0.0374824,0.00907658,0.0450711,0.0450713,0.059049,1.70192e-09,1.70273e-09,5.42031e-09,2.12912e-06,2.12906e-06,6.22262e-08,0,0,0,0,0,0,0,0 +15680000,0.983007,-0.007585,-0.0109411,0.183086,0.00600145,-0.00828666,0.0223291,0.00584693,-0.00514295,0.0416495,-1.18421e-05,-5.95531e-05,-1.52009e-06,2.35064e-06,4.50743e-05,-0.00135174,0.204984,0.000821313,0.434268,0,0,0,0,0,7.01691e-06,0.000133905,0.000133905,0.000201052,0.042231,0.0422325,0.00917795,0.0513891,0.0513895,0.0589249,1.702e-09,1.70276e-09,5.32182e-09,2.12912e-06,2.12906e-06,6.20444e-08,0,0,0,0,0,0,0,0 +15780000,0.983022,-0.00760024,-0.0108751,0.183006,0.00461691,-0.0076694,0.0223666,0.00456839,-0.00407559,0.0416275,-1.20988e-05,-5.96553e-05,-1.23113e-06,1.53988e-06,4.74202e-05,-0.00135072,0.204984,0.000821313,0.434268,0,0,0,0,0,7.0701e-06,0.000127781,0.000127778,0.000202652,0.0373702,0.0373714,0.00921201,0.0450706,0.0450709,0.0591832,1.55908e-09,1.5597e-09,5.24791e-09,2.11619e-06,2.11613e-06,6.15716e-08,0,0,0,0,0,0,0,0 +15880000,0.983005,-0.00766351,-0.0109201,0.183091,0.00371685,-0.0056899,0.0231454,0.00489887,-0.00475768,0.0425724,-1.21006e-05,-5.96524e-05,-1.35731e-06,1.60463e-06,4.73782e-05,-0.00135038,0.204984,0.000821313,0.434268,0,0,0,0,0,7.06392e-06,0.000131358,0.000131352,0.000202358,0.0420557,0.0420576,0.00932652,0.0513991,0.0513996,0.0590883,1.55917e-09,1.55973e-09,5.14933e-09,2.11619e-06,2.11613e-06,6.13713e-08,0,0,0,0,0,0,0,0 +15980000,0.983011,-0.00748393,-0.0108654,0.183074,0.00242912,-0.00420094,0.0209315,0.0039406,-0.00370544,0.0403045,-1.22842e-05,-5.9696e-05,-1.46991e-06,1.41262e-06,4.8956e-05,-0.0013483,0.204984,0.000821313,0.434268,0,0,0,0,0,7.04759e-06,0.000125036,0.000125025,0.000202075,0.037172,0.0371736,0.00929728,0.0450768,0.0450772,0.0585127,1.42231e-09,1.42275e-09,5.05124e-09,2.1023e-06,2.10225e-06,6.08035e-08,0,0,0,0,0,0,0,0 +16080000,0.98301,-0.00740309,-0.0108881,0.183081,0.00116994,-0.00568086,0.0190678,0.00405873,-0.0042216,0.0416306,-1.22929e-05,-5.96893e-05,-1.86922e-06,1.40213e-06,4.89827e-05,-0.00134815,0.204984,0.000821313,0.434268,0,0,0,0,0,7.02956e-06,0.000128394,0.000128384,0.000201777,0.0417938,0.0417955,0.00942251,0.0514127,0.0514132,0.0584567,1.42237e-09,1.42282e-09,4.95333e-09,2.10231e-06,2.10225e-06,6.05805e-08,0,0,0,0,0,0,0,0 +16180000,0.982991,-0.00730779,-0.0107829,0.183191,-0.00209718,-0.00416895,0.0181465,0.00199035,-0.0032811,0.0384284,-1.25297e-05,-5.98605e-05,-2.34921e-06,-4.06352e-07,5.12711e-05,-0.00134641,0.204984,0.000821313,0.434268,0,0,0,0,0,7.01511e-06,0.000121965,0.000121954,0.000201461,0.036883,0.0368844,0.00939859,0.0450855,0.0450859,0.0579207,1.29285e-09,1.29325e-09,4.85596e-09,2.08772e-06,2.08767e-06,5.99661e-08,0,0,0,0,0,0,0,0 +16280000,0.982989,-0.00732912,-0.0107113,0.183208,-0.00149958,-0.00484222,0.0168155,0.00178128,-0.00370994,0.0396293,-1.25276e-05,-5.98624e-05,-2.24555e-06,-3.89515e-07,5.12606e-05,-0.00134626,0.204984,0.000821313,0.434268,0,0,0,0,0,7.00774e-06,0.000125104,0.000125095,0.000201127,0.0414027,0.0414044,0.00953253,0.0514219,0.0514225,0.0579085,1.29291e-09,1.29332e-09,4.75932e-09,2.08773e-06,2.08768e-06,5.97201e-08,0,0,0,0,0,0,0,0 +16380000,0.982995,-0.00723639,-0.010729,0.183178,0.00163236,-0.00351909,0.0176223,0.00292776,-0.00287413,0.0393358,-1.25565e-05,-5.96405e-05,-1.83849e-06,2.36481e-06,5.15125e-05,-0.00134543,0.204984,0.000821313,0.434268,0,0,0,0,0,7.06514e-06,0.000118676,0.000118666,0.000202639,0.0364921,0.0364936,0.00958272,0.045092,0.0450923,0.0582497,1.17183e-09,1.17219e-09,4.68713e-09,2.07277e-06,2.07272e-06,5.91276e-08,0,0,0,0,0,0,0,0 +16480000,0.982979,-0.00732496,-0.0107173,0.183257,0.00327697,-0.00494041,0.0194835,0.00313794,-0.00332408,0.0424113,-1.25624e-05,-5.96351e-05,-2.12928e-06,2.32511e-06,5.15401e-05,-0.00134579,0.204984,0.000821313,0.434268,0,0,0,0,0,7.05259e-06,0.000121601,0.000121592,0.000202263,0.0408819,0.0408836,0.00972325,0.0514209,0.0514214,0.0582763,1.17189e-09,1.17226e-09,4.59174e-09,2.07277e-06,2.07273e-06,5.88612e-08,0,0,0,0,0,0,0,0 +16580000,0.982975,-0.00728842,-0.0107416,0.183282,0.00651978,-0.00569573,0.0223835,0.00262982,-0.00266241,0.043255,-1.27042e-05,-5.9673e-05,-2.15853e-06,1.9455e-06,5.30952e-05,-0.00134521,0.204984,0.000821313,0.434268,0,0,0,0,0,7.03869e-06,0.000115265,0.000115256,0.000201859,0.0359939,0.0359953,0.00970131,0.0450922,0.0450925,0.0578055,1.05984e-09,1.06017e-09,4.49712e-09,2.05774e-06,2.0577e-06,5.81601e-08,0,0,0,0,0,0,0,0 +16680000,0.982988,-0.00731631,-0.0107105,0.183213,0.00818471,-0.00821151,0.0230127,0.00334193,-0.00331296,0.0444409,-1.26999e-05,-5.96781e-05,-1.91705e-06,1.95054e-06,5.31023e-05,-0.00134488,0.204984,0.000821313,0.434268,0,0,0,0,0,7.02424e-06,0.000117982,0.000117972,0.000201431,0.0402598,0.0402614,0.00984413,0.0514047,0.0514052,0.0578644,1.05991e-09,1.06023e-09,4.40342e-09,2.05775e-06,2.05771e-06,5.78668e-08,0,0,0,0,0,0,0,0 +16780000,0.983002,-0.00715776,-0.0105984,0.183149,0.00982679,-0.00897942,0.0215495,0.00265019,-0.00262745,0.0435431,-1.29175e-05,-5.97707e-05,-1.79046e-06,9.60158e-07,5.56879e-05,-0.00134341,0.204984,0.000821313,0.434268,0,0,0,0,0,7.00482e-06,0.000111808,0.000111798,0.000200985,0.0354456,0.0354469,0.0098201,0.0450833,0.0450836,0.0574284,9.5709e-10,9.57362e-10,4.3108e-09,2.04289e-06,2.04286e-06,5.71253e-08,0,0,0,0,0,0,0,0 +16880000,0.983031,-0.00714943,-0.0107014,0.182989,0.00828223,-0.00870862,0.0227681,0.00355448,-0.00349384,0.0424714,-1.29072e-05,-5.97806e-05,-1.26665e-06,1.05486e-06,5.56336e-05,-0.00134234,0.204984,0.000821313,0.434268,0,0,0,0,0,6.98816e-06,0.000114325,0.000114315,0.000200509,0.0395707,0.0395721,0.00996372,0.0513722,0.0513727,0.0575222,9.57151e-10,9.57434e-10,4.21926e-09,2.0429e-06,2.04287e-06,5.68063e-08,0,0,0,0,0,0,0,0 +16980000,0.983028,-0.00720321,-0.0107492,0.183001,0.00953824,-0.00818304,0.0230386,0.00340099,-0.00266256,0.0414728,-1.30371e-05,-5.96442e-05,-1.16921e-06,3.27872e-06,5.70804e-05,-0.00134122,0.204984,0.000821313,0.434268,0,0,0,0,0,6.97243e-06,0.000108361,0.000108352,0.000200006,0.0348193,0.0348204,0.00993548,0.0450633,0.0450636,0.0571166,8.63403e-10,8.63641e-10,4.12894e-09,2.02836e-06,2.02834e-06,5.60276e-08,0,0,0,0,0,0,0,0 +17080000,0.983024,-0.00728416,-0.0107047,0.18302,0.0117146,-0.0106176,0.0240741,0.0044701,-0.00359996,0.0414279,-1.30388e-05,-5.96436e-05,-1.22869e-06,3.32781e-06,5.70687e-05,-0.00134043,0.204984,0.000821313,0.434268,0,0,0,0,0,7.01874e-06,0.000110688,0.00011068,0.000201332,0.0388066,0.0388078,0.0101546,0.0513201,0.0513206,0.0580785,8.63475e-10,8.6372e-10,4.06201e-09,2.02837e-06,2.02835e-06,5.57741e-08,0,0,0,0,0,0,0,0 +17180000,0.98297,-0.0073569,-0.0105976,0.183314,0.0111846,-0.0147155,0.0244159,0.0027875,-0.00720276,0.0436895,-1.29144e-05,-5.98347e-05,-1.91554e-06,1.18493e-06,5.51256e-05,-0.00133997,0.204984,0.000821313,0.434268,0,0,0,0,0,7.00446e-06,0.000104974,0.000104964,0.000200758,0.0341483,0.0341492,0.0101185,0.0450307,0.045031,0.0576828,7.78499e-10,7.78676e-10,3.97371e-09,2.0143e-06,2.01428e-06,5.49603e-08,0,0,0,0,0,0,0,0 +17280000,0.982938,-0.00733467,-0.0105999,0.183484,0.0117053,-0.0146881,0.0241062,0.00390877,-0.00866357,0.0440825,-1.29232e-05,-5.98222e-05,-2.47887e-06,1.37601e-06,5.49702e-05,-0.00133932,0.204984,0.000821313,0.434268,0,0,0,0,0,6.98473e-06,0.000107124,0.000107112,0.000200174,0.0379995,0.0380008,0.0102607,0.0512488,0.0512493,0.0578467,7.7858e-10,7.78731e-10,3.88694e-09,2.0143e-06,2.01428e-06,5.45979e-08,0,0,0,0,0,0,0,0 +17380000,0.982972,-0.00725326,-0.0106147,0.183304,0.0092631,-0.0140243,0.0246742,0.00534296,-0.00553854,0.0447009,-1.32837e-05,-5.95878e-05,-2.0814e-06,4.7866e-06,5.98079e-05,-0.00133823,0.204984,0.000821313,0.434268,0,0,0,0,0,6.95742e-06,0.000101682,0.00010167,0.000199561,0.0334402,0.0334408,0.0102172,0.0449851,0.0449855,0.0574732,7.01872e-10,7.01994e-10,3.80134e-09,2.00079e-06,2.00078e-06,5.37547e-08,0,0,0,0,0,0,0,0 +17480000,0.982966,-0.00722234,-0.0106382,0.183338,0.00723847,-0.0149308,0.0244598,0.00609839,-0.00695892,0.0451273,-1.32888e-05,-5.95841e-05,-2.31383e-06,4.81253e-06,5.98138e-05,-0.00133754,0.204984,0.000821313,0.434268,0,0,0,0,0,6.93315e-06,0.000103665,0.000103654,0.000198925,0.0371468,0.0371473,0.010354,0.0511574,0.0511579,0.0576577,7.01937e-10,7.02069e-10,3.71723e-09,2.0008e-06,2.00079e-06,5.33675e-08,0,0,0,0,0,0,0,0 +17580000,0.982963,-0.0071387,-0.0105173,0.183365,0.00328513,-0.011182,0.0229959,0.0022484,-0.00525884,0.0433307,-1.3677e-05,-5.98856e-05,-2.34013e-06,6.60326e-07,6.50863e-05,-0.00133563,0.204984,0.000821313,0.434268,0,0,0,0,0,6.91069e-06,9.85132e-05,9.85014e-05,0.000198262,0.0327084,0.0327089,0.0103031,0.0449261,0.0449265,0.0573071,6.32971e-10,6.33071e-10,3.63459e-09,1.98794e-06,1.98793e-06,5.25014e-08,0,0,0,0,0,0,0,0 +17680000,0.982981,-0.00725281,-0.0104381,0.183265,0.00261636,-0.0112241,0.0245361,0.00257922,-0.00640852,0.0457462,-1.36769e-05,-5.98864e-05,-2.31549e-06,6.36086e-07,6.51105e-05,-0.00133562,0.204984,0.000821313,0.434268,0,0,0,0,0,6.943e-06,0.000100343,0.000100331,0.000199393,0.0362661,0.0362667,0.0105145,0.0510468,0.0510473,0.0583521,6.33053e-10,6.33145e-10,3.57349e-09,1.98794e-06,1.98794e-06,5.21981e-08,0,0,0,0,0,0,0,0 +17780000,0.983011,-0.00725142,-0.0104309,0.183109,0.00469297,-0.00990973,0.0251206,0.00332544,-0.0055596,0.0498025,-1.38863e-05,-5.97197e-05,-2.29888e-06,3.12192e-06,6.82772e-05,-0.00133608,0.204984,0.000821313,0.434268,0,0,0,0,0,6.90521e-06,9.54871e-05,9.54734e-05,0.000198683,0.0319509,0.0319514,0.0104535,0.0448538,0.0448541,0.0580054,5.71227e-10,5.71269e-10,3.49338e-09,1.97575e-06,1.97575e-06,5.13115e-08,0,0,0,0,0,0,0,0 +17880000,0.98303,-0.0072016,-0.0105183,0.183003,0.00687079,-0.0124791,0.0253387,0.00392644,-0.0066667,0.0543199,-1.38823e-05,-5.97244e-05,-2.069e-06,3.02832e-06,6.83403e-05,-0.00133677,0.204984,0.000821313,0.434268,0,0,0,0,0,6.87686e-06,9.71753e-05,9.71589e-05,0.000197939,0.0353759,0.0353767,0.0105796,0.0509176,0.050918,0.0582352,5.71307e-10,5.71334e-10,3.41473e-09,1.97575e-06,1.97575e-06,5.08876e-08,0,0,0,0,0,0,0,0 +17980000,0.983025,-0.00696495,-0.0104959,0.183038,0.00508264,-0.00602517,0.023915,0.00309849,-0.00129468,0.0545339,-1.44502e-05,-5.96146e-05,-2.15792e-06,4.68656e-06,7.66956e-05,-0.00133596,0.204984,0.000821313,0.434268,0,0,0,0,0,6.84977e-06,9.26107e-05,9.25942e-05,0.000197168,0.0311927,0.0311932,0.0105081,0.0447685,0.0447689,0.0578933,5.15956e-10,5.15967e-10,3.33753e-09,1.96424e-06,1.96425e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18080000,0.983023,-0.00705202,-0.010468,0.183049,0.00559277,-0.00617293,0.0226733,0.00367029,-0.00192975,0.0538768,-1.44509e-05,-5.96147e-05,-2.17026e-06,4.74289e-06,7.66852e-05,-0.00133485,0.204984,0.000821313,0.434268,0,0,0,0,0,6.8234e-06,9.41665e-05,9.4151e-05,0.000196378,0.0344792,0.0344798,0.0106264,0.0507716,0.050772,0.0581369,5.16025e-10,5.16046e-10,3.26191e-09,1.96425e-06,1.96426e-06,5e-08,0,0,0,0,0,0,0,0 +18180000,0.983063,-0.00709045,-0.0104846,0.182833,0.00507397,-0.00464803,0.0239352,0.00407827,-0.00144786,0.0522567,-1.45033e-05,-5.9569e-05,-1.52853e-06,5.80718e-06,7.75575e-05,-0.00133316,0.204984,0.000821313,0.434268,0,0,0,0,0,6.79325e-06,8.98917e-05,8.98764e-05,0.000195568,0.0304159,0.0304164,0.0105453,0.0446712,0.0446715,0.0578013,4.66576e-10,4.66584e-10,3.18776e-09,1.95344e-06,1.95345e-06,5e-08,0,0,0,0,0,0,0,0 +18280000,0.983057,-0.0071308,-0.0104892,0.18286,0.00607517,-0.00590048,0.0228962,0.00457958,-0.00197723,0.0512089,-1.4503e-05,-5.957e-05,-1.48982e-06,5.87487e-06,7.75425e-05,-0.00133188,0.204984,0.000821313,0.434268,0,0,0,0,0,6.76771e-06,9.13277e-05,9.13129e-05,0.000194738,0.0335661,0.0335666,0.0106557,0.0506084,0.0506087,0.0580544,4.66646e-10,4.66663e-10,3.1152e-09,1.95345e-06,1.95346e-06,5e-08,0,0,0,0,0,0,0,0 +18380000,0.983037,-0.00708623,-0.0105036,0.18297,0.00559903,-0.00552884,0.0225385,0.00608534,-0.00151877,0.0508032,-1.45299e-05,-5.94223e-05,-1.6492e-06,8.26457e-06,7.78591e-05,-0.00133088,0.204984,0.000821313,0.434268,0,0,0,0,0,6.80232e-06,8.73368e-05,8.73217e-05,0.000195635,0.0296499,0.0296502,0.0106505,0.044562,0.0445623,0.0585724,4.22533e-10,4.22536e-10,3.06176e-09,1.94335e-06,1.94336e-06,5.0002e-08,0,0,0,0,0,0,0,0 +18480000,0.983041,-0.00709643,-0.0105121,0.182946,0.00884048,-0.00565219,0.0226483,0.00687285,-0.00209584,0.0533635,-1.45261e-05,-5.94255e-05,-1.46086e-06,8.27481e-06,7.78444e-05,-0.001331,0.204984,0.000821313,0.434268,0,0,0,0,0,6.77463e-06,8.86632e-05,8.86484e-05,0.000194749,0.0326705,0.032671,0.0107539,0.0504315,0.0504318,0.0588334,4.22605e-10,4.22615e-10,2.99175e-09,1.94336e-06,1.94337e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18580000,0.983012,-0.00696604,-0.0103829,0.183114,0.00724952,-0.00568329,0.023141,0.00549846,-0.00167072,0.0551798,-1.46418e-05,-5.9517e-05,-1.65713e-06,6.8338e-06,7.95858e-05,-0.0013304,0.204984,0.000821313,0.434268,0,0,0,0,0,6.75026e-06,8.49405e-05,8.49257e-05,0.00019385,0.0288903,0.0288906,0.0106554,0.0444423,0.0444425,0.0584968,3.83248e-10,3.83248e-10,2.92337e-09,1.93393e-06,1.93394e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18680000,0.983019,-0.00697296,-0.0103467,0.183079,0.00662567,-0.00445858,0.0219801,0.00619583,-0.0021814,0.0546429,-1.46394e-05,-5.95196e-05,-1.51691e-06,6.89238e-06,7.95687e-05,-0.00132935,0.204984,0.000821313,0.434268,0,0,0,0,0,6.71951e-06,8.61666e-05,8.61523e-05,0.000192935,0.0317872,0.0317876,0.010751,0.0502412,0.0502415,0.05876,3.83321e-10,3.83328e-10,2.85639e-09,1.93394e-06,1.93395e-06,5e-08,0,0,0,0,0,0,0,0 +18780000,0.983019,-0.00688136,-0.0102354,0.183089,0.00531188,-0.00557582,0.0210972,0.00616081,-0.00182339,0.0513888,-1.46929e-05,-5.95019e-05,-1.48923e-06,7.37137e-06,8.03819e-05,-0.00132652,0.204984,0.000821313,0.434268,0,0,0,0,0,6.68759e-06,8.26987e-05,8.26846e-05,0.000192008,0.0281419,0.0281421,0.0106442,0.0443127,0.0443129,0.0584159,3.48219e-10,3.48217e-10,2.79094e-09,1.92516e-06,1.92517e-06,5e-08,0,0,0,0,0,0,0,0 +18880000,0.983007,-0.0068505,-0.0102232,0.183153,0.00523287,-0.00516182,0.0195964,0.00668768,-0.00239125,0.04838,-1.46972e-05,-5.9499e-05,-1.67616e-06,7.44085e-06,8.03882e-05,-0.00132459,0.204984,0.000821313,0.434268,0,0,0,0,0,6.65542e-06,8.38336e-05,8.38197e-05,0.000191071,0.0309181,0.0309183,0.0107335,0.050039,0.0500392,0.0586836,3.48294e-10,3.48298e-10,2.72702e-09,1.92517e-06,1.92518e-06,5e-08,0,0,0,0,0,0,0,0 +18980000,0.982998,-0.00683623,-0.0102461,0.183203,0.00346098,-0.00554391,0.0215251,0.00543447,-0.00195009,0.0528583,-1.47796e-05,-5.95552e-05,-1.64323e-06,6.54639e-06,8.17273e-05,-0.00132499,0.204984,0.000821313,0.434268,0,0,0,0,0,6.68447e-06,8.06087e-05,8.05943e-05,0.000191792,0.0274076,0.0274077,0.0107078,0.0441739,0.0441741,0.0591989,3.16993e-10,3.16987e-10,2.67999e-09,1.91701e-06,1.91702e-06,5.0002e-08,0,0,0,0,0,0,0,0 +19080000,0.983005,-0.00691007,-0.0102499,0.183163,0.00151274,-0.00621344,0.0215181,0.00570996,-0.00253638,0.0491111,-1.47746e-05,-5.95605e-05,-1.35538e-06,6.65748e-06,8.17011e-05,-0.00132278,0.204984,0.000821313,0.434268,0,0,0,0,0,6.65479e-06,8.16603e-05,8.16464e-05,0.000190811,0.0300639,0.0300639,0.0107921,0.0498266,0.0498268,0.0594709,3.17069e-10,3.17069e-10,2.61861e-09,1.91702e-06,1.91703e-06,5.0002e-08,0,0,0,0,0,0,0,0 +19180000,0.982974,-0.00682799,-0.0103536,0.183325,-0.000829984,-0.00610636,0.0220417,0.00468047,-0.00206792,0.0477411,-1.48617e-05,-5.9562e-05,-1.89513e-06,6.54895e-06,8.29789e-05,-0.0013214,0.204984,0.000821313,0.434268,0,0,0,0,0,6.61865e-06,7.86643e-05,7.86494e-05,0.000189822,0.0266864,0.0266863,0.0106721,0.0440272,0.0440273,0.0591069,2.89142e-10,2.89132e-10,2.55862e-09,1.90946e-06,1.90948e-06,5.0001e-08,0,0,0,0,0,0,0,0 +19280000,0.982972,-0.00677809,-0.0103459,0.18334,-0.0017422,-0.00582858,0.0217087,0.0045759,-0.00268161,0.0479232,-1.4864e-05,-5.95602e-05,-2.00181e-06,6.57034e-06,8.29862e-05,-0.00132065,0.204984,0.000821313,0.434268,0,0,0,0,0,6.58268e-06,7.96402e-05,7.96254e-05,0.000188822,0.0292395,0.0292395,0.0107491,0.049605,0.0496052,0.0593672,2.89219e-10,2.89215e-10,2.50003e-09,1.90947e-06,1.90949e-06,5.0001e-08,0,0,0,0,0,0,0,0 +19380000,0.982971,-0.00682871,-0.0102352,0.183351,-0.00203971,-0.00304801,0.0235748,0.00388532,-0.000820691,0.0468568,-1.50035e-05,-5.95129e-05,-2.19e-06,7.41735e-06,8.53184e-05,-0.00131901,0.204984,0.000821313,0.434268,0,0,0,0,0,6.54333e-06,7.6855e-05,7.68411e-05,0.000187817,0.0259865,0.0259865,0.0106249,0.0438728,0.0438729,0.0589971,2.64282e-10,2.6427e-10,2.44286e-09,1.90246e-06,1.90248e-06,5e-08,0,0,0,0,0,0,0,0 +19480000,0.982921,-0.00691381,-0.0101385,0.183616,-0.00307675,-0.0028837,0.0237332,0.00360596,-0.00108732,0.0467133,-1.50111e-05,-5.95066e-05,-2.56716e-06,7.42646e-06,8.53444e-05,-0.00131805,0.204984,0.000821313,0.434268,0,0,0,0,0,6.518e-06,7.77616e-05,7.77488e-05,0.00018679,0.0284346,0.0284347,0.0106963,0.0493751,0.0493752,0.0592493,2.64361e-10,2.64354e-10,2.38705e-09,1.90247e-06,1.90249e-06,5e-08,0,0,0,0,0,0,0,0 +19580000,0.982904,-0.00685905,-0.0102573,0.183705,-0.00462575,-0.00586864,0.0243921,0.00405819,-0.00211598,0.0470627,-1.49388e-05,-5.9446e-05,-2.66177e-06,8.53638e-06,8.40154e-05,-0.00131699,0.204984,0.000821313,0.434268,0,0,0,0,0,6.48637e-06,7.51756e-05,7.51618e-05,0.000185764,0.0253125,0.0253124,0.010569,0.043712,0.0437121,0.0588726,2.42079e-10,2.42065e-10,2.33262e-09,1.89599e-06,1.89601e-06,5e-08,0,0,0,0,0,0,0,0 +19680000,0.98292,-0.00688256,-0.0102943,0.183616,-0.00565954,-0.00469646,0.0252697,0.0035781,-0.00266085,0.0489532,-1.49348e-05,-5.94496e-05,-2.45447e-06,8.55977e-06,8.40026e-05,-0.00131672,0.204984,0.000821313,0.434268,0,0,0,0,0,6.50507e-06,7.60202e-05,7.60063e-05,0.000186322,0.0276632,0.0276632,0.0107274,0.0491394,0.0491395,0.0600079,2.42164e-10,2.42153e-10,2.29269e-09,1.896e-06,1.89602e-06,5.0002e-08,0,0,0,0,0,0,0,0 +19780000,0.982907,-0.00692851,-0.0103151,0.183681,-0.00543684,-0.00338215,0.0233622,0.00601165,-0.00208481,0.0440578,-1.49279e-05,-5.9295e-05,-2.57718e-06,1.13128e-05,8.38601e-05,-0.00131372,0.204984,0.000821313,0.434268,0,0,0,0,0,6.4696e-06,7.36167e-05,7.36031e-05,0.000185265,0.0246637,0.0246637,0.0105948,0.0435461,0.0435461,0.0596072,2.22231e-10,2.22215e-10,2.2405e-09,1.89001e-06,1.89003e-06,5.0001e-08,0,0,0,0,0,0,0,0 +19880000,0.982883,-0.00695352,-0.0103893,0.183806,-0.00570187,-0.00291917,0.0224567,0.00541629,-0.00235556,0.0429821,-1.49339e-05,-5.929e-05,-2.87079e-06,1.13358e-05,8.38832e-05,-0.00131247,0.204984,0.000821313,0.434268,0,0,0,0,0,6.4353e-06,7.4404e-05,7.43904e-05,0.000184211,0.0269255,0.0269255,0.0106596,0.0488995,0.0488996,0.0598525,2.22312e-10,2.223e-10,2.18968e-09,1.89001e-06,1.89004e-06,5.0001e-08,0,0,0,0,0,0,0,0 +19980000,0.982897,-0.00694989,-0.0105525,0.183721,-0.00512684,-0.00203843,0.0204311,0.00569052,-0.000839871,0.0395092,-1.49946e-05,-5.91839e-05,-2.76156e-06,1.34431e-05,8.50091e-05,-0.00130962,0.204984,0.000821313,0.434268,0,0,0,0,0,6.39525e-06,7.21697e-05,7.21555e-05,0.00018315,0.0240417,0.0240417,0.0105256,0.0433759,0.0433759,0.0594451,2.04459e-10,2.04442e-10,2.14005e-09,1.88446e-06,1.88449e-06,5e-08,0,0,0,0,0,0,0,0 +20080000,0.982907,-0.00695475,-0.0105723,0.183669,-0.00379764,-0.00429307,0.0205018,0.0052321,-0.00120464,0.0428345,-1.49947e-05,-5.91837e-05,-2.77203e-06,1.34268e-05,8.50077e-05,-0.00131009,0.204984,0.000821313,0.434268,0,0,0,0,0,6.35499e-06,7.29048e-05,7.28908e-05,0.000182091,0.0262185,0.0262185,0.0105858,0.0486562,0.0486562,0.0596736,2.04541e-10,2.04527e-10,2.09169e-09,1.88447e-06,1.8845e-06,5e-08,0,0,0,0,0,0,0,0 +20180000,0.982883,-0.00694243,-0.0106912,0.183789,-0.0032035,-0.00338182,0.0202376,0.00622392,-0.000949256,0.0425509,-1.50154e-05,-5.91181e-05,-3.08166e-06,1.44975e-05,8.53233e-05,-0.00130897,0.204984,0.000821313,0.434268,0,0,0,0,0,6.31874e-06,7.08242e-05,7.08095e-05,0.000181027,0.0234424,0.0234424,0.0104524,0.0432023,0.0432023,0.0592658,1.88526e-10,1.88507e-10,2.04457e-09,1.87932e-06,1.87934e-06,5e-08,0,0,0,0,0,0,0,0 +20280000,0.982886,-0.00693737,-0.0107,0.18377,-0.00576786,-0.00341501,0.0219159,0.00580265,-0.00122233,0.0454387,-1.50175e-05,-5.91161e-05,-3.1943e-06,1.44802e-05,8.53286e-05,-0.00130927,0.204984,0.000821313,0.434268,0,0,0,0,0,6.33046e-06,7.1512e-05,7.14974e-05,0.000181467,0.0255326,0.0255326,0.0106011,0.04841,0.04841,0.0603806,1.88613e-10,1.88597e-10,2.00998e-09,1.87933e-06,1.87935e-06,5.0002e-08,0,0,0,0,0,0,0,0 +20380000,0.982874,-0.00686453,-0.0107079,0.183837,-0.00689488,-0.00276737,0.0203065,0.00666475,-0.00097655,0.0440947,-1.5017e-05,-5.90543e-05,-2.99093e-06,1.57285e-05,8.54184e-05,-0.00130733,0.204984,0.000821313,0.434268,0,0,0,0,0,6.30244e-06,6.95755e-05,6.95606e-05,0.000180374,0.0228639,0.022864,0.0104658,0.043026,0.043026,0.0599549,1.74234e-10,1.74213e-10,1.9649e-09,1.87456e-06,1.87459e-06,5.0002e-08,0,0,0,0,0,0,0,0 +20480000,0.982891,-0.00690787,-0.01069,0.183746,-0.00970608,-0.00283574,0.0210217,0.00583482,-0.00122247,0.0424233,-1.50174e-05,-5.90543e-05,-2.99881e-06,1.57717e-05,8.54288e-05,-0.00130593,0.204984,0.000821313,0.434268,0,0,0,0,0,6.25882e-06,7.02197e-05,7.02054e-05,0.000179296,0.0248759,0.0248759,0.010522,0.0481619,0.0481619,0.0601667,1.74317e-10,1.743e-10,1.92095e-09,1.87457e-06,1.8746e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20580000,0.982931,-0.00688573,-0.0107068,0.183534,-0.00912257,-0.00432736,0.0209621,0.00668961,-0.00104401,0.0409779,-1.5003e-05,-5.89844e-05,-2.51193e-06,1.73071e-05,8.53342e-05,-0.00130422,0.204984,0.000821313,0.434268,0,0,0,0,0,6.2188e-06,6.84164e-05,6.8402e-05,0.000178212,0.0223046,0.0223046,0.0103865,0.0428471,0.0428471,0.0597307,1.61389e-10,1.61368e-10,1.87809e-09,1.87016e-06,1.87019e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20680000,0.982914,-0.00681569,-0.0107158,0.183626,-0.0106925,-0.00425693,0.0217249,0.00576501,-0.00143794,0.0414569,-1.50093e-05,-5.89789e-05,-2.8325e-06,1.73064e-05,8.53585e-05,-0.00130362,0.204984,0.000821313,0.434268,0,0,0,0,0,6.17971e-06,6.90215e-05,6.90069e-05,0.000177131,0.0242453,0.0242454,0.010441,0.0479124,0.0479124,0.0599312,1.61473e-10,1.61455e-10,1.83634e-09,1.87017e-06,1.8702e-06,5e-08,0,0,0,0,0,0,0,0 +20780000,0.982937,-0.00651106,-0.0106663,0.183519,-0.012854,-0.00209676,0.0142341,0.00481754,-0.00117313,0.0403121,-1.50191e-05,-5.89371e-05,-2.68484e-06,1.82575e-05,8.55875e-05,-0.00130215,0.204984,0.000821313,0.434268,0,0,0,0,0,6.13826e-06,6.73416e-05,6.7326e-05,0.000176053,0.0217874,0.0217875,0.0103069,0.0426665,0.0426665,0.0594915,1.49833e-10,1.49811e-10,1.79564e-09,1.86609e-06,1.86612e-06,5e-08,0,0,0,0,0,0,0,0 +20880000,0.982998,0.00189247,-0.00741009,0.183458,-0.01934,0.00868746,-0.0916963,0.00315432,-0.000842619,0.0356734,-1.50175e-05,-5.89385e-05,-2.60044e-06,1.83055e-05,8.55879e-05,-0.00130154,0.204984,0.000821313,0.434268,0,0,0,0,0,6.09309e-06,6.79045e-05,6.78801e-05,0.000175006,0.0239188,0.0239192,0.0103603,0.0476721,0.0476722,0.0596812,1.49918e-10,1.49897e-10,1.756e-09,1.8661e-06,1.86613e-06,5e-08,0,0,0,0,0,0,0,0 +20980000,0.983006,0.006181,-0.00336409,0.18344,-0.029178,0.0265403,-0.235065,0.00236378,-8.8403e-05,0.023798,-1.49382e-05,-5.88741e-05,-2.51447e-06,1.95984e-05,8.38613e-05,-0.00130466,0.204984,0.000821313,0.434268,0,0,0,0,0,6.10425e-06,6.62556e-05,6.62409e-05,0.000175343,0.0218125,0.021813,0.0103181,0.0425032,0.0425033,0.0601352,1.39312e-10,1.39287e-10,1.72695e-09,1.86181e-06,1.86184e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21080000,0.982925,0.00504014,-0.00346662,0.183906,-0.0428434,0.0421696,-0.35224,-0.00123086,0.00339551,-0.0052931,-1.49413e-05,-5.88709e-05,-2.68249e-06,1.96465e-05,8.38393e-05,-0.00130476,0.204984,0.000821313,0.434268,0,0,0,0,0,6.09215e-06,6.6792e-05,6.6776e-05,0.000174219,0.0239389,0.0239396,0.0103708,0.0474954,0.0474955,0.0603144,1.39399e-10,1.39373e-10,1.68903e-09,1.86182e-06,1.86185e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21180000,0.982882,0.00216112,-0.00503066,0.184155,-0.0468917,0.0481836,-0.476838,-0.00108877,0.00292122,-0.0383288,-1.46525e-05,-5.87524e-05,-2.53563e-06,2.24863e-05,7.65284e-05,-0.00131244,0.204984,0.000821313,0.434268,0,0,0,0,0,6.07404e-06,6.51147e-05,6.50966e-05,0.000173105,0.0217738,0.0217743,0.01024,0.0423749,0.042375,0.0598629,1.29616e-10,1.29592e-10,1.65212e-09,1.85666e-06,1.85669e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21280000,0.982826,-0.000129134,-0.00646105,0.184423,-0.0478334,0.0523191,-0.60691,-0.00586264,0.00797717,-0.0932945,-1.46577e-05,-5.87474e-05,-2.80274e-06,2.25574e-05,7.65503e-05,-0.00131218,0.204984,0.000821313,0.434268,0,0,0,0,0,6.04763e-06,6.56204e-05,6.56011e-05,0.000172001,0.0238905,0.023891,0.0102924,0.0473494,0.0473496,0.0600326,1.29702e-10,1.29679e-10,1.61612e-09,1.85667e-06,1.8567e-06,5e-08,0,0,0,0,0,0,0,0 +21380000,0.982785,-0.001726,-0.00722022,0.184606,-0.0436862,0.0497088,-0.731466,-0.00488683,0.0105287,-0.154217,-1.45124e-05,-5.86042e-05,-2.84889e-06,2.62451e-05,7.24373e-05,-0.00131808,0.204984,0.000821313,0.434268,0,0,0,0,0,6.0215e-06,6.39087e-05,6.38911e-05,0.000170903,0.0217059,0.0217064,0.0101634,0.0422695,0.0422697,0.059575,1.20713e-10,1.20694e-10,1.58105e-09,1.85065e-06,1.85068e-06,5e-08,0,0,0,0,0,0,0,0 +21480000,0.982755,-0.00260779,-0.00769305,0.184734,-0.0397341,0.047344,-0.865918,-0.00912889,0.0154108,-0.237726,-1.45085e-05,-5.86079e-05,-2.64586e-06,2.62563e-05,7.24464e-05,-0.00131672,0.204984,0.000821313,0.434268,0,0,0,0,0,5.99817e-06,6.43794e-05,6.43625e-05,0.000169813,0.023787,0.0237875,0.010217,0.0472248,0.047225,0.0597416,1.20799e-10,1.20782e-10,1.54691e-09,1.85066e-06,1.85069e-06,5e-08,0,0,0,0,0,0,0,0 +21580000,0.982759,-0.0030658,-0.00775347,0.184705,-0.0313405,0.0422408,-0.989809,-0.00780848,0.0160678,-0.322324,-1.44038e-05,-5.85492e-05,-2.41541e-06,2.76341e-05,6.9822e-05,-0.00132428,0.204984,0.000821313,0.434268,0,0,0,0,0,6.01133e-06,6.26445e-05,6.26297e-05,0.000170058,0.0215939,0.0215944,0.0101786,0.0421791,0.0421793,0.0601764,1.12565e-10,1.12552e-10,1.52186e-09,1.84382e-06,1.84383e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21680000,0.982752,-0.00341162,-0.00762117,0.184738,-0.0288129,0.0393981,-1.12177,-0.0108022,0.0202097,-0.432918,-1.43999e-05,-5.85529e-05,-2.21396e-06,2.76631e-05,6.98537e-05,-0.00132247,0.204984,0.000821313,0.434268,0,0,0,0,0,5.98071e-06,6.30826e-05,6.30694e-05,0.000168971,0.0236199,0.0236205,0.0102335,0.0471127,0.047113,0.06034,1.12653e-10,1.12641e-10,1.48923e-09,1.84383e-06,1.84384e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21780000,0.982773,-0.00381242,-0.00780358,0.18461,-0.0211013,0.032637,-1.25017,-0.00374999,0.0175643,-0.547496,-1.42482e-05,-5.83954e-05,-1.77756e-06,3.24571e-05,6.67933e-05,-0.00132823,0.204984,0.000821313,0.434268,0,0,0,0,0,5.94608e-06,6.13413e-05,6.13299e-05,0.000167892,0.021433,0.0214335,0.0101081,0.0420969,0.0420971,0.0598706,1.0513e-10,1.0512e-10,1.45742e-09,1.83625e-06,1.83625e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21880000,0.982757,-0.0040674,-0.00789103,0.184689,-0.0177361,0.0288583,-1.37574,-0.00571312,0.0206676,-0.685969,-1.42527e-05,-5.83912e-05,-2.00417e-06,3.25124e-05,6.68954e-05,-0.00132579,0.204984,0.000821313,0.434268,0,0,0,0,0,5.90765e-06,6.17502e-05,6.17394e-05,0.000166822,0.0233905,0.0233912,0.0101626,0.0470058,0.047006,0.0600215,1.05218e-10,1.0521e-10,1.42642e-09,1.83626e-06,1.83626e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21980000,0.982778,-0.00473525,-0.00818098,0.184551,-0.0135519,0.0224529,-1.3722,-0.000157425,0.0162906,-0.820982,-1.4178e-05,-5.83789e-05,-1.84846e-06,3.13763e-05,6.70991e-05,-0.00133027,0.204984,0.000821313,0.434268,0,0,0,0,0,5.86588e-06,6.00205e-05,6.00118e-05,0.000165762,0.020913,0.0209135,0.01004,0.0420106,0.0420108,0.0595547,9.83695e-11,9.83622e-11,1.39622e-09,1.82812e-06,1.8281e-06,5e-08,0,0,0,0,0,0,0,0 +22080000,0.982773,-0.00548802,-0.00894366,0.184517,-0.0120329,0.0186661,-1.34918,-0.00147668,0.0182636,-0.962732,-1.41723e-05,-5.83843e-05,-1.55046e-06,3.14085e-05,6.71858e-05,-0.00132806,0.204984,0.000821313,0.434268,0,0,0,0,0,5.83552e-06,6.04029e-05,6.0394e-05,0.000164695,0.0224476,0.022448,0.0100947,0.0468484,0.0468487,0.0596993,9.84582e-11,9.84523e-11,1.36678e-09,1.82813e-06,1.82811e-06,5e-08,0,0,0,0,0,0,0,0 +22180000,0.982785,-0.00587894,-0.00929585,0.184428,-0.00446237,0.0121597,-1.36429,0.00623791,0.0125123,-1.10388,-1.40967e-05,-5.83348e-05,-1.3184e-06,3.18134e-05,6.78664e-05,-0.00132584,0.204984,0.000821313,0.434268,0,0,0,0,0,5.79925e-06,5.88423e-05,5.88343e-05,0.000163644,0.0201475,0.0201478,0.00997518,0.0418899,0.0418901,0.0592358,9.23602e-11,9.23538e-11,1.33811e-09,1.82118e-06,1.82114e-06,5e-08,0,0,0,0,0,0,0,0 +22280000,0.98278,-0.00663076,-0.00951833,0.184415,0.00193327,0.00716055,-1.36251,0.00614396,0.0135198,-1.24426,-1.40988e-05,-5.83328e-05,-1.42414e-06,3.18142e-05,6.79523e-05,-0.00132446,0.204984,0.000821313,0.434268,0,0,0,0,0,5.8027e-06,5.91982e-05,5.91921e-05,0.000163831,0.0216675,0.0216679,0.0101192,0.0466472,0.0466474,0.0602755,9.24525e-11,9.24465e-11,1.31711e-09,1.82119e-06,1.82114e-06,5.0002e-08,0,0,0,0,0,0,0,0 +22380000,0.983032,-0.00707765,-0.00965824,0.183044,0.00724794,-0.00245777,-1.36409,0.0133793,0.0037092,-1.39017,-1.39774e-05,-5.83775e-05,-1.51188e-06,2.88378e-05,6.64403e-05,-0.00132001,0.20395,0.000817194,0.434521,0,0,0,0,0,7.93155e-05,5.79543e-05,5.7851e-05,0.00230667,0.0192337,0.0192339,0.00999926,0.0417366,0.0417368,0.0597964,8.69934e-11,8.6984e-11,1.29649e-09,1.81511e-06,1.81504e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22480000,0.982722,-0.00725971,-0.010063,0.184672,0.0125795,-0.00940194,-1.36905,0.0143665,0.00311079,-1.53148,-1.39775e-05,-5.83775e-05,-1.51237e-06,2.88339e-05,6.65582e-05,-0.00131836,0.20395,0.000817194,0.434521,0,0,0,0,0,5.57198e-05,5.79618e-05,5.7874e-05,0.00161962,0.0192437,0.0192436,0.010056,0.0463101,0.0463103,0.0599409,8.70935e-11,8.7084e-11,1.29658e-09,1.81512e-06,1.81505e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22580000,0.982828,-0.00706782,-0.010667,0.184079,0.0210587,-0.0177222,-1.36886,0.0263147,-0.00607911,-1.67408,-1.38846e-05,-5.82836e-05,-1.50883e-06,3.21727e-05,6.08124e-05,-0.00131589,0.20395,0.000817194,0.434521,0,0,0,0,0,4.29905e-05,5.79241e-05,5.78338e-05,0.00124794,0.0170315,0.0170311,0.00993825,0.0414028,0.041403,0.0594662,8.25714e-11,8.25592e-11,1.29667e-09,1.8131e-06,1.81303e-06,5e-08,0,0,0,0,0,0,0,0 +22680000,0.982768,-0.00700937,-0.010896,0.184391,0.0235064,-0.0230085,-1.37202,0.0285766,-0.00814192,-1.81773,-1.38847e-05,-5.82836e-05,-1.51139e-06,3.21504e-05,6.10075e-05,-0.00131354,0.20395,0.000817194,0.434521,0,0,0,0,0,3.50162e-05,5.79627e-05,5.78845e-05,0.00101506,0.0186921,0.0186913,0.00999562,0.0455939,0.0455941,0.0596009,8.26714e-11,8.26592e-11,1.29674e-09,1.81311e-06,1.81303e-06,5e-08,0,0,0,0,0,0,0,0 +22780000,0.982705,-0.00684476,-0.0111805,0.184711,0.0290014,-0.0292897,-1.37596,0.0392778,-0.0184369,-1.9655,-1.38126e-05,-5.82671e-05,-1.51695e-06,4.12685e-05,4.60766e-05,-0.0013094,0.20395,0.000817194,0.434521,0,0,0,0,0,2.94631e-05,5.75092e-05,5.74359e-05,0.000855578,0.0183121,0.0183113,0.00988239,0.0408395,0.0408396,0.059137,7.91061e-11,7.90915e-11,1.29679e-09,1.80861e-06,1.80852e-06,5e-08,0,0,0,0,0,0,0,0 +22880000,0.982822,-0.00704768,-0.0115428,0.184062,0.032313,-0.0329435,-1.37641,0.0423526,-0.0215016,-2.10622,-1.38125e-05,-5.82673e-05,-1.50648e-06,4.1252e-05,4.61759e-05,-0.00130832,0.20395,0.000817194,0.434521,0,0,0,0,0,2.6279e-05,5.75636e-05,5.74943e-05,0.000765557,0.0214752,0.0214744,0.0100275,0.0448021,0.0448022,0.0601597,7.9206e-11,7.91915e-11,1.29683e-09,1.80862e-06,1.80852e-06,5.0002e-08,0,0,0,0,0,0,0,0 +22980000,0.982983,-0.00688177,-0.0118,0.183188,0.0360594,-0.0373191,-1.37984,0.0527817,-0.0323689,-2.25825,-1.37336e-05,-5.82545e-05,-1.48368e-06,5.71245e-05,2.33365e-05,-0.00130306,0.20395,0.000817194,0.434521,0,0,0,0,0,2.2972e-05,5.64052e-05,5.63378e-05,0.00067139,0.0221448,0.0221443,0.00991556,0.0402534,0.0402534,0.0596875,7.64232e-11,7.64066e-11,1.29683e-09,1.7927e-06,1.7926e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23080000,0.983026,-0.00686955,-0.0120901,0.182939,0.0397902,-0.0413837,-1.37826,0.0565508,-0.0363286,-2.40049,-1.37337e-05,-5.82546e-05,-1.48622e-06,5.71001e-05,2.34813e-05,-0.00130157,0.20395,0.000817194,0.434521,0,0,0,0,0,2.0387e-05,5.64524e-05,5.63885e-05,0.000597962,0.0265997,0.0265992,0.00997688,0.044199,0.044199,0.0598202,7.65232e-11,7.65066e-11,1.2968e-09,1.79271e-06,1.7926e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23180000,0.983009,-0.00669957,-0.0122152,0.183031,0.042067,-0.0401239,-1.38193,0.0680406,-0.046349,-2.54748,-1.36397e-05,-5.82048e-05,-1.5035e-06,7.47642e-05,1.26078e-06,-0.00129794,0.20395,0.000817194,0.434521,0,0,0,0,0,1.83242e-05,5.44605e-05,5.43993e-05,0.00053909,0.0274537,0.0274542,0.00986719,0.0398542,0.0398542,0.0593487,7.44168e-11,7.43986e-11,1.29673e-09,1.75984e-06,1.75973e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23280000,0.98305,-0.00717637,-0.0123268,0.182784,0.0453852,-0.0438451,-1.3775,0.0723884,-0.0505829,-2.69146,-1.36397e-05,-5.8205e-05,-1.4975e-06,7.47195e-05,1.47705e-06,-0.00129582,0.20395,0.000817194,0.434521,0,0,0,0,0,1.66555e-05,5.45002e-05,5.44476e-05,0.000490849,0.0329006,0.0329012,0.00993004,0.044003,0.044003,0.0594796,7.45167e-11,7.44986e-11,1.29662e-09,1.75985e-06,1.75974e-06,5e-08,0,0,0,0,0,0,0,0 +23380000,0.983001,-0.00698797,-0.0123806,0.183048,0.046214,-0.0415769,-1.37912,0.0828589,-0.0555787,-2.83188,-1.36008e-05,-5.8132e-05,-1.53484e-06,8.38854e-05,-3.3955e-05,-0.00129513,0.20395,0.000817194,0.434521,0,0,0,0,0,1.52606e-05,5.17583e-05,5.17094e-05,0.00045062,0.0330507,0.0330513,0.00982342,0.0397876,0.0397876,0.0590148,7.29908e-11,7.29715e-11,1.29647e-09,1.70913e-06,1.70901e-06,5e-08,0,0,0,0,0,0,0,0 +23480000,0.983044,-0.00708857,-0.0126441,0.182794,0.048544,-0.0421201,-1.38065,0.0875782,-0.0597931,-2.97558,-1.36007e-05,-5.81323e-05,-1.515e-06,8.38323e-05,-3.37513e-05,-0.00129309,0.20395,0.000817194,0.434521,0,0,0,0,0,1.41019e-05,5.17948e-05,5.17479e-05,0.000416557,0.0391575,0.0391586,0.00988768,0.0443153,0.0443153,0.0591446,7.30907e-11,7.30714e-11,1.29627e-09,1.70914e-06,1.70901e-06,5e-08,0,0,0,0,0,0,0,0 +23580000,0.983062,-0.00727283,-0.0124761,0.182703,0.0450492,-0.0427765,-1.38057,0.0942285,-0.0694252,-3.11946,-1.35109e-05,-5.81089e-05,-1.50881e-06,0.000107784,-5.0421e-05,-0.00129151,0.20395,0.000817194,0.434521,0,0,0,0,0,1.33431e-05,4.85617e-05,4.85196e-05,0.000394387,0.0379126,0.0379138,0.00986789,0.0400901,0.04009,0.0595661,7.2034e-11,7.20139e-11,1.29611e-09,1.64428e-06,1.64415e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23680000,0.983061,-0.00787218,-0.0129059,0.182653,0.0423281,-0.0438118,-1.29848,0.0986378,-0.0738049,-3.25954,-1.35108e-05,-5.81092e-05,-1.49313e-06,0.000107745,-5.02625e-05,-0.00128989,0.20395,0.000817194,0.434521,0,0,0,0,0,1.24696e-05,4.85957e-05,4.85567e-05,0.00036819,0.0439683,0.0439694,0.00993324,0.0450868,0.0450868,0.0596937,7.21339e-11,7.21138e-11,1.29581e-09,1.64429e-06,1.64416e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23780000,0.983052,-0.00940799,-0.0153611,0.18244,0.0371718,-0.0366712,-0.99644,0.107867,-0.0777508,-3.38398,-1.34436e-05,-5.80478e-05,-1.46111e-06,0.000108889,-7.46738e-05,-0.00128629,0.20395,0.000817194,0.434521,0,0,0,0,0,1.17041e-05,4.52914e-05,4.52413e-05,0.000345321,0.0401427,0.0401434,0.00983013,0.0406768,0.0406768,0.0592349,7.14235e-11,7.14029e-11,1.29545e-09,1.57148e-06,1.57135e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23880000,0.982955,-0.012761,-0.0195212,0.182363,0.0290945,-0.0345706,-0.567245,0.111146,-0.0812904,-3.46533,-1.34438e-05,-5.80478e-05,-1.46712e-06,0.000108877,-7.45648e-05,-0.00128523,0.20395,0.000817194,0.434521,0,0,0,0,0,1.10226e-05,4.53608e-05,4.52928e-05,0.000325189,0.0448568,0.0448579,0.00989567,0.0460533,0.0460533,0.0593623,7.15234e-11,7.15028e-11,1.29503e-09,1.57149e-06,1.57135e-06,5e-08,0,0,0,0,0,0,0,0 +23980000,0.982875,-0.01508,-0.0222006,0.182309,0.0301053,-0.0306351,-0.178721,0.119781,-0.0834076,-3.53509,-1.34008e-05,-5.79993e-05,-1.46952e-06,0.000102912,-8.65544e-05,-0.00126319,0.20395,0.000817194,0.434521,0,0,0,0,0,1.04111e-05,4.25732e-05,4.24974e-05,0.000307373,0.0400247,0.0400263,0.00979373,0.0413706,0.0413706,0.0589055,7.10454e-11,7.10245e-11,1.29455e-09,1.49436e-06,1.49422e-06,5e-08,0,0,0,0,0,0,0,0 +24080000,0.982887,-0.0149273,-0.0215701,0.182334,0.0341815,-0.0370657,0.0809414,0.122995,-0.0867877,-3.54033,-1.34015e-05,-5.79989e-05,-1.50475e-06,0.000102955,-8.65144e-05,-0.0012624,0.20395,0.000817194,0.434521,0,0,0,0,0,9.85885e-06,4.25961e-05,4.25287e-05,0.000291548,0.0450039,0.0450062,0.00986193,0.0470254,0.0470255,0.0590384,7.11451e-11,7.11244e-11,1.29399e-09,1.49437e-06,1.49423e-06,5e-08,0,0,0,0,0,0,0,0 +24180000,0.982975,-0.0121842,-0.0180111,0.182446,0.0464485,-0.0417151,0.087179,0.131442,-0.0916419,-3.55463,-1.33724e-05,-5.79678e-05,-1.49016e-06,0.00010124,-8.70946e-05,-0.00124459,0.20395,0.000817194,0.434521,0,0,0,0,0,9.50143e-06,4.0237e-05,4.01886e-05,0.000280966,0.0406236,0.040626,0.00984596,0.0420748,0.0420749,0.0594597,7.08119e-11,7.0791e-11,1.29355e-09,1.41762e-06,1.41748e-06,5.0002e-08,0,0,0,0,0,0,0,0 +24280000,0.983063,-0.00967086,-0.0144269,0.182444,0.0482119,-0.0439386,0.057216,0.136209,-0.0959929,-3.55258,-1.33726e-05,-5.79679e-05,-1.49086e-06,0.000101243,-8.69621e-05,-0.00124299,0.20395,0.000817194,0.434521,0,0,0,0,0,9.05207e-06,4.02468e-05,4.02176e-05,0.00026788,0.0460906,0.0460934,0.00991695,0.0480389,0.0480391,0.0595974,7.09117e-11,7.08908e-11,1.29286e-09,1.41763e-06,1.41749e-06,5.0002e-08,0,0,0,0,0,0,0,0 +24380000,0.983136,-0.008595,-0.0132761,0.182191,0.0438506,-0.0360389,0.0736649,0.14408,-0.0964331,-3.54867,-1.33475e-05,-5.7959e-05,-1.43837e-06,9.21098e-05,-9.95679e-05,-0.001242,0.20395,0.000817194,0.434521,0,0,0,0,0,8.64453e-06,3.81582e-05,3.8134e-05,0.000256024,0.0407992,0.0408014,0.00981828,0.0427696,0.0427697,0.059142,7.066e-11,7.06391e-11,1.29208e-09,1.34822e-06,1.34808e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24480000,0.983166,-0.0087349,-0.013263,0.182024,0.0369301,-0.0304455,0.0737425,0.14809,-0.0997791,-3.54084,-1.33462e-05,-5.796e-05,-1.36932e-06,9.20748e-05,-9.9606e-05,-0.00124211,0.20395,0.000817194,0.434521,0,0,0,0,0,8.289e-06,3.82037e-05,3.81818e-05,0.000245236,0.0457644,0.0457669,0.00988909,0.0489641,0.0489644,0.0592752,7.07596e-11,7.07388e-11,1.29122e-09,1.34823e-06,1.34808e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24580000,0.983119,-0.00938731,-0.0134438,0.182229,0.0356079,-0.0232612,0.0685677,0.153928,-0.0968163,-3.53515,-1.33432e-05,-5.79805e-05,-1.38035e-06,7.80766e-05,-0.000110036,-0.00124086,0.20395,0.000817194,0.434521,0,0,0,0,0,7.97345e-06,3.6432e-05,3.64137e-05,0.000235394,0.040022,0.0400239,0.00979233,0.0433968,0.0433971,0.0588276,7.05522e-11,7.05314e-11,1.29028e-09,1.28786e-06,1.28772e-06,5e-08,0,0,0,0,0,0,0,0 +24680000,0.983092,-0.00992888,-0.0133265,0.182355,0.0311759,-0.0204878,0.0681627,0.157314,-0.0989632,-3.52835,-1.33435e-05,-5.79803e-05,-1.39371e-06,7.8095e-05,-0.000110041,-0.00124081,0.20395,0.000817194,0.434521,0,0,0,0,0,7.67858e-06,3.64859e-05,3.64711e-05,0.000226404,0.0445226,0.0445248,0.009864,0.0497271,0.0497275,0.058962,7.06518e-11,7.06312e-11,1.28924e-09,1.28787e-06,1.28772e-06,5e-08,0,0,0,0,0,0,0,0 +24780000,0.983106,-0.010074,-0.0126606,0.182319,0.0297372,-0.0173851,0.0613636,0.161236,-0.095964,-3.52578,-1.33516e-05,-5.79858e-05,-1.39019e-06,7.23362e-05,-0.000115902,-0.00123983,0.20395,0.000817194,0.434521,0,0,0,0,0,7.39718e-06,3.50135e-05,3.50034e-05,0.000218173,0.0386,0.0386016,0.00976885,0.0439128,0.0439131,0.0585219,7.047e-11,7.04494e-11,1.2881e-09,1.23694e-06,1.2368e-06,5e-08,0,0,0,0,0,0,0,0 +24880000,0.983101,-0.00993703,-0.012166,0.182388,0.025277,-0.0184485,0.0510407,0.163985,-0.0977567,-3.52215,-1.33514e-05,-5.7986e-05,-1.37681e-06,7.23393e-05,-0.000115862,-0.00123913,0.20395,0.000817194,0.434521,0,0,0,0,0,7.2189e-06,3.5076e-05,3.50677e-05,0.000212654,0.0426541,0.0426559,0.00992543,0.0502929,0.0502933,0.0595361,7.05696e-11,7.05491e-11,1.28721e-09,1.23695e-06,1.23681e-06,5.0002e-08,0,0,0,0,0,0,0,0 +24980000,0.983081,-0.00966064,-0.011935,0.182527,0.0197959,-0.0108505,0.0431002,0.166262,-0.0899889,-3.51994,-1.33667e-05,-5.80122e-05,-1.37723e-06,6.2392e-05,-0.000126061,-0.00123839,0.20395,0.000817194,0.434521,0,0,0,0,0,6.98828e-06,3.38806e-05,3.38722e-05,0.000205527,0.0367965,0.036798,0.00982892,0.0442992,0.0442994,0.0590848,7.04062e-11,7.03857e-11,1.28589e-09,1.19487e-06,1.19474e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25080000,0.983066,-0.00996944,-0.0119981,0.182585,0.0142991,-0.00826801,0.0393271,0.167906,-0.0909923,-3.52169,-1.33672e-05,-5.80118e-05,-1.39952e-06,6.24854e-05,-0.000125994,-0.00123636,0.20395,0.000817194,0.434521,0,0,0,0,0,6.76693e-06,3.39552e-05,3.39475e-05,0.000198954,0.0403945,0.0403962,0.00990374,0.0506578,0.0506582,0.0592316,7.05057e-11,7.04853e-11,1.28448e-09,1.19488e-06,1.19475e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25180000,0.983011,-0.0101848,-0.0119124,0.182877,0.0138733,-0.00319644,0.0391655,0.171208,-0.0854418,-3.51942,-1.34092e-05,-5.80454e-05,-1.44954e-06,5.16572e-05,-0.000125713,-0.00123489,0.20395,0.000817194,0.434521,0,0,0,0,0,6.57444e-06,3.29997e-05,3.29931e-05,0.000192857,0.0347598,0.0347612,0.0098084,0.0445534,0.0445537,0.0587876,7.03595e-11,7.03392e-11,1.28295e-09,1.16049e-06,1.16037e-06,5e-08,0,0,0,0,0,0,0,0 +25280000,0.982958,-0.0103662,-0.0112511,0.183196,0.00629389,-0.00194907,0.0340609,0.172184,-0.0857187,-3.51686,-1.34109e-05,-5.80438e-05,-1.54607e-06,5.17576e-05,-0.000125742,-0.00123455,0.20395,0.000817194,0.434521,0,0,0,0,0,6.39229e-06,3.30813e-05,3.30784e-05,0.000187212,0.037959,0.0379608,0.00988281,0.050834,0.0508343,0.0589304,7.0459e-11,7.04387e-11,1.28131e-09,1.1605e-06,1.16038e-06,5e-08,0,0,0,0,0,0,0,0 +25380000,0.982952,-0.0105142,-0.0110558,0.183226,0.000346606,0.00443619,0.03165,0.170425,-0.0766542,-3.5177,-1.34332e-05,-5.80754e-05,-1.55057e-06,4.56345e-05,-0.00013262,-0.00123237,0.20395,0.000817194,0.434521,0,0,0,0,0,6.21561e-06,3.23265e-05,3.23248e-05,0.000181974,0.032663,0.0326646,0.00978946,0.0446829,0.0446831,0.0584988,7.03316e-11,7.03114e-11,1.27956e-09,1.13258e-06,1.13246e-06,5e-08,0,0,0,0,0,0,0,0 +25480000,0.982957,-0.0105654,-0.0107606,0.183216,-0.00617215,0.00652492,0.0311679,0.170118,-0.0761443,-3.5155,-1.34331e-05,-5.80755e-05,-1.54316e-06,4.5645e-05,-0.000132612,-0.00123204,0.20395,0.000817194,0.434521,0,0,0,0,0,6.10008e-06,3.24199e-05,3.24195e-05,0.000178557,0.0354961,0.0354981,0.00994748,0.0508452,0.0508455,0.0595157,7.04311e-11,7.0411e-11,1.27819e-09,1.13259e-06,1.13247e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25580000,0.982918,-0.0107916,-0.0106387,0.183421,-0.00913032,0.00720163,0.0331637,0.169034,-0.0723062,-3.51559,-1.34935e-05,-5.80982e-05,-1.64579e-06,4.14169e-05,-0.000127246,-0.00123056,0.20395,0.000817194,0.434521,0,0,0,0,0,5.9458e-06,3.18306e-05,3.18309e-05,0.000173941,0.0305799,0.0305816,0.0098532,0.0447005,0.0447007,0.0590781,7.03248e-11,7.03047e-11,1.27623e-09,1.10998e-06,1.10987e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25680000,0.982925,-0.0103074,-0.0103639,0.183425,-0.0107086,0.00876696,0.0220309,0.168052,-0.0715644,-3.5148,-1.34933e-05,-5.80983e-05,-1.63826e-06,4.1453e-05,-0.000127243,-0.00122984,0.20395,0.000817194,0.434521,0,0,0,0,0,5.80073e-06,3.19341e-05,3.19333e-05,0.000169643,0.0331107,0.0331123,0.00992895,0.0507164,0.0507167,0.0592281,7.04241e-11,7.0404e-11,1.27415e-09,1.10999e-06,1.10988e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25780000,0.982935,-0.0100604,-0.00964346,0.183426,-0.0188327,0.0147335,0.019623,0.163415,-0.0657213,-3.5177,-1.3533e-05,-5.81295e-05,-1.64688e-06,3.84723e-05,-0.000126668,-0.00122765,0.20395,0.000817194,0.434521,0,0,0,0,0,5.663e-06,3.14754e-05,3.1476e-05,0.00016563,0.0285937,0.0285953,0.00983462,0.044621,0.0446212,0.0587918,7.03409e-11,7.03208e-11,1.27194e-09,1.09174e-06,1.09163e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25880000,0.982891,-0.0101198,-0.00964063,0.183655,-0.0268396,0.0187132,0.0224001,0.161094,-0.0640538,-3.51658,-1.35355e-05,-5.8127e-05,-1.79077e-06,3.85781e-05,-0.000126711,-0.00122729,0.20395,0.000817194,0.434521,0,0,0,0,0,5.53764e-06,3.15891e-05,3.15895e-05,0.000161876,0.0308342,0.0308361,0.00991055,0.0504726,0.0504728,0.0589431,7.04402e-11,7.04201e-11,1.26961e-09,1.09175e-06,1.09164e-06,5e-08,0,0,0,0,0,0,0,0 +25980000,0.982888,-0.010273,-0.00983277,0.183657,-0.0340205,0.0215753,0.0162335,0.151324,-0.059108,-3.51682,-1.35761e-05,-5.8131e-05,-1.8293e-06,4.21741e-05,-0.000125629,-0.00122597,0.20395,0.000817194,0.434521,0,0,0,0,0,5.41607e-06,3.12411e-05,3.12407e-05,0.000158365,0.0267115,0.0267131,0.00981672,0.0444591,0.0444593,0.058513,7.03812e-11,7.03611e-11,1.26714e-09,1.07699e-06,1.07689e-06,5e-08,0,0,0,0,0,0,0,0 +26080000,0.982917,-0.00997841,-0.00973171,0.183523,-0.0409129,0.0242317,0.0147295,0.147539,-0.0568346,-3.5173,-1.35748e-05,-5.81322e-05,-1.76182e-06,4.21878e-05,-0.000125625,-0.00122525,0.20395,0.000817194,0.434521,0,0,0,0,0,5.30234e-06,3.13639e-05,3.13625e-05,0.000155082,0.0287199,0.0287218,0.00989261,0.0501357,0.050136,0.0586656,7.04804e-11,7.04603e-11,1.26455e-09,1.077e-06,1.0769e-06,5e-08,0,0,0,0,0,0,0,0 +26180000,0.982909,-0.00997306,-0.0102446,0.183534,-0.0446504,0.0244495,0.0110663,0.140064,-0.0554244,-3.52035,-1.36341e-05,-5.81567e-05,-1.71853e-06,4.15325e-05,-0.000118202,-0.00122334,0.20395,0.000817194,0.434521,0,0,0,0,0,5.2389e-06,3.11024e-05,3.10985e-05,0.000153065,0.0249614,0.024963,0.00988205,0.0442284,0.0442286,0.0591075,7.04467e-11,7.04265e-11,1.26254e-09,1.06509e-06,1.06499e-06,5.0002e-08,0,0,0,0,0,0,0,0 +26280000,0.9829,-0.0100379,-0.0105653,0.183561,-0.0485111,0.0274028,0.0044301,0.135342,-0.0528397,-3.52177,-1.36353e-05,-5.81554e-05,-1.79047e-06,4.16162e-05,-0.000118252,-0.00122258,0.20395,0.000817194,0.434521,0,0,0,0,0,5.13708e-06,3.12352e-05,3.123e-05,0.000150138,0.0267715,0.0267731,0.00995793,0.0497248,0.049725,0.0592602,7.05458e-11,7.05256e-11,1.2597e-09,1.0651e-06,1.065e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26380000,0.982921,-0.00956215,-0.010569,0.183476,-0.0543674,0.0296735,0.0071183,0.123455,-0.0500435,-3.5218,-1.3681e-05,-5.81547e-05,-1.84031e-06,4.54486e-05,-0.000114071,-0.00122231,0.20395,0.000817194,0.434521,0,0,0,0,0,5.03665e-06,3.10407e-05,3.10334e-05,0.000147397,0.0233498,0.023351,0.00986421,0.0439412,0.0439414,0.0588348,7.05366e-11,7.05162e-11,1.25674e-09,1.0555e-06,1.0554e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26480000,0.982923,-0.00926552,-0.0104466,0.183488,-0.0585995,0.0336876,0.0168764,0.117799,-0.0468858,-3.52072,-1.36819e-05,-5.81538e-05,-1.8942e-06,4.54721e-05,-0.000114094,-0.00122227,0.20395,0.000817194,0.434521,0,0,0,0,0,4.94735e-06,3.11811e-05,3.11731e-05,0.000144822,0.0249721,0.0249732,0.00993981,0.0492556,0.0492559,0.0589883,7.06356e-11,7.06153e-11,1.25363e-09,1.05551e-06,1.05541e-06,5e-08,0,0,0,0,0,0,0,0 +26580000,0.982906,-0.00879988,-0.0107121,0.183586,-0.0584461,0.0366761,0.0179579,0.11044,-0.0449443,-3.52093,-1.37303e-05,-5.81698e-05,-1.96321e-06,4.44229e-05,-0.000107712,-0.00122049,0.20395,0.000817194,0.434521,0,0,0,0,0,4.86731e-06,3.10443e-05,3.10337e-05,0.000142397,0.0218677,0.0218682,0.00984551,0.0436081,0.0436083,0.0585632,7.06496e-11,7.0629e-11,1.25038e-09,1.04771e-06,1.04761e-06,5e-08,0,0,0,0,0,0,0,0 +26680000,0.982893,-0.00865356,-0.010442,0.183676,-0.0601843,0.0424836,0.0174431,0.104528,-0.0409677,-3.51938,-1.37325e-05,-5.81676e-05,-2.09009e-06,4.44686e-05,-0.000107765,-0.00122041,0.20395,0.000817194,0.434521,0,0,0,0,0,4.7889e-06,3.11925e-05,3.11824e-05,0.000140127,0.0233504,0.0233505,0.00992166,0.0487427,0.0487429,0.0587227,7.07486e-11,7.0728e-11,1.247e-09,1.04772e-06,1.04762e-06,5e-08,0,0,0,0,0,0,0,0 +26780000,0.982908,-0.00849414,-0.00991424,0.183632,-0.0640859,0.0416084,0.0157308,0.0943177,-0.0409536,-3.5212,-1.37765e-05,-5.81714e-05,-2.12051e-06,4.6484e-05,-0.000100737,-0.00121861,0.20395,0.000817194,0.434521,0,0,0,0,0,4.7432e-06,3.10979e-05,3.10891e-05,0.000138873,0.0205327,0.0205326,0.00990985,0.0432389,0.043239,0.0591651,7.07846e-11,7.07637e-11,1.24438e-09,1.04142e-06,1.04132e-06,5.0002e-08,0,0,0,0,0,0,0,0 +26880000,0.982914,-0.00789484,-0.00991796,0.183631,-0.0703665,0.0454357,0.0115911,0.0875663,-0.0366066,-3.52265,-1.37761e-05,-5.81717e-05,-2.10304e-06,4.65574e-05,-0.000100797,-0.00121759,0.20395,0.000817194,0.434521,0,0,0,0,0,4.67598e-06,3.12555e-05,3.12451e-05,0.00013684,0.0218919,0.0218918,0.00998679,0.048199,0.0481991,0.0593299,7.08835e-11,7.08625e-11,1.24075e-09,1.04143e-06,1.04133e-06,5.0002e-08,0,0,0,0,0,0,0,0 +26980000,0.982908,-0.00734975,-0.0103964,0.183658,-0.0761275,0.0477506,0.00859198,0.0770272,-0.0348427,-3.5257,-1.38032e-05,-5.81758e-05,-2.10378e-06,4.76358e-05,-9.60799e-05,-0.00121555,0.20395,0.000817194,0.434521,0,0,0,0,0,4.61373e-06,3.11996e-05,3.11862e-05,0.000134923,0.0193315,0.0193313,0.00989126,0.0428428,0.0428428,0.0589025,7.09383e-11,7.09171e-11,1.23696e-09,1.03636e-06,1.03625e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27080000,0.982902,-0.00715929,-0.010769,0.183673,-0.0781331,0.0559199,0.0135008,0.0692933,-0.0296654,-3.52905,-1.38036e-05,-5.81753e-05,-2.13177e-06,4.77607e-05,-9.62072e-05,-0.00121393,0.20395,0.000817194,0.434521,0,0,0,0,0,4.55365e-06,3.1366e-05,3.1351e-05,0.000133124,0.0205783,0.0205775,0.0099668,0.0476346,0.0476346,0.0590622,7.1037e-11,7.1016e-11,1.23303e-09,1.03637e-06,1.03626e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27180000,0.982904,-0.00717845,-0.0106505,0.183672,-0.0822893,0.0576956,0.0140067,0.0605971,-0.0277841,-3.53148,-1.38232e-05,-5.81775e-05,-2.15718e-06,4.79011e-05,-9.12895e-05,-0.0012123,0.20395,0.000817194,0.434521,0,0,0,0,0,4.49637e-06,3.13371e-05,3.13229e-05,0.000131433,0.0182472,0.0182462,0.00987148,0.042427,0.0424271,0.0586398,7.11074e-11,7.10866e-11,1.22895e-09,1.03228e-06,1.03216e-06,5e-08,0,0,0,0,0,0,0,0 +27280000,0.982911,-0.0072859,-0.0115267,0.183575,-0.0894885,0.0638948,0.102614,0.0520352,-0.0217644,-3.53018,-1.38231e-05,-5.81775e-05,-2.1583e-06,4.79811e-05,-9.13781e-05,-0.00121127,0.20395,0.000817194,0.434521,0,0,0,0,0,4.43973e-06,3.15125e-05,3.14956e-05,0.000129845,0.0193486,0.0193475,0.0099464,0.0470563,0.0470564,0.0587994,7.12059e-11,7.11855e-11,1.22473e-09,1.03228e-06,1.03217e-06,5e-08,0,0,0,0,0,0,0,0 +27380000,0.98287,-0.008538,-0.0138815,0.183579,-0.0913339,0.0668701,0.407065,0.0454238,-0.0180533,-3.51331,-1.38321e-05,-5.81839e-05,-2.15728e-06,4.54216e-05,-8.75462e-05,-0.00120671,0.20395,0.000817194,0.434521,0,0,0,0,0,4.39273e-06,3.1522e-05,3.14988e-05,0.000128338,0.0170585,0.0170575,0.00985056,0.0419906,0.0419907,0.0583817,7.12875e-11,7.12673e-11,1.22036e-09,1.02885e-06,1.02873e-06,5e-08,0,0,0,0,0,0,0,0 +27480000,0.982813,-0.0100562,-0.016006,0.183636,-0.0948503,0.072806,0.73534,0.0360469,-0.0110885,-3.45682,-1.38337e-05,-5.81826e-05,-2.24445e-06,4.54181e-05,-8.7587e-05,-0.00120611,0.20395,0.000817194,0.434521,0,0,0,0,0,4.37418e-06,3.17093e-05,3.16805e-05,0.000127669,0.017956,0.0179547,0.0100092,0.0464354,0.0464354,0.059416,7.13863e-11,7.13664e-11,1.21701e-09,1.02886e-06,1.02873e-06,5.0002e-08,0,0,0,0,0,0,0,0 +27580000,0.982819,-0.0101461,-0.0151846,0.183667,-0.0891871,0.0726697,0.857305,0.0299453,-0.0105917,-3.39726,-1.38416e-05,-5.81837e-05,-2.27806e-06,4.38588e-05,-8.10028e-05,-0.00119094,0.20395,0.000817194,0.434521,0,0,0,0,0,4.32859e-06,3.17689e-05,3.17452e-05,0.000126333,0.0160181,0.0160164,0.00991145,0.0415229,0.0415229,0.0589848,7.14726e-11,7.14531e-11,1.21238e-09,1.02506e-06,1.02493e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27680000,0.982883,-0.00908753,-0.0123237,0.183594,-0.0850448,0.0704102,0.771306,0.0212664,-0.00340027,-3.31836,-1.38407e-05,-5.81843e-05,-2.24155e-06,4.39822e-05,-8.11477e-05,-0.00118965,0.20395,0.000817194,0.434521,0,0,0,0,0,4.28225e-06,3.1948e-05,3.19336e-05,0.000125092,0.0170548,0.0170529,0.00998743,0.04581,0.0458099,0.059154,7.15711e-11,7.15516e-11,1.20762e-09,1.02507e-06,1.02493e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27780000,0.982909,-0.00767401,-0.0105353,0.183629,-0.08247,0.0639304,0.746824,0.0172105,-0.00422488,-3.24479,-1.38404e-05,-5.81835e-05,-2.18432e-06,4.14027e-05,-7.25135e-05,-0.00119027,0.20395,0.000817194,0.434521,0,0,0,0,0,4.24544e-06,3.20232e-05,3.20121e-05,0.000123913,0.0153491,0.0153476,0.00988976,0.0410553,0.0410552,0.0587272,7.1663e-11,7.16433e-11,1.2027e-09,1.02189e-06,1.02174e-06,5e-08,0,0,0,0,0,0,0,0 +27880000,0.982909,-0.00717788,-0.0106023,0.183645,-0.0882682,0.0698941,0.792438,0.00870263,0.00243894,-3.17049,-1.38401e-05,-5.81836e-05,-2.17972e-06,4.14944e-05,-7.26425e-05,-0.00118916,0.20395,0.000817194,0.434521,0,0,0,0,0,4.2101e-06,3.2219e-05,3.22067e-05,0.000122804,0.0162818,0.0162801,0.00996425,0.0452135,0.0452133,0.0588905,7.17613e-11,7.17418e-11,1.19764e-09,1.02189e-06,1.02174e-06,5e-08,0,0,0,0,0,0,0,0 +27980000,0.982895,-0.00757542,-0.0109318,0.183684,-0.0875877,0.0702099,0.779779,0.0053849,0.00132534,-3.09999,-1.38267e-05,-5.81758e-05,-2.16692e-06,3.89868e-05,-6.53318e-05,-0.00118429,0.20395,0.000817194,0.434521,0,0,0,0,0,4.17851e-06,3.23104e-05,3.22981e-05,0.000121757,0.0147131,0.0147114,0.00986797,0.0406014,0.0406013,0.0584733,7.18524e-11,7.18334e-11,1.19244e-09,1.01926e-06,1.01909e-06,5e-08,0,0,0,0,0,0,0,0 +28080000,0.982905,-0.00798292,-0.0109856,0.183611,-0.0911988,0.071441,0.784385,-0.00351077,0.00844189,-3.02326,-1.38249e-05,-5.81777e-05,-2.06427e-06,3.90111e-05,-6.53535e-05,-0.0011838,0.20395,0.000817194,0.434521,0,0,0,0,0,4.17006e-06,3.25131e-05,3.25013e-05,0.000121453,0.0156292,0.0156275,0.010026,0.0446374,0.0446371,0.0595082,7.19512e-11,7.19321e-11,1.18847e-09,1.01926e-06,1.01909e-06,5.0002e-08,0,0,0,0,0,0,0,0 +28180000,0.982916,-0.00746826,-0.0112536,0.183559,-0.0903427,0.0663252,0.790704,-0.00853455,0.00637191,-2.94755,-1.37995e-05,-5.81677e-05,-2.0157e-06,3.78714e-05,-5.88037e-05,-0.00118166,0.20395,0.000817194,0.434521,0,0,0,0,0,4.13911e-06,3.26106e-05,3.2597e-05,0.000120525,0.0141782,0.0141768,0.00992787,0.0401612,0.040161,0.0590826,7.20351e-11,7.20163e-11,1.18302e-09,1.01714e-06,1.01695e-06,5.0002e-08,0,0,0,0,0,0,0,0 +28280000,0.982931,-0.00694196,-0.0115146,0.183485,-0.0961221,0.0698047,0.791876,-0.0178017,0.0132051,-2.87168,-1.37969e-05,-5.81697e-05,-1.88703e-06,3.80216e-05,-5.89828e-05,-0.00118046,0.20395,0.000817194,0.434521,0,0,0,0,0,4.11171e-06,3.2821e-05,3.28058e-05,0.000119654,0.0150686,0.0150672,0.0100024,0.0440852,0.0440848,0.0592492,7.21331e-11,7.21148e-11,1.17744e-09,1.01714e-06,1.01695e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28380000,0.98292,-0.00692387,-0.0121283,0.183505,-0.0953646,0.0709795,0.792403,-0.0209261,0.0141875,-2.79898,-1.37596e-05,-5.8147e-05,-1.74781e-06,3.55045e-05,-5.45026e-05,-0.00117757,0.20395,0.000817194,0.434521,0,0,0,0,0,4.09083e-06,3.29218e-05,3.2905e-05,0.000118828,0.0137328,0.0137314,0.00990385,0.0397374,0.0397371,0.0588223,7.2202e-11,7.21846e-11,1.1717e-09,1.01544e-06,1.01523e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28480000,0.982909,-0.00723234,-0.0126576,0.183512,-0.096949,0.073631,0.793767,-0.0305417,0.0214105,-2.72444,-1.37593e-05,-5.81469e-05,-1.75102e-06,3.56427e-05,-5.47298e-05,-0.0011759,0.20395,0.000817194,0.434521,0,0,0,0,0,4.06704e-06,3.31393e-05,3.31215e-05,0.000118062,0.0146036,0.0146021,0.00997761,0.0435607,0.0435602,0.0589879,7.22999e-11,7.2283e-11,1.16584e-09,1.01544e-06,1.01524e-06,5e-08,0,0,0,0,0,0,0,0 +28580000,0.982936,-0.00729911,-0.0126679,0.183367,-0.0902922,0.068977,0.790736,-0.032546,0.0171539,-2.64893,-1.36983e-05,-5.8125e-05,-1.64732e-06,3.42074e-05,-4.86278e-05,-0.00117396,0.20395,0.000817194,0.434521,0,0,0,0,0,4.04066e-06,3.32377e-05,3.32205e-05,0.000117346,0.0133689,0.0133674,0.00987911,0.0393335,0.0393331,0.0585649,7.23459e-11,7.23301e-11,1.15983e-09,1.0141e-06,1.01388e-06,5e-08,0,0,0,0,0,0,0,0 +28680000,0.982934,-0.00713314,-0.012072,0.183422,-0.0902646,0.0701414,0.792179,-0.0415376,0.0241313,-2.57383,-1.36984e-05,-5.81246e-05,-1.66918e-06,3.43223e-05,-4.88348e-05,-0.00117248,0.20395,0.000817194,0.434521,0,0,0,0,0,4.02057e-06,3.34589e-05,3.34439e-05,0.000116675,0.0142275,0.0142259,0.00995221,0.0430667,0.0430662,0.0587294,7.24437e-11,7.24284e-11,1.15371e-09,1.0141e-06,1.01388e-06,5e-08,0,0,0,0,0,0,0,0 +28780000,0.982946,-0.00649669,-0.0118548,0.183396,-0.0847322,0.069205,0.79076,-0.0429135,0.0244162,-2.50031,-1.36428e-05,-5.80868e-05,-1.53974e-06,3.27235e-05,-4.59053e-05,-0.00116926,0.20395,0.000817194,0.434521,0,0,0,0,0,4.02381e-06,3.35527e-05,3.35378e-05,0.000116668,0.0130777,0.0130762,0.0099376,0.0389519,0.0389515,0.0591782,7.24585e-11,7.24443e-11,1.14904e-09,1.01307e-06,1.01283e-06,5.0002e-08,0,0,0,0,0,0,0,0 +28880000,0.982972,-0.00628383,-0.0115603,0.183282,-0.0883682,0.0710037,0.789769,-0.0515576,0.0314086,-2.42568,-1.36401e-05,-5.80888e-05,-1.41558e-06,3.28959e-05,-4.61514e-05,-0.00116769,0.20395,0.000817194,0.434521,0,0,0,0,0,4.00305e-06,3.37811e-05,3.37672e-05,0.000116076,0.0139317,0.0139302,0.0100104,0.042606,0.0426054,0.0593409,7.25562e-11,7.25425e-11,1.14268e-09,1.01307e-06,1.01283e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28980000,0.982954,-0.00603143,-0.0117828,0.183373,-0.0840169,0.066356,0.789152,-0.0500035,0.0290828,-2.35437,-1.35599e-05,-5.80458e-05,-1.36139e-06,3.12621e-05,-4.30161e-05,-0.00116381,0.20395,0.000817194,0.434521,0,0,0,0,0,3.9909e-06,3.38681e-05,3.38535e-05,0.000115514,0.0128557,0.0128545,0.00991159,0.0385955,0.038595,0.0589185,7.25297e-11,7.25173e-11,1.13619e-09,1.01229e-06,1.01203e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29080000,0.982955,-0.00590151,-0.0118061,0.183375,-0.087543,0.0682586,0.789503,-0.0586281,0.0357677,-2.27756,-1.35593e-05,-5.80461e-05,-1.34131e-06,3.13307e-05,-4.31293e-05,-0.00116306,0.20395,0.000817194,0.434521,0,0,0,0,0,3.97518e-06,3.41032e-05,3.40888e-05,0.000114994,0.0137084,0.0137073,0.00998382,0.0421811,0.0421805,0.0590798,7.26273e-11,7.26154e-11,1.12959e-09,1.0123e-06,1.01203e-06,5e-08,0,0,0,0,0,0,0,0 +29180000,0.982984,-0.00582751,-0.0120607,0.1832,-0.0827568,0.0657719,0.784062,-0.0554361,0.0337814,-2.20902,-1.3468e-05,-5.79861e-05,-1.17691e-06,2.99743e-05,-4.10272e-05,-0.00115805,0.20395,0.000817194,0.434521,0,0,0,0,0,3.95659e-06,3.41794e-05,3.41646e-05,0.000114511,0.0126995,0.0126985,0.00988459,0.0382668,0.0382663,0.0586558,7.25509e-11,7.25404e-11,1.12285e-09,1.01171e-06,1.01144e-06,5e-08,0,0,0,0,0,0,0,0 +29280000,0.982968,-0.00601535,-0.0120886,0.183278,-0.0839678,0.0713928,0.785428,-0.0637344,0.0406223,-2.13206,-1.34664e-05,-5.79874e-05,-1.10259e-06,3.00403e-05,-4.11149e-05,-0.00115752,0.20395,0.000817194,0.434521,0,0,0,0,0,3.94791e-06,3.44201e-05,3.44059e-05,0.000114054,0.0135556,0.0135543,0.00995726,0.0417947,0.0417941,0.0588211,7.26483e-11,7.26384e-11,1.11601e-09,1.01172e-06,1.01144e-06,5e-08,0,0,0,0,0,0,0,0 +29380000,0.982968,-0.00644893,-0.0115715,0.183299,-0.0790058,0.0690679,0.787918,-0.0612688,0.0404299,-2.05721,-1.33781e-05,-5.79318e-05,-1.04588e-06,2.8936e-05,-3.97276e-05,-0.00115545,0.20395,0.000817194,0.434521,0,0,0,0,0,3.95723e-06,3.44801e-05,3.44689e-05,0.000114225,0.0125967,0.0125956,0.00994134,0.0379679,0.0379675,0.059266,7.25133e-11,7.25048e-11,1.11081e-09,1.0113e-06,1.01101e-06,5.0002e-08,0,0,0,0,0,0,0,0 +29480000,0.982981,-0.00654055,-0.0114467,0.183233,-0.081779,0.0697931,0.789422,-0.0692667,0.0473827,-1.97949,-1.33737e-05,-5.79357e-05,-8.17292e-07,2.90424e-05,-3.98154e-05,-0.00115504,0.20395,0.000817194,0.434521,0,0,0,0,0,3.94777e-06,3.47258e-05,3.47155e-05,0.000113826,0.0134597,0.0134587,0.0100145,0.0414483,0.0414477,0.0594349,7.26107e-11,7.26027e-11,1.10377e-09,1.0113e-06,1.01101e-06,5.0002e-08,0,0,0,0,0,0,0,0 +29580000,0.982997,-0.00642846,-0.0114171,0.183154,-0.0771358,0.0660796,0.791649,-0.0660511,0.0454583,-1.90217,-1.3262e-05,-5.7879e-05,-6.26124e-07,2.82726e-05,-3.87094e-05,-0.00115437,0.20395,0.000817194,0.434521,0,0,0,0,0,3.93755e-06,3.47702e-05,3.47603e-05,0.000113453,0.0125467,0.0125459,0.00991427,0.0377007,0.0377002,0.0590056,7.24071e-11,7.24008e-11,1.09661e-09,1.01099e-06,1.01069e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29680000,0.983022,-0.00651555,-0.011237,0.183026,-0.080567,0.0657623,0.786281,-0.0738682,0.0521104,-1.82741,-1.3258e-05,-5.78823e-05,-4.34441e-07,2.84529e-05,-3.89511e-05,-0.00115289,0.20395,0.000817194,0.434521,0,0,0,0,0,3.92595e-06,3.50206e-05,3.50117e-05,0.000113109,0.013425,0.0134244,0.00998606,0.0411436,0.0411431,0.0591675,7.25044e-11,7.24986e-11,1.08935e-09,1.011e-06,1.01069e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29780000,0.983034,-0.00640247,-0.0116642,0.182942,-0.0757413,0.0577057,0.783301,-0.0685286,0.0484277,-1.75526,-1.31393e-05,-5.78107e-05,-2.14293e-07,2.81376e-05,-3.83774e-05,-0.00114971,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91792e-06,3.50453e-05,3.50354e-05,0.000112785,0.01255,0.0125498,0.00988622,0.0374667,0.0374662,0.0587421,7.2224e-11,7.22198e-11,1.08198e-09,1.01077e-06,1.01044e-06,5e-08,0,0,0,0,0,0,0,0 +29880000,0.983035,-0.00591166,-0.0121139,0.18292,-0.076997,0.0579147,0.778959,-0.0760944,0.0542044,-1.6833,-1.31353e-05,-5.78137e-05,-3.33576e-08,2.83681e-05,-3.87165e-05,-0.00114754,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91229e-06,3.53017e-05,3.52899e-05,0.000112482,0.0134409,0.0134407,0.0099575,0.0408824,0.0408819,0.0589024,7.23213e-11,7.23175e-11,1.07452e-09,1.01077e-06,1.01045e-06,5e-08,0,0,0,0,0,0,0,0 +29980000,0.983035,-0.00590672,-0.0121185,0.182924,-0.0715264,0.0526868,0.776201,-0.0711204,0.0488393,-1.61353,-1.29968e-05,-5.7752e-05,3.34774e-08,2.83384e-05,-3.90496e-05,-0.00114349,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90533e-06,3.53014e-05,3.529e-05,0.000112201,0.0125924,0.0125924,0.00985827,0.0372671,0.0372667,0.0584808,7.19562e-11,7.19539e-11,1.06696e-09,1.01058e-06,1.01024e-06,5e-08,0,0,0,0,0,0,0,0 +30080000,0.98303,-0.00606818,-0.0122933,0.182934,-0.0710965,0.0543109,0.775392,-0.0782452,0.0541976,-1.53861,-1.2999e-05,-5.77497e-05,-9.48819e-08,2.83839e-05,-3.91759e-05,-0.00114252,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91522e-06,3.55609e-05,3.55495e-05,0.000112525,0.0134966,0.0134966,0.0100143,0.0406645,0.0406641,0.0595175,7.20541e-11,7.20521e-11,1.06126e-09,1.01059e-06,1.01025e-06,5.0002e-08,0,0,0,0,0,0,0,0 +30180000,0.982995,-0.00605991,-0.0122653,0.183123,-0.0643267,0.0498644,0.774863,-0.0712179,0.051579,-1.46785,-1.29077e-05,-5.7656e-05,-2.96414e-07,2.85965e-05,-3.92663e-05,-0.00113943,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91103e-06,3.5534e-05,3.55233e-05,0.000112277,0.012666,0.0126661,0.00991281,0.0371022,0.0371018,0.0590816,7.15982e-11,7.15977e-11,1.05352e-09,1.01041e-06,1.01006e-06,5.0001e-08,0,0,0,0,0,0,0,0 +30280000,0.982984,-0.00606984,-0.012273,0.18318,-0.0628697,0.0506178,0.774472,-0.0775598,0.0566273,-1.39545,-1.29063e-05,-5.76568e-05,-2.47551e-07,2.87562e-05,-3.9523e-05,-0.00113763,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90784e-06,3.57962e-05,3.57858e-05,0.000112049,0.0135858,0.0135859,0.0099852,0.0404897,0.0404893,0.059249,7.16953e-11,7.16952e-11,1.04574e-09,1.01041e-06,1.01006e-06,5.0001e-08,0,0,0,0,0,0,0,0 +30380000,0.982972,-0.00605438,-0.012181,0.183252,-0.0553596,0.0446414,0.771996,-0.0689704,0.0528743,-1.32749,-1.27803e-05,-5.75516e-05,3.65209e-08,2.99123e-05,-4.05737e-05,-0.00113322,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91077e-06,3.57409e-05,3.57312e-05,0.000111828,0.0127681,0.0127683,0.0098843,0.0369714,0.0369711,0.058817,7.11438e-11,7.11451e-11,1.03784e-09,1.01022e-06,1.00986e-06,5e-08,0,0,0,0,0,0,0,0 +30480000,0.982998,-0.00606729,-0.0122598,0.183109,-0.0584759,0.0456006,0.773158,-0.074626,0.0574225,-1.25576,-1.27762e-05,-5.75549e-05,2.26866e-07,3.01202e-05,-4.08594e-05,-0.00113124,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90324e-06,3.60058e-05,3.59963e-05,0.000111634,0.0137036,0.013704,0.00995553,0.0403566,0.0403564,0.0589773,7.12408e-11,7.12425e-11,1.02989e-09,1.01022e-06,1.00986e-06,5e-08,0,0,0,0,0,0,0,0 +30580000,0.983019,-0.00632258,-0.0125628,0.182963,-0.0529889,0.0414741,0.772742,-0.0671349,0.0527927,-1.18396,-1.26431e-05,-5.7465e-05,4.47e-07,3.1214e-05,-4.2228e-05,-0.0011285,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89683e-06,3.5921e-05,3.59114e-05,0.000111451,0.0128906,0.012891,0.00985626,0.0368739,0.0368737,0.0585546,7.05905e-11,7.05935e-11,1.02185e-09,1.00999e-06,1.00962e-06,5e-08,0,0,0,0,0,0,0,0 +30680000,0.98303,-0.00669573,-0.0127865,0.182877,-0.0520233,0.0395764,0.771976,-0.0724547,0.0568629,-1.11246,-1.26425e-05,-5.74651e-05,4.54797e-07,3.1382e-05,-4.24956e-05,-0.00112645,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90858e-06,3.61882e-05,3.61789e-05,0.000111856,0.0138458,0.0138463,0.0100114,0.0402638,0.0402636,0.0595881,7.06883e-11,7.06915e-11,1.01581e-09,1.00999e-06,1.00962e-06,5.0002e-08,0,0,0,0,0,0,0,0 +30780000,0.983057,-0.00648215,-0.0125498,0.182754,-0.0432204,0.0330819,0.77118,-0.064838,0.0548203,-1.04151,-1.25832e-05,-5.73749e-05,5.88595e-07,3.25501e-05,-4.26559e-05,-0.00112346,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90109e-06,3.60703e-05,3.60618e-05,0.0001117,0.0130319,0.0130324,0.00991078,0.0368082,0.0368081,0.0591568,6.99376e-11,6.99419e-11,1.00766e-09,1.0097e-06,1.00932e-06,5.0002e-08,0,0,0,0,0,0,0,0 +30880000,0.98305,-0.00580092,-0.0123659,0.182831,-0.0427138,0.0310829,0.768587,-0.0690842,0.0580715,-0.970647,-1.25851e-05,-5.73726e-05,4.69071e-07,3.26923e-05,-4.29099e-05,-0.00112133,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89694e-06,3.63382e-05,3.63293e-05,0.000111551,0.0140069,0.0140075,0.00998221,0.0402091,0.0402091,0.0593187,7.00345e-11,7.00391e-11,9.9945e-10,1.00971e-06,1.00933e-06,5.0001e-08,0,0,0,0,0,0,0,0 +30980000,0.983042,-0.00595071,-0.0122483,0.182874,-0.0348027,0.025149,0.770825,-0.0588207,0.0505817,-0.901474,-1.24395e-05,-5.72782e-05,4.86282e-07,3.4053e-05,-4.50163e-05,-0.00111798,0.20395,0.000817194,0.434521,0,0,0,0,0,3.8948e-06,3.61872e-05,3.61792e-05,0.000111408,0.0131826,0.0131832,0.00988142,0.0367725,0.0367725,0.058886,6.91835e-11,6.91888e-11,9.91171e-10,1.00934e-06,1.00896e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31080000,0.983003,-0.00606887,-0.0124023,0.183069,-0.0333855,0.0218688,0.769806,-0.0621817,0.052879,-0.827338,-1.24407e-05,-5.72768e-05,4.14362e-07,3.41186e-05,-4.51286e-05,-0.00111697,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89788e-06,3.64563e-05,3.64483e-05,0.00011127,0.0141742,0.0141748,0.00995251,0.0401891,0.0401892,0.0590464,6.92804e-11,6.92859e-11,9.82855e-10,1.00935e-06,1.00896e-06,5e-08,0,0,0,0,0,0,0,0 +31180000,0.983015,-0.00622644,-0.0125162,0.18299,-0.0286307,0.0180999,0.771709,-0.0534452,0.0474856,-0.757459,-1.23463e-05,-5.71999e-05,7.06106e-07,3.54888e-05,-4.62895e-05,-0.00111421,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89734e-06,3.62728e-05,3.6265e-05,0.000111142,0.0133394,0.01334,0.00985247,0.036764,0.0367642,0.0586176,6.83322e-11,6.83381e-11,9.74475e-10,1.0089e-06,1.00852e-06,5e-08,0,0,0,0,0,0,0,0 +31280000,0.983037,-0.00651963,-0.0125951,0.182858,-0.0252621,0.016678,0.774554,-0.056136,0.0492549,-0.685641,-1.23427e-05,-5.72029e-05,8.7688e-07,3.56821e-05,-4.65142e-05,-0.00111226,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89231e-06,3.65417e-05,3.65345e-05,0.000111027,0.0143419,0.0143426,0.00992325,0.0402004,0.0402007,0.0587767,6.8429e-11,6.84352e-11,9.66065e-10,1.00891e-06,1.00852e-06,5e-08,0,0,0,0,0,0,0,0 +31380000,0.983055,-0.00630948,-0.01243,0.182778,-0.0195253,0.00928821,0.774805,-0.047097,0.0432467,-0.611024,-1.22565e-05,-5.71411e-05,8.06192e-07,3.64321e-05,-4.76391e-05,-0.00111027,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90369e-06,3.63257e-05,3.63188e-05,0.000111492,0.0134952,0.0134958,0.00990743,0.0367798,0.03678,0.0592212,6.73895e-11,6.73957e-11,9.59745e-10,1.00838e-06,1.008e-06,5.0002e-08,0,0,0,0,0,0,0,0 +31480000,0.983027,-0.00608522,-0.0126622,0.18292,-0.0190373,0.0059864,0.770591,-0.0490129,0.0439601,-0.537666,-1.22576e-05,-5.71398e-05,7.40791e-07,3.65241e-05,-4.77714e-05,-0.00110891,0.20395,0.000817194,0.434521,0,0,0,0,0,3.9054e-06,3.65945e-05,3.65866e-05,0.000111381,0.0145219,0.0145225,0.00997811,0.0402395,0.0402398,0.059378,6.74863e-11,6.74927e-11,9.51254e-10,1.00839e-06,1.008e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31580000,0.983047,-0.0059079,-0.0131446,0.182787,-0.0151682,0.00328026,0.773912,-0.0378792,0.0393378,-0.466188,-1.21904e-05,-5.70366e-05,9.34327e-07,3.86094e-05,-4.86154e-05,-0.00110613,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90128e-06,3.63468e-05,3.63373e-05,0.000111282,0.0136514,0.0136519,0.00987858,0.0368169,0.0368172,0.0589502,6.63585e-11,6.63644e-11,9.42735e-10,1.00777e-06,1.00739e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31680000,0.983075,-0.00590087,-0.0136111,0.182604,-0.0165497,0.00183214,0.770197,-0.039475,0.0395502,-0.396746,-1.21854e-05,-5.70409e-05,1.17131e-06,3.88723e-05,-4.88868e-05,-0.00110333,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89633e-06,3.66147e-05,3.6604e-05,0.000111186,0.0146898,0.0146904,0.00994901,0.0403019,0.0403024,0.0591056,6.64553e-11,6.64615e-11,9.34182e-10,1.00778e-06,1.0074e-06,5e-08,0,0,0,0,0,0,0,0 +31780000,0.983095,-0.00613825,-0.0143536,0.182427,-0.00776113,2.45941e-05,0.769669,-0.0278275,0.0377055,-0.325358,-1.21795e-05,-5.69102e-05,1.3702e-06,4.17879e-05,-4.83112e-05,-0.00110072,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89095e-06,3.63368e-05,3.63245e-05,0.000111094,0.0138029,0.0138033,0.00984926,0.0368718,0.0368722,0.0586766,6.52489e-11,6.52542e-11,9.25599e-10,1.00708e-06,1.0067e-06,5e-08,0,0,0,0,0,0,0,0 +31880000,0.9831,-0.00592907,-0.0141601,0.182424,-0.0032621,-0.00155836,0.768222,-0.0283459,0.0375716,-0.25607,-1.21765e-05,-5.69127e-05,1.51179e-06,4.20258e-05,-4.85427e-05,-0.00109802,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89089e-06,3.66013e-05,3.65896e-05,0.000111003,0.0148509,0.0148514,0.00992025,0.040384,0.0403845,0.058836,6.53456e-11,6.53513e-11,9.17008e-10,1.00709e-06,1.00671e-06,5e-08,0,0,0,0,0,0,0,0 +31980000,0.98307,-0.00609115,-0.0137176,0.182614,0.00567769,-0.0024829,0.766518,-0.0163248,0.0344204,-0.187424,-1.21567e-05,-5.68078e-05,1.41992e-06,4.42739e-05,-4.85896e-05,-0.00109441,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91341e-06,3.62919e-05,3.62822e-05,0.000111479,0.0139414,0.0139418,0.00990391,0.0369414,0.0369418,0.0592768,6.407e-11,6.40745e-11,9.10561e-10,1.00631e-06,1.00593e-06,5.0002e-08,0,0,0,0,0,0,0,0 +32080000,0.983091,-0.00646755,-0.013366,0.182513,0.00686732,-0.00520813,0.768333,-0.0157193,0.0340832,-0.116511,-1.21546e-05,-5.68095e-05,1.51901e-06,4.44512e-05,-4.87488e-05,-0.00109235,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90843e-06,3.65536e-05,3.65461e-05,0.000111395,0.0149964,0.0149969,0.00997574,0.0404808,0.0404813,0.0594396,6.41667e-11,6.41715e-11,9.01938e-10,1.00631e-06,1.00594e-06,5.0002e-08,0,0,0,0,0,0,0,0 +32180000,0.983082,-0.00676353,-0.0135779,0.182535,0.0107826,-0.00965903,0.769693,-0.00460305,0.0327017,-0.0496018,-1.21936e-05,-5.67212e-05,1.48969e-06,4.64926e-05,-4.73358e-05,-0.00108791,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90611e-06,3.62194e-05,3.62122e-05,0.000111309,0.0140591,0.0140593,0.00987562,0.0370214,0.0370218,0.0590063,6.28309e-11,6.28343e-11,8.93292e-10,1.00546e-06,1.00509e-06,5.0001e-08,0,0,0,0,0,0,0,0 +32280000,0.983106,-0.00667791,-0.0138397,0.182393,0.0120832,-0.013656,0.767627,-0.00344975,0.0315426,0.0195137,-1.21903e-05,-5.67241e-05,1.64859e-06,4.67384e-05,-4.75216e-05,-0.00108515,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90119e-06,3.64797e-05,3.64717e-05,0.000111227,0.0151264,0.0151265,0.0099463,0.0405873,0.0405879,0.0591624,6.29275e-11,6.29313e-11,8.84642e-10,1.00547e-06,1.0051e-06,5.0001e-08,0,0,0,0,0,0,0,0 +32380000,0.983088,-0.00670747,-0.0139702,0.182478,0.0180935,-0.0143539,0.765803,0.00771502,0.0290713,0.0922325,-1.22126e-05,-5.66522e-05,1.60961e-06,4.82994e-05,-4.64393e-05,-0.00108247,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90124e-06,3.61219e-05,3.61138e-05,0.000111141,0.0141712,0.0141712,0.00984684,0.0371085,0.037109,0.0587335,6.15432e-11,6.1545e-11,8.75986e-10,1.00456e-06,1.00419e-06,5e-08,0,0,0,0,0,0,0,0 +32480000,0.983087,-0.0088364,-0.0124189,0.182504,0.041131,-0.0650001,0.0741365,0.0111143,0.0245357,0.116274,-1.22147e-05,-5.665e-05,1.49367e-06,4.83169e-05,-4.64587e-05,-0.00108206,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89661e-06,3.63746e-05,3.63762e-05,0.000111059,0.0165012,0.0164989,0.00975114,0.0407518,0.0407523,0.0588822,6.16403e-11,6.16416e-11,8.67332e-10,0,0,0,0,0,0,0,0,0,0,0 +32580000,0.983101,-0.00884407,-0.0123676,0.182429,0.0420086,-0.0625358,0.0538485,0.0229477,0.0212433,0.108518,-1.23385e-05,-5.65882e-05,1.64934e-06,4.83169e-05,-4.64587e-05,-0.00108206,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89345e-06,3.57522e-05,3.57533e-05,0.000110974,0.0160211,0.016019,0.00938759,0.0372714,0.0372718,0.0584256,6.008e-11,6.00763e-11,8.58677e-10,0,0,0,0,0,0,0,0,0,0,0 +32680000,0.983098,-0.00883534,-0.0122497,0.182457,0.0390482,-0.0673687,0.0529197,0.0270318,0.0147428,0.109987,-1.23392e-05,-5.65874e-05,1.6116e-06,4.83169e-05,-4.64587e-05,-0.00108206,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91083e-06,3.60027e-05,3.60037e-05,0.000111459,0.0180014,0.0179991,0.00927272,0.041025,0.0410254,0.0593739,6.01779e-11,6.01738e-11,8.5222e-10,0,0,0,0,0,0,0,0,0,0,0 +32780000,0.983098,-0.00867518,-0.0123024,0.182459,0.0386874,-0.0653867,0.0486573,0.03653,0.0129648,0.102546,-1.24958e-05,-5.65305e-05,1.74532e-06,4.83169e-05,-4.64587e-05,-0.00108206,0.20395,0.000817194,0.434521,0,0,0,0,0,3.91025e-06,3.49853e-05,3.49849e-05,0.000111368,0.0176212,0.0176191,0.0089394,0.0375022,0.0375026,0.0588574,5.85209e-11,5.85113e-11,8.43568e-10,0,0,0,0,0,0,0,0,0,0,0 +32880000,0.983115,-0.00863769,-0.0123598,0.182365,0.0397026,-0.0711446,0.0465898,0.0404868,0.00614718,0.10181,-1.2495e-05,-5.65315e-05,1.79475e-06,4.83169e-05,-4.64587e-05,-0.00108206,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90443e-06,3.52272e-05,3.52261e-05,0.000111284,0.0199586,0.0199563,0.00876167,0.041375,0.0413753,0.0588701,5.8618e-11,5.86079e-11,8.3495e-10,0,0,0,0,0,0,0,0,0,0,0 +32980000,0.983127,-0.00852574,-0.0123023,0.18231,0.0367803,-0.0688536,0.0442556,0.047945,0.00253789,0.0964126,-1.26218e-05,-5.65056e-05,1.98303e-06,4.83169e-05,-4.64587e-05,-0.00108206,0.20395,0.000817194,0.434521,0,0,0,0,0,3.9024e-06,3.37825e-05,3.37804e-05,0.000111191,0.0195363,0.0195343,0.00846081,0.0377974,0.0377976,0.0583236,5.69075e-11,5.68924e-11,8.26328e-10,0,0,0,0,0,0,0,0,0,0,0 +33080000,0.983131,-0.00847375,-0.0123408,0.182292,0.0352973,-0.0723439,0.045006,0.0515942,-0.00453702,0.0991969,-1.26227e-05,-5.65048e-05,1.93677e-06,4.83168e-05,-4.64586e-05,-0.00108206,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89764e-06,3.40127e-05,3.40103e-05,0.000111102,0.0222237,0.0222216,0.00830243,0.0418282,0.0418284,0.0582725,5.70042e-11,5.69895e-11,8.17738e-10,1.00457e-06,1.0042e-06,5.0009e-08,0,0,0,0,0,0,0,0 +33180000,0.98313,-0.00832595,-0.0122228,0.182312,0.0321126,-0.0714099,0.043127,0.057319,-0.00726798,0.0990408,-1.27512e-05,-5.64789e-05,1.84455e-06,4.87001e-05,-4.88698e-05,-0.00108202,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89253e-06,3.21616e-05,3.21582e-05,0.00011101,0.0218385,0.0218367,0.00804527,0.0381732,0.0381733,0.0577106,5.52957e-11,5.52766e-11,8.09167e-10,1.00428e-06,1.00391e-06,5.00186e-08,0,0,0,0,0,0,0,0 +33280000,0.983145,-0.00840575,-0.0122017,0.182224,0.0294273,-0.0721956,0.0421122,0.060355,-0.014451,0.10178,-1.27477e-05,-5.64824e-05,2.03304e-06,4.87006e-05,-4.88703e-05,-0.00108202,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90957e-06,3.23781e-05,3.23749e-05,0.000111483,0.0251251,0.0251236,0.00798986,0.0424027,0.0424028,0.0584536,5.53934e-11,5.53743e-11,8.02777e-10,1.00429e-06,1.00392e-06,5.00286e-08,0,0,0,0,0,0,0,0 +33380000,0.983162,-0.0081549,-0.0122274,0.182145,0.0250226,-0.0634421,0.0408594,0.062938,-0.0109692,0.0980764,-1.29571e-05,-5.64426e-05,2.11988e-06,4.81608e-05,-5.89406e-05,-0.00108181,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90379e-06,3.01948e-05,3.01899e-05,0.000111385,0.0246112,0.0246102,0.00777558,0.0386406,0.0386406,0.0578635,5.37496e-11,5.37261e-11,7.94249e-10,1.00138e-06,1.00102e-06,5.0035e-08,0,0,0,0,0,0,0,0 +33480000,0.983157,-0.00817823,-0.0121926,0.182173,0.0225376,-0.0640301,0.0401998,0.0652931,-0.017292,0.0961685,-1.2957e-05,-5.64429e-05,2.13349e-06,4.81779e-05,-5.89553e-05,-0.00108177,0.20395,0.000817194,0.434521,0,0,0,0,0,3.90179e-06,3.03964e-05,3.03918e-05,0.000111282,0.0283557,0.028355,0.00768731,0.0431129,0.0431129,0.0577242,5.38462e-11,5.38235e-11,7.85755e-10,1.00139e-06,1.00103e-06,5.00448e-08,0,0,0,0,0,0,0,0 +33580000,0.983179,-0.00794131,-0.0121241,0.18207,0.0184578,-0.0588418,0.0402354,0.0670998,-0.0148713,0.0942758,-1.31024e-05,-5.64173e-05,2.32154e-06,4.76906e-05,-7.02397e-05,-0.00108157,0.20395,0.000817194,0.434521,0,0,0,0,0,3.8969e-06,2.80062e-05,2.80002e-05,0.000111176,0.0274241,0.0274237,0.00751446,0.0392027,0.0392027,0.057127,5.23315e-11,5.23051e-11,7.77283e-10,9.93997e-07,9.93641e-07,5.00443e-08,0,0,0,0,0,0,0,0 +33680000,0.983191,-0.00794862,-0.0121156,0.182006,0.0151691,-0.0614925,0.0362348,0.0688363,-0.0208956,0.0932467,-1.31014e-05,-5.64183e-05,2.37789e-06,4.77224e-05,-7.02659e-05,-0.0010815,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89166e-06,2.81931e-05,2.81872e-05,0.00011107,0.0314878,0.0314877,0.00745949,0.0439496,0.0439496,0.0569617,5.2428e-11,5.24025e-11,7.68858e-10,9.94007e-07,9.93651e-07,5.00537e-08,0,0,0,0,0,0,0,0 +33780000,0.983201,-0.00775383,-0.0120943,0.181961,0.0102043,-0.0549186,0.0382005,0.0716317,-0.0175121,0.0903037,-1.32315e-05,-5.63669e-05,2.31706e-06,4.54572e-05,-8.38822e-05,-0.00108115,0.20395,0.000817194,0.434521,0,0,0,0,0,3.88356e-06,2.5746e-05,2.57388e-05,0.000110961,0.0299192,0.0299194,0.00732435,0.0398446,0.0398445,0.0563704,5.10948e-11,5.1066e-11,7.60459e-10,9.81338e-07,9.80991e-07,5.00429e-08,0,0,0,0,0,0,0,0 +33880000,0.983221,-0.00777304,-0.0120443,0.181853,0.0064059,-0.0534378,0.0372224,0.0724353,-0.0229602,0.0893532,-1.32283e-05,-5.63698e-05,2.47886e-06,4.55069e-05,-8.39207e-05,-0.00108104,0.20395,0.000817194,0.434521,0,0,0,0,0,3.8785e-06,2.59188e-05,2.59119e-05,0.000110847,0.0341262,0.0341269,0.00730027,0.0448744,0.0448743,0.0561902,5.11913e-11,5.11634e-11,7.52113e-10,9.81347e-07,9.81001e-07,5.00512e-08,0,0,0,0,0,0,0,0 +33980000,0.983213,-0.00760929,-0.0121673,0.181898,0.00431208,-0.0423031,0.0364481,0.0741595,-0.0167187,0.0888466,-1.33624e-05,-5.63048e-05,2.44573e-06,3.78644e-05,-0.000101464,-0.00108062,0.20395,0.000817194,0.434521,0,0,0,0,0,3.89444e-06,2.35609e-05,2.35523e-05,0.000111295,0.031844,0.0318449,0.00725405,0.0405327,0.0405327,0.0564002,5.00716e-11,5.0041e-11,7.45897e-10,9.63631e-07,9.63296e-07,5.00273e-08,0,0,0,0,0,0,0,0 +34080000,0.983211,-0.0075509,-0.0121647,0.181907,0.00245972,-0.0447286,0.0371773,0.0745395,-0.0211168,0.0890553,-1.33639e-05,-5.63037e-05,2.37866e-06,3.79223e-05,-0.00010151,-0.0010805,0.20395,0.000817194,0.434521,0,0,0,0,0,3.88901e-06,2.37216e-05,2.37131e-05,0.000111172,0.0360592,0.0360604,0.00725738,0.0458281,0.0458281,0.0562058,5.01682e-11,5.01384e-11,7.37617e-10,9.6364e-07,9.63306e-07,5.00338e-08,0,0,0,0,0,0,0,0 +34180000,0.983209,-0.00742545,-0.0121983,0.181922,-0.00158954,-0.0361687,0.0358241,0.0765298,-0.0159623,0.0889232,-1.34536e-05,-5.62541e-05,2.44742e-06,3.23313e-05,-0.000116739,-0.00107966,0.20395,0.000817194,0.434521,0,0,0,0,0,3.88592e-06,2.15638e-05,2.1554e-05,0.000111043,0.0330791,0.0330804,0.0071838,0.0412235,0.0412235,0.0556348,4.92666e-11,4.9235e-11,7.29388e-10,9.41831e-07,9.41512e-07,5.00055e-08,0,0,0,0,0,0,0,0 +34280000,0.983205,-0.00731914,-0.0122469,0.181945,-0.00283805,-0.037097,0.0347989,0.0763308,-0.0196115,0.0862471,-1.34518e-05,-5.62558e-05,2.53772e-06,3.24658e-05,-0.000116837,-0.00107937,0.20395,0.000817194,0.434521,0,0,0,0,0,3.88418e-06,2.17147e-05,2.17048e-05,0.000110908,0.0371945,0.0371962,0.00721334,0.0467452,0.0467452,0.055445,4.93631e-11,4.93324e-11,7.21204e-10,9.41839e-07,9.41522e-07,5.00088e-08,0,0,0,0,0,0,0,0 +34380000,0.983222,-0.0071815,-0.0122628,0.181859,-0.00480875,-0.0272929,0.0360586,0.0765893,-0.0144971,0.0840492,-1.35234e-05,-5.62232e-05,2.55443e-06,2.65416e-05,-0.000130419,-0.00107892,0.20395,0.000817194,0.434521,0,0,0,0,0,3.8755e-06,1.98254e-05,1.98144e-05,0.000110776,0.0336238,0.0336254,0.00716496,0.0418741,0.0418741,0.0548951,4.86669e-11,4.86349e-11,7.13068e-10,9.1724e-07,9.16941e-07,5.00015e-08,0,0,0,0,0,0,0,0 +34480000,0.983222,-0.00727279,-0.0122018,0.181861,-0.00720452,-0.02943,0.0356493,0.0759747,-0.0173833,0.0843118,-1.35213e-05,-5.6225e-05,2.65869e-06,2.66319e-05,-0.00013048,-0.00107872,0.20395,0.000817194,0.434521,0,0,0,0,0,3.87297e-06,1.99685e-05,1.99579e-05,0.000110636,0.0375543,0.0375562,0.00721875,0.047569,0.047569,0.0547219,4.87635e-11,4.87324e-11,7.04994e-10,9.17248e-07,9.1695e-07,5.00001e-08,0,0,0,0,0,0,0,0 +34580000,0.983223,-0.00716984,-0.0120296,0.181868,-0.00735233,-0.0235401,0.708982,0.0764055,-0.0139652,0.106802,-1.35624e-05,-5.61988e-05,2.65333e-06,2.11742e-05,-0.000139002,-0.00107808,0.20395,0.000817194,0.434521,0,0,0,0,0,3.88707e-06,1.83743e-05,1.83633e-05,0.000111057,0.0322745,0.0322763,0.00724031,0.0424214,0.0424214,0.0549455,4.82474e-11,4.82154e-11,6.98988e-10,8.91175e-07,8.90897e-07,5.0002e-08,0,0,0,0,0,0,0,0 +34680000,0.983228,-0.00715718,-0.0117414,0.181861,-0.00834715,-0.0221805,1.6979,0.0756198,-0.0162303,0.21756,-1.35625e-05,-5.61987e-05,2.64544e-06,2.14978e-05,-0.000139231,-0.00107735,0.20395,0.000817194,0.434521,0,0,0,0,0,3.88111e-06,1.85116e-05,1.85015e-05,0.000110911,0.0340257,0.034028,0.00731216,0.0480363,0.0480364,0.0547871,4.8344e-11,4.83129e-11,6.91008e-10,8.91181e-07,8.90906e-07,5.0002e-08,0,0,0,0,0,0,0,0 +34780000,0.983238,-0.0070914,-0.0115037,0.181827,-0.00901071,-0.0159289,2.66207,0.0758571,-0.0126849,0.374118,-1.35809e-05,-5.61729e-05,2.73138e-06,2.61064e-05,-0.000153867,-0.00105203,0.20395,0.000817194,0.434521,0,0,0,0,0,3.87464e-06,1.74068e-05,1.73967e-05,0.000110759,0.0292056,0.0292078,0.0073001,0.0427328,0.0427328,0.0542844,4.80134e-11,4.79822e-11,6.83078e-10,8.61807e-07,8.61555e-07,5.0001e-08,0,0,0,0,0,0,0,0 +34880000,0.983243,-0.00707821,-0.0112181,0.181816,-0.0101685,-0.0143819,3.64546,0.0748838,-0.0141331,0.659671,-1.35802e-05,-5.61728e-05,2.73744e-06,2.73118e-05,-0.000154708,-0.00104923,0.20395,0.000817194,0.434521,0,0,0,0,0,3.86834e-06,1.75418e-05,1.75326e-05,0.000110603,0.0310539,0.0310566,0.00739022,0.0481216,0.0481218,0.0541473,4.81101e-11,4.80797e-11,6.75207e-10,8.61812e-07,8.61563e-07,5.0001e-08,0,0,0,0,0,0,0,0 diff --git a/test/test_EKF_externalVision.cpp b/test/test_EKF_externalVision.cpp index 76a6e8c89d..6c181c4bf6 100644 --- a/test/test_EKF_externalVision.cpp +++ b/test/test_EKF_externalVision.cpp @@ -59,7 +59,7 @@ class EkfExternalVisionTest : public ::testing::Test { void SetUp() override { _ekf->init(0); - _sensor_simulator.runSeconds(2); + _sensor_simulator.runSeconds(3); } // Use this method to clean up any memory, network etc. after each test @@ -112,17 +112,19 @@ TEST_F(EkfExternalVisionTest, visionVelocityReset) _sensor_simulator._vio.setVelocity(simulated_velocity); _ekf_wrapper.enableExternalVisionVelocityFusion(); _sensor_simulator.startExternalVision(); - _sensor_simulator.runMicroseconds(6e5); + // Note: test duration needs to allow time for tilt alignment to complete + _sensor_simulator.runMicroseconds(2e5); // THEN: a reset to Vision velocity should be done + // Note: velocity will drift after reset due to INAV errors so the tolerance needs to allow for this const Vector3f estimated_velocity = _ekf->getVelocity(); - EXPECT_TRUE(isEqual(estimated_velocity, simulated_velocity, 1e-5f)); + EXPECT_TRUE(isEqual(estimated_velocity, simulated_velocity, 0.01f)); // AND: the reset in velocity should be saved correctly reset_logging_checker.capturePostResetState(); EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1)); EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(1)); - EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-5f)); + EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(0.01f)); } TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment) @@ -143,11 +145,11 @@ TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment) _sensor_simulator._vio.setVelocity(simulated_velocity_in_vision_frame); _ekf_wrapper.enableExternalVisionVelocityFusion(); _sensor_simulator.startExternalVision(); - _sensor_simulator.runMicroseconds(6e5); + _sensor_simulator.runMicroseconds(2e5); // THEN: a reset to Vision velocity should be done const Vector3f estimated_velocity_in_ekf_frame = _ekf->getVelocity(); - EXPECT_TRUE(isEqual(estimated_velocity_in_ekf_frame, simulated_velocity_in_ekf_frame, 1e-5f)); + EXPECT_TRUE(isEqual(estimated_velocity_in_ekf_frame, simulated_velocity_in_ekf_frame, 0.01f)); // And: the frame offset should be estimated correctly Quatf estimatedExternalVisionFrameOffset = _ekf->getVisionAlignmentQuaternion(); EXPECT_TRUE(matrix::isEqual(vision_to_ekf.canonical(), @@ -157,7 +159,7 @@ TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment) reset_logging_checker.capturePostResetState(); EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1)); EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(1)); - EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(1e-5f)); + EXPECT_TRUE(reset_logging_checker.isVelocityDeltaLoggedCorrectly(0.01f)); } TEST_F(EkfExternalVisionTest, visionVarianceCheck) diff --git a/test/test_EKF_flow.cpp b/test/test_EKF_flow.cpp index 81fd76c085..33f16f6fc9 100644 --- a/test/test_EKF_flow.cpp +++ b/test/test_EKF_flow.cpp @@ -120,7 +120,7 @@ TEST_F(EkfFlowTest, resetToFlowVelocityOnGround) // WHEN: start fusing flow data _ekf_wrapper.enableFlowFusion(); _sensor_simulator.startFlow(); - _sensor_simulator.runSeconds(0.6); + _sensor_simulator.runSeconds(1.0); // THEN: estimated velocity should match simulated velocity const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); diff --git a/test/test_EKF_fusionLogic.cpp b/test/test_EKF_fusionLogic.cpp index 28764d1ee4..60b523631f 100644 --- a/test/test_EKF_fusionLogic.cpp +++ b/test/test_EKF_fusionLogic.cpp @@ -335,14 +335,14 @@ TEST_F(EkfFusionLogicTest, doRangeHeightFusion) // WHEN: commanding range height and sending range data _ekf_wrapper.setRangeHeight(); _sensor_simulator.startRangeFinder(); - _sensor_simulator.runSeconds(2); + _sensor_simulator.runSeconds(2.5); // THEN: EKF should intend to fuse range height EXPECT_TRUE(_ekf_wrapper.isIntendingRangeHeightFusion()); // WHEN: stop sending range data _sensor_simulator.stopRangeFinder(); - _sensor_simulator.runSeconds(2); + _sensor_simulator.runSeconds(2.5); // THEN: EKF should stop to intend to use range height EXPECT_FALSE(_ekf_wrapper.isIntendingRangeHeightFusion()); diff --git a/test/test_EKF_imuSampling.cpp b/test/test_EKF_imuSampling.cpp index 5ee426e44b..3a98f727d0 100644 --- a/test/test_EKF_imuSampling.cpp +++ b/test/test_EKF_imuSampling.cpp @@ -76,8 +76,10 @@ TEST_P(EkfImuSamplingTest, imuSamplingAtMultipleRates) imu_sample.delta_vel = accel * imu_sample.delta_vel_dt; // The higher the imu rate is the more measurements we have to set before reaching the FILTER_UPDATE_PERIOD + int n_samples = 0; for(int i = 0; i<(int)20/std::get<0>(GetParam()); ++i) { + n_samples++; imu_sample.time_us = _t_us; _ekf.setIMUData(imu_sample); _t_us += dt_us; @@ -90,8 +92,9 @@ TEST_P(EkfImuSamplingTest, imuSamplingAtMultipleRates) // WHEN: downsampling the imu measurement // THEN: the delta vel should be accumulated correctly - EXPECT_TRUE(matrix::isEqual(ang_vel, imu_sample_buffered.delta_ang/imu_sample_buffered.delta_ang_dt, 1e-7f)); - EXPECT_TRUE(matrix::isEqual(accel, imu_sample_buffered.delta_vel/imu_sample_buffered.delta_vel_dt, 1e-7f)); + // Allow for accumulation of rounding error with each sample + EXPECT_TRUE(matrix::isEqual(ang_vel, imu_sample_buffered.delta_ang/imu_sample_buffered.delta_ang_dt, float(n_samples) * 1e-7f)); + EXPECT_TRUE(matrix::isEqual(accel, imu_sample_buffered.delta_vel/imu_sample_buffered.delta_vel_dt, float(n_samples) * 1e-7f)); } INSTANTIATE_TEST_SUITE_P(imuSamplingAtMultipleRates, diff --git a/test/test_EKF_initialization.cpp b/test/test_EKF_initialization.cpp index 6bd781a4cc..f319c6837f 100644 --- a/test/test_EKF_initialization.cpp +++ b/test/test_EKF_initialization.cpp @@ -49,7 +49,7 @@ class EkfInitializationTest : public ::testing::Test { SensorSimulator _sensor_simulator; EkfWrapper _ekf_wrapper; - const float _init_tilt_period = 0.5; // seconds + const float _init_tilt_period = 1.0; // seconds // GTests is calling this void SetUp() override @@ -155,7 +155,10 @@ TEST_F(EkfInitializationTest, initializeWithTilt) TEST_F(EkfInitializationTest, initializeWithPitch90) { - const Quatf quat_sim(0.0f, 0.7071068f, 0.0f, 0.7071068f); + const float pitch = math::radians(90.0f); + const float roll = math::radians(0.0f); + const Eulerf euler_angles_sim(roll, pitch, 0.0f); + const Quatf quat_sim(euler_angles_sim); _sensor_simulator.simulateOrientation(quat_sim); _sensor_simulator.runSeconds(_init_tilt_period); @@ -167,7 +170,10 @@ TEST_F(EkfInitializationTest, initializeWithPitch90) TEST_F(EkfInitializationTest, initializeWithRoll90) { - const Quatf quat_sim(0.7071068f, 0.7071068f, 0.0f, 0.0f); + const float pitch = math::radians(0.0f); + const float roll = math::radians(90.0f); + const Eulerf euler_angles_sim(roll, pitch, 0.0f); + const Quatf quat_sim(euler_angles_sim); _sensor_simulator.simulateOrientation(quat_sim); _sensor_simulator.runSeconds(_init_tilt_period);