From 230c865fa9c02b07b0371df050b339bc37ce0c29 Mon Sep 17 00:00:00 2001 From: Mathieu Bresciani Date: Wed, 4 Mar 2020 10:31:22 +0100 Subject: [PATCH] EKF: do not fuse multiple times the same height (#767) * EKF: do not fuse multiple times the same height The _fuse_height flag was never set to zero, hence the fusion was called at each iteration, even if no new data is available. The effects were: high CPU usage and virtually less measurement noise due to multiple fusion of the same sample Also remve unused variables --- EKF/control.cpp | 37 +- EKF/ekf.h | 6 - EKF/vel_pos_fusion.cpp | 2 +- test/change_indication/iris_gps.csv | 690 ++++++++++++++-------------- test/test_EKF_basics.cpp | 10 +- 5 files changed, 368 insertions(+), 377 deletions(-) diff --git a/EKF/control.cpp b/EKF/control.cpp index 80a9ba03ac..bd537e7916 100644 --- a/EKF/control.cpp +++ b/EKF/control.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2015 Estimation and Control Library (ECL). All rights reserved. + * Copyright (c) 2015-2020 Estimation and Control Library (ECL). All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -284,7 +284,6 @@ void Ekf::controlExternalVisionFusion() if (_fuse_hpos_as_odom) { if (!_hpos_prev_available) { // no previous observation available to calculate position change - _fuse_pos = false; _hpos_prev_available = true; } else { @@ -928,10 +927,11 @@ void Ekf::controlHeightSensorTimeouts() void Ekf::controlHeightFusion() { - checkRangeAidSuitability(); _range_aid_mode_selected = (_params.range_aid == 1) && isRangeAidSuitable(); + bool fuse_height = false; + switch (_params.vdist_sensor_type) { default: ECL_ERR("Invalid height mode: %d", _params.vdist_sensor_type); @@ -940,7 +940,7 @@ void Ekf::controlHeightFusion() case VDIST_SENSOR_BARO: if (_range_aid_mode_selected && _range_data_ready && _rng_hgt_valid) { setControlRangeHeight(); - _fuse_height = true; + fuse_height = true; // we have just switched to using range finder, calculate height sensor offset such that current // measurement matches our current height estimate @@ -955,7 +955,7 @@ void Ekf::controlHeightFusion() } else if (!_range_aid_mode_selected && _baro_data_ready && !_baro_hgt_faulty) { setControlBaroHeight(); - _fuse_height = true; + fuse_height = true; // we have just switched to using baro height, we don't need to set a height sensor offset // since we track a separate _baro_hgt_offset @@ -973,7 +973,7 @@ void Ekf::controlHeightFusion() } else if (_control_status.flags.gps_hgt && _gps_data_ready && !_gps_hgt_intermittent) { // switch to gps if there was a reset to gps - _fuse_height = true; + fuse_height = true; // we have just switched to using gps height, calculate height sensor offset such that current // measurement matches our current height estimate @@ -987,7 +987,7 @@ void Ekf::controlHeightFusion() case VDIST_SENSOR_RANGE: if (_range_data_ready && _rng_hgt_valid) { setControlRangeHeight(); - _fuse_height = _range_data_ready; + fuse_height = _range_data_ready; } else if (_control_status_prev.flags.rng_hgt != _control_status.flags.rng_hgt) { // we have just switched to using range finder, calculate height sensor offset such that current @@ -1005,7 +1005,7 @@ void Ekf::controlHeightFusion() } else if (_baro_data_ready && !_baro_hgt_faulty) { setControlBaroHeight(); - _fuse_height = true; + fuse_height = true; // we have just switched to using baro height, we don't need to set a height sensor offset // since we track a separate _baro_hgt_offset @@ -1021,7 +1021,7 @@ void Ekf::controlHeightFusion() // Determine if GPS should be used as the height source if (_range_aid_mode_selected && _range_data_ready && _rng_hgt_valid) { setControlRangeHeight(); - _fuse_height = true; + fuse_height = true; // we have just switched to using range finder, calculate height sensor offset such that current // measurement matches our current height estimate @@ -1036,7 +1036,7 @@ void Ekf::controlHeightFusion() } else if (!_range_aid_mode_selected && _gps_data_ready && !_gps_hgt_intermittent && _gps_checks_passed) { setControlGPSHeight(); - _fuse_height = true; + fuse_height = true; // we have just switched to using gps height, calculate height sensor offset such that current // measurement matches our current height estimate @@ -1046,7 +1046,7 @@ void Ekf::controlHeightFusion() } else if (_control_status.flags.baro_hgt && _baro_data_ready && !_baro_hgt_faulty) { // switch to baro if there was a reset to baro - _fuse_height = true; + fuse_height = true; // we have just switched to using baro height, we don't need to set a height sensor offset // since we track a separate _baro_hgt_offset @@ -1061,14 +1061,14 @@ void Ekf::controlHeightFusion() // don't start using EV data unless data is arriving frequently if (!_control_status.flags.ev_hgt && isRecent(_time_last_ext_vision, 2 * EV_MAX_INTERVAL)) { - _fuse_height = true; + fuse_height = true; setControlEVHeight(); resetHeight(); } if (_control_status.flags.baro_hgt && _baro_data_ready && !_baro_hgt_faulty) { // switch to baro if there was a reset to baro - _fuse_height = true; + fuse_height = true; // we have just switched to using baro height, we don't need to set a height sensor offset // since we track a separate _baro_hgt_offset @@ -1079,7 +1079,7 @@ void Ekf::controlHeightFusion() // determine if we should use the vertical position observation if (_control_status.flags.ev_hgt) { - _fuse_height = true; + fuse_height = true; } break; @@ -1107,11 +1107,10 @@ void Ekf::controlHeightFusion() } - _fuse_height = true; + fuse_height = true; } - if (_fuse_height) { - + if (fuse_height) { if (_control_status.flags.baro_hgt) { Vector2f baro_hgt_innov_gate; Vector3f baro_hgt_obs_var; @@ -1186,9 +1185,7 @@ void Ekf::controlHeightFusion() fuseVerticalPosition(_ev_pos_innov,ev_hgt_innov_gate, ev_hgt_obs_var, _ev_pos_innov_var,_ev_pos_test_ratio); } - } - } void Ekf::checkRangeAidSuitability() @@ -1331,7 +1328,7 @@ void Ekf::controlFakePosFusion() _using_synthetic_position = true; // Fuse synthetic position observations every 200msec - if (isTimedOut(_time_last_fake_pos, (uint64_t)2e5) || _fuse_height) { + if (isTimedOut(_time_last_fake_pos, (uint64_t)2e5)) { Vector3f fake_pos_obs_var; Vector2f fake_pos_innov_gate; diff --git a/EKF/ekf.h b/EKF/ekf.h index 0538e62366..ea2a061329 100644 --- a/EKF/ekf.h +++ b/EKF/ekf.h @@ -308,12 +308,6 @@ private: bool _filter_initialised{false}; ///< true when the EKF sttes and covariances been initialised - bool _fuse_height{false}; ///< true when baro height data should be fused - bool _fuse_pos{false}; ///< true when gps position data should be fused - bool _fuse_hor_vel{false}; ///< true when gps horizontal velocity measurement should be fused - bool _fuse_vert_vel{false}; ///< true when gps vertical velocity measurement should be fused - bool _fuse_hor_vel_aux{false}; ///< true when auxiliary horizontal velocity measurement should be fused - // variables used when position data is being fused using a relative position odometry model bool _fuse_hpos_as_odom{false}; ///< true when the NE position data is being fused using an odometry assumption Vector3f _pos_meas_prev; ///< previous value of NED position measurement fused using odometry assumption (m) diff --git a/EKF/vel_pos_fusion.cpp b/EKF/vel_pos_fusion.cpp index d1dc525179..be8c47a45a 100644 --- a/EKF/vel_pos_fusion.cpp +++ b/EKF/vel_pos_fusion.cpp @@ -139,7 +139,7 @@ bool Ekf::fuseVerticalPosition(const Vector3f &innov, const Vector2f &innov_gate // Helper function that fuses a single velocity or position measurement void Ekf::fuseVelPosHeight(const float innov, const float innov_var, const int obs_index) { - float Kfusion[24] = {}; // Kalman gain vector for any single observation - sequential fusion is used. + float Kfusion[24]; // Kalman gain vector for any single observation - sequential fusion is used. const unsigned state_index = obs_index + 4; // we start with vx and this is the 4. state // calculate kalman gain K = PHS, where S = 1/innovation variance diff --git a/test/change_indication/iris_gps.csv b/test/change_indication/iris_gps.csv index 7526ae2f13..e3fae1b91e 100644 --- a/test/change_indication/iris_gps.csv +++ b/test/change_indication/iris_gps.csv @@ -4,348 +4,348 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 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.00795401,-0.0134176,0.183833,0.000493858,-0.000283938,-0.00241826,1.97543e-06,-1.13575e-06,-1.9725e-05,0,0,0,0,0,0,0.203491,2.14204e-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.00798434,-0.0137631,0.181638,0.000718693,-0.000264641,-0.0216737,2.00536e-05,-1.52371e-05,0.0430711,3.09817e-08,5.01529e-11,1.30798e-06,3.54307e-09,-3.19828e-09,1.41824e-07,0.203491,2.14204e-08,0.43426,0,0,0,0,0,9.07318e-05,0.00250276,0.00250253,0.00257188,12.0236,12.0236,0.562179,0.0455429,0.0455429,0.334522,6.4e-07,6.4e-07,6.38957e-07,2.56e-06,2.56e-06,2.56001e-06,0,0,0,0,0,0,0,0 -592000,0.983276,-0.00801853,-0.014002,0.181405,0.000351945,3.5004e-05,-0.0426403,2.08652e-05,-1.06353e-05,0.0231778,4.28391e-08,-1.88297e-10,1.81294e-06,1.33522e-08,-1.1985e-08,4.95307e-07,0.203491,2.14204e-08,0.43426,0,0,0,0,0,6.3195e-05,0.00258644,0.00258631,0.00178375,2.60288,2.60288,0.557647,0.0342057,0.0342057,0.165232,6.39994e-07,6.39997e-07,6.34828e-07,2.55994e-06,2.55994e-06,2.55998e-06,0,0,0,0,0,0,0,0 -688000,0.983194,-0.00807102,-0.0143686,0.181816,0.00242318,-0.00030416,-0.0515555,9.68914e-05,-4.85836e-06,0.02409,3.60616e-09,-2.79896e-09,2.42197e-07,1.03319e-08,-7.0765e-09,1.37656e-07,0.203491,2.14204e-08,0.43426,0,0,0,0,0,5.30925e-05,0.00270786,0.00270775,0.00149413,0.903247,0.903249,0.545417,0.0251284,0.0251284,0.119474,6.39961e-07,6.39968e-07,6.28838e-07,2.55975e-06,2.55975e-06,2.55983e-06,0,0,0,0,0,0,0,0 -792000,0.983149,-0.00805428,-0.0146093,0.182046,0.00420606,0.00217751,-0.062951,0.000193567,7.99815e-05,0.019293,-3.39021e-08,-1.77485e-08,-1.18071e-06,3.55036e-08,-9.48279e-09,4.88506e-08,0.203491,2.14204e-08,0.43426,0,0,0,0,0,4.49714e-05,0.00287841,0.00287831,0.00126116,0.411575,0.411581,0.520333,0.0192979,0.019298,0.0999413,6.39759e-07,6.39773e-07,6.16042e-07,2.5591e-06,2.5591e-06,2.55925e-06,0,0,0,0,0,0,0,0 -888000,0.983115,-0.00809,-0.0149317,0.182199,0.00509783,0.00386691,-0.08595,0.000358919,0.000227202,0.00364514,-7.24078e-08,-8.18836e-08,-3.06346e-06,1.67998e-07,-3.32881e-08,1.84168e-06,0.203491,2.14204e-08,0.43426,0,0,0,0,0,4.01681e-05,0.00305458,0.00305448,0.00112318,0.264294,0.264305,0.48585,0.0160456,0.0160456,0.0932086,6.39031e-07,6.39058e-07,5.97167e-07,2.55762e-06,2.55762e-06,2.55797e-06,0,0,0,0,0,0,0,0 -992000,0.982951,-0.00804531,-0.0151901,0.183061,0.00698846,0.0059772,-0.102893,0.000613566,0.000409456,-0.00852876,-2.52842e-07,-2.94933e-07,-1.18759e-05,4.25967e-07,5.42982e-09,2.42525e-06,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.77994e-05,0.00323131,0.0032312,0.00105441,0.213284,0.213302,0.438755,0.0139335,0.0139337,0.0912114,6.36643e-07,6.36686e-07,5.72108e-07,2.55437e-06,2.55437e-06,2.55533e-06,0,0,0,0,0,0,0,0 -1088000,0.98302,-0.00818278,-0.0152921,0.182676,0.0136075,0.00426056,-0.124622,0.0010423,0.000601645,-0.0263305,-2.81541e-08,-7.95671e-07,-7.34943e-06,9.7798e-07,6.15286e-08,4.83434e-06,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.61848e-05,0.00333691,0.00333682,0.00100802,0.206914,0.206939,0.390396,0.0129006,0.0129009,0.0911613,6.31333e-07,6.31395e-07,5.41398e-07,2.54921e-06,2.54921e-06,2.55137e-06,0,0,0,0,0,0,0,0 -1192000,0.983114,-0.00818696,-0.015378,0.182165,0.0166956,0.00230009,-0.106569,0.00166325,0.000541827,-0.0160973,1.62517e-07,-1.96415e-06,-1.07023e-06,1.72313e-06,3.11648e-07,-5.78946e-06,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.56424e-05,0.00333803,0.00333796,0.000994192,0.216265,0.216293,0.337621,0.0124997,0.0125002,0.0912638,6.19904e-07,6.19988e-07,5.0613e-07,2.54109e-06,2.54109e-06,2.54518e-06,0,0,0,0,0,0,0,0 -1288000,0.983307,-0.00811895,-0.0153436,0.181122,0.0194865,0.00190544,-0.12074,0.0022263,0.000420128,-0.0265567,2.66956e-07,-3.86476e-06,1.26448e-05,3.10516e-06,1.35149e-07,-5.955e-06,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.6511e-05,0.00321167,0.00321162,0.00102366,0.225728,0.225759,0.292031,0.0125512,0.0125518,0.0908001,6.02511e-07,6.0261e-07,4.77681e-07,2.53194e-06,2.53194e-06,2.53758e-06,0,0,0,0,0,0,0,0 -1392000,0.983422,-0.00811839,-0.0150915,0.18052,0.0211172,0.00140607,-0.10527,0.00268895,0.000344979,-0.0159095,-2.10062e-07,-6.77794e-06,1.89045e-05,4.59567e-06,3.20636e-08,-2.00775e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.62724e-05,0.00295909,0.00295908,0.00102454,0.228056,0.228085,0.24831,0.0127765,0.0127771,0.0895009,5.76241e-07,5.76357e-07,4.38045e-07,2.52185e-06,2.52185e-06,2.52724e-06,0,0,0,0,0,0,0,0 -1488000,0.983377,-0.00804809,-0.0147223,0.180798,0.0179411,0.000425948,-0.117932,0.00280178,0.000281397,-0.0271866,-1.1984e-06,-1.00742e-05,1.31805e-05,6.32618e-06,-4.23071e-07,-1.941e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.55599e-05,0.00267316,0.00267316,0.00101096,0.221107,0.22113,0.213949,0.012936,0.0129366,0.0876596,5.4687e-07,5.47e-07,3.98062e-07,2.51385e-06,2.51385e-06,2.5157e-06,0,0,0,0,0,0,0,0 -1592000,0.983405,-0.00806457,-0.0144699,0.180664,0.0157248,-0.000331174,-0.130681,0.00265184,9.79779e-05,-0.0380818,-2.29907e-06,-1.36773e-05,1.38261e-05,7.82434e-06,-8.58626e-07,-2.13316e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.5287e-05,0.00236855,0.00236856,0.00100967,0.206942,0.206959,0.183117,0.0129511,0.0129516,0.0851778,5.12145e-07,5.12284e-07,3.59052e-07,2.50752e-06,2.50752e-06,2.50092e-06,0,0,0,0,0,0,0,0 -1688000,0.983428,-0.00806451,-0.0142501,0.180557,0.0136858,0.000918172,-0.134273,0.00244647,0.000117862,-0.0410834,-3.32662e-06,-1.67722e-05,1.45994e-05,8.6731e-06,-1.03701e-06,-2.97617e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.44662e-05,0.00212656,0.00212655,0.000991079,0.191198,0.191212,0.159994,0.0128196,0.0128201,0.0826287,4.79251e-07,4.79396e-07,3.22017e-07,2.50385e-06,2.50386e-06,2.48503e-06,0,0,0,0,0,0,0,0 -1792000,0.983438,-0.00811313,-0.0140246,0.180518,0.0142614,0.000410687,-0.135015,0.00233875,9.62603e-05,-0.0438611,-4.3956e-06,-1.98828e-05,1.31468e-05,9.18536e-06,-1.06412e-06,-4.08367e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.39806e-05,0.00191892,0.0019189,0.000982705,0.174215,0.174227,0.139911,0.0125667,0.012567,0.0797643,4.43787e-07,4.43935e-07,2.87614e-07,2.50175e-06,2.50175e-06,2.46516e-06,0,0,0,0,0,0,0,0 -1888000,0.983552,-0.00803242,-0.0138143,0.179918,0.0124334,0.0023023,-0.133032,0.00221706,0.000176211,-0.0449894,-5.12656e-06,-2.26636e-05,1.97491e-05,9.36116e-06,-9.40981e-07,-5.33645e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.29938e-05,0.00177336,0.00177333,0.000958258,0.160329,0.160341,0.125207,0.0122823,0.0122826,0.0771434,4.11503e-07,4.11653e-07,2.56201e-07,2.50095e-06,2.50096e-06,2.44411e-06,0,0,0,0,0,0,0,0 -1992000,0.983597,-0.00808381,-0.0137044,0.17968,0.010979,0.00216385,-0.133432,0.00206397,0.000223391,-0.0461371,-5.87593e-06,-2.54739e-05,2.11873e-05,9.25555e-06,-6.91667e-07,-6.8534e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.23465e-05,0.00165384,0.0016538,0.000943607,0.148115,0.148125,0.112676,0.0119652,0.0119655,0.0744203,3.76972e-07,3.77123e-07,2.27888e-07,2.50073e-06,2.50074e-06,2.41806e-06,0,0,0,0,0,0,0,0 -2088000,0.983515,-0.00812211,-0.0135733,0.180135,0.00971431,0.00124922,-0.132014,0.00193239,0.000229549,-0.0446699,-6.6264e-06,-2.78461e-05,1.46343e-05,8.83927e-06,-3.13597e-07,-8.7888e-05,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.26476e-05,0.00156686,0.00156682,0.000956082,0.139265,0.139274,0.103662,0.0116941,0.0116944,0.072067,3.45371e-07,3.45517e-07,2.08612e-07,2.50071e-06,2.50072e-06,2.3907e-06,0,0,0,0,0,0,0,0 -2192000,0.98351,-0.00807756,-0.0135497,0.180163,0.00846988,0.000754518,-0.132836,0.00173214,0.000239831,-0.0474539,-7.23878e-06,-3.02376e-05,1.26346e-05,8.35077e-06,4.16648e-08,-0.000103912,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.18574e-05,0.00148641,0.00148637,0.000935844,0.131714,0.131722,0.096116,0.011436,0.0114363,0.0697268,3.11383e-07,3.11525e-07,1.85519e-07,2.50055e-06,2.50056e-06,2.35712e-06,0,0,0,0,0,0,0,0 -2288000,0.983659,-0.00814627,-0.0134851,0.179349,0.00730803,0.000821232,-0.125773,0.00157476,0.000223183,-0.0435293,-7.51475e-06,-3.23071e-05,2.0975e-05,7.59832e-06,6.31686e-07,-0.000129891,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.07076e-05,0.00141704,0.00141701,0.0009041,0.126138,0.126147,0.0907955,0.0112342,0.0112345,0.0677769,2.8038e-07,2.80517e-07,1.65128e-07,2.50008e-06,2.50009e-06,2.32217e-06,0,0,0,0,0,0,0,0 -2392000,0.983663,-0.00816144,-0.0133991,0.179337,0.00782136,-0.000768679,-0.123048,0.00144909,0.00011039,-0.0400192,-8.03564e-06,-3.42221e-05,1.9834e-05,6.69561e-06,1.27865e-06,-0.000158121,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.9857e-05,0.00134135,0.00134133,0.000882093,0.121305,0.121313,0.0864441,0.0110523,0.0110525,0.065899,2.47538e-07,2.47667e-07,1.47181e-07,2.49909e-06,2.4991e-06,2.27973e-06,0,0,0,0,0,0,0,0 -2488000,0.983793,-0.00806154,-0.0133556,0.178628,0.00493139,0.000193844,-0.12509,0.00131033,5.16054e-05,-0.0432763,-8.40563e-06,-3.58916e-05,2.65232e-05,6.04695e-06,1.71546e-06,-0.000173872,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.87279e-05,0.00126801,0.001268,0.000850816,0.11725,0.117258,0.0834564,0.0109126,0.0109129,0.0643811,2.18319e-07,2.18439e-07,1.31419e-07,2.49771e-06,2.49773e-06,2.23609e-06,0,0,0,0,0,0,0,0 -2592000,0.98382,-0.00816722,-0.0132685,0.178479,0.00298669,-0.00201901,-0.128266,0.00100229,-3.37514e-05,-0.0480451,-8.92121e-06,-3.72538e-05,2.5367e-05,5.37577e-06,2.16029e-06,-0.000190036,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.78318e-05,0.00118388,0.00118389,0.000828731,0.112982,0.112987,0.0810827,0.0107797,0.01078,0.0629627,1.88376e-07,1.88485e-07,1.17584e-07,2.49575e-06,2.49576e-06,2.18379e-06,0,0,0,0,0,0,0,0 -2688000,0.983847,-0.00817912,-0.0132644,0.178332,0.00161973,-0.00104591,-0.126858,0.000747268,-0.000127111,-0.0483259,-9.35071e-06,-3.81348e-05,2.60783e-05,4.62485e-06,2.79257e-06,-0.000215469,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.77741e-05,0.00110265,0.00110267,0.000829763,0.108892,0.108898,0.0794985,0.0106655,0.0106657,0.0618514,1.62754e-07,1.62851e-07,1.08323e-07,2.49358e-06,2.49359e-06,2.13081e-06,0,0,0,0,0,0,0,0 -2792000,0.983834,-0.00807034,-0.0132924,0.178409,0.00238702,-0.00200874,-0.119737,0.0006292,-0.000182781,-0.0412613,-9.84805e-06,-3.87675e-05,2.3452e-05,3.52509e-06,3.82226e-06,-0.000260803,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.68842e-05,0.00101268,0.0010127,0.00080684,0.104215,0.104221,0.0782631,0.0105403,0.0105405,0.0608468,1.37557e-07,1.37642e-07,9.73084e-08,2.49097e-06,2.49097e-06,2.06836e-06,0,0,0,0,0,0,0,0 -2888000,0.983884,-0.00806703,-0.0133034,0.17813,0.00319474,-0.00242965,-0.117926,0.00052797,-0.00030749,-0.0389913,-1.02712e-05,-3.92224e-05,2.40971e-05,2.74734e-06,4.60448e-06,-0.000292885,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.58073e-05,0.000929901,0.000929922,0.000777468,0.0996281,0.0996326,0.0774325,0.0104187,0.0104189,0.0600872,1.16857e-07,1.16932e-07,8.76266e-08,2.48842e-06,2.48842e-06,2.00618e-06,0,0,0,0,0,0,0,0 -2992000,0.983918,-0.00801373,-0.0133084,0.177942,0.00256815,-0.00273625,-0.120728,0.000576352,-0.000379765,-0.043592,-1.07986e-05,-3.96463e-05,2.45198e-05,2.22192e-06,5.18169e-06,-0.000312067,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.50079e-05,0.0008428,0.000842823,0.000756024,0.0943556,0.0943591,0.0767431,0.010275,0.0102752,0.0594261,9.72613e-08,9.7325e-08,7.91015e-08,2.48562e-06,2.48563e-06,1.93421e-06,0,0,0,0,0,0,0,0 -3088000,0.98384,-0.00798172,-0.0133957,0.178369,0.0047212,-0.00364715,-0.121295,0.000615523,-0.000508575,-0.0455117,-1.14242e-05,-3.99378e-05,2.11755e-05,1.61314e-06,5.88507e-06,-0.000336929,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.40946e-05,0.000766482,0.000766504,0.000729106,0.0893494,0.0893524,0.076208,0.0101302,0.0101304,0.0589458,8.17044e-08,8.1759e-08,7.15826e-08,2.48311e-06,2.48311e-06,1.86392e-06,0,0,0,0,0,0,0,0 -3192000,0.983709,-0.00793188,-0.0134355,0.179091,0.00541007,-0.00481731,-0.126005,0.000755717,-0.000679395,-0.0545038,-1.22769e-05,-4.02232e-05,1.47247e-05,1.28122e-06,6.36551e-06,-0.00034614,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.34013e-05,0.000689577,0.000689597,0.000709328,0.0838215,0.0838236,0.0756524,0.00996036,0.00996048,0.0585441,6.73991e-08,6.74446e-08,6.49363e-08,2.48051e-06,2.48052e-06,1.78413e-06,0,0,0,0,0,0,0,0 -3288000,0.98369,-0.00785894,-0.0133308,0.179206,0.00467182,-0.00454075,-0.128654,0.000821676,-0.000818507,-0.0619249,-1.30503e-05,-4.05632e-05,1.34238e-05,8.76272e-07,6.95063e-06,-0.000359317,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.32955e-05,0.000624642,0.000624659,0.000707299,0.0787726,0.0787743,0.075101,0.00979261,0.00979271,0.0582623,5.63131e-08,5.63511e-08,6.04562e-08,2.47829e-06,2.47829e-06,1.70774e-06,0,0,0,0,0,0,0,0 -3392000,0.983618,-0.00762545,-0.0133137,0.179613,0.00356812,-0.00322416,-0.12603,0.000773376,-0.000808355,-0.0605746,-1.39051e-05,-4.08334e-05,9.48414e-06,-2.06341e-08,8.07664e-06,-0.000399599,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.26202e-05,0.000561147,0.000561155,0.000688052,0.0735178,0.0735193,0.0744101,0.00960282,0.00960289,0.0580311,4.63075e-08,4.63387e-08,5.50727e-08,2.47609e-06,2.47609e-06,1.62275e-06,0,0,0,0,0,0,0,0 -3488000,0.983526,-0.00749582,-0.0132622,0.180122,0.00567591,-4.57543e-05,-0.118079,0.000852719,-0.000611773,-0.0551756,-1.45894e-05,-4.10744e-05,5.14322e-06,-1.04354e-06,9.26804e-06,-0.000447325,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.18309e-05,0.000508777,0.00050878,0.000664666,0.0688054,0.068808,0.0736531,0.00942214,0.00942223,0.057867,3.86602e-08,3.86861e-08,5.02849e-08,2.47425e-06,2.47426e-06,1.54296e-06,0,0,0,0,0,0,0,0 -3592000,0.983502,-0.00735045,-0.0131333,0.180269,0.00641847,-0.000164399,-0.122392,0.00102765,-0.00038008,-0.0609649,-1.51001e-05,-4.14779e-05,3.30572e-06,-1.60008e-06,9.85859e-06,-0.000465968,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.12333e-05,0.000458486,0.000458486,0.000647197,0.0639993,0.0640012,0.0726796,0.00922308,0.00922318,0.0577227,3.18255e-08,3.18467e-08,4.60164e-08,2.47248e-06,2.47248e-06,1.45592e-06,0,0,0,0,0,0,0,0 -3688000,0.983562,-0.00734249,-0.0130946,0.179944,0.00525634,-0.00028325,-0.118135,0.00114848,-0.000274095,-0.0597312,-1.54063e-05,-4.19905e-05,5.39529e-06,-2.52666e-06,1.07233e-05,-0.000502518,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.05357e-05,0.000417573,0.000417571,0.00062608,0.0597808,0.059782,0.0716287,0.00903802,0.00903811,0.0576044,2.66348e-08,2.66525e-08,4.22022e-08,2.47102e-06,2.47102e-06,1.37574e-06,0,0,0,0,0,0,0,0 -3792000,0.983531,-0.00726124,-0.0130956,0.180118,0.00367024,0.00346929,-0.11691,0.00106517,2.87302e-05,-0.0610615,-1.56943e-05,-4.24685e-05,3.9066e-06,-3.34039e-06,1.14231e-05,-0.000532692,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.00106e-05,0.000378681,0.000378675,0.00061024,0.0555139,0.0555154,0.0703231,0.0088371,0.0088372,0.0574767,2.20122e-08,2.20266e-08,3.87855e-08,2.46962e-06,2.46962e-06,1.28984e-06,0,0,0,0,0,0,0,0 -3888000,0.983548,-0.00721052,-0.0131009,0.180025,0.00238943,0.00423792,-0.116136,0.000958511,0.000348379,-0.0641785,-1.57442e-05,-4.29165e-05,4.82896e-06,-3.98207e-06,1.18638e-05,-0.000554557,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.994e-05,0.000347281,0.00034727,0.000607745,0.0518313,0.0518322,0.0689698,0.00865335,0.00865344,0.0573475,1.85068e-08,1.85187e-08,3.64566e-08,2.46849e-06,2.46849e-06,1.21208e-06,0,0,0,0,0,0,0,0 -3992000,0.983085,-0.00719172,-0.0131029,0.18254,0.00389022,0.00465385,-0.114212,0.000887056,0.000557439,-0.0634608,-1.5736e-05,-4.33038e-05,3.15559e-06,-4.84081e-06,1.24907e-05,-0.000590069,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,8.00364e-05,0.000337875,0.000337644,0.00236114,0.0422996,0.0423,0.0673554,0.0084119,0.00841198,0.0571848,1.53901e-08,1.53997e-08,3.49984e-08,2.46744e-06,2.46744e-06,1.13014e-06,0,0,0,0,0,0,0,0 -4088000,0.98298,-0.00713389,-0.013019,0.183114,0.00427849,0.00455412,-0.0985652,0.000972345,0.000730993,-0.0500091,-1.56426e-05,-4.36872e-05,3.15017e-06,-6.13366e-06,1.36387e-05,-0.000654953,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,5.5932e-05,0.000338514,0.000338371,0.0016482,0.0348282,0.0348285,0.0657439,0.00800425,0.0080043,0.0570065,1.31081e-08,1.31159e-08,3.49911e-08,2.46706e-06,2.46706e-06,1.0571e-06,0,0,0,0,0,0,0,0 -4192000,0.983124,-0.00722726,-0.0129324,0.18234,0.00428827,0.00334423,-0.0960499,0.00100832,0.000801517,-0.0502542,-1.55201e-05,-4.4079e-05,3.34917e-06,-6.52213e-06,1.41322e-05,-0.000681113,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,4.30468e-05,0.000338362,0.00033827,0.00126834,0.0332689,0.0332691,0.0638876,0.00754065,0.00754069,0.0567772,1.12137e-08,1.122e-08,3.49704e-08,2.46688e-06,2.46687e-06,9.81216e-07,0,0,0,0,0,0,0,0 -4288000,0.983266,-0.00728598,-0.0129563,0.181571,0.00603686,0.00386143,-0.0994728,0.00115288,0.000823684,-0.0569741,-1.5418e-05,-4.44149e-05,3.63113e-06,-6.26054e-06,1.43701e-05,-0.00068856,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,3.50696e-05,0.000335402,0.000335337,0.00103294,0.035971,0.0359715,0.0620916,0.00721919,0.00721922,0.0565292,9.89395e-09,9.89916e-09,3.4931e-08,2.46489e-06,2.46488e-06,9.14453e-07,0,0,0,0,0,0,0,0 -4392000,0.983407,-0.00724522,-0.0129383,0.180804,0.00749286,0.00260789,-0.088321,0.00138786,0.000786953,-0.0462894,-1.53379e-05,-4.47823e-05,4.0917e-06,-6.27152e-06,1.54932e-05,-0.000741173,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,2.96782e-05,0.000326815,0.000326766,0.000874267,0.0415565,0.0415571,0.0600789,0.00705633,0.00705636,0.0562198,8.83483e-09,8.83917e-09,3.48679e-08,2.45724e-06,2.45724e-06,8.45907e-07,0,0,0,0,0,0,0,0 -4488000,0.983388,-0.0072959,-0.0128563,0.180915,0.00721218,0.00440754,-0.0856541,0.00159355,0.000888554,-0.0448867,-1.52949e-05,-4.5099e-05,4.02478e-06,-5.21734e-06,1.61306e-05,-0.000765366,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,2.58273e-05,0.000312328,0.000312293,0.00076007,0.0476111,0.0476122,0.0581785,0.00709169,0.00709173,0.0558964,8.14098e-09,8.14475e-09,3.47768e-08,2.44169e-06,2.44169e-06,7.86242e-07,0,0,0,0,0,0,0,0 -4592000,0.983299,-0.00727257,-0.0128601,0.181396,0.00784304,0.00287344,-0.0867189,0.00173371,0.00091049,-0.0491832,-1.52623e-05,-4.53965e-05,3.52941e-06,-3.0939e-06,1.66501e-05,-0.000776869,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,2.29816e-05,0.000289149,0.000289119,0.000675611,0.0534903,0.0534913,0.0560941,0.00729841,0.00729845,0.0555067,7.64611e-09,7.64947e-09,3.46534e-08,2.41307e-06,2.41306e-06,7.25565e-07,0,0,0,0,0,0,0,0 -4688000,0.983416,-0.0072507,-0.0127561,0.180768,0.00637003,0.00197582,-0.0770068,0.00181317,0.000855165,-0.0420547,-1.5225e-05,-4.56436e-05,4.29726e-06,-1.0663e-06,1.75315e-05,-0.00081263,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,2.13343e-05,0.000262219,0.000262193,0.000627814,0.0570638,0.0570645,0.0541628,0.00757794,0.00757799,0.0551124,7.37969e-09,7.38282e-09,3.45369e-08,2.37579e-06,2.37579e-06,6.73197e-07,0,0,0,0,0,0,0,0 -4792000,0.983364,-0.00712785,-0.0127536,0.181056,0.000678655,0.00232242,-0.0765495,0.0014313,0.000788005,-0.0439096,-1.5218e-05,-4.57977e-05,3.92241e-06,1.63402e-06,1.8068e-05,-0.000827077,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.95428e-05,0.000230208,0.000230181,0.000574633,0.0582422,0.0582424,0.052079,0.0078864,0.00788644,0.0546509,7.23853e-09,7.24155e-09,3.4348e-08,2.32672e-06,2.32672e-06,6.20338e-07,0,0,0,0,0,0,0,0 -4888000,0.983391,-0.00710159,-0.0127327,0.180916,-0.00053139,0.000185421,-0.0705332,0.000949983,0.000628593,-0.0402568,-1.51997e-05,-4.58731e-05,4.28548e-06,3.25834e-06,1.88674e-05,-0.000851159,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.8089e-05,0.000201332,0.000201305,0.000531696,0.056832,0.0568318,0.0501765,0.00810595,0.00810598,0.0541961,7.19107e-09,7.19404e-09,3.41173e-08,2.27788e-06,2.27787e-06,5.75019e-07,0,0,0,0,0,0,0,0 -4992000,0.983394,-0.00706505,-0.0126832,0.1809,-0.000418693,0.00106699,-0.0650197,0.000571905,0.000484419,-0.0368315,-1.51975e-05,-4.58945e-05,4.19281e-06,4.27405e-06,1.96683e-05,-0.000874127,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.69448e-05,0.000173702,0.000173676,0.000498481,0.0532233,0.0532233,0.0481501,0.00822964,0.00822966,0.053676,7.18055e-09,7.18353e-09,3.38422e-08,2.22613e-06,2.22613e-06,5.29538e-07,0,0,0,0,0,0,0,0 -5088000,0.983346,-0.00692829,-0.012592,0.181173,-0.000505025,0.00136125,-0.0627777,0.000346631,0.000388974,-0.0354697,-1.52126e-05,-4.5883e-05,3.52582e-06,4.78679e-06,2.03143e-05,-0.000890036,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.60039e-05,0.000152979,0.000152952,0.000470654,0.0487244,0.0487244,0.0463201,0.00823186,0.00823187,0.0531739,7.1799e-09,7.1829e-09,3.35205e-08,2.18269e-06,2.18269e-06,4.90738e-07,0,0,0,0,0,0,0,0 -5192000,0.983356,-0.0068167,-0.0126248,0.181124,-0.00335244,0.00402733,-0.0604169,5.71758e-05,0.000479452,-0.034016,-1.52137e-05,-4.58844e-05,3.80377e-06,4.95187e-06,2.10678e-05,-0.000906273,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.52881e-05,0.00013603,0.000136,0.000449409,0.0433309,0.043331,0.0443897,0.00812942,0.00812943,0.0526097,7.17331e-09,7.17634e-09,3.31509e-08,2.14213e-06,2.14213e-06,4.51961e-07,0,0,0,0,0,0,0,0 -5288000,0.983364,-0.00672905,-0.0125736,0.181088,-0.00183454,0.00507573,-0.0494327,-0.000132293,0.000684296,-0.0270223,-1.52264e-05,-4.58875e-05,4.03669e-06,4.62725e-06,2.22169e-05,-0.000930795,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.4964e-05,0.000125039,0.000125009,0.000439715,0.0383467,0.0383469,0.0426613,0.00796104,0.00796106,0.0520736,7.15791e-09,7.16095e-09,3.28416e-08,2.11103e-06,2.11103e-06,4.18995e-07,0,0,0,0,0,0,0,0 -5392000,0.983353,-0.00667257,-0.012563,0.181148,-0.0039766,0.00732315,-0.047424,-0.000329678,0.000943277,-0.0238309,-1.52646e-05,-4.58804e-05,3.72363e-06,4.3839e-06,2.35065e-05,-0.000946695,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.44834e-05,0.000117371,0.000117342,0.00042566,0.0333372,0.0333374,0.0408512,0.00772544,0.00772546,0.0514795,7.1328e-09,7.13586e-09,3.2387e-08,2.08371e-06,2.08372e-06,3.8614e-07,0,0,0,0,0,0,0,0 -5488000,0.98335,-0.00668345,-0.0126387,0.181159,-0.00323658,0.00938433,-0.0443125,-0.000530654,0.00130083,-0.0226062,-1.53149e-05,-4.58776e-05,3.48575e-06,4.13499e-06,2.49059e-05,-0.000957502,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.40461e-05,0.000113441,0.000113412,0.000412936,0.0291858,0.0291861,0.0392408,0.00747925,0.00747927,0.0509216,7.10551e-09,7.1086e-09,3.18843e-08,2.06361e-06,2.06363e-06,3.58269e-07,0,0,0,0,0,0,0,0 -5592000,0.983351,-0.00670152,-0.0126577,0.181154,-0.00358141,0.0119286,-0.0374898,-0.00059513,0.00182226,-0.0155999,-1.53914e-05,-4.58702e-05,3.06202e-06,3.72687e-06,2.6858e-05,-0.000977849,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.37395e-05,0.000111844,0.000111818,0.000404273,0.0252758,0.0252761,0.0375636,0.00719791,0.00719793,0.05031,7.07582e-09,7.07893e-09,3.1335e-08,2.04647e-06,2.04649e-06,3.3054e-07,0,0,0,0,0,0,0,0 -5688000,0.983338,-0.00668321,-0.0125851,0.18123,-0.00299338,0.0141169,-0.0394924,-0.000735446,0.00228801,-0.0170484,-1.54826e-05,-4.58532e-05,2.33628e-06,3.72412e-06,2.86306e-05,-0.000981737,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.34437e-05,0.000112285,0.000112261,0.000395838,0.0222136,0.0222139,0.0360784,0.00693572,0.00693575,0.0497409,7.05136e-09,7.0545e-09,3.0741e-08,2.03414e-06,2.03416e-06,3.07046e-07,0,0,0,0,0,0,0,0 -5792000,0.983386,-0.00655739,-0.0125578,0.180974,-0.00266663,0.0152043,-0.0370315,-0.00075477,0.00285907,-0.0147298,-1.55572e-05,-4.58611e-05,3.06022e-06,3.6513e-06,3.08076e-05,-0.000992382,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.32618e-05,0.000114375,0.000114352,0.000390783,0.0194488,0.019449,0.0345379,0.00665766,0.00665768,0.0491221,7.03041e-09,7.03358e-09,3.0105e-08,2.02385e-06,2.02387e-06,2.83692e-07,0,0,0,0,0,0,0,0 -5888000,0.98338,-0.00654584,-0.0126266,0.181001,-0.000232425,0.0152144,-0.0354911,-0.000671851,0.00336658,-0.0170081,-1.56398e-05,-4.5849e-05,2.97867e-06,3.87749e-06,3.27397e-05,-0.000994185,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.33139e-05,0.000117485,0.000117462,0.000392146,0.0173697,0.0173699,0.0331783,0.0064118,0.00641182,0.0485505,7.01717e-09,7.02037e-09,2.96027e-08,2.01663e-06,2.01667e-06,2.63915e-07,0,0,0,0,0,0,0,0 -5992000,0.983348,-0.00656957,-0.01276,0.181167,0.000480056,0.0139238,-0.0312881,-0.000463995,0.00370027,-0.0132621,-1.57331e-05,-4.58166e-05,2.00966e-06,4.03716e-06,3.49258e-05,-0.00100579,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.32216e-05,0.000121875,0.000121853,0.000389362,0.015596,0.0155963,0.0317722,0.00616179,0.00616182,0.0479329,7.00915e-09,7.01241e-09,2.89014e-08,2.01081e-06,2.01085e-06,2.44258e-07,0,0,0,0,0,0,0,0 -6088000,0.983313,-0.00657387,-0.0127038,0.181358,0.000233028,0.0135489,-0.0271343,-0.000338943,0.00389572,-0.00853299,-1.58191e-05,-4.57669e-05,-6.48873e-08,4.2142e-06,3.67687e-05,-0.00101748,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.3066e-05,0.000126695,0.000126676,0.000385505,0.0143634,0.0143637,0.0305344,0.00594928,0.00594931,0.0473655,7.00638e-09,7.00969e-09,2.81682e-08,2.00692e-06,2.00697e-06,2.2761e-07,0,0,0,0,0,0,0,0 -6192000,0.98328,-0.00661022,-0.0126864,0.181536,-6.1737e-06,0.0138186,-0.0267061,-0.000175783,0.0040972,-0.00860022,-1.58479e-05,-4.57472e-05,-1.00928e-06,4.58975e-06,3.836e-05,-0.00102187,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.30324e-05,0.000132596,0.000132579,0.000384264,0.0134335,0.0134337,0.0292568,0.00574221,0.00574224,0.0467554,7.00582e-09,7.0092e-09,2.74075e-08,2.00401e-06,2.00405e-06,2.11057e-07,0,0,0,0,0,0,0,0 -6288000,0.983265,-0.00660871,-0.0127071,0.18162,-0.00124199,0.0139937,-0.0306652,-0.000190473,0.0042701,-0.0144391,-1.5822e-05,-4.57529e-05,-1.30033e-06,5.09082e-06,3.94335e-05,-0.00101741,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29518e-05,0.000138546,0.00013853,0.000381504,0.0129239,0.0129242,0.0281341,0.00557498,0.00557501,0.0461975,7.00402e-09,7.00747e-09,2.66241e-08,2.00226e-06,2.00231e-06,1.97031e-07,0,0,0,0,0,0,0,0 -6392000,0.983293,-0.00657907,-0.0126321,0.18147,-0.000258222,0.0137431,-0.0309315,-0.000245119,0.00444283,-0.016048,-1.5725e-05,-4.57923e-05,-7.3809e-07,5.36225e-06,4.0466e-05,-0.00101972,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29414e-05,0.000145398,0.000145384,0.000381149,0.012722,0.0127222,0.026977,0.00542275,0.00542277,0.0455998,6.99555e-09,6.99906e-09,2.58227e-08,2.00117e-06,2.00123e-06,1.83075e-07,0,0,0,0,0,0,0,0 -6488000,0.983291,-0.00655618,-0.0126581,0.181483,-0.00196863,0.0115566,-0.0287459,-0.000289539,0.0044425,-0.0137799,-1.56086e-05,-4.58231e-05,-1.34118e-06,5.40952e-06,4.12441e-05,-0.00102678,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.30909e-05,0.000151961,0.000151948,0.00038575,0.0128377,0.0128378,0.0259612,0.00531143,0.00531145,0.045055,6.97591e-09,6.97945e-09,2.52136e-08,2.00069e-06,2.00075e-06,1.71239e-07,0,0,0,0,0,0,0,0 -6592000,0.983261,-0.00655322,-0.012599,0.18165,-0.00272157,0.0114185,-0.0325892,-0.000412256,0.00434126,-0.017529,-1.54382e-05,-4.58571e-05,-2.59491e-06,5.5564e-06,4.16062e-05,-0.00102612,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.30926e-05,0.000159144,0.000159133,0.000385793,0.0132701,0.0132702,0.0249152,0.00522526,0.00522529,0.0444731,6.93404e-09,6.9376e-09,2.4392e-08,2.00054e-06,2.0006e-06,1.5945e-07,0,0,0,0,0,0,0,0 -6688000,0.983237,-0.00652348,-0.0125773,0.181781,-0.00559885,0.0115371,-0.0347452,-0.00069926,0.00434643,-0.0172303,-1.52185e-05,-4.58985e-05,-3.48939e-06,5.46933e-06,4.17419e-05,-0.00103083,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.30299e-05,0.000165645,0.000165636,0.000383802,0.0139218,0.0139219,0.0239976,0.00517956,0.00517958,0.0439441,6.86879e-09,6.87234e-09,2.35653e-08,2.00052e-06,2.00059e-06,1.4944e-07,0,0,0,0,0,0,0,0 -6792000,0.983197,-0.00658958,-0.0125458,0.181996,-0.00298392,0.0123207,-0.033635,-0.00092672,0.00437486,-0.0187949,-1.49177e-05,-4.59303e-05,-4.83942e-06,5.38705e-06,4.15062e-05,-0.00103326,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.30399e-05,0.00017229,0.000172283,0.000383899,0.0148378,0.014838,0.0230531,0.00516758,0.0051676,0.0433803,6.76067e-09,6.76416e-09,2.27378e-08,2.00043e-06,2.0005e-06,1.39458e-07,0,0,0,0,0,0,0,0 -6888000,0.983179,-0.00644258,-0.012435,0.182107,-0.00287952,0.0103154,-0.0302896,-0.000973482,0.00431212,-0.0174559,-1.45683e-05,-4.59723e-05,-5.55996e-06,5.18317e-06,4.10386e-05,-0.00103869,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29776e-05,0.000177798,0.000177791,0.000381856,0.0158396,0.0158397,0.0222249,0.0051907,0.00519072,0.0428689,6.61913e-09,6.62254e-09,2.19135e-08,2.00008e-06,2.00015e-06,1.3097e-07,0,0,0,0,0,0,0,0 -6992000,0.983172,-0.00647018,-0.0123852,0.182146,-0.00312232,0.0102338,-0.0287342,-0.00104575,0.00419852,-0.0171811,-1.41245e-05,-4.60265e-05,-5.84973e-06,4.98107e-06,4.0185e-05,-0.00104269,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29841e-05,0.000182793,0.000182788,0.000381784,0.0170366,0.0170367,0.0213726,0.00525025,0.00525026,0.0423248,6.41466e-09,6.4179e-09,2.10962e-08,1.9992e-06,1.99927e-06,1.22493e-07,0,0,0,0,0,0,0,0 -7088000,0.983149,-0.00644027,-0.012314,0.182278,-0.00332532,0.0128217,-0.0293737,-0.00109995,0.00430437,-0.0192444,-1.36585e-05,-4.60793e-05,-6.03564e-06,4.8501e-06,3.90574e-05,-0.00104357,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.2931e-05,0.000186258,0.000186253,0.000379509,0.0181756,0.018176,0.0206252,0.00533306,0.00533308,0.0418321,6.17598e-09,6.17903e-09,2.02893e-08,1.99779e-06,1.99786e-06,1.15274e-07,0,0,0,0,0,0,0,0 -7192000,0.983122,-0.00645733,-0.0123975,0.182417,-0.00341364,0.0123422,-0.0299306,-0.00117353,0.00443535,-0.0233412,-1.30959e-05,-4.61287e-05,-6.81812e-06,4.74485e-06,3.74666e-05,-0.00104257,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29286e-05,0.000188549,0.000188544,0.000379132,0.0193587,0.019359,0.0198561,0.00544584,0.00544587,0.0413086,5.86443e-09,5.86723e-09,1.94957e-08,1.9955e-06,1.99557e-06,1.08054e-07,0,0,0,0,0,0,0,0 -7288000,0.983109,-0.00653418,-0.0123812,0.182485,-0.00180672,0.0135385,-0.0276093,-0.00115747,0.00448156,-0.0205281,-1.25232e-05,-4.61834e-05,-7.28548e-06,4.41766e-06,3.5873e-05,-0.00104873,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.30754e-05,0.000189197,0.000189191,0.000383241,0.0203448,0.0203454,0.0191815,0.00556327,0.0055633,0.040835,5.53296e-09,5.53549e-09,1.89101e-08,1.99264e-06,1.99272e-06,1.01896e-07,0,0,0,0,0,0,0,0 -7392000,0.983137,-0.00655917,-0.0123663,0.182336,-0.00239258,0.013483,-0.0258295,-0.00103931,0.00459874,-0.0178861,-1.18367e-05,-4.62866e-05,-6.64513e-06,4.00014e-06,3.38779e-05,-0.00105452,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.30544e-05,0.000188287,0.000188281,0.000382471,0.02123,0.0212306,0.0184872,0.00569548,0.00569552,0.0403325,5.13584e-09,5.13805e-09,1.81457e-08,1.98877e-06,1.98885e-06,9.57269e-08,0,0,0,0,0,0,0,0 -7488000,0.983163,-0.00666354,-0.0123654,0.182189,-0.000289058,0.0138347,-0.0204316,-0.000885123,0.00460615,-0.0121992,-1.11749e-05,-4.64087e-05,-5.68357e-06,3.44726e-06,3.19306e-05,-0.00106279,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29675e-05,0.000186048,0.000186042,0.00037951,0.0218228,0.0218234,0.0178782,0.00581342,0.00581347,0.0398784,4.74555e-09,4.74748e-09,1.7401e-08,1.98458e-06,1.98466e-06,9.04565e-08,0,0,0,0,0,0,0,0 -7592000,0.983173,-0.00687307,-0.0123105,0.182132,0.00067086,0.0124848,-0.0178778,-0.000628682,0.00451213,-0.00789748,-1.04794e-05,-4.65583e-05,-5.30561e-06,2.80553e-06,2.97058e-05,-0.00106925,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29368e-05,0.000182304,0.000182301,0.000378333,0.022222,0.0222226,0.0172511,0.00592848,0.00592853,0.0393968,4.31119e-09,4.31281e-09,1.66773e-08,1.97953e-06,1.97961e-06,8.51678e-08,0,0,0,0,0,0,0,0 -7688000,0.983178,-0.00699372,-0.0123589,0.182099,0.00121563,0.0125988,-0.0181604,-0.000405452,0.00446209,-0.00396652,-9.86963e-06,-4.67176e-05,-5.29729e-06,2.10989e-06,2.76577e-05,-0.00107486,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.28272e-05,0.000177872,0.000177868,0.000375053,0.0223675,0.0223681,0.0167007,0.00601758,0.00601763,0.038962,3.91185e-09,3.91319e-09,1.59759e-08,1.97455e-06,1.97463e-06,8.06426e-08,0,0,0,0,0,0,0,0 -7792000,0.98317,-0.00700332,-0.0123582,0.18214,0.00281457,0.0104605,-0.0195973,-0.000134078,0.00419403,-0.00784729,-9.24959e-06,-4.69124e-05,-5.28063e-06,1.4979e-06,2.53513e-05,-0.00107296,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.27861e-05,0.000172306,0.000172301,0.000373489,0.0222668,0.0222672,0.0161338,0.00609144,0.0060915,0.0385012,3.49293e-09,3.49399e-09,1.52977e-08,1.96901e-06,1.96908e-06,7.60945e-08,0,0,0,0,0,0,0,0 -7888000,0.983155,-0.00714296,-0.0123931,0.182211,0.00193777,0.0102303,-0.0203641,1.32417e-05,0.00396157,-0.0106284,-8.73439e-06,-4.71064e-05,-5.10232e-06,8.4081e-07,2.34098e-05,-0.00107214,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.29037e-05,0.000166729,0.000166723,0.000376323,0.0219805,0.0219809,0.0156361,0.00613712,0.00613717,0.0380853,3.1273e-09,3.12811e-09,1.48045e-08,1.96389e-06,1.96397e-06,7.21969e-08,0,0,0,0,0,0,0,0 -7992000,0.983171,-0.0072209,-0.0122844,0.182134,0.00232932,0.00813827,-0.0184215,0.00018197,0.00360755,-0.0103864,-8.2296e-06,-4.73232e-05,-4.34034e-06,2.6589e-08,2.15708e-05,-0.00107429,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.2851e-05,0.00016047,0.000160464,0.000374341,0.0214946,0.0214948,0.0151231,0.0061625,0.00616254,0.0376449,2.76026e-09,2.76084e-09,1.41683e-08,1.95851e-06,1.95858e-06,6.82733e-08,0,0,0,0,0,0,0,0 -8088000,0.983152,-0.00723242,-0.0122508,0.182234,0.00344982,0.00783197,-0.0170488,0.000398825,0.00331031,-0.00921351,-7.86125e-06,-4.74978e-05,-4.96796e-06,-7.62183e-07,2.01219e-05,-0.0010769,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.27167e-05,0.000154689,0.000154682,0.000370414,0.0209286,0.0209288,0.0146725,0.00616513,0.00616517,0.0372476,2.4515e-09,2.45188e-09,1.35564e-08,1.95376e-06,1.95384e-06,6.49055e-08,0,0,0,0,0,0,0,0 -8192000,0.983143,-0.00740335,-0.0121302,0.182284,0.00374288,0.00908351,-0.0137266,0.000606212,0.00317536,-0.00464712,-7.50813e-06,-4.77014e-05,-5.13288e-06,-1.7398e-06,1.88101e-05,-0.00108242,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.26449e-05,0.000148587,0.000148582,0.00036813,0.020221,0.0202213,0.0142079,0.00614816,0.00614819,0.0368269,2.15079e-09,2.15099e-09,1.29688e-08,1.94895e-06,1.94902e-06,6.15099e-08,0,0,0,0,0,0,0,0 -8288000,0.983167,-0.0074843,-0.0120648,0.182159,0.00576791,0.00822225,-0.0114004,0.000841295,0.00304263,-0.0027813,-7.20743e-06,-4.79075e-05,-4.69573e-06,-2.60909e-06,1.76683e-05,-0.00108497,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.25027e-05,0.000143209,0.000143204,0.000364,0.0195086,0.0195089,0.0137995,0.00611664,0.00611668,0.0364476,1.90383e-09,1.9039e-09,1.24054e-08,1.94484e-06,1.94491e-06,5.85906e-08,0,0,0,0,0,0,0,0 -8392000,0.983183,-0.00752756,-0.012017,0.182071,0.00282359,0.00553319,-0.0105849,0.000978155,0.00277363,-0.000577505,-6.93011e-06,-4.81325e-05,-4.21599e-06,-3.57565e-06,1.66133e-05,-0.00108775,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.24213e-05,0.000137732,0.000137727,0.000361463,0.0187113,0.0187114,0.0133782,0.00606883,0.00606886,0.0360461,1.66775e-09,1.66769e-09,1.18658e-08,1.94076e-06,1.94083e-06,5.56426e-08,0,0,0,0,0,0,0,0 -8488000,0.983214,-0.00752025,-0.0119671,0.181906,0.00168645,0.00579545,-0.011918,0.000935656,0.00249429,-0.00549591,-6.70339e-06,-4.83306e-05,-3.1947e-06,-4.22618e-06,1.56559e-05,-0.00108463,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.24894e-05,0.000133034,0.000133028,0.000363166,0.0179588,0.0179589,0.0130077,0.00601454,0.00601456,0.0356841,1.47661e-09,1.47645e-09,1.14766e-08,1.93734e-06,1.9374e-06,5.31041e-08,0,0,0,0,0,0,0,0 -8592000,0.983246,-0.00759382,-0.0120297,0.181727,0.00221353,0.00461569,-0.00637001,0.000824936,0.00231679,-4.18379e-05,-6.50349e-06,-4.85058e-05,-2.64551e-06,-5.07475e-06,1.49729e-05,-0.00108969,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.23867e-05,0.000128347,0.00012834,0.000360347,0.0171442,0.0171443,0.0126251,0.00594711,0.00594713,0.0353011,1.29566e-09,1.29541e-09,1.09775e-08,1.93399e-06,1.93406e-06,5.05364e-08,0,0,0,0,0,0,0,0 -8688000,0.983287,-0.00770836,-0.0120511,0.1815,0.00122883,0.00223831,-0.00861972,0.000730939,0.00200507,-0.00188353,-6.34011e-06,-4.86469e-05,-1.89583e-06,-5.59425e-06,1.42948e-05,-0.00108879,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.22258e-05,0.000124389,0.000124382,0.000355857,0.016422,0.0164219,0.0122885,0.00587924,0.00587925,0.0349558,1.15013e-09,1.14982e-09,1.05009e-08,1.93121e-06,1.93128e-06,5e-08,0,0,0,0,0,0,0,0 -8792000,0.983298,-0.00775771,-0.0119895,0.181441,0.00179847,0.000696352,-0.00957419,0.000598311,0.00159115,7.75807e-05,-6.21612e-06,-4.8756e-05,-1.79912e-06,-6.12662e-06,1.38124e-05,-0.00109097,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.21193e-05,0.000120484,0.000120477,0.000352883,0.0156666,0.0156665,0.0119414,0.00580165,0.00580165,0.0345906,1.01298e-09,1.01261e-09,1.00459e-08,1.9285e-06,1.92857e-06,5e-08,0,0,0,0,0,0,0,0 -8888000,0.983354,-0.00789381,-0.0119663,0.181135,0.000966385,0.000223026,-0.00583363,0.000568333,0.00123699,0.00591351,-6.11053e-06,-4.88571e-05,-5.77982e-07,-6.60956e-06,1.35975e-05,-0.00109583,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.19605e-05,0.00011721,0.000117204,0.000348337,0.0149897,0.0149895,0.011637,0.00572763,0.00572763,0.0342614,9.02893e-10,9.02476e-10,9.61203e-09,1.92626e-06,1.92633e-06,5e-08,0,0,0,0,0,0,0,0 -8992000,0.983419,-0.00788913,-0.0118546,0.180789,-0.000699453,-0.000282951,-0.00411493,0.000374923,0.000876499,0.00433041,-6.01824e-06,-4.89479e-05,9.69371e-07,-6.85937e-06,1.32967e-05,-0.00109501,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.18554e-05,0.000113997,0.000113991,0.000345252,0.0142872,0.014287,0.0113242,0.00564555,0.00564554,0.0339133,7.99186e-10,7.98728e-10,9.19839e-09,1.92408e-06,1.92415e-06,5e-08,0,0,0,0,0,0,0,0 -9088000,0.983481,-0.00793834,-0.0119088,0.180446,-0.000443893,-0.000352369,-0.00659181,0.000235595,0.000607328,0.00193962,-5.95743e-06,-4.90031e-05,2.07937e-06,-6.9759e-06,1.30772e-05,-0.00109368,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.18729e-05,0.000111318,0.00011131,0.000346149,0.0136827,0.0136825,0.0110511,0.00556935,0.00556933,0.0335997,7.15927e-10,7.15433e-10,8.90121e-09,1.92229e-06,1.92235e-06,5e-08,0,0,0,0,0,0,0,0 -9192000,0.983541,-0.00795878,-0.0119364,0.180113,0.00224977,-0.00196858,-0.00522722,0.000257093,0.000376117,0.00183091,-5.90838e-06,-4.90492e-05,3.20326e-06,-7.09675e-06,1.29692e-05,-0.00109402,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.17504e-05,0.000108693,0.000108684,0.000342908,0.013058,0.0130578,0.0107717,0.00548702,0.00548701,0.0332683,6.37302e-10,6.36783e-10,8.52115e-09,1.92054e-06,1.9206e-06,5e-08,0,0,0,0,0,0,0,0 -9288000,0.983588,-0.00788371,-0.0117726,0.179871,0.00342869,-0.0029943,-0.00315308,0.00047122,3.45703e-05,0.00483863,-5.88605e-06,-4.90902e-05,4.13156e-06,-7.26467e-06,1.30407e-05,-0.00109631,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.15848e-05,0.000106502,0.000106494,0.000338258,0.012517,0.0125168,0.0105288,0.00541174,0.00541172,0.03297,5.73968e-10,5.73435e-10,8.15922e-09,1.91909e-06,1.91915e-06,5e-08,0,0,0,0,0,0,0,0 -9392000,0.983589,-0.00781216,-0.0117881,0.179869,0.00314344,-0.00467611,-0.00249746,0.000675046,-0.000299919,0.00384395,-5.90917e-06,-4.91151e-05,3.95652e-06,-7.39031e-06,1.31164e-05,-0.00109582,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.14631e-05,0.000104359,0.000104349,0.000334984,0.0119661,0.0119659,0.0102816,0.0053314,0.00533138,0.0326551,5.13994e-10,5.13451e-10,7.81463e-09,1.91768e-06,1.91773e-06,5e-08,0,0,0,0,0,0,0,0 -9488000,0.983638,-0.0078743,-0.0118576,0.179591,0.00241411,-0.00604355,-0.000537015,0.000738637,-0.000712924,0.00629399,-5.92959e-06,-4.9153e-05,4.69415e-06,-7.54472e-06,1.33621e-05,-0.00109749,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.12913e-05,0.00010257,0.00010256,0.000330395,0.0114901,0.0114898,0.0100678,0.00525877,0.00525874,0.0323721,4.65499e-10,4.64952e-10,7.48662e-09,1.91651e-06,1.91656e-06,5e-08,0,0,0,0,0,0,0,0 -9592000,0.983598,-0.00796173,-0.0118388,0.179811,0.00189982,-0.00817132,7.90729e-05,0.000665916,-0.00122151,0.00540669,-6.00372e-06,-4.91535e-05,3.91877e-06,-7.60895e-06,1.36233e-05,-0.00109687,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.11782e-05,0.000100817,0.000100807,0.00032711,0.0110072,0.0110068,0.00985141,0.00518192,0.00518189,0.0320738,4.1939e-10,4.18838e-10,7.17442e-09,1.91536e-06,1.91541e-06,5e-08,0,0,0,0,0,0,0,0 -9688000,0.983619,-0.0079688,-0.0117604,0.179699,0.00124105,-0.00989254,0.0014724,0.000715198,-0.00165076,0.00406876,-6.07061e-06,-4.91609e-05,3.98571e-06,-7.61702e-06,1.39328e-05,-0.001096,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.1009e-05,9.93509e-05,9.93415e-05,0.000322598,0.0105885,0.0105881,0.00966526,0.0051129,0.00511287,0.0318063,3.8194e-10,3.81389e-10,6.87729e-09,1.91441e-06,1.91446e-06,5e-08,0,0,0,0,0,0,0,0 -9792000,0.983593,-0.00794653,-0.0117089,0.179848,0.00165106,-0.010339,0.00135204,0.000687113,-0.00216308,0.00536864,-6.17687e-06,-4.91442e-05,3.19797e-06,-7.61805e-06,1.44225e-05,-0.00109672,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.08879e-05,9.79112e-05,9.79016e-05,0.000319343,0.0101693,0.0101689,0.00947795,0.00504037,0.00504032,0.031525,3.4617e-10,3.45619e-10,6.59451e-09,1.91348e-06,1.91353e-06,5e-08,0,0,0,0,0,0,0,0 -9888000,0.983626,-0.00793678,-0.0116802,0.179666,0.00249733,-0.0117533,0.002575,0.000681641,-0.00271466,0.00471446,-6.25825e-06,-4.91479e-05,3.87995e-06,-7.54828e-06,1.4894e-05,-0.0010962,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.08919e-05,9.67052e-05,9.66952e-05,0.000319557,0.00980414,0.00980367,0.00931782,0.00497552,0.00497547,0.0312733,3.17008e-10,3.16453e-10,6.39129e-09,1.9127e-06,1.91275e-06,5e-08,0,0,0,0,0,0,0,0 -9992000,0.983596,-0.00796089,-0.0117356,0.179829,0.00361672,-0.0133752,0.00290737,0.000788305,-0.00328289,0.00283884,-6.38986e-06,-4.91211e-05,3.27418e-06,-7.43274e-06,1.54542e-05,-0.0010949,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.07765e-05,9.55176e-05,9.55069e-05,0.000316241,0.00943519,0.0094347,0.0091577,0.00490752,0.00490747,0.0310094,2.8899e-10,2.88439e-10,6.13196e-09,1.91194e-06,1.91198e-06,5e-08,0,0,0,0,0,0,0,0 -10088000,0.983578,-0.00790089,-0.0118608,0.17992,0.00193054,-0.0162729,0.0033987,0.000864808,-0.00390276,0.00406541,-6.52641e-06,-4.90924e-05,2.62933e-06,-7.33237e-06,1.61286e-05,-0.00109543,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.06143e-05,9.45201e-05,9.45077e-05,0.000311819,0.00911855,0.0091179,0.00902175,0.00484689,0.00484683,0.030774,2.66014e-10,2.65468e-10,5.88511e-09,1.9113e-06,1.91134e-06,5e-08,0,0,0,0,0,0,0,0 -10192000,0.983543,-0.00786733,-0.0117722,0.180121,-0.000634127,-0.016096,0.00438438,0.000727265,-0.00449273,0.0030186,-6.68924e-06,-4.90509e-05,1.80807e-06,-7.15426e-06,1.68622e-05,-0.00109457,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.04988e-05,9.3534e-05,9.35219e-05,0.000308565,0.00879558,0.00879498,0.00888688,0.00478355,0.00478348,0.0305279,2.43858e-10,2.43318e-10,5.65011e-09,1.91067e-06,1.91071e-06,5e-08,0,0,0,0,0,0,0,0 -10288000,0.983588,-0.0078839,-0.0116915,0.17988,-0.000282098,-0.016229,0.00347034,0.000516468,-0.00499266,0.00385963,-6.81693e-06,-4.90273e-05,2.35985e-06,-6.93582e-06,1.76229e-05,-0.00109483,0.203363,-1.39698e-09,0.43388,0,0,0,0,0,1.03411e-05,9.27027e-05,9.26913e-05,0.000304266,0.00852013,0.00851956,0.00877331,0.00472722,0.00472714,0.0303091,2.25601e-10,2.25068e-10,5.42636e-09,1.91013e-06,1.91017e-06,5e-08,0,0,0,0,0,0,0,0 -10392000,0.983235,-0.00788582,-0.0116092,0.181803,0.00689366,0.000473582,-0.00237472,0.00080904,-5.22115e-05,0.00419042,-6.81687e-06,-4.90274e-05,2.36292e-06,-6.93818e-06,1.76339e-05,-0.00109506,0.205007,0.000821404,0.434388,0,0,0,0,0,6.23997e-05,9.31321e-05,9.30096e-05,0.00181482,0.0349972,0.0349973,0.0374296,0.125319,0.125319,0.0280982,2.25654e-10,2.25121e-10,5.42636e-09,1.91014e-06,1.91017e-06,5e-08,0,0,0,0,0,0,0,0 -10488000,0.983141,-0.00781382,-0.0115551,0.182317,0.00724258,-0.00239952,-0.000729606,0.00147867,-0.000165009,0.00692264,-6.81717e-06,-4.90272e-05,2.35014e-06,-6.95563e-06,1.77142e-05,-0.00109669,0.205007,0.000821404,0.434388,0,0,0,0,0,4.98846e-05,9.3144e-05,9.30497e-05,0.00145188,0.0367006,0.0367006,0.0374476,0.126288,0.126288,0.0268582,2.25704e-10,2.2517e-10,5.42622e-09,1.91014e-06,1.91017e-06,5e-08,0,0,0,0,0,0,0,0 -10592000,0.983279,-0.00779771,-0.0114769,0.181575,0.0047312,-0.00444964,0.000796401,0.00111502,-0.000310587,0.0093649,-6.81597e-06,-4.9027e-05,2.38317e-06,-4.51108e-06,1.64332e-05,-0.00109796,0.205007,0.000821404,0.434388,0,0,0,0,0,3.94233e-05,9.27956e-05,9.27256e-05,0.00114652,0.0347581,0.0347579,0.0350112,0.0849751,0.0849751,0.0261867,2.25756e-10,2.25222e-10,5.42568e-09,1.90343e-06,1.90346e-06,5e-08,0,0,0,0,0,0,0,0 -10688000,0.983305,-0.00777358,-0.0114895,0.181437,0.00576184,-0.00791749,0.000706171,0.00164144,-0.00089079,0.00920666,-6.81595e-06,-4.9027e-05,2.38431e-06,-4.50984e-06,1.64271e-05,-0.00109784,0.205007,0.000821404,0.434388,0,0,0,0,0,3.25615e-05,9.28668e-05,9.28111e-05,0.000947684,0.0386641,0.0386635,0.0347593,0.0867491,0.0867491,0.026232,2.25804e-10,2.25271e-10,5.42464e-09,1.90344e-06,1.90347e-06,5e-08,0,0,0,0,0,0,0,0 -10792000,0.983326,-0.00779225,-0.0116074,0.181316,0.00563263,-0.0107591,0.00139497,0.00149382,-0.00165839,0.0107566,-6.81577e-06,-4.90264e-05,2.39061e-06,-2.605e-06,1.63433e-05,-0.00109856,0.205007,0.000821404,0.434388,0,0,0,0,0,2.77478e-05,9.14815e-05,9.14331e-05,0.000808127,0.038034,0.0380333,0.0323223,0.0660145,0.0660145,0.0264086,2.25852e-10,2.25319e-10,5.42299e-09,1.87786e-06,1.87789e-06,5e-08,0,0,0,0,0,0,0,0 -10888000,0.983438,-0.0077873,-0.0116276,0.180706,0.00550652,-0.0123829,-0.000481875,0.00199806,-0.00281025,0.00795725,-6.81345e-06,-4.90283e-05,2.49762e-06,-2.59383e-06,1.62871e-05,-0.00109735,0.205007,0.000821404,0.434388,0,0,0,0,0,2.42159e-05,9.16002e-05,9.15594e-05,0.00070474,0.0437561,0.0437551,0.0317572,0.0685607,0.0685607,0.0271349,2.259e-10,2.25367e-10,5.42059e-09,1.87787e-06,1.87789e-06,5e-08,0,0,0,0,0,0,0,0 -10992000,0.983414,-0.00776938,-0.0117155,0.180831,0.00364688,-0.00768318,0.00195077,0.00173101,-0.00249159,0.00984583,-6.81227e-06,-4.90275e-05,2.46004e-06,-2.45521e-06,1.07133e-05,-0.00109795,0.205007,0.000821404,0.434388,0,0,0,0,0,2.14803e-05,8.88443e-05,8.8807e-05,0.000625388,0.0429885,0.0429878,0.029342,0.0558777,0.0558776,0.027636,2.25946e-10,2.25413e-10,5.41734e-09,1.82812e-06,1.82814e-06,5e-08,0,0,0,0,0,0,0,0 -11088000,0.983344,-0.00790611,-0.0116807,0.181205,0.00383032,-0.00670372,0.00671387,0.00205189,-0.00324833,0.0160406,-6.81445e-06,-4.90258e-05,2.35924e-06,-2.47609e-06,1.08039e-05,-0.00109997,0.205007,0.000821404,0.434388,0,0,0,0,0,1.98335e-05,8.90047e-05,8.89738e-05,0.000577382,0.0500256,0.0500249,0.0285203,0.0592558,0.0592558,0.0286386,2.25993e-10,2.25461e-10,5.41431e-09,1.82812e-06,1.82814e-06,5e-08,0,0,0,0,0,0,0,0 -11192000,0.983299,-0.00793385,-0.0116672,0.181451,0.00390406,-0.00440356,0.0108522,0.00259829,-0.00270284,0.0196275,-6.8162e-06,-4.90246e-05,2.24939e-06,-6.22469e-06,8.42729e-06,-0.00110057,0.205007,0.000821404,0.434388,0,0,0,0,0,1.79736e-05,8.5005e-05,8.49782e-05,0.000523982,0.0479494,0.0479489,0.0262065,0.0503343,0.0503342,0.0291529,2.2604e-10,2.25509e-10,5.40933e-09,1.75659e-06,1.75662e-06,5e-08,0,0,0,0,0,0,0,0 -11288000,0.983289,-0.00796474,-0.0116919,0.181504,0.0032526,-0.00639021,0.0116089,0.00291776,-0.00317098,0.0210708,-6.81668e-06,-4.90242e-05,2.22708e-06,-6.22538e-06,8.43183e-06,-0.00110068,0.205007,0.000821404,0.434388,0,0,0,0,0,1.64669e-05,8.5202e-05,8.51787e-05,0.000479958,0.0557478,0.055747,0.02523,0.0545665,0.0545664,0.0301644,2.26086e-10,2.25556e-10,5.4032e-09,1.7566e-06,1.75662e-06,5e-08,0,0,0,0,0,0,0,0 -11392000,0.983305,-0.00784353,-0.0116893,0.18142,0.00138656,-0.0054972,0.00701529,0.00231558,-0.00258991,0.0154698,-6.81583e-06,-4.90244e-05,2.24272e-06,-5.52105e-06,4.03565e-06,-0.00109908,0.205007,0.000821404,0.434388,0,0,0,0,0,1.52044e-05,8.0433e-05,8.04099e-05,0.000443439,0.0517369,0.0517362,0.0230991,0.047445,0.047445,0.0305281,2.26135e-10,2.25605e-10,5.39584e-09,1.67157e-06,1.67159e-06,5e-08,0,0,0,0,0,0,0,0 -11488000,0.983329,-0.00783444,-0.0116592,0.181293,-0.000704032,-0.00830471,0.0100852,0.0022827,-0.0032154,0.0195045,-6.81558e-06,-4.90246e-05,2.25347e-06,-5.53259e-06,4.0662e-06,-0.00109982,0.205007,0.000821404,0.434388,0,0,0,0,0,1.41273e-05,8.06658e-05,8.06454e-05,0.000412415,0.0597602,0.0597591,0.022073,0.052472,0.0524718,0.0313942,2.2618e-10,2.25651e-10,5.38713e-09,1.67158e-06,1.6716e-06,5e-08,0,0,0,0,0,0,0,0 -11592000,0.983323,-0.00787814,-0.0116568,0.181326,0.00108477,-0.00734292,0.0107924,0.00197042,-0.00257844,0.0199921,-6.81692e-06,-4.90236e-05,2.20151e-06,-7.10649e-06,-3.55706e-07,-0.00109994,0.205007,0.000821404,0.434388,0,0,0,0,0,1.32198e-05,7.56978e-05,7.56784e-05,0.000386138,0.0537807,0.0537799,0.0201813,0.046112,0.0461119,0.0315462,2.26228e-10,2.257e-10,5.37699e-09,1.58313e-06,1.58315e-06,5e-08,0,0,0,0,0,0,0,0 -11688000,0.983324,-0.00783882,-0.011632,0.181318,0.00124355,-0.0075198,0.0127531,0.00209664,-0.00331027,0.0210078,-6.81637e-06,-4.9024e-05,2.22711e-06,-7.10684e-06,-3.57269e-07,-0.0010999,0.205007,0.000821404,0.434388,0,0,0,0,0,1.2653e-05,7.59659e-05,7.59476e-05,0.000369459,0.061606,0.0616051,0.0191892,0.051801,0.0518009,0.0322004,2.26273e-10,2.25747e-10,5.36842e-09,1.58314e-06,1.58315e-06,5e-08,0,0,0,0,0,0,0,0 -11792000,0.983369,-0.00790118,-0.0116176,0.181074,1.94304e-05,-0.00665883,0.0134848,0.00163691,-0.00375202,0.0219465,-6.81219e-06,-4.90275e-05,2.3996e-06,-5.98713e-06,1.4236e-07,-0.00109986,0.205007,0.000821404,0.434388,0,0,0,0,0,1.19581e-05,7.12717e-05,7.12541e-05,0.00034923,0.0541238,0.0541232,0.0175603,0.0456497,0.0456496,0.0321432,2.26313e-10,2.25788e-10,5.35555e-09,1.49943e-06,1.49944e-06,5e-08,0,0,0,0,0,0,0,0 -11888000,0.983373,-0.00799682,-0.0115463,0.181054,0.00145975,-0.00701452,0.0121594,0.00168131,-0.00443669,0.0220944,-6.81322e-06,-4.90266e-05,2.35212e-06,-5.98327e-06,1.34927e-07,-0.00109967,0.205007,0.000821404,0.434388,0,0,0,0,0,1.13379e-05,7.15706e-05,7.15559e-05,0.00033136,0.0614979,0.0614974,0.0166565,0.0518333,0.0518331,0.0325772,2.26355e-10,2.25833e-10,5.34099e-09,1.49943e-06,1.49944e-06,5e-08,0,0,0,0,0,0,0,0 -11992000,0.983374,-0.0080014,-0.0116226,0.181042,0.00348609,-0.00230051,0.0120244,0.00264173,-0.0020693,0.0216943,-6.81738e-06,-4.90222e-05,2.30822e-06,-1.22573e-05,-6.32791e-06,-0.00109942,0.205007,0.000821404,0.434388,0,0,0,0,0,1.08036e-05,6.74205e-05,6.74054e-05,0.00031598,0.0531257,0.0531255,0.0152877,0.0456293,0.0456292,0.0323449,2.26379e-10,2.25858e-10,5.32468e-09,1.42521e-06,1.42522e-06,5e-08,0,0,0,0,0,0,0,0 -12088000,0.983352,-0.00794239,-0.0116697,0.181162,0.00418598,-0.0035513,0.0156457,0.00300142,-0.00238037,0.0271547,-6.81932e-06,-4.90205e-05,2.21671e-06,-1.22634e-05,-6.30739e-06,-0.00110004,0.205007,0.000821404,0.434388,0,0,0,0,0,1.03349e-05,6.77512e-05,6.77363e-05,0.000302158,0.0598918,0.0598915,0.0145,0.0521398,0.0521397,0.0325827,2.26419e-10,2.25901e-10,5.30654e-09,1.42522e-06,1.42522e-06,5e-08,0,0,0,0,0,0,0,0 -12192000,0.983338,-0.00782424,-0.0116721,0.181241,0.00452966,-0.00264479,0.0151189,0.00243433,-0.000449765,0.0293602,-6.82918e-06,-4.90167e-05,2.02769e-06,-1.23615e-05,-1.31129e-05,-0.00110024,0.205007,0.000821404,0.434388,0,0,0,0,0,9.91681e-06,6.42467e-05,6.42314e-05,0.000290268,0.051213,0.0512128,0.0133716,0.045795,0.0457949,0.0322199,2.26416e-10,2.25901e-10,5.28651e-09,1.36218e-06,1.36218e-06,5e-08,0,0,0,0,0,0,0,0 -12288000,0.983323,-0.0078901,-0.0116434,0.181323,0.00204641,-0.00429583,0.0139518,0.00276226,-0.000768496,0.0302289,-6.83265e-06,-4.90138e-05,1.86766e-06,-1.23579e-05,-1.31165e-05,-0.00110017,0.205007,0.000821404,0.434388,0,0,0,0,0,9.54111e-06,6.46061e-05,6.45923e-05,0.000279422,0.0573477,0.0573474,0.0127083,0.0524868,0.0524867,0.0322989,2.26455e-10,2.25943e-10,5.26451e-09,1.36218e-06,1.36219e-06,5e-08,0,0,0,0,0,0,0,0 -12392000,0.983321,-0.0079223,-0.0115944,0.181338,0.00104268,-0.00545418,0.0124058,0.00226169,-0.000511365,0.025785,-6.83809e-06,-4.90115e-05,1.73715e-06,-1.20347e-05,-1.52504e-05,-0.00109938,0.205007,0.000821404,0.434388,0,0,0,0,0,9.21438e-06,6.17302e-05,6.17173e-05,0.000270126,0.0487691,0.0487688,0.0117923,0.0460022,0.0460021,0.0318485,2.26414e-10,2.25906e-10,5.24051e-09,1.3101e-06,1.3101e-06,5e-08,0,0,0,0,0,0,0,0 -12488000,0.983304,-0.00794814,-0.0115855,0.181428,0.00119359,-0.0055984,0.0151825,0.00236724,-0.00106144,0.0258458,-6.83929e-06,-4.90105e-05,1.68254e-06,-1.20331e-05,-1.52562e-05,-0.00109921,0.205007,0.000821404,0.434388,0,0,0,0,0,9.03427e-06,6.21182e-05,6.2106e-05,0.000264693,0.0542677,0.0542674,0.0112501,0.0527593,0.0527592,0.0318082,2.26454e-10,2.25948e-10,5.22114e-09,1.31011e-06,1.31011e-06,5e-08,0,0,0,0,0,0,0,0 -12592000,0.98328,-0.00797477,-0.011519,0.181561,0.00441382,-0.00881947,0.0165921,0.00349972,-0.00220011,0.0281554,-6.83768e-06,-4.90026e-05,1.52922e-06,-1.42865e-05,-1.30984e-05,-0.00109922,0.205007,0.000821404,0.434388,0,0,0,0,0,8.78032e-06,5.98087e-05,5.9796e-05,0.000257197,0.0460777,0.0460775,0.0105165,0.0461769,0.0461769,0.0313068,2.26366e-10,2.25862e-10,5.19353e-09,1.26772e-06,1.26772e-06,5e-08,0,0,0,0,0,0,0,0 -12688000,0.983279,-0.00794421,-0.0115207,0.181568,0.00449772,-0.0110062,0.0163053,0.00388656,-0.00315421,0.0290645,-6.83936e-06,-4.9001e-05,1.44597e-06,-1.42635e-05,-1.31229e-05,-0.00109914,0.205007,0.000821404,0.434388,0,0,0,0,0,8.53521e-06,6.02245e-05,6.02101e-05,0.000250155,0.0510156,0.0510154,0.0100853,0.0529136,0.0529135,0.0311831,2.26403e-10,2.259e-10,5.1638e-09,1.26773e-06,1.26772e-06,5e-08,0,0,0,0,0,0,0,0 -12792000,0.983329,-0.00802939,-0.011419,0.181297,0.00667857,-0.0124117,0.0173902,0.00591307,-0.00499479,0.0307845,-6.82231e-06,-4.89984e-05,1.76437e-06,-1.73993e-05,-9.54799e-06,-0.00109902,0.205007,0.000821404,0.434388,0,0,0,0,0,8.32549e-06,5.83904e-05,5.83754e-05,0.000244267,0.0433535,0.0433534,0.00950525,0.0462854,0.0462853,0.0306593,2.26253e-10,2.25752e-10,5.13195e-09,1.23356e-06,1.23355e-06,5e-08,0,0,0,0,0,0,0,0 -12888000,0.983366,-0.00806398,-0.0113442,0.181101,0.0064312,-0.0142658,0.018784,0.00657871,-0.00626216,0.0346036,-6.81834e-06,-4.90021e-05,1.95711e-06,-1.74419e-05,-9.49928e-06,-0.00109931,0.205007,0.000821404,0.434388,0,0,0,0,0,8.12448e-06,5.88321e-05,5.88164e-05,0.000238623,0.0477811,0.047781,0.00917251,0.0529413,0.0529412,0.0304822,2.26288e-10,2.25788e-10,5.09795e-09,1.23356e-06,1.23356e-06,5e-08,0,0,0,0,0,0,0,0 -12992000,0.983405,-0.00806659,-0.0113531,0.180887,0.00607802,-0.0112047,0.0198167,0.00522729,-0.00462043,0.0375488,-6.82943e-06,-4.90071e-05,2.15349e-06,-1.67085e-05,-1.47549e-05,-0.00109952,0.205007,0.000821404,0.434388,0,0,0,0,0,7.95624e-06,5.73899e-05,5.73727e-05,0.000234001,0.0407089,0.0407089,0.00872018,0.0463171,0.0463171,0.0299578,2.26063e-10,2.25564e-10,5.0618e-09,1.20613e-06,1.20612e-06,5e-08,0,0,0,0,0,0,0,0 -13088000,0.983421,-0.00807855,-0.0112463,0.180811,0.00683059,-0.0119623,0.0167813,0.00582693,-0.00568567,0.0341726,-6.82567e-06,-4.90109e-05,2.3455e-06,-1.67544e-05,-1.47402e-05,-0.00109873,0.205007,0.000821404,0.434388,0,0,0,0,0,7.8862e-06,5.78572e-05,5.78397e-05,0.000231906,0.044695,0.0446951,0.00847281,0.0528518,0.0528519,0.0297515,2.261e-10,2.25603e-10,5.03329e-09,1.20613e-06,1.20613e-06,5e-08,0,0,0,0,0,0,0,0 -13192000,0.983432,-0.00808059,-0.0112113,0.180749,0.00464592,-0.0121097,0.0164656,0.00464093,-0.00570346,0.0359715,-6.82781e-06,-4.90214e-05,2.53835e-06,-1.4954e-05,-1.68274e-05,-0.00109878,0.205007,0.000821404,0.434388,0,0,0,0,0,7.76236e-06,5.673e-05,5.67112e-05,0.000228208,0.0382184,0.0382184,0.00812586,0.0462731,0.0462731,0.029242,2.25783e-10,2.25288e-10,4.99341e-09,1.18416e-06,1.18416e-06,5e-08,0,0,0,0,0,0,0,0 -13288000,0.983433,-0.00812885,-0.011195,0.180745,0.00463167,-0.0136823,0.0135219,0.0050326,-0.00690919,0.0343368,-6.83051e-06,-4.90191e-05,2.41191e-06,-1.49364e-05,-1.68629e-05,-0.00109824,0.205007,0.000821404,0.434388,0,0,0,0,0,7.62942e-06,5.72226e-05,5.72029e-05,0.000224486,0.0418229,0.0418229,0.0079514,0.0526618,0.0526618,0.0290251,2.25814e-10,2.25321e-10,4.95142e-09,1.18417e-06,1.18416e-06,5e-08,0,0,0,0,0,0,0,0 -13392000,0.983422,-0.00808115,-0.0112868,0.180801,0.00263683,-0.0113375,0.0128274,0.00395643,-0.00518563,0.0348917,-6.85565e-06,-4.90135e-05,2.14113e-06,-1.47444e-05,-2.10272e-05,-0.00109805,0.205007,0.000821404,0.434388,0,0,0,0,0,7.5258e-06,5.63478e-05,5.63262e-05,0.000221633,0.0359138,0.0359137,0.00769088,0.0461606,0.0461606,0.0285415,2.25387e-10,2.24897e-10,4.90736e-09,1.16659e-06,1.16658e-06,5e-08,0,0,0,0,0,0,0,0 -13488000,0.983425,-0.00806809,-0.0112559,0.180787,0.00205747,-0.0106291,0.0124032,0.00417061,-0.00617457,0.0315022,-6.8557e-06,-4.90138e-05,2.14816e-06,-1.47586e-05,-2.10494e-05,-0.00109717,0.205007,0.000821404,0.434388,0,0,0,0,0,7.42262e-06,5.68649e-05,5.68423e-05,0.000218637,0.0391834,0.0391833,0.00757808,0.0523889,0.0523889,0.0283283,2.25417e-10,2.24929e-10,4.86126e-09,1.16659e-06,1.16658e-06,5e-08,0,0,0,0,0,0,0,0 -13592000,0.983404,-0.00804932,-0.0112511,0.180904,0.00502066,-0.0106078,0.0128535,0.00618711,-0.00484402,0.029003,-6.86652e-06,-4.89808e-05,1.94279e-06,-1.84382e-05,-2.26133e-05,-0.00109623,0.205007,0.000821404,0.434388,0,0,0,0,0,7.34983e-06,5.61916e-05,5.61682e-05,0.000216452,0.0337993,0.0337993,0.00738799,0.0459892,0.0459893,0.0278781,2.2486e-10,2.24376e-10,4.81318e-09,1.15252e-06,1.15251e-06,5e-08,0,0,0,0,0,0,0,0 -13688000,0.983436,-0.00799856,-0.0111554,0.180737,0.0045023,-0.0128993,0.0136223,0.00664923,-0.005956,0.0329229,-6.86298e-06,-4.89839e-05,2.10908e-06,-1.84536e-05,-2.25759e-05,-0.0010968,0.205007,0.000821404,0.434388,0,0,0,0,0,7.33149e-06,5.67323e-05,5.67083e-05,0.000216183,0.0367929,0.0367929,0.00732687,0.0520503,0.0520503,0.0276793,2.24894e-10,2.24412e-10,4.77588e-09,1.15253e-06,1.15252e-06,5e-08,0,0,0,0,0,0,0,0 -13792000,0.983424,-0.00797821,-0.0111997,0.1808,0.00954839,-0.00995616,0.014471,0.0094421,-0.00328723,0.0321149,-6.89007e-06,-4.89307e-05,1.87575e-06,-2.31706e-05,-2.55954e-05,-0.001096,0.205007,0.000821404,0.434388,0,0,0,0,0,7.27143e-06,5.62199e-05,5.61948e-05,0.000214515,0.0318915,0.0318916,0.00719379,0.0457693,0.0457693,0.0272671,2.24187e-10,2.2371e-10,4.72447e-09,1.14127e-06,1.14126e-06,5e-08,0,0,0,0,0,0,0,0 -13888000,0.983437,-0.00792266,-0.0111618,0.180731,0.00994027,-0.0103325,0.0154043,0.0103489,-0.00424213,0.0343734,-6.88524e-06,-4.89351e-05,2.10819e-06,-2.31973e-05,-2.55629e-05,-0.00109622,0.205007,0.000821404,0.434388,0,0,0,0,0,7.20576e-06,5.67838e-05,5.67577e-05,0.000212544,0.0346469,0.034647,0.00717563,0.0516629,0.0516629,0.0270905,2.24214e-10,2.23739e-10,4.67126e-09,1.14127e-06,1.14126e-06,5e-08,0,0,0,0,0,0,0,0 -13992000,0.983452,-0.00793576,-0.01098,0.180662,0.00989104,-0.00847714,0.0145594,0.00845359,-0.00447446,0.0342603,-6.88836e-06,-4.89584e-05,2.35631e-06,-2.10997e-05,-2.67965e-05,-0.00109591,0.205007,0.000821404,0.434388,0,0,0,0,0,7.16522e-06,5.6397e-05,5.6371e-05,0.000211317,0.0301826,0.0301827,0.00708812,0.0455112,0.0455113,0.0267191,2.23333e-10,2.22864e-10,4.61632e-09,1.13228e-06,1.13227e-06,5e-08,0,0,0,0,0,0,0,0 -14088000,0.983387,-0.00796804,-0.0109228,0.181017,0.00732698,-0.0132918,0.0154831,0.00936474,-0.00554812,0.0314554,-6.90721e-06,-4.89413e-05,1.45557e-06,-2.10141e-05,-2.69139e-05,-0.00109478,0.205007,0.000821404,0.434388,0,0,0,0,0,7.11192e-06,5.69832e-05,5.69567e-05,0.00020973,0.0327357,0.0327356,0.00710517,0.051241,0.051241,0.0265702,2.23358e-10,2.22893e-10,4.55974e-09,1.13228e-06,1.13227e-06,5e-08,0,0,0,0,0,0,0,0 -14192000,0.98335,-0.00795521,-0.0108517,0.181222,0.00438547,-0.0113493,0.0153783,0.00868943,-0.00426851,0.0317469,-6.944e-06,-4.89199e-05,9.64023e-07,-2.12856e-05,-2.93063e-05,-0.00109401,0.205007,0.000821404,0.434388,0,0,0,0,0,7.08356e-06,5.66959e-05,5.66688e-05,0.000208857,0.0286568,0.0286566,0.00705343,0.0452246,0.0452246,0.0262406,2.22281e-10,2.21821e-10,4.50161e-09,1.12512e-06,1.12511e-06,5e-08,0,0,0,0,0,0,0,0 -14288000,0.983346,-0.00791278,-0.010828,0.181247,0.00570443,-0.0125439,0.0141631,0.00907051,-0.0054532,0.0347174,-6.94444e-06,-4.89193e-05,9.37509e-07,-2.12718e-05,-2.9297e-05,-0.00109448,0.205007,0.000821404,0.434388,0,0,0,0,0,7.10882e-06,5.73041e-05,5.7276e-05,0.000209576,0.0310505,0.0310503,0.00709909,0.0507968,0.0507969,0.026123,2.22311e-10,2.21854e-10,4.45711e-09,1.12513e-06,1.12511e-06,5e-08,0,0,0,0,0,0,0,0 -14392000,0.983353,-0.00797921,-0.010785,0.181208,0.0067229,-0.0140307,0.0148332,0.00873256,-0.00563534,0.0387179,-6.94626e-06,-4.89151e-05,1.1159e-06,-2.12443e-05,-3.01043e-05,-0.0010951,0.205007,0.000821404,0.434388,0,0,0,0,0,7.08994e-06,5.70907e-05,5.70621e-05,0.000208968,0.0273142,0.027314,0.00707487,0.0449179,0.0449179,0.0258353,2.21009e-10,2.20558e-10,4.39651e-09,1.11947e-06,1.11945e-06,5e-08,0,0,0,0,0,0,0,0 -14488000,0.983334,-0.00809445,-0.010697,0.181314,0.00455044,-0.0148093,0.0188266,0.00923095,-0.00702394,0.0414941,-6.95513e-06,-4.89067e-05,6.8326e-07,-2.1193e-05,-3.01265e-05,-0.00109546,0.205007,0.000821404,0.434388,0,0,0,0,0,7.0499e-06,5.77187e-05,5.769e-05,0.000207905,0.0295602,0.0295599,0.00714305,0.050341,0.0503411,0.0257509,2.21031e-10,2.20584e-10,4.33463e-09,1.11947e-06,1.11946e-06,5e-08,0,0,0,0,0,0,0,0 -14592000,0.983317,-0.00816597,-0.010603,0.181405,0.00373095,-0.0140865,0.0160486,0.00646445,-0.00684575,0.0369127,-6.98791e-06,-4.8933e-05,4.3315e-07,-1.95999e-05,-3.18912e-05,-0.00109329,0.205007,0.000821404,0.434388,0,0,0,0,0,7.03696e-06,5.75617e-05,5.75326e-05,0.000207514,0.0261272,0.0261269,0.00713908,0.0445991,0.0445991,0.0255038,2.19481e-10,2.19041e-10,4.27159e-09,1.11502e-06,1.115e-06,5e-08,0,0,0,0,0,0,0,0 -14688000,0.983328,-0.00816861,-0.010647,0.181344,0.00298139,-0.0152741,0.0161158,0.00675451,-0.00822872,0.0365217,-6.98634e-06,-4.89347e-05,5.16698e-07,-1.96255e-05,-3.19025e-05,-0.00109258,0.205007,0.000821404,0.434388,0,0,0,0,0,7.00478e-06,5.82099e-05,5.81795e-05,0.000206629,0.0282629,0.0282626,0.00722455,0.0498827,0.0498827,0.0254536,2.19503e-10,2.19067e-10,4.2075e-09,1.11502e-06,1.11501e-06,5e-08,0,0,0,0,0,0,0,0 -14792000,0.983364,-0.00825182,-0.0106444,0.181147,0.00509144,-0.0095112,0.0149179,0.00570866,-0.00313649,0.0383958,-7.09061e-06,-4.89115e-05,9.81619e-07,-2.04717e-05,-3.60986e-05,-0.00109311,0.205007,0.000821404,0.434388,0,0,0,0,0,6.99426e-06,5.8091e-05,5.80602e-05,0.0002064,0.0250974,0.0250972,0.00723455,0.044275,0.044275,0.0252451,2.17676e-10,2.17248e-10,4.14247e-09,1.11155e-06,1.11154e-06,5e-08,0,0,0,0,0,0,0,0 -14888000,0.983401,-0.00817134,-0.010575,0.180952,0.00349839,-0.0125111,0.0169442,0.00608555,-0.00419586,0.0386155,-7.08178e-06,-4.89198e-05,1.41331e-06,-2.05194e-05,-3.6089e-05,-0.00109258,0.205007,0.000821404,0.434388,0,0,0,0,0,6.96501e-06,5.87568e-05,5.8725e-05,0.000205646,0.0271367,0.0271364,0.00733256,0.0494297,0.0494297,0.0252285,2.17697e-10,2.17273e-10,4.0766e-09,1.11156e-06,1.11154e-06,5e-08,0,0,0,0,0,0,0,0 -14992000,0.983408,-0.0082592,-0.0104849,0.180917,0.00208627,-0.0120503,0.0195428,0.00503334,-0.00448948,0.0408437,-7.09359e-06,-4.8932e-05,1.56048e-06,-2.00963e-05,-3.67741e-05,-0.0010922,0.205007,0.000821404,0.434388,0,0,0,0,0,6.96186e-06,5.86607e-05,5.86289e-05,0.000205528,0.0241982,0.0241979,0.00735097,0.0439515,0.0439515,0.0250558,2.1557e-10,2.15155e-10,4.01002e-09,1.10889e-06,1.10888e-06,5e-08,0,0,0,0,0,0,0,0 -15088000,0.983403,-0.00824616,-0.0105668,0.18094,0.00113828,-0.0131109,0.021582,0.00519277,-0.00573062,0.0419065,-7.09599e-06,-4.89299e-05,1.44898e-06,-2.01001e-05,-3.67877e-05,-0.00109181,0.205007,0.000821404,0.434388,0,0,0,0,0,7.00389e-06,5.93441e-05,5.93106e-05,0.000206811,0.0261616,0.0261611,0.00745737,0.0489878,0.0489878,0.0250717,2.15597e-10,2.15186e-10,3.95966e-09,1.1089e-06,1.10888e-06,5e-08,0,0,0,0,0,0,0,0 -15192000,0.983391,-0.00836787,-0.0106542,0.180992,-0.000614294,-0.0132757,0.0225389,0.0042959,-0.00481967,0.044102,-7.14201e-06,-4.89173e-05,1.23289e-06,-2.01188e-05,-3.79478e-05,-0.00109158,0.205007,0.000821404,0.434388,0,0,0,0,0,7.00073e-06,5.92597e-05,5.9225e-05,0.000206767,0.0234302,0.0234298,0.00747954,0.0436336,0.0436336,0.0249312,2.13149e-10,2.12747e-10,3.8921e-09,1.10688e-06,1.10686e-06,5e-08,0,0,0,0,0,0,0,0 -15288000,0.983409,-0.00847388,-0.0106904,0.180889,-0.000702446,-0.015397,0.0207833,0.00427719,-0.00617168,0.0398856,-7.13505e-06,-4.89247e-05,1.59987e-06,-2.02252e-05,-3.79958e-05,-0.00108876,0.205007,0.000821404,0.434388,0,0,0,0,0,6.98145e-06,5.99575e-05,5.9922e-05,0.000206144,0.0253358,0.0253353,0.00759064,0.0485631,0.0485631,0.0249773,2.13169e-10,2.12771e-10,3.82414e-09,1.10688e-06,1.10687e-06,5e-08,0,0,0,0,0,0,0,0 -15392000,0.983392,-0.00852208,-0.0107287,0.180976,0.000189745,-0.0120988,0.0203146,0.00360422,-0.00500732,0.0395782,-7.18893e-06,-4.89065e-05,1.47332e-06,-2.04076e-05,-3.90926e-05,-0.00108731,0.205007,0.000821404,0.434388,0,0,0,0,0,6.98468e-06,5.98702e-05,5.98337e-05,0.000206138,0.0227824,0.022782,0.00761269,0.0433264,0.0433264,0.0248652,2.10378e-10,2.09989e-10,3.75588e-09,1.10538e-06,1.10537e-06,5e-08,0,0,0,0,0,0,0,0 -15488000,0.983393,-0.00857959,-0.0107034,0.180972,-0.000107492,-0.0156384,0.020966,0.00358932,-0.00631788,0.0403652,-7.18831e-06,-4.89073e-05,1.50975e-06,-2.0427e-05,-3.91032e-05,-0.00108675,0.205007,0.000821404,0.434388,0,0,0,0,0,6.96515e-06,6.0581e-05,6.05439e-05,0.000205544,0.0246404,0.02464,0.00772527,0.0481605,0.0481605,0.0249388,2.10398e-10,2.10014e-10,3.68743e-09,1.10538e-06,1.10537e-06,5e-08,0,0,0,0,0,0,0,0 -15592000,0.983392,-0.00861659,-0.0107226,0.180972,0.00246395,-0.0171419,0.0203046,0.00523599,-0.00842831,0.0387915,-7.12664e-06,-4.88686e-05,1.68954e-06,-2.08969e-05,-3.88516e-05,-0.00108472,0.205007,0.000821404,0.434388,0,0,0,0,0,6.97e-06,6.04788e-05,6.0441e-05,0.000205552,0.0222395,0.0222392,0.00774386,0.0430335,0.0430335,0.0248507,2.07245e-10,2.06872e-10,3.61889e-09,1.10429e-06,1.10428e-06,5e-08,0,0,0,0,0,0,0,0 -15688000,0.98341,-0.00860097,-0.0107353,0.180876,0.00482252,-0.0207773,0.0204285,0.00557038,-0.0102523,0.0386786,-7.12217e-06,-4.88731e-05,1.91644e-06,-2.094e-05,-3.88682e-05,-0.00108371,0.205007,0.000821404,0.434388,0,0,0,0,0,7.01445e-06,6.12015e-05,6.11625e-05,0.00020692,0.024062,0.0240618,0.00785529,0.0477835,0.0477835,0.0249484,2.07273e-10,2.06902e-10,3.56748e-09,1.1043e-06,1.10429e-06,5e-08,0,0,0,0,0,0,0,0 -15792000,0.983437,-0.00864576,-0.0106727,0.180727,0.00271445,-0.0197992,0.0207238,0.00460983,-0.0086771,0.0389342,-7.20054e-06,-4.88713e-05,2.27972e-06,-2.09908e-05,-3.9919e-05,-0.00108244,0.205007,0.000821404,0.434388,0,0,0,0,0,7.01221e-06,6.10739e-05,6.10348e-05,0.000206929,0.0217919,0.0217916,0.00786782,0.0427583,0.0427583,0.0248798,2.03748e-10,2.03388e-10,3.49903e-09,1.10353e-06,1.10351e-06,5e-08,0,0,0,0,0,0,0,0 -15888000,0.983412,-0.00872781,-0.0107016,0.180859,0.00221644,-0.0194152,0.0213006,0.00479602,-0.0105703,0.0398802,-7.20788e-06,-4.88647e-05,1.93127e-06,-2.09971e-05,-3.99378e-05,-0.00108185,0.205007,0.000821404,0.434388,0,0,0,0,0,6.99252e-06,6.18057e-05,6.17656e-05,0.000206321,0.0235879,0.0235875,0.00797578,0.0474352,0.0474351,0.024998,2.03768e-10,2.03412e-10,3.43075e-09,1.10353e-06,1.10352e-06,5e-08,0,0,0,0,0,0,0,0 -15992000,0.983418,-0.00855028,-0.0106854,0.180838,0.000865999,-0.0183652,0.0177734,0.00401904,-0.00886016,0.0373256,-7.29256e-06,-4.88464e-05,1.82928e-06,-2.11347e-05,-4.0743e-05,-0.00107871,0.205007,0.000821404,0.434388,0,0,0,0,0,6.98718e-06,6.16438e-05,6.16026e-05,0.000206308,0.0214334,0.0214329,0.00798042,0.0425033,0.0425033,0.0249444,1.99865e-10,1.9952e-10,3.36274e-09,1.10299e-06,1.10298e-06,5e-08,0,0,0,0,0,0,0,0 -16088000,0.983424,-0.00848961,-0.0106826,0.180807,9.43195e-05,-0.0203676,0.0154945,0.00403732,-0.0107132,0.0373066,-7.29877e-06,-4.8841e-05,1.53819e-06,-2.11542e-05,-4.07654e-05,-0.00107786,0.205007,0.000821404,0.434388,0,0,0,0,0,6.95573e-06,6.23826e-05,6.23402e-05,0.000205685,0.0232158,0.0232152,0.00808323,0.0471181,0.047118,0.0250792,1.99885e-10,1.99545e-10,3.29508e-09,1.103e-06,1.10299e-06,5e-08,0,0,0,0,0,0,0,0 -16192000,0.983407,-0.00841088,-0.0106277,0.180906,-0.00231532,-0.0175739,0.0135235,0.00232019,-0.00895238,0.0333661,-7.4099e-06,-4.88417e-05,1.15692e-06,-2.12382e-05,-4.135e-05,-0.00107465,0.205007,0.000821404,0.434388,0,0,0,0,0,6.95149e-06,6.21747e-05,6.21318e-05,0.000205634,0.0211503,0.0211497,0.0080787,0.0422708,0.0422708,0.0250362,1.956e-10,1.95272e-10,3.22786e-09,1.10263e-06,1.10262e-06,5e-08,0,0,0,0,0,0,0,0 -16288000,0.983401,-0.008436,-0.010538,0.180943,-0.00134835,-0.0200549,0.0122262,0.00211597,-0.0107941,0.0328218,-7.40948e-06,-4.88424e-05,1.18793e-06,-2.12726e-05,-4.13708e-05,-0.00107368,0.205007,0.000821404,0.434388,0,0,0,0,0,6.99852e-06,6.29176e-05,6.28744e-05,0.000206915,0.0229187,0.0229181,0.00817515,0.0468333,0.0468332,0.0251836,1.95628e-10,1.95303e-10,3.17779e-09,1.10263e-06,1.10262e-06,5e-08,0,0,0,0,0,0,0,0 -16392000,0.983418,-0.00836521,-0.0105128,0.180855,0.000491342,-0.0184607,0.012621,0.00285916,-0.00911546,0.0325196,-7.47525e-06,-4.8779e-05,1.54802e-06,-2.12972e-05,-4.16709e-05,-0.00107261,0.205007,0.000821404,0.434388,0,0,0,0,0,6.99766e-06,6.26576e-05,6.26138e-05,0.00020681,0.0209284,0.0209279,0.00816078,0.0420619,0.0420618,0.025147,1.90973e-10,1.90659e-10,3.11149e-09,1.10236e-06,1.10235e-06,5e-08,0,0,0,0,0,0,0,0 -16488000,0.983409,-0.00849323,-0.0105386,0.180894,0.00265037,-0.0212326,0.0157696,0.00300075,-0.01106,0.0375637,-7.47879e-06,-4.87752e-05,1.35469e-06,-2.12205e-05,-4.16261e-05,-0.00107467,0.205007,0.000821404,0.434388,0,0,0,0,0,6.97131e-06,6.34031e-05,6.33586e-05,0.000206091,0.0226851,0.0226847,0.00825008,0.0465813,0.0465812,0.0253034,1.90994e-10,1.90685e-10,3.04582e-09,1.10236e-06,1.10236e-06,5e-08,0,0,0,0,0,0,0,0 -16592000,0.983409,-0.00844917,-0.0105787,0.180895,0.00602084,-0.0208788,0.0189148,0.00276454,-0.00945597,0.0373774,-7.58234e-06,-4.87498e-05,1.30397e-06,-2.12145e-05,-4.16916e-05,-0.00107347,0.205007,0.000821404,0.434388,0,0,0,0,0,6.96477e-06,6.30859e-05,6.30406e-05,0.000205935,0.0207521,0.0207519,0.00822576,0.0418769,0.0418768,0.0252695,1.85985e-10,1.85688e-10,2.98084e-09,1.10215e-06,1.10214e-06,5e-08,0,0,0,0,0,0,0,0 -16688000,0.983419,-0.0084891,-0.0105264,0.180842,0.00747715,-0.0253309,0.0189261,0.00342022,-0.0116667,0.0383842,-7.57892e-06,-4.87531e-05,1.47482e-06,-2.1233e-05,-4.17013e-05,-0.00107303,0.205007,0.000821404,0.434388,0,0,0,0,0,6.93931e-06,6.38307e-05,6.3785e-05,0.000205165,0.0225064,0.0225062,0.00830753,0.0463616,0.0463614,0.0254313,1.86007e-10,1.85714e-10,2.9166e-09,1.10215e-06,1.10215e-06,5e-08,0,0,0,0,0,0,0,0 -16792000,0.983444,-0.00833922,-0.0104564,0.180719,0.00957051,-0.0251243,0.0168744,0.00307606,-0.0100572,0.037166,-7.70753e-06,-4.87456e-05,1.64881e-06,-2.12785e-05,-4.1471e-05,-0.00107096,0.205007,0.000821404,0.434388,0,0,0,0,0,6.92719e-06,6.34515e-05,6.34056e-05,0.000204956,0.0206315,0.0206315,0.0082735,0.0417161,0.0417161,0.0253969,1.8067e-10,1.80389e-10,2.85315e-09,1.10194e-06,1.10194e-06,5e-08,0,0,0,0,0,0,0,0 -16888000,0.983472,-0.00835445,-0.0105449,0.18056,0.00880287,-0.0265206,0.0185357,0.00394449,-0.0125229,0.036722,-7.70117e-06,-4.87518e-05,1.97217e-06,-2.13288e-05,-4.14982e-05,-0.0010697,0.205007,0.000821404,0.434388,0,0,0,0,0,6.96143e-06,6.41946e-05,6.41471e-05,0.000206077,0.0223796,0.0223795,0.00834768,0.0461741,0.0461739,0.025561,1.80699e-10,1.80422e-10,2.80615e-09,1.10194e-06,1.10194e-06,5e-08,0,0,0,0,0,0,0,0 -16992000,0.983466,-0.00841452,-0.0105708,0.180586,0.010068,-0.0253103,0.0176339,0.00535203,-0.0107378,0.033729,-7.81202e-06,-4.86685e-05,2.05064e-06,-2.09231e-05,-4.12176e-05,-0.00106687,0.205007,0.000821404,0.434388,0,0,0,0,0,6.95587e-06,6.3749e-05,6.37015e-05,0.000205793,0.0205386,0.0205386,0.0083045,0.0415789,0.0415789,0.0255234,1.75061e-10,1.74797e-10,2.7442e-09,1.1017e-06,1.1017e-06,5e-08,0,0,0,0,0,0,0,0 -17088000,0.983469,-0.00850915,-0.0105229,0.180572,0.012906,-0.0288465,0.0172677,0.00646988,-0.0133699,0.0321947,-7.81374e-06,-4.86674e-05,1.98832e-06,-2.09971e-05,-4.12513e-05,-0.00106498,0.205007,0.000821404,0.434388,0,0,0,0,0,6.9232e-06,6.44856e-05,6.4438e-05,0.000204915,0.0222887,0.0222889,0.00837158,0.0460167,0.0460166,0.025687,1.75085e-10,1.74824e-10,2.68316e-09,1.1017e-06,1.10171e-06,5e-08,0,0,0,0,0,0,0,0 -17192000,0.983418,-0.00854096,-0.010462,0.180849,0.0125513,-0.0310283,0.0185798,0.00653447,-0.0134816,0.0347396,-7.89491e-06,-4.8657e-05,1.38871e-06,-2.09585e-05,-4.10854e-05,-0.00106521,0.205007,0.000821404,0.434388,0,0,0,0,0,6.91634e-06,6.39709e-05,6.39237e-05,0.000204569,0.020475,0.0204752,0.00832029,0.0414642,0.0414642,0.0256441,1.69184e-10,1.68935e-10,2.62306e-09,1.1014e-06,1.10141e-06,5e-08,0,0,0,0,0,0,0,0 -17288000,0.983391,-0.0085171,-0.0104648,0.180995,0.0138193,-0.0318932,0.0178126,0.00779196,-0.0164404,0.0344304,-7.90353e-06,-4.86494e-05,9.80957e-07,-2.10079e-05,-4.10973e-05,-0.00106402,0.205007,0.000821404,0.434388,0,0,0,0,0,6.88512e-06,6.47002e-05,6.46523e-05,0.000203636,0.0222264,0.0222266,0.00838066,0.0458881,0.045888,0.0258052,1.69208e-10,1.68964e-10,2.56393e-09,1.10141e-06,1.10141e-06,5e-08,0,0,0,0,0,0,0,0 -17392000,0.983435,-0.00844798,-0.0104388,0.180765,0.00969097,-0.0318635,0.0177932,0.00839461,-0.0132007,0.0342649,-8.09457e-06,-4.85701e-05,1.28647e-06,-2.0271e-05,-3.98258e-05,-0.00106258,0.205007,0.000821404,0.434388,0,0,0,0,0,6.86259e-06,6.41166e-05,6.4069e-05,0.000203244,0.0204312,0.0204311,0.00832223,0.0413709,0.0413708,0.0257556,1.63087e-10,1.62855e-10,2.50581e-09,1.10102e-06,1.10103e-06,5e-08,0,0,0,0,0,0,0,0 -17488000,0.983418,-0.0084673,-0.0104758,0.180855,0.0084845,-0.0334037,0.0178338,0.00922191,-0.0163045,0.034661,-8.09987e-06,-4.85655e-05,1.03537e-06,-2.03047e-05,-3.98316e-05,-0.00106182,0.205007,0.000821404,0.434388,0,0,0,0,0,6.82975e-06,6.48361e-05,6.47877e-05,0.000202263,0.0221805,0.0221803,0.00837658,0.0457855,0.0457854,0.0259122,1.63113e-10,1.62884e-10,2.4487e-09,1.10102e-06,1.10103e-06,5e-08,0,0,0,0,0,0,0,0 -17592000,0.983416,-0.00843296,-0.0104241,0.180867,0.00567061,-0.0297816,0.0165975,0.00588843,-0.0138947,0.0330953,-8.31707e-06,-4.86335e-05,1.02626e-06,-2.09829e-05,-3.81222e-05,-0.00105972,0.205007,0.000821404,0.434388,0,0,0,0,0,6.81512e-06,6.41852e-05,6.41367e-05,0.000201803,0.0203978,0.0203977,0.00831243,0.0412968,0.0412967,0.0258549,1.5682e-10,1.56603e-10,2.39263e-09,1.10053e-06,1.10055e-06,5e-08,0,0,0,0,0,0,0,0 -17688000,0.983444,-0.00854823,-0.0103531,0.180713,0.00531793,-0.0314764,0.017104,0.00645611,-0.0168422,0.0339348,-8.31594e-06,-4.86346e-05,1.08815e-06,-2.10024e-05,-3.81288e-05,-0.00105923,0.205007,0.000821404,0.434388,0,0,0,0,0,6.83408e-06,6.48924e-05,6.48437e-05,0.000202662,0.0221443,0.0221441,0.00836171,0.045706,0.0457059,0.026006,1.56853e-10,1.56637e-10,2.35126e-09,1.10054e-06,1.10055e-06,5e-08,0,0,0,0,0,0,0,0 -17792000,0.983485,-0.00849809,-0.0103177,0.180493,0.00706865,-0.0288281,0.0194112,0.00648696,-0.0134556,0.0412787,-8.51282e-06,-4.85515e-05,1.15261e-06,-1.99344e-05,-3.63114e-05,-0.00106246,0.205007,0.000821404,0.434388,0,0,0,0,0,6.80171e-06,6.4176e-05,6.41277e-05,0.000202154,0.0203676,0.0203675,0.00829303,0.0412397,0.0412396,0.0259404,1.50437e-10,1.50233e-10,2.29704e-09,1.09994e-06,1.09995e-06,5e-08,0,0,0,0,0,0,0,0 -17888000,0.983497,-0.0084641,-0.0104117,0.180428,0.00841921,-0.0323646,0.0189703,0.00728836,-0.0164067,0.045459,-8.50971e-06,-4.8554e-05,1.2882e-06,-1.98745e-05,-3.63022e-05,-0.00106383,0.205007,0.000821404,0.434388,0,0,0,0,0,6.76467e-06,6.487e-05,6.48202e-05,0.000201073,0.0221151,0.022115,0.0083381,0.0456464,0.0456463,0.0260851,1.50465e-10,1.50264e-10,2.24389e-09,1.09994e-06,1.09996e-06,5e-08,0,0,0,0,0,0,0,0 -17992000,0.983497,-0.00832478,-0.0103828,0.180436,0.00763336,-0.0269133,0.018298,0.00619859,-0.0110391,0.0451677,-8.81631e-06,-4.84934e-05,1.23671e-06,-1.91707e-05,-3.30575e-05,-0.00106264,0.205007,0.000821404,0.434388,0,0,0,0,0,6.74446e-06,6.40915e-05,6.40419e-05,0.000200499,0.0203381,0.0203381,0.00826601,0.0411972,0.0411971,0.0260114,1.43975e-10,1.43786e-10,2.19182e-09,1.09922e-06,1.09924e-06,5e-08,0,0,0,0,0,0,0,0 -18088000,0.983502,-0.00842315,-0.0103477,0.180404,0.00782787,-0.0281959,0.0165053,0.00697467,-0.0137271,0.0427354,-8.8154e-06,-4.8495e-05,1.31254e-06,-1.92704e-05,-3.30789e-05,-0.00106023,0.205007,0.000821404,0.434388,0,0,0,0,0,6.70695e-06,6.47689e-05,6.47191e-05,0.000199379,0.0220764,0.0220763,0.00830768,0.0456035,0.0456034,0.0261494,1.44004e-10,1.43817e-10,2.14082e-09,1.09922e-06,1.09925e-06,5e-08,0,0,0,0,0,0,0,0 -18192000,0.983545,-0.00841719,-0.0103751,0.180169,0.00731946,-0.0262683,0.0165349,0.00684829,-0.011779,0.0397052,-8.95214e-06,-4.8454e-05,1.75979e-06,-1.87062e-05,-3.1558e-05,-0.00105733,0.205007,0.000821404,0.434388,0,0,0,0,0,6.68129e-06,6.39344e-05,6.38847e-05,0.000198761,0.0202936,0.0202935,0.00823331,0.0411666,0.0411666,0.0260676,1.37493e-10,1.37318e-10,2.0909e-09,1.09838e-06,1.09841e-06,5e-08,0,0,0,0,0,0,0,0 -18288000,0.983541,-0.00848434,-0.0103336,0.18019,0.00793725,-0.0281969,0.0144994,0.00752719,-0.0143928,0.0363023,-8.95248e-06,-4.84546e-05,1.78077e-06,-1.88285e-05,-3.15762e-05,-0.00105443,0.205007,0.000821404,0.434388,0,0,0,0,0,6.70559e-06,6.45947e-05,6.45446e-05,0.000199421,0.0220228,0.0220226,0.0082725,0.0455727,0.0455727,0.0261988,1.37527e-10,1.37354e-10,2.05418e-09,1.09839e-06,1.09841e-06,5e-08,0,0,0,0,0,0,0,0 -18392000,0.983514,-0.00836351,-0.0103448,0.180339,0.00746611,-0.0268016,0.0144342,0.00826449,-0.0123858,0.036472,-9.08811e-06,-4.83655e-05,1.59026e-06,-1.76615e-05,-3.00909e-05,-0.00105373,0.205007,0.000821404,0.434388,0,0,0,0,0,6.68819e-06,6.37112e-05,6.36614e-05,0.000198738,0.0202404,0.0202402,0.00819688,0.041145,0.0411449,0.0261096,1.31046e-10,1.30884e-10,2.00615e-09,1.09744e-06,1.09746e-06,5e-08,0,0,0,0,0,0,0,0 -18488000,0.983526,-0.00844695,-0.010345,0.180273,0.0100164,-0.028287,0.0143469,0.00917517,-0.0150534,0.0380525,-9.0843e-06,-4.8369e-05,1.77818e-06,-1.76479e-05,-3.00964e-05,-0.0010539,0.205007,0.000821404,0.434388,0,0,0,0,0,6.64854e-06,6.43529e-05,6.43027e-05,0.000197538,0.0219589,0.0219588,0.00823441,0.0455516,0.0455515,0.0262341,1.31076e-10,1.30917e-10,1.95918e-09,1.09744e-06,1.09747e-06,5e-08,0,0,0,0,0,0,0,0 -18592000,0.983492,-0.00824738,-0.0102328,0.180475,0.00858475,-0.0270411,0.0147229,0.00779048,-0.0129642,0.0403916,-9.25825e-06,-4.83682e-05,1.49227e-06,-1.76378e-05,-2.797e-05,-0.00105419,0.205007,0.000821404,0.434388,0,0,0,0,0,6.63064e-06,6.34264e-05,6.33768e-05,0.000196815,0.0201734,0.0201733,0.00815843,0.04113,0.0411299,0.0261383,1.24669e-10,1.2452e-10,1.91328e-09,1.09638e-06,1.09641e-06,5e-08,0,0,0,0,0,0,0,0 -18688000,0.983519,-0.00824263,-0.01018,0.18033,0.00833633,-0.0272151,0.0134774,0.00861451,-0.0155577,0.0394642,-9.25351e-06,-4.8373e-05,1.74714e-06,-1.76848e-05,-2.79827e-05,-0.00105284,0.205007,0.000821404,0.434388,0,0,0,0,0,6.58643e-06,6.40482e-05,6.39985e-05,0.000195594,0.021878,0.0218778,0.00819486,0.0455362,0.0455361,0.0262565,1.247e-10,1.24554e-10,1.86843e-09,1.09638e-06,1.09642e-06,5e-08,0,0,0,0,0,0,0,0 -18792000,0.983517,-0.00817209,-0.0100666,0.180348,0.00744859,-0.0267077,0.0127984,0.00820973,-0.0134424,0.037326,-9.40137e-06,-4.83322e-05,1.69624e-06,-1.71424e-05,-2.60671e-05,-0.00105025,0.205007,0.000821404,0.434388,0,0,0,0,0,6.56069e-06,6.3086e-05,6.30375e-05,0.000194842,0.020087,0.0200868,0.00811924,0.0411189,0.0411188,0.0261548,1.18409e-10,1.18272e-10,1.82463e-09,1.09523e-06,1.09526e-06,5e-08,0,0,0,0,0,0,0,0 -18888000,0.983508,-0.00814262,-0.0100981,0.180401,0.00665826,-0.0274091,0.0106863,0.00885862,-0.01608,0.0329471,-9.40558e-06,-4.83294e-05,1.5279e-06,-1.72882e-05,-2.60594e-05,-0.00104698,0.205007,0.000821404,0.434388,0,0,0,0,0,6.57637e-06,6.36885e-05,6.36389e-05,0.00019534,0.0217737,0.0217734,0.00815528,0.0455234,0.0455233,0.0262674,1.18445e-10,1.18311e-10,1.79247e-09,1.09523e-06,1.09527e-06,5e-08,0,0,0,0,0,0,0,0 -18992000,0.983495,-0.00805948,-0.010108,0.180473,0.00477356,-0.0271624,0.0125048,0.00751151,-0.0138341,0.0372306,-9.56369e-06,-4.83193e-05,1.50981e-06,-1.70186e-05,-2.38582e-05,-0.00104847,0.205007,0.000821404,0.434388,0,0,0,0,0,6.55423e-06,6.27007e-05,6.26512e-05,0.000194538,0.0199821,0.0199818,0.00808062,0.0411093,0.0411092,0.0261608,1.12307e-10,1.12183e-10,1.75046e-09,1.09399e-06,1.09403e-06,5e-08,0,0,0,0,0,0,0,0 -19088000,0.983503,-0.00817076,-0.0101175,0.180425,0.00271653,-0.0285824,0.0126056,0.00791818,-0.0164774,0.0322654,-9.5613e-06,-4.83227e-05,1.67745e-06,-1.71608e-05,-2.38582e-05,-0.00104489,0.205007,0.000821404,0.434388,0,0,0,0,0,6.51292e-06,6.32818e-05,6.32318e-05,0.000193257,0.0216443,0.0216439,0.00811674,0.0455104,0.0455103,0.0262683,1.1234e-10,1.12218e-10,1.70947e-09,1.094e-06,1.09404e-06,5e-08,0,0,0,0,0,0,0,0 -19192000,0.983469,-0.00803222,-0.0102389,0.180608,0.000642779,-0.0269627,0.0121713,0.00665711,-0.0141671,0.0310919,-9.72642e-06,-4.82855e-05,1.19004e-06,-1.67454e-05,-2.15849e-05,-0.00104356,0.205007,0.000821404,0.434388,0,0,0,0,0,6.48397e-06,6.22765e-05,6.22258e-05,0.000192434,0.019854,0.0198535,0.00804348,0.0410991,0.041099,0.0261576,1.0639e-10,1.06276e-10,1.66946e-09,1.09269e-06,1.09274e-06,5e-08,0,0,0,0,0,0,0,0 -19288000,0.983474,-0.00800371,-0.010214,0.180584,-5.27876e-05,-0.028011,0.0120065,0.00671588,-0.0168061,0.0296533,-9.72835e-06,-4.82841e-05,1.11228e-06,-1.68112e-05,-2.15748e-05,-0.00104205,0.205007,0.000821404,0.434388,0,0,0,0,0,6.43691e-06,6.28364e-05,6.27853e-05,0.000191146,0.0214983,0.0214978,0.00808015,0.0454946,0.0454944,0.0262609,1.06423e-10,1.06312e-10,1.63044e-09,1.0927e-06,1.09274e-06,5e-08,0,0,0,0,0,0,0,0 -19392000,0.983465,-0.00807007,-0.0101155,0.180635,-0.000746823,-0.0237587,0.0131498,0.00570565,-0.0132893,0.0284359,-9.91368e-06,-4.82289e-05,9.17245e-07,-1.59981e-05,-1.87683e-05,-0.00104036,0.205007,0.000821404,0.434388,0,0,0,0,0,6.40644e-06,6.18182e-05,6.17683e-05,0.000190302,0.0197076,0.0197071,0.00800866,0.0410862,0.0410861,0.0261471,1.00684e-10,1.0058e-10,1.59238e-09,1.09134e-06,1.09139e-06,5e-08,0,0,0,0,0,0,0,0 -19488000,0.983429,-0.00811556,-0.0100111,0.180833,-0.00136379,-0.0248417,0.0128869,0.00559121,-0.0155959,0.0275185,-9.91906e-06,-4.82243e-05,6.61622e-07,-1.60649e-05,-1.87478e-05,-0.00103906,0.205007,0.000821404,0.434388,0,0,0,0,0,6.42518e-06,6.23567e-05,6.2307e-05,0.000190655,0.0213287,0.0213282,0.00804618,0.0454734,0.0454732,0.0262468,1.00722e-10,1.0062e-10,1.56447e-09,1.09135e-06,1.09139e-06,5e-08,0,0,0,0,0,0,0,0 -19592000,0.983413,-0.00800717,-0.0101204,0.180923,-0.00296001,-0.0260421,0.0151406,0.00556709,-0.0144264,0.0288954,-9.99843e-06,-4.81582e-05,5.4408e-07,-1.49715e-05,-1.76184e-05,-0.0010389,0.205007,0.000821404,0.434388,0,0,0,0,0,6.39881e-06,6.13354e-05,6.12852e-05,0.000189771,0.0195441,0.0195436,0.00797664,0.0410693,0.0410691,0.0261306,9.52124e-11,9.51182e-11,1.52806e-09,1.08995e-06,1.09e-06,5e-08,0,0,0,0,0,0,0,0 -19688000,0.983427,-0.00802653,-0.0101375,0.180846,-0.00437133,-0.0258288,0.0145975,0.00522727,-0.016916,0.0296203,-9.99624e-06,-4.81604e-05,6.61431e-07,-1.49808e-05,-1.76205e-05,-0.00103846,0.205007,0.000821404,0.434388,0,0,0,0,0,6.35292e-06,6.18532e-05,6.18027e-05,0.000188448,0.0211416,0.021141,0.00801519,0.0454459,0.0454457,0.0262274,9.52477e-11,9.51553e-11,1.49255e-09,1.08995e-06,1.09e-06,5e-08,0,0,0,0,0,0,0,0 -19792000,0.983405,-0.00804841,-0.0101816,0.18096,-0.00556902,-0.0227782,0.0113506,0.00529851,-0.0144241,0.0233854,-1.01139e-05,-4.80694e-05,3.88327e-07,-1.36403e-05,-1.58024e-05,-0.00103396,0.205007,0.000821404,0.434388,0,0,0,0,0,6.32293e-06,6.08332e-05,6.0783e-05,0.000187553,0.0193704,0.0193698,0.00794769,0.0410473,0.0410471,0.0261097,8.99836e-11,8.98983e-11,1.45795e-09,1.08853e-06,1.08858e-06,5e-08,0,0,0,0,0,0,0,0 -19888000,0.983387,-0.00809128,-0.0102584,0.181051,-0.00525907,-0.0236031,0.0111553,0.00471885,-0.01661,0.0211413,-1.01172e-05,-4.80669e-05,2.45299e-07,-1.37201e-05,-1.57777e-05,-0.00103206,0.205007,0.000821404,0.434388,0,0,0,0,0,6.28107e-06,6.13305e-05,6.12796e-05,0.000186225,0.0209381,0.0209375,0.0079875,0.0454113,0.0454111,0.0262043,9.00196e-11,8.9936e-11,1.42422e-09,1.08854e-06,1.08859e-06,5e-08,0,0,0,0,0,0,0,0 -19992000,0.983403,-0.00805972,-0.01043,0.180954,-0.00488482,-0.0221534,0.00855334,0.00492261,-0.0132648,0.0186122,-1.02514e-05,-4.79682e-05,2.62231e-07,-1.20024e-05,-1.34991e-05,-0.00102949,0.205007,0.000821404,0.434388,0,0,0,0,0,6.24502e-06,6.03187e-05,6.02673e-05,0.000185323,0.0191803,0.0191798,0.00792217,0.0410197,0.0410195,0.0260857,8.50101e-11,8.4933e-11,1.39136e-09,1.0871e-06,1.08715e-06,5e-08,0,0,0,0,0,0,0,0 -20088000,0.983411,-0.00805973,-0.0104252,0.180912,-0.00436951,-0.0250559,0.00919891,0.00446966,-0.0155403,0.0229688,-1.02521e-05,-4.79669e-05,1.99114e-07,-1.1936e-05,-1.35184e-05,-0.0010315,0.205007,0.000821404,0.434388,0,0,0,0,0,6.19633e-06,6.07952e-05,6.07436e-05,0.000184003,0.0207241,0.0207237,0.00796329,0.0453686,0.0453683,0.0261788,8.50469e-11,8.49714e-11,1.35934e-09,1.0871e-06,1.08716e-06,5e-08,0,0,0,0,0,0,0,0 -20192000,0.983384,-0.00799374,-0.0105093,0.181056,-0.00424923,-0.0214833,0.00982927,0.00371797,-0.0132869,0.0224085,-1.03735e-05,-4.79118e-05,-1.56178e-07,-1.1092e-05,-1.15218e-05,-0.00103052,0.205007,0.000821404,0.434388,0,0,0,0,0,6.16519e-06,5.97937e-05,5.9742e-05,0.000183088,0.0189757,0.0189753,0.00789999,0.0409855,0.0409853,0.0260599,8.02948e-11,8.0225e-11,1.32814e-09,1.08566e-06,1.08572e-06,5e-08,0,0,0,0,0,0,0,0 -20288000,0.983389,-0.00799877,-0.0105464,0.181029,-0.00755576,-0.0233154,0.0110047,0.00318563,-0.0153967,0.0252383,-1.03742e-05,-4.79108e-05,-2.04872e-07,-1.10599e-05,-1.15332e-05,-0.00103159,0.205007,0.000821404,0.434388,0,0,0,0,0,6.1698e-06,6.02507e-05,6.01984e-05,0.000183305,0.0204879,0.0204874,0.00794236,0.0453166,0.0453163,0.026152,8.03353e-11,8.02664e-11,1.30528e-09,1.08566e-06,1.08572e-06,5e-08,0,0,0,0,0,0,0,0 -20392000,0.983382,-0.00790116,-0.0105233,0.181072,-0.00888647,-0.0206934,0.0108666,0.00254953,-0.0131511,0.0249859,-1.04722e-05,-4.78552e-05,-6.39067e-08,-9.98092e-06,-9.74096e-06,-0.00103035,0.205007,0.000821404,0.434388,0,0,0,0,0,6.14614e-06,5.92654e-05,5.92137e-05,0.000182361,0.0187581,0.0187577,0.00788103,0.0409442,0.0409441,0.0260332,7.5844e-11,7.57804e-11,1.27548e-09,1.08423e-06,1.08428e-06,5e-08,0,0,0,0,0,0,0,0 -20488000,0.983397,-0.00793097,-0.0104937,0.180991,-0.0115511,-0.0223474,0.0107027,0.00154785,-0.015174,0.0230432,-1.04736e-05,-4.78544e-05,-1.12867e-07,-1.00378e-05,-9.71412e-06,-0.00102863,0.205007,0.000821404,0.434388,0,0,0,0,0,6.09505e-06,5.97023e-05,5.96508e-05,0.000181035,0.020239,0.0202385,0.00792473,0.045255,0.0452547,0.0261248,7.5882e-11,7.58197e-11,1.24645e-09,1.08423e-06,1.08429e-06,5e-08,0,0,0,0,0,0,0,0 -20592000,0.983425,-0.00787044,-0.0105102,0.180839,-0.0113523,-0.0221711,0.0108101,0.00118099,-0.0130726,0.0220333,-1.0556e-05,-4.77872e-05,1.4421e-07,-8.67948e-06,-8.13265e-06,-0.00102715,0.205007,0.000821404,0.434388,0,0,0,0,0,6.06172e-06,5.87381e-05,5.86869e-05,0.000180097,0.0185285,0.0185282,0.00786531,0.0408954,0.0408952,0.0260066,7.165e-11,7.15923e-11,1.21818e-09,1.08281e-06,1.08287e-06,5e-08,0,0,0,0,0,0,0,0 -20688000,0.983416,-0.00780608,-0.0105045,0.180891,-0.0133768,-0.0225834,0.0113174,4.55292e-05,-0.0151741,0.0213026,-1.05603e-05,-4.77835e-05,-6.18527e-08,-8.72427e-06,-8.10639e-06,-0.00102612,0.205007,0.000821404,0.434388,0,0,0,0,0,6.01495e-06,5.91567e-05,5.91053e-05,0.000178776,0.0199786,0.0199782,0.00791027,0.0451835,0.0451833,0.0260981,7.16886e-11,7.16322e-11,1.19064e-09,1.08282e-06,1.08288e-06,5e-08,0,0,0,0,0,0,0,0 -20792000,0.983439,-0.00716915,-0.0104138,0.180799,-0.0156401,-0.0185224,-0.00276915,-0.000233728,-0.0130101,0.0211168,-1.06424e-05,-4.77092e-05,-2.07657e-08,-7.29077e-06,-6.56315e-06,-0.00102533,0.205007,0.000821404,0.434388,0,0,0,0,0,5.97866e-06,5.82159e-05,5.81648e-05,0.000177841,0.0183166,0.0183163,0.00785248,0.0408392,0.040839,0.0259808,6.77101e-11,6.76584e-11,1.16382e-09,1.08142e-06,1.08148e-06,5e-08,0,0,0,0,0,0,0,0 -20888000,0.983502,0.00163275,-0.00674025,0.180765,-0.0218403,-0.00792895,-0.113556,-0.00208961,-0.0142629,0.0165556,-1.06423e-05,-4.77091e-05,-1.8006e-08,-7.2673e-06,-6.56766e-06,-0.00102552,0.205007,0.000821404,0.434388,0,0,0,0,0,5.97872e-06,5.86035e-05,5.85734e-05,0.000177984,0.0199498,0.0199492,0.00789862,0.045112,0.0451117,0.0260725,6.77506e-11,6.77014e-11,1.14418e-09,1.08143e-06,1.08148e-06,5e-08,0,0,0,0,0,0,0,0 -20992000,0.983493,0.00539418,-0.00310592,0.180841,-0.0327134,0.0118928,-0.260297,-0.00245946,-0.0113122,-4.11155e-05,-1.06659e-05,-4.76218e-05,-7.01319e-08,-5.40677e-06,-6.27282e-06,-0.00102891,0.205007,0.000821404,0.434388,0,0,0,0,0,5.95187e-06,5.76193e-05,5.76126e-05,0.000177028,0.0185182,0.0185169,0.00784243,0.0407958,0.0407955,0.0259564,6.39737e-11,6.393e-11,1.11857e-09,1.07981e-06,1.07987e-06,5e-08,0,0,0,0,0,0,0,0 -21088000,0.983432,0.00388642,-0.00341791,0.181207,-0.0451761,0.025865,-0.371678,-0.0061919,-0.00945776,-0.0271545,-1.06674e-05,-4.762e-05,-1.63614e-07,-5.38718e-06,-6.29625e-06,-0.0010307,0.205007,0.000821404,0.434388,0,0,0,0,0,5.92809e-06,5.8004e-05,5.79913e-05,0.000175688,0.0201529,0.0201507,0.00788976,0.0450854,0.0450851,0.0260485,6.40125e-11,6.39706e-11,1.09363e-09,1.07981e-06,1.07987e-06,5e-08,0,0,0,0,0,0,0,0 -21192000,0.983373,0.000955857,-0.00508875,0.181526,-0.049141,0.0330414,-0.503296,-0.00595106,-0.00744689,-0.0666333,-1.0556e-05,-4.75021e-05,-1.19883e-07,-2.30932e-06,-9.69047e-06,-0.00103863,0.205007,0.000821404,0.434388,0,0,0,0,0,5.91773e-06,5.69621e-05,5.69377e-05,0.000174711,0.0186537,0.0186513,0.00783507,0.0407782,0.0407779,0.0259337,6.04028e-11,6.03685e-11,1.06934e-09,1.07769e-06,1.07774e-06,5e-08,0,0,0,0,0,0,0,0 -21288000,0.983311,-0.0011553,-0.00638058,0.181817,-0.0494,0.0358501,-0.62662,-0.0107017,-0.004109,-0.119916,-1.05634e-05,-4.74955e-05,-4.81603e-07,-2.35202e-06,-9.56814e-06,-0.00103921,0.205007,0.000821404,0.434388,0,0,0,0,0,5.8818e-06,5.73313e-05,5.72998e-05,0.000173395,0.0202997,0.0202969,0.00788359,0.0450807,0.0450802,0.0260266,6.04418e-11,6.04096e-11,1.04569e-09,1.07769e-06,1.07774e-06,5e-08,0,0,0,0,0,0,0,0 -21392000,0.98327,-0.00267977,-0.00711033,0.181996,-0.0458514,0.0340262,-0.757243,-0.0112777,0.000535817,-0.187722,-1.05428e-05,-4.73881e-05,-4.46611e-07,8.59677e-07,-1.05532e-05,-0.00104528,0.205007,0.000821404,0.434388,0,0,0,0,0,5.86354e-06,5.62139e-05,5.61799e-05,0.000172431,0.0187537,0.0187516,0.00783025,0.0407768,0.0407764,0.0259132,5.70108e-11,5.69867e-11,1.02265e-09,1.07503e-06,1.07508e-06,5e-08,0,0,0,0,0,0,0,0 -21488000,0.983235,-0.00348962,-0.00754386,0.182152,-0.0416159,0.0309084,-0.887274,-0.0155529,0.00369667,-0.269416,-1.05422e-05,-4.7389e-05,-4.05256e-07,8.3735e-07,-1.05221e-05,-0.00104363,0.205007,0.000821404,0.434388,0,0,0,0,0,5.87843e-06,5.65611e-05,5.65257e-05,0.000172488,0.0203949,0.0203929,0.00787978,0.0450896,0.0450891,0.026007,5.70527e-11,5.70303e-11,1.00579e-09,1.07504e-06,1.07508e-06,5e-08,0,0,0,0,0,0,0,0 -21592000,0.983239,-0.00390175,-0.00754326,0.182122,-0.0346784,0.0288961,-1.01714,-0.0170181,0.00801264,-0.364072,-1.05689e-05,-4.73421e-05,-2.64259e-07,2.42717e-06,-9.87845e-06,-0.00105072,0.205007,0.000821404,0.434388,0,0,0,0,0,5.84932e-06,5.53782e-05,5.53444e-05,0.000171529,0.0188099,0.0188085,0.00782753,0.0407846,0.0407842,0.0258951,5.38085e-11,5.37931e-11,9.83801e-10,1.07183e-06,1.07187e-06,5e-08,0,0,0,0,0,0,0,0 -21688000,0.98323,-0.00421701,-0.00741688,0.182168,-0.033097,0.0245478,-1.14493,-0.0202538,0.0105853,-0.47295,-1.05669e-05,-4.73445e-05,-1.41615e-07,2.39745e-06,-9.81059e-06,-0.00104775,0.205007,0.000821404,0.434388,0,0,0,0,0,5.81297e-06,5.57042e-05,5.56719e-05,0.000170233,0.0204244,0.0204232,0.00787779,0.0451044,0.0451038,0.0259899,5.38486e-11,5.38351e-11,9.62387e-10,1.07183e-06,1.07187e-06,5e-08,0,0,0,0,0,0,0,0 -21792000,0.983242,-0.00450408,-0.007586,0.182094,-0.0282029,0.0213085,-1.28061,-0.019141,0.0146269,-0.598072,-1.06051e-05,-4.72506e-05,5.4335e-08,6.03225e-06,-8.30449e-06,-0.00105256,0.205007,0.000821404,0.434388,0,0,0,0,0,5.78305e-06,5.44735e-05,5.44423e-05,0.000169283,0.0188163,0.0188155,0.00782629,0.0407957,0.0407953,0.0258794,5.07988e-11,5.07908e-11,9.41533e-10,1.06813e-06,1.06816e-06,5e-08,0,0,0,0,0,0,0,0 -21888000,0.983227,-0.00479982,-0.00770495,0.182158,-0.0249218,0.0166794,-1.3953,-0.0216955,0.0164823,-0.731159,-1.06092e-05,-4.72474e-05,-1.30221e-07,5.91845e-06,-8.12193e-06,-0.00105013,0.205007,0.000821404,0.434388,0,0,0,0,0,5.73864e-06,5.47818e-05,5.47511e-05,0.000168013,0.020379,0.0203785,0.00787721,0.0451184,0.0451179,0.0259752,5.08395e-11,5.08332e-11,9.21222e-10,1.06813e-06,1.06816e-06,5e-08,0,0,0,0,0,0,0,0 -21992000,0.983237,-0.00539987,-0.00795726,0.182078,-0.0248375,0.0142101,-1.3809,-0.024193,0.0196103,-0.87338,-1.07005e-05,-4.72667e-05,-5.80545e-08,4.85507e-06,-4.03673e-06,-0.0010552,0.205007,0.000821404,0.434388,0,0,0,0,0,5.70504e-06,5.35217e-05,5.34921e-05,0.000167076,0.0184571,0.0184568,0.00782612,0.0407965,0.0407962,0.0258661,4.79894e-11,4.7987e-11,9.01442e-10,1.06402e-06,1.06403e-06,5e-08,0,0,0,0,0,0,0,0 -22088000,0.983226,-0.00613137,-0.00871022,0.182078,-0.0225936,0.0101675,-1.36442,-0.026518,0.0207309,-1.01016,-1.06986e-05,-4.72693e-05,6.54626e-08,4.77006e-06,-3.84381e-06,-0.00105201,0.205007,0.000821404,0.434388,0,0,0,0,0,5.71125e-06,5.38144e-05,5.37827e-05,0.000167092,0.0197063,0.0197061,0.00787728,0.0450785,0.0450782,0.0259629,4.8033e-11,4.8031e-11,8.86962e-10,1.06402e-06,1.06403e-06,5e-08,0,0,0,0,0,0,0,0 -22192000,0.983247,-0.00650119,-0.00909104,0.181938,-0.0104402,0.00830991,-1.37894,-0.0124313,0.023104,-1.15596,-1.07178e-05,-4.70936e-05,2.24326e-07,9.32859e-06,-1.15146e-06,-0.00105021,0.205007,0.000821404,0.434388,0,0,0,0,0,5.67632e-06,5.26513e-05,5.26203e-05,0.000166154,0.0179155,0.0179156,0.00782658,0.0407573,0.040757,0.025855,4.54327e-11,4.54328e-11,8.68073e-10,1.06042e-06,1.06042e-06,5e-08,0,0,0,0,0,0,0,0 -22288000,0.983224,-0.00720556,-0.00933702,0.182022,-0.00548963,0.00278858,-1.3764,-0.0132116,0.0236576,-1.2918,-1.07213e-05,-4.70906e-05,5.99074e-08,9.25815e-06,-1.00324e-06,-0.00104821,0.205007,0.000821404,0.434388,0,0,0,0,0,5.63461e-06,5.29251e-05,5.28945e-05,0.000164903,0.0191512,0.0191514,0.00787812,0.0449904,0.0449902,0.0259529,4.5475e-11,4.54751e-11,8.49671e-10,1.06042e-06,1.06042e-06,5e-08,0,0,0,0,0,0,0,0 -22392000,0.983171,-0.00751321,-0.00956959,0.182284,0.00263571,-0.00283951,-1.37896,-0.00201831,0.0226295,-1.44277,-1.07201e-05,-4.70182e-05,-3.65665e-08,9.99482e-06,5.60852e-07,-0.00104294,0.204042,0.000817565,0.434436,0,0,0,0,0,7.05432e-05,5.19333e-05,5.18347e-05,0.0020874,0.0167936,0.0167938,0.00782725,0.0406723,0.0406721,0.0258461,4.30976e-11,4.30983e-11,8.4067e-10,1.05719e-06,1.05718e-06,5e-08,0,0,0,0,0,0,0,0 -22488000,0.982963,-0.00769426,-0.00998897,0.183371,0.00686151,-0.0094202,-1.38322,-0.00155904,0.0220266,-1.57698,-1.07203e-05,-4.70183e-05,-3.81675e-08,9.95896e-06,6.44442e-07,-0.00104199,0.204042,0.000817565,0.434436,0,0,0,0,0,5.09923e-05,5.19364e-05,5.18499e-05,0.00150863,0.0169726,0.0169725,0.0078784,0.0447217,0.0447216,0.0259448,4.31468e-11,4.31475e-11,8.40716e-10,1.0572e-06,1.05718e-06,5e-08,0,0,0,0,0,0,0,0 -22592000,0.983071,-0.00751489,-0.0105802,0.182764,0.016637,-0.0147136,-1.38174,0.0119258,0.0216718,-1.72394,-1.07381e-05,-4.68887e-05,-3.36363e-08,1.42318e-05,-1.35524e-06,-0.0010399,0.204042,0.000817565,0.434436,0,0,0,0,0,3.9975e-05,5.18817e-05,5.1789e-05,0.00118116,0.0154075,0.0154073,0.00782788,0.040369,0.0403689,0.0258389,4.1168e-11,4.11688e-11,8.40756e-10,1.05625e-06,1.05623e-06,5e-08,0,0,0,0,0,0,0,0 -22688000,0.982945,-0.00744404,-0.0107915,0.183434,0.0188039,-0.0188422,-1.38514,0.0136517,0.0200249,-1.86038,-1.07386e-05,-4.68888e-05,-4.06698e-08,1.4149e-05,-1.16097e-06,-0.00103784,0.204042,0.000817565,0.434436,0,0,0,0,0,3.28903e-05,5.19104e-05,5.18235e-05,0.00097055,0.0170029,0.0170028,0.00787969,0.0441129,0.0441129,0.0259384,4.12171e-11,4.1218e-11,8.40782e-10,1.05626e-06,1.05623e-06,5e-08,0,0,0,0,0,0,0,0 -22792000,0.982883,-0.00730965,-0.0111451,0.183749,0.0239504,-0.0222118,-1.38916,0.022505,0.018821,-2.01298,-1.078e-05,-4.68534e-05,-4.89941e-08,2.12397e-05,-9.18403e-06,-0.0010326,0.204042,0.000817565,0.434436,0,0,0,0,0,2.78568e-05,5.14841e-05,5.14017e-05,0.000823836,0.0170412,0.0170412,0.00782984,0.0398671,0.039867,0.0258333,3.96265e-11,3.96272e-11,8.40796e-10,1.05345e-06,1.05341e-06,5e-08,0,0,0,0,0,0,0,0 -22888000,0.983036,-0.00749119,-0.0114586,0.182899,0.0270175,-0.0269668,-1.39089,0.0249496,0.0165199,-2.1511,-1.07803e-05,-4.68538e-05,-3.74548e-08,2.11275e-05,-8.9112e-06,-0.00102992,0.204042,0.000817565,0.434436,0,0,0,0,0,2.49429e-05,5.15238e-05,5.14463e-05,0.000740099,0.0199322,0.0199324,0.0078823,0.0434461,0.0434461,0.0259334,3.96756e-11,3.96763e-11,8.40806e-10,1.05346e-06,1.05341e-06,5e-08,0,0,0,0,0,0,0,0 -22992000,0.983178,-0.00733962,-0.0117278,0.182125,0.0294475,-0.0282187,-1.39661,0.0322776,0.0149154,-2.30962,-1.0818e-05,-4.68362e-05,-2.47651e-08,3.23935e-05,-2.2433e-05,-0.00102179,0.204042,0.000817565,0.434436,0,0,0,0,0,2.189e-05,5.04954e-05,5.04205e-05,0.000651806,0.0209113,0.0209121,0.00783289,0.0393719,0.0393719,0.0258291,3.84145e-11,3.84149e-11,8.40787e-10,1.04413e-06,1.04407e-06,5e-08,0,0,0,0,0,0,0,0 -23088000,0.983221,-0.00731442,-0.012043,0.181874,0.03349,-0.0319595,-1.39449,0.0353185,0.0120006,-2.44558,-1.08183e-05,-4.68363e-05,-2.81567e-08,3.23474e-05,-2.23141e-05,-0.00102065,0.204042,0.000817565,0.434436,0,0,0,0,0,1.9488e-05,5.05306e-05,5.04589e-05,0.000582421,0.0249192,0.0249206,0.00788581,0.0429779,0.0429779,0.0259299,3.84636e-11,3.84641e-11,8.40745e-10,1.04413e-06,1.04407e-06,5e-08,0,0,0,0,0,0,0,0 -23192000,0.983208,-0.00721335,-0.0121489,0.181938,0.035031,-0.0292893,-1.3967,0.0425767,0.00958191,-2.59592,-1.08274e-05,-4.68115e-05,-4.21299e-08,4.48697e-05,-3.56668e-05,-0.00101723,0.204042,0.000817565,0.434436,0,0,0,0,0,1.7563e-05,4.87964e-05,4.87292e-05,0.000526485,0.0260682,0.0260707,0.00783672,0.0390855,0.0390856,0.0258262,3.74957e-11,3.74958e-11,8.4068e-10,1.02535e-06,1.02528e-06,5e-08,0,0,0,0,0,0,0,0 -23288000,0.983243,-0.0076828,-0.0122543,0.181728,0.0384704,-0.0334427,-1.39324,0.0460716,0.0065364,-2.73483,-1.0828e-05,-4.68119e-05,-3.94736e-08,4.47576e-05,-3.5364e-05,-0.00101433,0.204042,0.000817565,0.434436,0,0,0,0,0,1.60012e-05,4.88252e-05,4.87667e-05,0.000480402,0.0309413,0.0309444,0.00789003,0.0429167,0.0429169,0.0259277,3.75448e-11,3.7545e-11,8.40585e-10,1.02535e-06,1.02528e-06,5e-08,0,0,0,0,0,0,0,0 -23392000,0.983205,-0.00749951,-0.0122889,0.181934,0.0384501,-0.0300231,-1.39412,0.0531137,0.00761837,-2.87954,-1.08567e-05,-4.6769e-05,-6.77648e-08,5.07661e-05,-5.92453e-05,-0.00101469,0.204042,0.000817565,0.434436,0,0,0,0,0,1.46836e-05,4.64516e-05,4.63978e-05,0.000441856,0.0314654,0.0314683,0.00784124,0.0391427,0.0391429,0.0258247,3.68345e-11,3.68343e-11,8.40463e-10,9.96574e-07,9.96495e-07,5e-08,0,0,0,0,0,0,0,0 -23488000,0.983235,-0.00760188,-0.0125925,0.181752,0.0409896,-0.0312133,-1.39549,0.0569219,0.00464701,-3.01647,-1.08569e-05,-4.67694e-05,-5.69229e-08,5.06997e-05,-5.90679e-05,-0.0010129,0.204042,0.000817565,0.434436,0,0,0,0,0,1.38511e-05,4.64808e-05,4.64275e-05,0.000416906,0.0369216,0.0369255,0.00789483,0.0433566,0.043357,0.0259269,3.68835e-11,3.68834e-11,8.4036e-10,9.96578e-07,9.96493e-07,5e-08,0,0,0,0,0,0,0,0 -23592000,0.983255,-0.00781687,-0.0124347,0.181643,0.0377412,-0.0308843,-1.39509,0.0609982,0.00178262,-3.16801,-1.0851e-05,-4.67533e-05,-4.99368e-08,6.73092e-05,-6.9207e-05,-0.00100962,0.204042,0.000817565,0.434436,0,0,0,0,0,1.28749e-05,4.36762e-05,4.36297e-05,0.000387717,0.0361719,0.0361757,0.00784615,0.0395703,0.0395707,0.0258244,3.6386e-11,3.63857e-11,8.40179e-10,9.59739e-07,9.59647e-07,5e-08,0,0,0,0,0,0,0,0 -23688000,0.983268,-0.00844034,-0.0129453,0.181508,0.0346931,-0.0319319,-1.29908,0.0644929,-0.00127611,-3.30171,-1.0851e-05,-4.67538e-05,-3.12328e-08,6.72504e-05,-6.90524e-05,-0.00100794,0.204042,0.000817565,0.434436,0,0,0,0,0,1.20431e-05,4.37026e-05,4.36585e-05,0.000362385,0.0415316,0.0415355,0.00789963,0.0442454,0.0442459,0.0259272,3.64351e-11,3.64348e-11,8.39959e-10,9.59743e-07,9.59645e-07,5e-08,0,0,0,0,0,0,0,0 -23792000,0.983231,-0.0102504,-0.0157924,0.181391,0.0269515,-0.0237272,-0.962771,0.069841,0.000195759,-3.42597,-1.0852e-05,-4.6724e-05,-1.46614e-08,6.7676e-05,-8.56403e-05,-0.0010043,0.204042,0.000817565,0.434436,0,0,0,0,0,1.13185e-05,4.08331e-05,4.07759e-05,0.00034025,0.0382912,0.0382942,0.00785011,0.0402723,0.0402727,0.0258252,3.60983e-11,3.60978e-11,8.39701e-10,9.18126e-07,9.18023e-07,5e-08,0,0,0,0,0,0,0,0 -23888000,0.983135,-0.0134995,-0.0197442,0.181313,0.021116,-0.0225682,-0.548814,0.0721573,-0.00198417,-3.49935,-1.08522e-05,-4.6724e-05,-2.09777e-08,6.76685e-05,-8.5595e-05,-0.00100384,0.204042,0.000817565,0.434436,0,0,0,0,0,1.06673e-05,4.08928e-05,4.08191e-05,0.000320696,0.0425199,0.0425235,0.00790285,0.0453177,0.0453184,0.0259285,3.61473e-11,3.61469e-11,8.39398e-10,9.18131e-07,9.18023e-07,5e-08,0,0,0,0,0,0,0,0 -23992000,0.983062,-0.0157261,-0.0222678,0.181233,0.022403,-0.0195915,-0.149924,0.0776511,-0.00139968,-3.55732,-1.08497e-05,-4.67049e-05,-3.01673e-08,6.31221e-05,-9.16374e-05,-0.000980794,0.204042,0.000817565,0.434436,0,0,0,0,0,1.00793e-05,3.84428e-05,3.83587e-05,0.000303411,0.0383675,0.038371,0.00785315,0.0410665,0.041067,0.0258268,3.59206e-11,3.59202e-11,8.39053e-10,8.73763e-07,8.73653e-07,5e-08,0,0,0,0,0,0,0,0 -24088000,0.983091,-0.0152911,-0.0212465,0.181237,0.0268064,-0.0264699,0.0763387,0.0799916,-0.00358885,-3.56244,-1.08504e-05,-4.67049e-05,-4.96634e-08,6.31247e-05,-9.14956e-05,-0.000978857,0.204042,0.000817565,0.434436,0,0,0,0,0,9.6816e-06,3.84534e-05,3.83795e-05,0.00029185,0.0429157,0.0429201,0.00790671,0.0463943,0.0463952,0.0259304,3.59696e-11,3.59693e-11,8.38774e-10,8.73767e-07,8.73654e-07,5e-08,0,0,0,0,0,0,0,0 -24192000,0.983184,-0.0123655,-0.0174505,0.181364,0.0378338,-0.0323116,0.067799,0.0858843,-0.00636518,-3.5685,-1.0851e-05,-4.66937e-05,-4.7542e-08,6.20698e-05,-8.95138e-05,-0.000961462,0.204042,0.000817565,0.434436,0,0,0,0,0,9.212e-06,3.63338e-05,3.6281e-05,0.000277715,0.0391651,0.0391693,0.00785823,0.0418671,0.0418678,0.0258289,3.58129e-11,3.58126e-11,8.38345e-10,8.29431e-07,8.29318e-07,5e-08,0,0,0,0,0,0,0,0 -24288000,0.983268,-0.0100379,-0.0141684,0.181337,0.0394796,-0.0340819,0.0448702,0.0896749,-0.00959972,-3.56713,-1.08513e-05,-4.66939e-05,-4.59292e-08,6.20676e-05,-8.93772e-05,-0.000959463,0.204042,0.000817565,0.434436,0,0,0,0,0,8.78053e-06,3.63363e-05,3.62997e-05,0.000264921,0.0440939,0.0440989,0.00791238,0.0475059,0.047507,0.0259329,3.58618e-11,3.58617e-11,8.37861e-10,8.29435e-07,8.2932e-07,5e-08,0,0,0,0,0,0,0,0 -24392000,0.983333,-0.00911262,-0.0131155,0.181109,0.0346115,-0.0271281,0.0614499,0.0956176,-0.00852527,-3.56248,-1.08497e-05,-4.66954e-05,-5.33603e-09,5.44119e-05,-9.66039e-05,-0.000958987,0.204042,0.000817565,0.434436,0,0,0,0,0,8.39277e-06,3.44532e-05,3.44214e-05,0.000253372,0.0393918,0.0393954,0.00786349,0.0426486,0.0426494,0.0258319,3.5745e-11,3.57449e-11,8.37326e-10,7.88997e-07,7.88885e-07,5e-08,0,0,0,0,0,0,0,0 -24488000,0.983361,-0.00934211,-0.0131819,0.180945,0.0282356,-0.0227323,0.058924,0.098627,-0.0109112,-3.55659,-1.08487e-05,-4.66964e-05,5.11292e-08,5.43614e-05,-9.66057e-05,-0.000958992,0.204042,0.000817565,0.434436,0,0,0,0,0,8.05124e-06,3.44871e-05,3.44566e-05,0.000242798,0.0438989,0.0439029,0.00791746,0.0485161,0.0485173,0.0259363,3.5794e-11,3.57939e-11,8.36731e-10,7.89001e-07,7.88888e-07,5e-08,0,0,0,0,0,0,0,0 -24592000,0.983314,-0.0100539,-0.0133666,0.181145,0.0286511,-0.0178226,0.0549942,0.104772,-0.00852464,-3.55002,-1.0851e-05,-4.67131e-05,3.96839e-08,4.20729e-05,-0.000101281,-0.00095879,0.204042,0.000817565,0.434436,0,0,0,0,0,7.74902e-06,3.28796e-05,3.28524e-05,0.000233204,0.0387129,0.0387159,0.00786849,0.043347,0.0433478,0.0258355,3.56986e-11,3.56988e-11,8.36081e-10,7.53537e-07,7.53429e-07,5e-08,0,0,0,0,0,0,0,0 -24688000,0.983294,-0.0105268,-0.0131475,0.181241,0.0245858,-0.0159802,0.0550165,0.107366,-0.010079,-3.54284,-1.0851e-05,-4.67129e-05,3.23012e-08,4.20587e-05,-0.000101328,-0.000959838,0.204042,0.000817565,0.434436,0,0,0,0,0,7.54113e-06,3.29185e-05,3.28954e-05,0.000226711,0.0428029,0.0428062,0.00792249,0.0493523,0.0493534,0.0259404,3.57476e-11,3.57478e-11,8.35564e-10,7.53541e-07,7.53433e-07,5e-08,0,0,0,0,0,0,0,0 -24792000,0.983308,-0.0106483,-0.0125157,0.181208,0.0224793,-0.0161633,0.0453788,0.109787,-0.00937457,-3.543,-1.08577e-05,-4.67253e-05,2.67235e-08,3.82731e-05,-0.000102946,-0.000957189,0.204042,0.000817565,0.434436,0,0,0,0,0,7.2648e-06,3.15745e-05,3.15565e-05,0.00021852,0.0373966,0.037399,0.00787335,0.0439196,0.0439204,0.0258397,3.56641e-11,3.56644e-11,8.34805e-10,7.23381e-07,7.23278e-07,5e-08,0,0,0,0,0,0,0,0 -24888000,0.983305,-0.0104578,-0.0120469,0.181266,0.0185221,-0.0174589,0.0356082,0.111799,-0.0109858,-3.54011,-1.08575e-05,-4.67256e-05,4.21129e-08,3.82752e-05,-0.000102925,-0.000956629,0.204042,0.000817565,0.434436,0,0,0,0,0,7.02129e-06,3.16199e-05,3.16038e-05,0.000210909,0.0410868,0.0410895,0.00792727,0.0499792,0.0499803,0.0259449,3.57129e-11,3.57133e-11,8.33977e-10,7.23385e-07,7.23282e-07,5e-08,0,0,0,0,0,0,0,0 -24992000,0.983285,-0.0102585,-0.0118438,0.1814,0.0140322,-0.0144454,0.0270799,0.114679,-0.00867973,-3.53906,-1.08601e-05,-4.67502e-05,3.81436e-08,3.03709e-05,-0.000106347,-0.000955605,0.204042,0.000817565,0.434436,0,0,0,0,0,6.80041e-06,3.05234e-05,3.05079e-05,0.000203959,0.0356907,0.0356928,0.00787789,0.0443491,0.0443498,0.0258444,3.56372e-11,3.56377e-11,8.33085e-10,6.98274e-07,6.98176e-07,5e-08,0,0,0,0,0,0,0,0 -25088000,0.983272,-0.0106126,-0.0118775,0.181446,0.00964439,-0.0124408,0.0232371,0.115763,-0.0100206,-3.54169,-1.08606e-05,-4.675e-05,1.83026e-08,3.04996e-05,-0.000106296,-0.000952711,0.204042,0.000817565,0.434436,0,0,0,0,0,6.58523e-06,3.05786e-05,3.05644e-05,0.000197474,0.0389696,0.0389719,0.00793166,0.0503934,0.0503943,0.0259497,3.5686e-11,3.56866e-11,8.32121e-10,6.98277e-07,6.98181e-07,5e-08,0,0,0,0,0,0,0,0 -25192000,0.983217,-0.0109107,-0.0117529,0.181734,0.00888574,-0.0119964,0.0228732,0.119697,-0.010624,-3.53938,-1.08807e-05,-4.67802e-05,-2.69619e-08,2.18922e-05,-0.000102444,-0.000951978,0.204042,0.000817565,0.434436,0,0,0,0,0,6.40135e-06,2.96978e-05,2.96856e-05,0.00019153,0.0337449,0.0337467,0.00788201,0.0446346,0.0446352,0.0258493,3.56172e-11,3.5618e-11,8.31087e-10,6.77609e-07,6.77519e-07,5e-08,0,0,0,0,0,0,0,0 -25288000,0.983164,-0.0110165,-0.0111122,0.182055,0.00285944,-0.0125761,0.0171674,0.120253,-0.0117869,-3.538,-1.08822e-05,-4.67788e-05,-1.04618e-07,2.19542e-05,-0.00010245,-0.000951717,0.204042,0.000817565,0.434436,0,0,0,0,0,6.22566e-06,2.97579e-05,2.97494e-05,0.000185947,0.0366643,0.0366665,0.0079357,0.0506081,0.0506088,0.0259548,3.5666e-11,3.56668e-11,8.29978e-10,6.77612e-07,6.77523e-07,5e-08,0,0,0,0,0,0,0,0 -25392000,0.983163,-0.0112008,-0.0109509,0.18206,-0.00126078,-0.00992159,0.015994,0.120811,-0.0094457,-3.53713,-1.08863e-05,-4.68059e-05,-1.0632e-07,1.60747e-05,-0.000104552,-0.000950634,0.204042,0.000817565,0.434436,0,0,0,0,0,6.05628e-06,2.90591e-05,2.9052e-05,0.000180844,0.0317267,0.0317286,0.00788581,0.0447851,0.0447856,0.0258543,3.56048e-11,3.56057e-11,8.28795e-10,6.60722e-07,6.60638e-07,5e-08,0,0,0,0,0,0,0,0 -25488000,0.983166,-0.011228,-0.0106448,0.182056,-0.00743878,-0.00857327,0.0158524,0.120368,-0.0103439,-3.53601,-1.08863e-05,-4.68059e-05,-1.06889e-07,1.6087e-05,-0.000104554,-0.000950416,0.204042,0.000817565,0.434436,0,0,0,0,0,5.94371e-06,2.91288e-05,2.9123e-05,0.000177452,0.0343112,0.0343134,0.00793931,0.0506482,0.0506488,0.02596,3.56536e-11,3.56546e-11,8.27866e-10,6.60724e-07,6.60643e-07,5e-08,0,0,0,0,0,0,0,0 -25592000,0.983135,-0.0114806,-0.0104756,0.18222,-0.00871794,-0.0125506,0.0165334,0.121125,-0.0134931,-3.53549,-1.09169e-05,-4.68266e-05,-1.69389e-07,1.21659e-05,-9.80595e-05,-0.000949567,0.204042,0.000817565,0.434436,0,0,0,0,0,5.79736e-06,2.85804e-05,2.8576e-05,0.00017296,0.0297122,0.0297141,0.00788907,0.0448156,0.044816,0.0258595,3.56011e-11,3.56022e-11,8.26546e-10,6.46961e-07,6.46884e-07,5e-08,0,0,0,0,0,0,0,0 -25688000,0.983143,-0.0109517,-0.0101825,0.182224,-0.0100187,-0.0108338,0.00532794,0.120252,-0.0146354,-3.53589,-1.09168e-05,-4.68267e-05,-1.64696e-07,1.22172e-05,-9.80766e-05,-0.000948688,0.204042,0.000817565,0.434436,0,0,0,0,0,5.65616e-06,2.86581e-05,2.86527e-05,0.000168689,0.0320208,0.0320228,0.00794226,0.0505404,0.050541,0.0259652,3.56498e-11,3.56509e-11,8.25143e-10,6.46964e-07,6.46889e-07,5e-08,0,0,0,0,0,0,0,0 -25792000,0.983156,-0.0107669,-0.00949478,0.182202,-0.0157872,-0.00761306,0.00392752,0.120834,-0.0142579,-3.53984,-1.09336e-05,-4.68525e-05,-1.82538e-07,7.07539e-06,-9.61201e-05,-0.000945936,0.204042,0.000817565,0.434436,0,0,0,0,0,5.52295e-06,2.82292e-05,2.82256e-05,0.000164794,0.0277788,0.0277807,0.00789182,0.0447424,0.0447428,0.0258645,3.56073e-11,3.56085e-11,8.2366e-10,6.35789e-07,6.35718e-07,5e-08,0,0,0,0,0,0,0,0 -25888000,0.983121,-0.0108221,-0.00955383,0.182388,-0.02177,-0.00485761,0.00579778,0.118977,-0.0148338,-3.5397,-1.09355e-05,-4.68507e-05,-2.87273e-07,7.12749e-06,-9.61282e-05,-0.000945764,0.204042,0.000817565,0.434436,0,0,0,0,0,5.39981e-06,2.83151e-05,2.83113e-05,0.000161056,0.0298214,0.0298234,0.00794488,0.0503107,0.0503112,0.0259703,3.56559e-11,3.56571e-11,8.22092e-10,6.35791e-07,6.35723e-07,5e-08,0,0,0,0,0,0,0,0 -25992000,0.983126,-0.0109282,-0.00973253,0.182346,-0.0271072,-0.00413402,-0.000861431,0.115147,-0.0158635,-3.53854,-1.09524e-05,-4.68562e-05,-2.903e-07,7.2697e-06,-9.38017e-05,-0.000945893,0.204042,0.000817565,0.434436,0,0,0,0,0,5.28486e-06,2.7988e-05,2.79836e-05,0.000157652,0.0259433,0.0259451,0.0078941,0.0445816,0.0445819,0.0258694,3.5624e-11,3.56253e-11,8.20439e-10,6.26699e-07,6.26633e-07,5e-08,0,0,0,0,0,0,0,0 -26088000,0.983151,-0.0106771,-0.00968971,0.182226,-0.0324091,-0.00306119,-0.00138224,0.112273,-0.016219,-3.53818,-1.09516e-05,-4.6857e-05,-2.47464e-07,7.24087e-06,-9.37937e-05,-0.000946126,0.204042,0.000817565,0.434436,0,0,0,0,0,5.21048e-06,2.80811e-05,2.80758e-05,0.000155476,0.0277705,0.0277726,0.00794694,0.0499827,0.0499832,0.0259751,3.56727e-11,3.5674e-11,8.19154e-10,6.26701e-07,6.26638e-07,5e-08,0,0,0,0,0,0,0,0 -26192000,0.983144,-0.0106821,-0.0102507,0.182231,-0.0325723,-0.00332387,-0.00712848,0.11327,-0.0191974,-3.54337,-1.09834e-05,-4.68787e-05,-2.1113e-07,2.90562e-06,-8.73735e-05,-0.000943102,0.204042,0.000817565,0.434436,0,0,0,0,0,5.11459e-06,2.7834e-05,2.78261e-05,0.000152447,0.0242286,0.0242303,0.00789588,0.0443477,0.044348,0.025874,3.56522e-11,3.56535e-11,8.17348e-10,6.19319e-07,6.19257e-07,5e-08,0,0,0,0,0,0,0,0 -26288000,0.983137,-0.0107049,-0.0105307,0.182254,-0.0353792,-0.00174008,-0.0124093,0.110008,-0.0194721,-3.54434,-1.09845e-05,-4.68776e-05,-2.69537e-07,2.92025e-06,-8.73795e-05,-0.000943126,0.204042,0.000817565,0.434436,0,0,0,0,0,5.01474e-06,2.79348e-05,2.79257e-05,0.000149517,0.0258715,0.0258732,0.00794848,0.0495761,0.0495765,0.0259797,3.57007e-11,3.5702e-11,8.15452e-10,6.19321e-07,6.19261e-07,5e-08,0,0,0,0,0,0,0,0 -26392000,0.983156,-0.0101699,-0.010469,0.182184,-0.0452354,-0.000709007,-0.0080532,0.0908273,-0.0217283,-3.54484,-1.10055e-05,-4.68711e-05,-3.28081e-07,1.07774e-05,-8.63432e-05,-0.000943779,0.204042,0.000817565,0.434436,0,0,0,0,0,4.91941e-06,2.77494e-05,2.77385e-05,0.000146875,0.022641,0.0226422,0.0078971,0.0440541,0.0440544,0.0258784,3.56917e-11,3.56929e-11,8.13466e-10,6.13329e-07,6.13269e-07,5e-08,0,0,0,0,0,0,0,0 -26488000,0.983164,-0.00994792,-0.0103607,0.182162,-0.0492265,0.00218388,0.00240735,0.0862746,-0.0216854,-3.54167,-1.10061e-05,-4.68706e-05,-3.51719e-07,1.06439e-05,-8.62362e-05,-0.000945814,0.204042,0.000817565,0.434436,0,0,0,0,0,4.83172e-06,2.78558e-05,2.78445e-05,0.000144288,0.0241103,0.0241115,0.00794948,0.0491074,0.0491078,0.0259839,3.57402e-11,3.57414e-11,8.11389e-10,6.1333e-07,6.13272e-07,5e-08,0,0,0,0,0,0,0,0 -26592000,0.983146,-0.00941705,-0.0106128,0.182272,-0.050759,0.00518781,0.0034824,0.0745453,-0.0234389,-3.54068,-1.10317e-05,-4.68802e-05,-4.19163e-07,1.21725e-05,-8.3245e-05,-0.000945514,0.204042,0.000817565,0.434436,0,0,0,0,0,4.75681e-06,2.7724e-05,2.77101e-05,0.000141958,0.0211785,0.0211791,0.0078978,0.0437119,0.0437122,0.0258823,3.57423e-11,3.57434e-11,8.0922e-10,6.08433e-07,6.08374e-07,5e-08,0,0,0,0,0,0,0,0 -26688000,0.983135,-0.00930199,-0.0102914,0.182355,-0.0528259,0.00915826,0.00254766,0.0695457,-0.0227486,-3.53874,-1.10335e-05,-4.68783e-05,-5.18983e-07,1.21246e-05,-8.32021e-05,-0.000946491,0.204042,0.000817565,0.434436,0,0,0,0,0,4.70973e-06,2.78363e-05,2.78233e-05,0.000140571,0.0225172,0.0225175,0.00794994,0.048592,0.0485923,0.0259877,3.57909e-11,3.5792e-11,8.07545e-10,6.08435e-07,6.08376e-07,5e-08,0,0,0,0,0,0,0,0 -26792000,0.98315,-0.00911863,-0.00975511,0.182311,-0.057708,0.00816446,0.00103047,0.0592213,-0.0253413,-3.54201,-1.10588e-05,-4.68828e-05,-5.41537e-07,1.3749e-05,-7.93036e-05,-0.000944194,0.204042,0.000817565,0.434436,0,0,0,0,0,4.63827e-06,2.77433e-05,2.77316e-05,0.000138503,0.0198539,0.0198541,0.00789805,0.0433316,0.0433319,0.0258859,3.58038e-11,3.58047e-11,8.05213e-10,6.0445e-07,6.04389e-07,5e-08,0,0,0,0,0,0,0,0 -26888000,0.983165,-0.00850021,-0.00985284,0.182257,-0.0635508,0.0113551,-0.00469444,0.0533813,-0.0243903,-3.54385,-1.10579e-05,-4.68836e-05,-4.96762e-07,1.38094e-05,-7.93629e-05,-0.000943211,0.204042,0.000817565,0.434436,0,0,0,0,0,4.57106e-06,2.78635e-05,2.785e-05,0.000136444,0.0210765,0.0210767,0.00795002,0.0480429,0.0480432,0.0259911,3.58521e-11,3.5853e-11,8.02787e-10,6.04452e-07,6.04391e-07,5e-08,0,0,0,0,0,0,0,0 -26992000,0.983155,-0.00794132,-0.0103375,0.182308,-0.0678522,0.0151312,-0.00545946,0.0444776,-0.0243274,-3.54692,-1.10736e-05,-4.68899e-05,-5.25597e-07,1.37009e-05,-7.71044e-05,-0.000941386,0.204042,0.000817565,0.434436,0,0,0,0,0,4.51298e-06,2.78073e-05,2.77909e-05,0.00013462,0.0186555,0.0186554,0.00789794,0.0429227,0.0429228,0.025889,3.58749e-11,3.58756e-11,8.00265e-10,6.01216e-07,6.0115e-07,5e-08,0,0,0,0,0,0,0,0 -27088000,0.983156,-0.00778769,-0.0106564,0.182294,-0.0698996,0.0215406,-0.00258671,0.0378253,-0.0225686,-3.55206,-1.10735e-05,-4.68898e-05,-5.38298e-07,1.38902e-05,-7.73283e-05,-0.000938558,0.204042,0.000817565,0.434436,0,0,0,0,0,4.45229e-06,2.79341e-05,2.79162e-05,0.000132792,0.0197712,0.0197707,0.00794965,0.0474707,0.0474708,0.025994,3.59232e-11,3.59238e-11,7.9765e-10,6.01218e-07,6.01151e-07,5e-08,0,0,0,0,0,0,0,0 -27192000,0.983161,-0.00782251,-0.0105752,0.182267,-0.0744334,0.0238805,-0.000936044,0.0302802,-0.021597,-3.5554,-1.10853e-05,-4.68944e-05,-5.6945e-07,1.32611e-05,-7.51187e-05,-0.000936727,0.204042,0.000817565,0.434436,0,0,0,0,0,4.39767e-06,2.79035e-05,2.78859e-05,0.000131193,0.0175682,0.0175675,0.00789736,0.0424924,0.0424925,0.0258916,3.59545e-11,3.5955e-11,7.94937e-10,5.98584e-07,5.98512e-07,5e-08,0,0,0,0,0,0,0,0 -27288000,0.983163,-0.00795646,-0.0115171,0.182193,-0.0808963,0.0294791,0.103415,0.0228598,-0.0190362,-3.55293,-1.10853e-05,-4.68944e-05,-5.69823e-07,1.32927e-05,-7.51578e-05,-0.000936245,0.204042,0.000817565,0.434436,0,0,0,0,0,4.36824e-06,2.80384e-05,2.80174e-05,0.000130346,0.0185385,0.0185377,0.00794881,0.0468818,0.0468819,0.0259964,3.6003e-11,3.60035e-11,7.92856e-10,5.98587e-07,5.98512e-07,5e-08,0,0,0,0,0,0,0,0 -27392000,0.983114,-0.00939481,-0.0141231,0.182208,-0.0813313,0.0341367,0.435458,0.0204546,-0.0155739,-3.5316,-1.10919e-05,-4.69076e-05,-5.59529e-07,9.23266e-06,-7.33956e-05,-0.000931285,0.204042,0.000817565,0.434436,0,0,0,0,0,4.3259e-06,2.80456e-05,2.8017e-05,0.00012891,0.0163754,0.0163745,0.00789584,0.0420383,0.0420384,0.0258937,3.60409e-11,3.60413e-11,7.89975e-10,5.96346e-07,5.96265e-07,5e-08,0,0,0,0,0,0,0,0 -27488000,0.983061,-0.0107185,-0.0159333,0.182273,-0.0844201,0.0395729,0.73775,0.0124754,-0.0120068,-3.4767,-1.10935e-05,-4.6906e-05,-6.56748e-07,9.25692e-06,-7.34932e-05,-0.000929872,0.204042,0.000817565,0.434436,0,0,0,0,0,4.2797e-06,2.8189e-05,2.81556e-05,0.000127441,0.0171827,0.0171816,0.00794694,0.046248,0.046248,0.0259982,3.6089e-11,3.60896e-11,7.87e-10,5.96347e-07,5.96264e-07,5e-08,0,0,0,0,0,0,0,0 -27592000,0.983081,-0.0106419,-0.0147878,0.182262,-0.0761101,0.0408316,0.840437,0.00980465,-0.0112679,-3.40699,-1.11013e-05,-4.69137e-05,-6.56804e-07,6.38569e-06,-7.00799e-05,-0.000914617,0.204042,0.000817565,0.434436,0,0,0,0,0,4.23752e-06,2.82347e-05,2.8207e-05,0.000126197,0.0153653,0.0153636,0.00789428,0.0415526,0.0415525,0.0258952,3.613e-11,3.61306e-11,7.83929e-10,5.93921e-07,5.93831e-07,5e-08,0,0,0,0,0,0,0,0 -27688000,0.983143,-0.00951036,-0.0119831,0.182196,-0.0723899,0.0369623,0.744927,0.00270865,-0.00747882,-3.33486,-1.11005e-05,-4.69142e-05,-6.33035e-07,6.55114e-06,-7.03299e-05,-0.00091194,0.204042,0.000817565,0.434436,0,0,0,0,0,4.19135e-06,2.8369e-05,2.83507e-05,0.000124912,0.0162814,0.0162797,0.00794545,0.0456113,0.0456112,0.0259994,3.61782e-11,3.61786e-11,7.80766e-10,5.93923e-07,5.93829e-07,5e-08,0,0,0,0,0,0,0,0 -27792000,0.98317,-0.00809184,-0.0103887,0.182217,-0.0693519,0.0335272,0.734585,0.00128046,-0.00767929,-3.26169,-1.11048e-05,-4.69184e-05,-5.99642e-07,3.53645e-06,-6.57628e-05,-0.000911843,0.204042,0.000817565,0.434436,0,0,0,0,0,4.15789e-06,2.843e-05,2.84149e-05,0.000123823,0.014665,0.0146635,0.00789258,0.0410684,0.0410683,0.0258962,3.6224e-11,3.62243e-11,7.77506e-10,5.91897e-07,5.91794e-07,5e-08,0,0,0,0,0,0,0,0 -27888000,0.983164,-0.00775001,-0.0104795,0.182262,-0.0752304,0.0391443,0.772608,-0.00564916,-0.00424025,-3.19101,-1.11047e-05,-4.69184e-05,-6.01754e-07,3.61622e-06,-6.58944e-05,-0.000910533,0.204042,0.000817565,0.434436,0,0,0,0,0,4.12305e-06,2.85796e-05,2.85636e-05,0.000122665,0.0154832,0.0154814,0.0079437,0.0449991,0.0449988,0.0260002,3.62721e-11,3.62723e-11,7.74154e-10,5.91899e-07,5.91793e-07,5e-08,0,0,0,0,0,0,0,0 -27992000,0.983157,-0.00820463,-0.0108663,0.182256,-0.0727109,0.040563,0.759204,-0.00526471,-0.00444436,-3.11733,-1.11034e-05,-4.69198e-05,-5.81029e-07,2.12966e-07,-6.17189e-05,-0.000905483,0.204042,0.000817565,0.434436,0,0,0,0,0,4.09391e-06,2.86573e-05,2.8641e-05,0.000121709,0.0140061,0.0140042,0.00789091,0.0405952,0.040595,0.0258968,3.63203e-11,3.63204e-11,7.70707e-10,5.90195e-07,5.9008e-07,5e-08,0,0,0,0,0,0,0,0 -28088000,0.983168,-0.00849324,-0.0108695,0.182181,-0.0764773,0.0408059,0.765733,-0.0124079,-0.000523177,-3.04329,-1.11021e-05,-4.69213e-05,-5.01837e-07,1.79582e-07,-6.16465e-05,-0.00090603,0.204042,0.000817565,0.434436,0,0,0,0,0,4.08391e-06,2.88119e-05,2.87961e-05,0.000121354,0.0147996,0.0147978,0.00794181,0.0444046,0.0444042,0.0260006,3.63686e-11,3.63687e-11,7.68072e-10,5.90197e-07,5.90077e-07,5e-08,0,0,0,0,0,0,0,0 -28192000,0.983171,-0.0079315,-0.0111803,0.182174,-0.0742465,0.0375789,0.771699,-0.0128886,-0.00137601,-2.96641,-1.10958e-05,-4.69198e-05,-4.87174e-07,-2.26062e-06,-5.78499e-05,-0.000903499,0.204042,0.000817565,0.434436,0,0,0,0,0,4.05803e-06,2.88971e-05,2.88794e-05,0.000120513,0.0134374,0.0134359,0.00788881,0.0401338,0.0401335,0.025897,3.64165e-11,3.64165e-11,7.64462e-10,5.88803e-07,5.88673e-07,5e-08,0,0,0,0,0,0,0,0 -28288000,0.983188,-0.00743869,-0.0114227,0.182085,-0.0797605,0.0402802,0.770644,-0.0202485,0.00241114,-2.89644,-1.10934e-05,-4.69217e-05,-3.79671e-07,-2.0719e-06,-5.81271e-05,-0.000901106,0.204042,0.000817565,0.434436,0,0,0,0,0,4.02898e-06,2.90581e-05,2.9039e-05,0.000119588,0.0142037,0.0142022,0.0079397,0.0438309,0.0438305,0.0260005,3.64643e-11,3.64645e-11,7.60764e-10,5.88805e-07,5.8867e-07,5e-08,0,0,0,0,0,0,0,0 -28392000,0.983172,-0.00745307,-0.0120628,0.182131,-0.0777456,0.0423317,0.770612,-0.0181727,0.0031675,-2.8219,-1.10814e-05,-4.69142e-05,-2.94996e-07,-5.57695e-06,-5.52089e-05,-0.000897514,0.204042,0.000817565,0.434436,0,0,0,0,0,4.01203e-06,2.91484e-05,2.91276e-05,0.000118851,0.0129538,0.0129522,0.00788679,0.0396866,0.0396863,0.0258967,3.65087e-11,3.65092e-11,7.56971e-10,5.87668e-07,5.87525e-07,5e-08,0,0,0,0,0,0,0,0 -28488000,0.98317,-0.00773764,-0.0125608,0.182094,-0.0787402,0.045462,0.770546,-0.025648,0.0073717,-2.75305,-1.10806e-05,-4.69146e-05,-2.75743e-07,-5.4041e-06,-5.55217e-05,-0.000894578,0.204042,0.000817565,0.434436,0,0,0,0,0,3.98578e-06,2.93149e-05,2.92932e-05,0.000118028,0.0136971,0.0136953,0.0079375,0.0432815,0.0432809,0.0260001,3.65564e-11,3.65572e-11,7.53094e-10,5.8767e-07,5.87522e-07,5e-08,0,0,0,0,0,0,0,0 -28592000,0.983197,-0.00777006,-0.0125348,0.18195,-0.0702447,0.0419126,0.769034,-0.0234701,0.00498342,-2.67395,-1.10576e-05,-4.69059e-05,-2.30309e-07,-7.92706e-06,-5.15057e-05,-0.000893758,0.204042,0.000817565,0.434436,0,0,0,0,0,3.96205e-06,2.94051e-05,2.93843e-05,0.000117402,0.0125461,0.0125443,0.00788437,0.0392569,0.0392564,0.0258961,3.6594e-11,3.65952e-11,7.49124e-10,5.86756e-07,5.866e-07,5e-08,0,0,0,0,0,0,0,0 -28688000,0.983187,-0.00755709,-0.0118942,0.182055,-0.0702907,0.0426691,0.769491,-0.0302247,0.00907447,-2.60154,-1.10579e-05,-4.69055e-05,-2.5252e-07,-7.89217e-06,-5.15901e-05,-0.000892898,0.204042,0.000817565,0.434436,0,0,0,0,0,3.96391e-06,2.95738e-05,2.95553e-05,0.000117298,0.0132737,0.0132718,0.00793495,0.0427591,0.0427584,0.0259992,3.6642e-11,3.66435e-11,7.46106e-10,5.86758e-07,5.86597e-07,5e-08,0,0,0,0,0,0,0,0 -28792000,0.983206,-0.00683561,-0.0116235,0.182001,-0.0765991,0.0432677,0.766868,-0.0549713,0.00968835,-2.52807,-1.10367e-05,-4.68861e-05,-1.60219e-07,-2.86816e-06,-5.25036e-05,-0.000888511,0.204042,0.000817565,0.434436,0,0,0,0,0,3.9478e-06,2.9663e-05,2.96448e-05,0.000116752,0.0122085,0.0122066,0.00788191,0.038847,0.0388465,0.0258951,3.66691e-11,3.66711e-11,7.41987e-10,5.86037e-07,5.85868e-07,5e-08,0,0,0,0,0,0,0,0 -28888000,0.983231,-0.00668755,-0.0113591,0.181889,-0.080248,0.0442026,0.764957,-0.0624663,0.0138716,-2.45786,-1.10344e-05,-4.6888e-05,-5.6925e-08,-2.72367e-06,-5.2729e-05,-0.000886555,0.204042,0.000817565,0.434436,0,0,0,0,0,3.9259e-06,2.98378e-05,2.98207e-05,0.000116097,0.0129264,0.0129246,0.00793246,0.0422662,0.0422655,0.025998,3.67167e-11,3.67189e-11,7.37789e-10,5.86039e-07,5.85865e-07,5e-08,0,0,0,0,0,0,0,0 -28992000,0.983211,-0.0064131,-0.0115799,0.18199,-0.0738401,0.0413208,0.763728,-0.0547068,0.0122562,-2.38461,-1.10006e-05,-4.68616e-05,-5.02701e-08,-6.01192e-06,-5.00366e-05,-0.000882064,0.204042,0.000817565,0.434436,0,0,0,0,0,3.91666e-06,2.99245e-05,2.99069e-05,0.000115625,0.0119364,0.0119349,0.00787936,0.0384596,0.038459,0.0258938,3.67293e-11,3.67322e-11,7.33506e-10,5.8548e-07,5.85299e-07,5e-08,0,0,0,0,0,0,0,0 -29088000,0.983212,-0.00627913,-0.0116461,0.181984,-0.0766539,0.0427384,0.76403,-0.0619818,0.0162517,-2.31144,-1.10002e-05,-4.68619e-05,-3.00453e-08,-5.99872e-06,-5.0052e-05,-0.000881949,0.204042,0.000817565,0.434436,0,0,0,0,0,3.89927e-06,3.0105e-05,3.00874e-05,0.00011504,0.0126483,0.0126467,0.00792987,0.0418055,0.0418047,0.0259965,3.67769e-11,3.678e-11,7.29146e-10,5.85483e-07,5.85297e-07,5e-08,0,0,0,0,0,0,0,0 -29192000,0.983238,-0.00619561,-0.0118395,0.181836,-0.0704683,0.041592,0.758384,-0.0537495,0.0152528,-2.23928,-1.096e-05,-4.68257e-05,8.9116e-08,-8.74517e-06,-4.80859e-05,-0.000876811,0.204042,0.000817565,0.434436,0,0,0,0,0,3.88516e-06,3.01858e-05,3.01681e-05,0.000114645,0.0117273,0.0117258,0.00787685,0.0380973,0.0380967,0.0258922,3.67711e-11,3.67748e-11,7.24705e-10,5.85057e-07,5.84864e-07,5e-08,0,0,0,0,0,0,0,0 -29288000,0.983218,-0.00644787,-0.0118606,0.181936,-0.0720574,0.0471086,0.760923,-0.0605591,0.0195505,-2.16509,-1.09599e-05,-4.68259e-05,9.99552e-08,-8.77735e-06,-4.80146e-05,-0.000877577,0.204042,0.000817565,0.434436,0,0,0,0,0,3.89452e-06,3.03707e-05,3.03535e-05,0.000114722,0.0124373,0.0124355,0.00792739,0.0413796,0.0413787,0.0259948,3.6819e-11,3.68229e-11,7.21339e-10,5.8506e-07,5.84863e-07,5e-08,0,0,0,0,0,0,0,0 -29392000,0.983223,-0.00687685,-0.0113189,0.181929,-0.0659891,0.0454576,0.76319,-0.0539311,0.0189287,-2.0871,-1.09207e-05,-4.67924e-05,1.72788e-07,-1.08271e-05,-4.62654e-05,-0.00087638,0.204042,0.000817565,0.434436,0,0,0,0,0,3.88675e-06,3.0441e-05,3.04269e-05,0.000114383,0.0115708,0.0115692,0.00787441,0.0377623,0.0377616,0.0258903,3.67904e-11,3.6795e-11,7.16765e-10,5.84742e-07,5.84539e-07,5e-08,0,0,0,0,0,0,0,0 -29488000,0.983238,-0.00687897,-0.0112218,0.181851,-0.068758,0.0457892,0.764671,-0.0603694,0.0233376,-2.01319,-1.09176e-05,-4.67954e-05,3.37224e-07,-1.07764e-05,-4.6267e-05,-0.000876716,0.204042,0.000817565,0.434436,0,0,0,0,0,3.87435e-06,3.063e-05,3.06166e-05,0.000113914,0.0122831,0.0122816,0.00792489,0.0409901,0.0409892,0.0259928,3.68378e-11,3.68427e-11,7.12123e-10,5.84745e-07,5.84538e-07,5e-08,0,0,0,0,0,0,0,0 -29592000,0.983259,-0.00675044,-0.0112042,0.181742,-0.0631679,0.0438694,0.766567,-0.0538178,0.0214994,-1.93329,-1.08663e-05,-4.67605e-05,4.82478e-07,-1.23214e-05,-4.47652e-05,-0.000877035,0.204042,0.000817565,0.434436,0,0,0,0,0,3.86638e-06,3.06915e-05,3.06785e-05,0.000113632,0.0114668,0.0114655,0.00787197,0.0374564,0.0374557,0.0258883,3.67823e-11,3.6788e-11,7.07407e-10,5.8451e-07,5.84298e-07,5e-08,0,0,0,0,0,0,0,0 -29688000,0.983277,-0.00683702,-0.0110128,0.181654,-0.0671428,0.042967,0.761467,-0.0600439,0.0256997,-1.86263,-1.08635e-05,-4.67629e-05,6.13407e-07,-1.2203e-05,-4.49255e-05,-0.000875464,0.204042,0.000817565,0.434436,0,0,0,0,0,3.8539e-06,3.08843e-05,3.08725e-05,0.000113215,0.0121881,0.012187,0.00792246,0.0406392,0.0406383,0.0259906,3.68297e-11,3.68356e-11,7.02627e-10,5.84513e-07,5.84297e-07,5e-08,0,0,0,0,0,0,0,0 -29792000,0.983284,-0.00661019,-0.011487,0.181595,-0.0628804,0.036997,0.758344,-0.0537292,0.0239995,-1.78679,-1.0813e-05,-4.67204e-05,7.75921e-07,-1.31835e-05,-4.40477e-05,-0.00087301,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85012e-06,3.09336e-05,3.09204e-05,0.000112979,0.011415,0.0114144,0.00786958,0.0371818,0.0371811,0.0258861,3.67429e-11,3.67496e-11,6.97776e-10,5.8434e-07,5.8412e-07,5e-08,0,0,0,0,0,0,0,0 -29888000,0.983284,-0.00613938,-0.0118373,0.181588,-0.0638191,0.0373064,0.753799,-0.0597446,0.0275336,-1.71886,-1.08108e-05,-4.67221e-05,8.7087e-07,-1.3038e-05,-4.42797e-05,-0.000870355,0.204042,0.000817565,0.434436,0,0,0,0,0,3.86137e-06,3.11319e-05,3.11171e-05,0.00011319,0.0121441,0.0121435,0.00792005,0.0403288,0.0403281,0.0259883,3.67906e-11,3.67975e-11,6.94114e-10,5.84343e-07,5.8412e-07,5e-08,0,0,0,0,0,0,0,0 -29992000,0.983282,-0.00619818,-0.0118863,0.181594,-0.0584544,0.0339363,0.750752,-0.0541047,0.0241861,-1.64702,-1.07476e-05,-4.66853e-05,9.24412e-07,-1.36416e-05,-4.39611e-05,-0.000865754,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85821e-06,3.11638e-05,3.11494e-05,0.000112996,0.011404,0.0114035,0.00786727,0.0369399,0.0369393,0.0258838,3.66685e-11,3.66761e-11,6.89154e-10,5.8421e-07,5.83985e-07,5e-08,0,0,0,0,0,0,0,0 -30088000,0.983272,-0.00630818,-0.0120097,0.181636,-0.0587164,0.0350191,0.748802,-0.0597576,0.0275085,-1.57663,-1.07507e-05,-4.66823e-05,7.59361e-07,-1.36602e-05,-4.40031e-05,-0.000864817,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84537e-06,3.13646e-05,3.13503e-05,0.000112661,0.0121429,0.0121423,0.00791775,0.0400597,0.040059,0.0259859,3.67157e-11,3.67235e-11,6.8414e-10,5.84213e-07,5.83986e-07,5e-08,0,0,0,0,0,0,0,0 -30192000,0.983238,-0.00623951,-0.0119761,0.181827,-0.053561,0.0328533,0.74873,-0.0539791,0.0268498,-1.50182,-1.07201e-05,-4.66279e-05,5.96366e-07,-1.39963e-05,-4.35112e-05,-0.000862685,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84508e-06,3.1378e-05,3.13643e-05,0.000112504,0.0114284,0.011428,0.00786506,0.0367314,0.0367308,0.0258813,3.65545e-11,3.65631e-11,6.79065e-10,5.84103e-07,5.83874e-07,5e-08,0,0,0,0,0,0,0,0 -30288000,0.983222,-0.00625599,-0.0119707,0.181912,-0.0523403,0.0330452,0.747186,-0.0590166,0.0300288,-1.43587,-1.0719e-05,-4.66286e-05,6.34967e-07,-1.38526e-05,-4.37435e-05,-0.000859275,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84079e-06,3.15815e-05,3.15682e-05,0.000112195,0.0121778,0.0121774,0.00791555,0.0398322,0.0398315,0.0259834,3.66018e-11,3.66105e-11,6.7394e-10,5.84107e-07,5.83876e-07,5e-08,0,0,0,0,0,0,0,0 -30392000,0.983218,-0.00619829,-0.0118449,0.181946,-0.0462614,0.0296509,0.744155,-0.0517896,0.0282581,-1.36576,-1.06652e-05,-4.65674e-05,8.27447e-07,-1.34702e-05,-4.3855e-05,-0.000854235,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84473e-06,3.15745e-05,3.1562e-05,0.000112068,0.0114843,0.011484,0.00786295,0.0365566,0.0365561,0.0258789,3.63984e-11,3.64079e-11,6.6876e-10,5.84005e-07,5.83773e-07,5e-08,0,0,0,0,0,0,0,0 -30488000,0.983241,-0.00618901,-0.0119769,0.18181,-0.0497775,0.0295437,0.744702,-0.0563822,0.0311332,-1.29819,-1.06623e-05,-4.65699e-05,9.63855e-07,-1.33433e-05,-4.40098e-05,-0.000851946,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83488e-06,3.1781e-05,3.17684e-05,0.000111794,0.0122461,0.0122459,0.00791351,0.0396459,0.0396454,0.0259809,3.64456e-11,3.64552e-11,6.63535e-10,5.84009e-07,5.83775e-07,5e-08,0,0,0,0,0,0,0,0 -30592000,0.983248,-0.00647807,-0.0122365,0.181745,-0.0460945,0.0273094,0.744403,-0.0502319,0.0285214,-1.22404,-1.06039e-05,-4.65159e-05,1.06303e-06,-1.29505e-05,-4.42802e-05,-0.000849654,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83332e-06,3.17526e-05,3.17401e-05,0.0001117,0.0115658,0.0115658,0.00786098,0.0364153,0.0364149,0.0258764,3.61975e-11,3.62078e-11,6.5826e-10,5.839e-07,5.83666e-07,5e-08,0,0,0,0,0,0,0,0 -30688000,0.983264,-0.00683339,-0.0124286,0.181634,-0.044151,0.0258671,0.742479,-0.0546225,0.0310897,-1.15777,-1.06031e-05,-4.65164e-05,1.09334e-06,-1.28364e-05,-4.44357e-05,-0.000846691,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84204e-06,3.19614e-05,3.19491e-05,0.000112026,0.0123436,0.0123436,0.00791154,0.0395003,0.0394998,0.0259784,3.62452e-11,3.62556e-11,6.54288e-10,5.83903e-07,5.83669e-07,5e-08,0,0,0,0,0,0,0,0 -30792000,0.983293,-0.00650429,-0.0120685,0.181515,-0.0382261,0.0212561,0.740457,-0.0497726,0.0308413,-1.08444,-1.05934e-05,-4.64657e-05,1.12284e-06,-1.23352e-05,-4.39119e-05,-0.00084409,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83625e-06,3.19077e-05,3.18965e-05,0.000111961,0.0116725,0.0116726,0.00785912,0.036307,0.0363066,0.0258739,3.59503e-11,3.59613e-11,6.48938e-10,5.83775e-07,5.8354e-07,5e-08,0,0,0,0,0,0,0,0 -30888000,0.983273,-0.00584498,-0.0119729,0.181651,-0.0380554,0.0185292,0.738364,-0.0533591,0.0327688,-1.01771,-1.05954e-05,-4.64636e-05,1.011e-06,-1.2287e-05,-4.39968e-05,-0.000841647,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83189e-06,3.21178e-05,3.21061e-05,0.000111727,0.0124657,0.0124659,0.00790975,0.0393943,0.039394,0.0259759,3.59975e-11,3.60086e-11,6.43554e-10,5.83779e-07,5.83544e-07,5e-08,0,0,0,0,0,0,0,0 -30992000,0.983266,-0.00596535,-0.0118776,0.181693,-0.0323796,0.0149414,0.740005,-0.0472029,0.028782,-0.945823,-1.05348e-05,-4.6411e-05,9.99494e-07,-1.15796e-05,-4.47197e-05,-0.000838513,0.204042,0.000817565,0.434436,0,0,0,0,0,3.8328e-06,3.20391e-05,3.20282e-05,0.000111675,0.0117933,0.0117935,0.0078574,0.0362305,0.0362303,0.0258715,3.56546e-11,3.5666e-11,6.3813e-10,5.8362e-07,5.83386e-07,5e-08,0,0,0,0,0,0,0,0 -31088000,0.983229,-0.00611617,-0.0119712,0.181881,-0.0313556,0.0125446,0.739461,-0.0502099,0.0300298,-0.875042,-1.05357e-05,-4.64101e-05,9.5335e-07,-1.15885e-05,-4.47164e-05,-0.000838387,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83344e-06,3.22505e-05,3.22399e-05,0.000111453,0.0126017,0.0126019,0.00790806,0.0393255,0.0393253,0.0259734,3.57016e-11,3.57132e-11,6.32676e-10,5.83624e-07,5.8339e-07,5e-08,0,0,0,0,0,0,0,0 -31192000,0.983238,-0.00626435,-0.0120556,0.181819,-0.0287005,0.0103373,0.741922,-0.0450482,0.0276619,-0.801907,-1.05031e-05,-4.63658e-05,1.12025e-06,-1.08288e-05,-4.48845e-05,-0.000836284,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83544e-06,3.21459e-05,3.21358e-05,0.000111415,0.0119266,0.0119268,0.00785579,0.036184,0.0361839,0.0258691,3.53105e-11,3.53223e-11,6.27189e-10,5.83428e-07,5.83196e-07,5e-08,0,0,0,0,0,0,0,0 -31288000,0.983253,-0.00652055,-0.0121465,0.181723,-0.0261171,0.00855843,0.743966,-0.0476383,0.0286196,-0.73496,-1.05014e-05,-4.63673e-05,1.20026e-06,-1.07287e-05,-4.49551e-05,-0.000833765,0.204042,0.000817565,0.434436,0,0,0,0,0,3.8475e-06,3.23581e-05,3.23483e-05,0.000111788,0.0127454,0.0127456,0.00790647,0.0392916,0.0392915,0.025971,3.53581e-11,3.53699e-11,6.23068e-10,5.83432e-07,5.832e-07,5e-08,0,0,0,0,0,0,0,0 -31392000,0.983266,-0.00623249,-0.0118973,0.181678,-0.0219358,0.00323176,0.743996,-0.0432199,0.0254537,-0.657087,-1.04741e-05,-4.63357e-05,1.12198e-06,-1.04224e-05,-4.5076e-05,-0.000833487,0.204042,0.000817565,0.434436,0,0,0,0,0,3.8436e-06,3.22268e-05,3.22175e-05,0.00011177,0.0120676,0.0120677,0.00785432,0.0361652,0.0361652,0.0258668,3.49197e-11,3.49316e-11,6.17534e-10,5.83197e-07,5.82967e-07,5e-08,0,0,0,0,0,0,0,0 -31488000,0.98324,-0.00599691,-0.0122268,0.181806,-0.0225288,0.000711609,0.739871,-0.045378,0.0255894,-0.588185,-1.04752e-05,-4.63346e-05,1.06272e-06,-1.04008e-05,-4.50878e-05,-0.00083219,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84211e-06,3.24398e-05,3.24294e-05,0.000111574,0.0129077,0.0129078,0.00790504,0.0392897,0.0392898,0.0259687,3.49667e-11,3.49787e-11,6.11978e-10,5.832e-07,5.82971e-07,5e-08,0,0,0,0,0,0,0,0 -31592000,0.983258,-0.0058502,-0.0126518,0.181683,-0.0213698,-0.000606387,0.74393,-0.0399535,0.0234234,-0.512438,-1.04569e-05,-4.62796e-05,1.18607e-06,-9.21872e-06,-4.5028e-05,-0.000830983,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84118e-06,3.22824e-05,3.22708e-05,0.000111562,0.0122138,0.0122139,0.00785291,0.0361719,0.0361719,0.0258646,3.44818e-11,3.44935e-11,6.064e-10,5.82916e-07,5.82689e-07,5e-08,0,0,0,0,0,0,0,0 -31688000,0.983284,-0.00583482,-0.0131532,0.181509,-0.023963,-0.00146933,0.73999,-0.0421472,0.0232701,-0.445674,-1.04537e-05,-4.62828e-05,1.35174e-06,-9.10341e-06,-4.50579e-05,-0.000828307,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83343e-06,3.24955e-05,3.24824e-05,0.00011138,0.0130663,0.0130663,0.00790363,0.0393164,0.0393166,0.0259666,3.45288e-11,3.45406e-11,6.00805e-10,5.8292e-07,5.82694e-07,5e-08,0,0,0,0,0,0,0,0 -31792000,0.983297,-0.00606991,-0.0137874,0.181382,-0.0169473,-0.00227898,0.739627,-0.0369094,0.0234454,-0.372207,-1.04733e-05,-4.62105e-05,1.48128e-06,-7.31943e-06,-4.40639e-05,-0.000826049,0.204042,0.000817565,0.434436,0,0,0,0,0,3.8329e-06,3.23118e-05,3.22976e-05,0.000111375,0.0123619,0.0123618,0.00785159,0.036201,0.0362012,0.0258625,3.40001e-11,3.40116e-11,5.95194e-10,5.82589e-07,5.82364e-07,5e-08,0,0,0,0,0,0,0,0 -31888000,0.983294,-0.00578376,-0.0135564,0.181427,-0.0135061,-0.00376957,0.736807,-0.0383582,0.0230972,-0.308636,-1.04723e-05,-4.62117e-05,1.54106e-06,-7.18981e-06,-4.40513e-05,-0.000821791,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85045e-06,3.25225e-05,3.25087e-05,0.000111767,0.0132245,0.0132243,0.00790234,0.0393685,0.0393687,0.0259645,3.40476e-11,3.40592e-11,5.9099e-10,5.82593e-07,5.82369e-07,5e-08,0,0,0,0,0,0,0,0 -31992000,0.98327,-0.00600941,-0.013084,0.181583,-0.00786947,-0.00318132,0.733948,-0.0332782,0.0218726,-0.239925,-1.04812e-05,-4.6156e-05,1.44086e-06,-5.86267e-06,-4.34422e-05,-0.000816937,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85473e-06,3.23101e-05,3.22988e-05,0.000111764,0.0125039,0.0125037,0.00785033,0.0362497,0.0362499,0.0258605,3.34781e-11,3.34891e-11,5.85358e-10,5.82214e-07,5.81991e-07,5e-08,0,0,0,0,0,0,0,0 -32088000,0.983283,-0.00638084,-0.012746,0.181528,-0.00765351,-0.00651959,0.735595,-0.0340439,0.021462,-0.17261,-1.04809e-05,-4.61564e-05,1.45905e-06,-5.80908e-06,-4.34185e-05,-0.000815043,0.204042,0.000817565,0.434436,0,0,0,0,0,3.8476e-06,3.25189e-05,3.25098e-05,0.000111591,0.0133747,0.0133743,0.00790116,0.0394415,0.0394417,0.0259625,3.35251e-11,3.35361e-11,5.79718e-10,5.82218e-07,5.81996e-07,5e-08,0,0,0,0,0,0,0,0 -32192000,0.983273,-0.00655374,-0.0129602,0.181557,-0.00627753,-0.00957752,0.736,-0.0302655,0.0216262,-0.102675,-1.05265e-05,-4.61108e-05,1.3979e-06,-4.67573e-06,-4.17845e-05,-0.00081073,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84825e-06,3.22838e-05,3.22749e-05,0.000111593,0.0126326,0.0126321,0.00784929,0.0363141,0.0363142,0.0258586,3.29188e-11,3.29291e-11,5.74072e-10,5.81795e-07,5.81574e-07,5e-08,0,0,0,0,0,0,0,0 -32288000,0.983291,-0.00651942,-0.0132143,0.181444,-0.00579063,-0.0127148,0.732834,-0.0308595,0.0205356,-0.0377578,-1.05248e-05,-4.61127e-05,1.49466e-06,-4.56594e-06,-4.17253e-05,-0.000807423,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84117e-06,3.24926e-05,3.24831e-05,0.000111421,0.0135171,0.0135164,0.00790013,0.0395307,0.0395309,0.0259606,3.29657e-11,3.29762e-11,5.68422e-10,5.81799e-07,5.81579e-07,5e-08,0,0,0,0,0,0,0,0 -32392000,0.983268,-0.00661755,-0.0133827,0.18155,0.00271044,-0.0135201,0.73325,-0.0142034,0.019439,0.0400769,-1.0526e-05,-4.60008e-05,1.41599e-06,-2.28949e-06,-4.11675e-05,-0.000807577,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84448e-06,3.22345e-05,3.22253e-05,0.000111422,0.0127586,0.0127578,0.00784825,0.0363909,0.0363911,0.0258568,3.2327e-11,3.23365e-11,5.62772e-10,5.81334e-07,5.81115e-07,5e-08,0,0,0,0,0,0,0,0 -32488000,0.983273,-0.0087132,-0.0118118,0.181545,0.0234208,-0.0601384,0.0258793,-0.0124832,0.0144063,0.0558003,-1.05274e-05,-4.59994e-05,1.34694e-06,-2.28156e-06,-4.11593e-05,-0.000807265,0.204042,0.000817565,0.434436,0,0,0,0,0,3.8565e-06,3.24366e-05,3.2437e-05,0.000111825,0.0148442,0.0148414,0.00766038,0.0396862,0.0396863,0.0259505,3.23748e-11,3.23839e-11,5.58547e-10,0,0,0,0,0,0,0,0,0,0,0 -32592000,0.983276,-0.00869709,-0.0118045,0.181533,0.0267333,-0.060597,0.0205561,0.00310825,0.0120196,0.0493061,-1.06011e-05,-4.59043e-05,1.40683e-06,-2.28156e-06,-4.11593e-05,-0.000807265,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85797e-06,3.19482e-05,3.19483e-05,0.000111825,0.0145576,0.0145549,0.00728246,0.0365561,0.0365562,0.0258085,3.16408e-11,3.16471e-11,5.52899e-10,0,0,0,0,0,0,0,0,0,0,0 -32688000,0.983273,-0.00866576,-0.0116924,0.181557,0.0231933,-0.064939,0.0187557,0.00551368,0.00598084,0.0478039,-1.06023e-05,-4.59032e-05,1.35188e-06,-2.28156e-06,-4.11593e-05,-0.000807265,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85207e-06,3.21501e-05,3.21503e-05,0.000111651,0.0162654,0.0162624,0.00703774,0.039948,0.039948,0.0258384,3.1688e-11,3.16939e-11,5.47256e-10,0,0,0,0,0,0,0,0,0,0,0 -32792000,0.983271,-0.00852897,-0.0117537,0.181567,0.0252086,-0.0631211,0.0141719,0.0186003,0.00486912,0.0417702,-1.06976e-05,-4.58147e-05,1.43358e-06,-2.28156e-06,-4.11593e-05,-0.000807265,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85482e-06,3.13289e-05,3.13282e-05,0.000111647,0.0161173,0.0161146,0.00670446,0.0367877,0.0367877,0.025648,3.0895e-11,3.08978e-11,5.4162e-10,0,0,0,0,0,0,0,0,0,0,0 -32888000,0.983282,-0.00849243,-0.0118368,0.181508,0.0252059,-0.0682698,0.0118865,0.0210627,-0.00142333,0.0387313,-1.06977e-05,-4.5815e-05,1.44499e-06,-2.28155e-06,-4.11593e-05,-0.000807265,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84719e-06,3.15247e-05,3.15236e-05,0.000111471,0.0181481,0.0181451,0.00648756,0.0402952,0.0402951,0.0256243,3.09422e-11,3.09446e-11,5.35993e-10,5.81336e-07,5.81117e-07,5.00012e-08,0,0,0,0,0,0,0,0 -32992000,0.983292,-0.00837827,-0.0118433,0.181458,0.0251606,-0.0651942,0.00969134,0.0319427,-0.00289779,0.0334984,-1.07821e-05,-4.57479e-05,1.55721e-06,-2.25455e-06,-4.1804e-05,-0.000807255,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84798e-06,3.03371e-05,3.03352e-05,0.000111465,0.0181241,0.0181215,0.00620821,0.0370944,0.0370943,0.0253979,3.011e-11,3.01092e-11,5.30379e-10,5.81322e-07,5.81102e-07,5.00065e-08,0,0,0,0,0,0,0,0 -33088000,0.983283,-0.00832671,-0.011832,0.18151,0.0222272,-0.0686629,0.0112847,0.0342398,-0.00930712,0.0369985,-1.07835e-05,-4.57462e-05,1.47266e-06,-2.25762e-06,-4.1801e-05,-0.000807268,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84224e-06,3.0524e-05,3.05219e-05,0.000111284,0.0207122,0.0207096,0.0060437,0.0407601,0.0407599,0.0253324,3.01572e-11,3.01561e-11,5.24777e-10,5.81327e-07,5.81107e-07,5.00114e-08,0,0,0,0,0,0,0,0 -33192000,0.983278,-0.00819248,-0.0117794,0.181543,0.0213689,-0.0661308,0.0102702,0.0432285,-0.0102464,0.0392256,-1.08671e-05,-4.5683e-05,1.38475e-06,-2.3978e-06,-4.56628e-05,-0.000807252,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84093e-06,2.89821e-05,2.8979e-05,0.000111275,0.0207997,0.0207974,0.00583327,0.0375,0.0374998,0.0250822,2.93134e-11,2.93092e-11,5.19192e-10,5.80303e-07,5.80084e-07,5.00129e-08,0,0,0,0,0,0,0,0 -33288000,0.983299,-0.00825669,-0.0117618,0.18143,0.0187836,-0.0667286,0.00966421,0.0450988,-0.016625,0.0414936,-1.08645e-05,-4.56856e-05,1.51701e-06,-2.40381e-06,-4.56575e-05,-0.000807272,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85355e-06,2.91586e-05,2.91556e-05,0.000111661,0.0238984,0.0238963,0.00572227,0.0413779,0.0413776,0.0249875,2.9361e-11,2.93567e-11,5.15025e-10,5.80308e-07,5.80089e-07,5.00174e-08,0,0,0,0,0,0,0,0 -33392000,0.983307,-0.00806275,-0.0118417,0.18139,0.0171083,-0.057921,0.00902233,0.0523846,-0.0134364,0.0389699,-1.09895e-05,-4.56128e-05,1.55048e-06,-4.28886e-06,-5.51736e-05,-0.000806996,0.204042,0.000817565,0.434436,0,0,0,0,0,3.85215e-06,2.73246e-05,2.73205e-05,0.000111646,0.0237786,0.0237769,0.00557374,0.0380261,0.0380259,0.0247256,2.85394e-11,2.85326e-11,5.09471e-10,5.77074e-07,5.76858e-07,5.00092e-08,0,0,0,0,0,0,0,0 -33488000,0.983301,-0.00807211,-0.0118257,0.181423,0.0143939,-0.0586835,0.00778224,0.0538612,-0.0189888,0.0359524,-1.09896e-05,-4.5613e-05,1.55528e-06,-4.26225e-06,-5.51954e-05,-0.00080689,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84761e-06,2.74895e-05,2.74858e-05,0.000111452,0.0272543,0.0272526,0.00551225,0.042166,0.0421657,0.0246142,2.85863e-11,2.85799e-11,5.03938e-10,5.77079e-07,5.76863e-07,5.00121e-08,0,0,0,0,0,0,0,0 -33592000,0.983321,-0.00788766,-0.0118117,0.181322,0.0130861,-0.0541599,0.00756185,0.0598798,-0.0168371,0.0337123,-1.1073e-05,-4.5559e-05,1.6585e-06,-6.15726e-06,-6.40599e-05,-0.000806734,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84519e-06,2.54712e-05,2.54663e-05,0.000111431,0.0266574,0.0266561,0.00541855,0.0386738,0.0386735,0.0243519,2.78227e-11,2.78141e-11,4.98428e-10,5.70965e-07,5.70754e-07,5.00014e-08,0,0,0,0,0,0,0,0 -33688000,0.983328,-0.00787908,-0.0117912,0.181287,0.00929725,-0.0558865,0.0044805,0.0610029,-0.0221421,0.0329606,-1.10726e-05,-4.55594e-05,1.68117e-06,-6.13551e-06,-6.40777e-05,-0.000806645,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83802e-06,2.56244e-05,2.562e-05,0.000111233,0.0303811,0.0303797,0.00540184,0.0431066,0.0431062,0.0242355,2.78696e-11,2.78614e-11,4.92942e-10,5.7097e-07,5.70759e-07,5.00003e-08,0,0,0,0,0,0,0,0 -33792000,0.983339,-0.00771441,-0.0117722,0.181238,0.00624987,-0.0497037,0.00613181,0.0658624,-0.0190351,0.029108,-1.11527e-05,-4.55045e-05,1.61785e-06,-9.25978e-06,-7.4243e-05,-0.000806231,0.204042,0.000817565,0.434436,0,0,0,0,0,3.833e-06,2.35503e-05,2.35446e-05,0.000111208,0.0291116,0.0291105,0.00535559,0.0394177,0.0394174,0.0239825,2.71929e-11,2.71829e-11,4.87482e-10,5.6188e-07,5.61676e-07,5e-08,0,0,0,0,0,0,0,0 -33888000,0.983346,-0.00774795,-0.0117355,0.181199,0.00266578,-0.0483705,0.00525675,0.0662319,-0.0237749,0.0291993,-1.11511e-05,-4.5506e-05,1.69844e-06,-9.24682e-06,-7.4253e-05,-0.000806175,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84654e-06,2.36926e-05,2.36874e-05,0.000111572,0.0329322,0.0329312,0.00537853,0.0441466,0.044146,0.0238717,2.72404e-11,2.72307e-11,4.83416e-10,5.61884e-07,5.6168e-07,5e-08,0,0,0,0,0,0,0,0 -33992000,0.983334,-0.00756048,-0.0118806,0.181261,0.00298701,-0.038476,0.0054849,0.07149,-0.0178514,0.0289759,-1.1233e-05,-4.54356e-05,1.63888e-06,-1.68909e-05,-8.69611e-05,-0.000805965,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84608e-06,2.16867e-05,2.16799e-05,0.000111533,0.0309354,0.0309347,0.00537268,0.0402117,0.0402112,0.0236361,2.66685e-11,2.66573e-11,4.78004e-10,5.50205e-07,5.5001e-07,5e-08,0,0,0,0,0,0,0,0 -34088000,0.983329,-0.00754649,-0.0118872,0.181289,0.000654706,-0.0405406,0.00605843,0.0716934,-0.0216735,0.0308317,-1.12342e-05,-4.54345e-05,1.57825e-06,-1.69264e-05,-8.69362e-05,-0.000806112,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83879e-06,2.18194e-05,2.18129e-05,0.000111319,0.0347345,0.0347338,0.0054304,0.0452129,0.0452122,0.0235397,2.67154e-11,2.67046e-11,4.72623e-10,5.50209e-07,5.50014e-07,5e-08,0,0,0,0,0,0,0,0 -34192000,0.983323,-0.00744948,-0.0119151,0.181325,-0.00233847,-0.0321719,0.00576046,0.075016,-0.0168414,0.0312225,-1.12904e-05,-4.53914e-05,1.6359e-06,-2.20196e-05,-9.76427e-05,-0.000805507,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84015e-06,1.99763e-05,1.99687e-05,0.00011127,0.0320477,0.0320473,0.0054582,0.0410009,0.0410004,0.0233281,2.6253e-11,2.62411e-11,4.67273e-10,5.36629e-07,5.36445e-07,5e-08,0,0,0,0,0,0,0,0 -34288000,0.983322,-0.00732442,-0.0119718,0.181331,-0.00324477,-0.0331006,0.0044208,0.0747722,-0.0199727,0.0290271,-1.12896e-05,-4.53921e-05,1.67447e-06,-2.19137e-05,-9.77181e-05,-0.000805066,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83425e-06,2.01012e-05,2.00935e-05,0.000111047,0.035732,0.0357316,0.0055456,0.0462296,0.0462289,0.0232534,2.62999e-11,2.62884e-11,4.61955e-10,5.36632e-07,5.36449e-07,5e-08,0,0,0,0,0,0,0,0 -34392000,0.983337,-0.00722625,-0.0119937,0.181253,-0.00424168,-0.0249054,0.00536491,0.0779065,-0.0150724,0.0267782,-1.13326e-05,-4.53546e-05,1.67173e-06,-2.74336e-05,-0.00010704,-0.000804749,0.204042,0.000817565,0.434436,0,0,0,0,0,3.82894e-06,1.848e-05,1.84712e-05,0.000110995,0.0324751,0.032475,0.00560049,0.0417357,0.0417351,0.0230708,2.59411e-11,2.59288e-11,4.56672e-10,5.21933e-07,5.21762e-07,5e-08,0,0,0,0,0,0,0,0 -34488000,0.983332,-0.00729846,-0.0119425,0.181281,-0.0062315,-0.0255677,0.00476813,0.0774277,-0.0175255,0.0257413,-1.1331e-05,-4.5356e-05,1.74871e-06,-2.73643e-05,-0.000107086,-0.000804456,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84426e-06,1.85986e-05,1.85902e-05,0.000111331,0.0359744,0.0359745,0.00571272,0.0471351,0.0471343,0.0230235,2.59886e-11,2.59766e-11,4.52744e-10,5.21934e-07,5.21765e-07,5e-08,0,0,0,0,0,0,0,0 -34592000,0.983334,-0.00720435,-0.0117384,0.181289,-0.00434716,-0.0202427,0.796824,0.0802868,-0.0143116,0.0560387,-1.13547e-05,-4.53273e-05,1.72664e-06,-3.20565e-05,-0.000112623,-0.000803939,0.204042,0.000817565,0.434436,0,0,0,0,0,3.84162e-06,1.72226e-05,1.72139e-05,0.000111267,0.030919,0.0309194,0.00578663,0.0423375,0.0423369,0.022873,2.57209e-11,2.57085e-11,4.47523e-10,5.06832e-07,5.06677e-07,5e-08,0,0,0,0,0,0,0,0 -34688000,0.983336,-0.00718817,-0.0114593,0.181292,-0.00479021,-0.0186607,1.7445,0.0798275,-0.0161244,0.168536,-1.13547e-05,-4.53267e-05,1.70927e-06,-3.15053e-05,-0.000113004,-0.000801557,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83327e-06,1.73364e-05,1.73287e-05,0.00011103,0.0324794,0.0324802,0.00591668,0.0476503,0.0476496,0.022857,2.57679e-11,2.57558e-11,4.42338e-10,5.06832e-07,5.06679e-07,5e-08,0,0,0,0,0,0,0,0 -34792000,0.983342,-0.00712548,-0.0112127,0.181279,-0.0043325,-0.0125508,2.74794,0.0819499,-0.0126614,0.35447,-1.1361e-05,-4.53001e-05,1.75855e-06,-2.726e-05,-0.00012376,-0.000763992,0.204042,0.000817565,0.434436,0,0,0,0,0,3.83026e-06,1.63857e-05,1.63779e-05,0.000110958,0.0280122,0.0280134,0.00600487,0.0426808,0.0426802,0.0227402,2.5597e-11,2.55848e-11,4.37192e-10,4.90093e-07,4.89956e-07,5e-08,0,0,0,0,0,0,0,0 -34888000,0.983346,-0.00710629,-0.0109387,0.181277,-0.00512516,-0.0106519,3.68548,0.0813879,-0.0135656,0.627391,-1.13588e-05,-4.52986e-05,1.76263e-06,-2.48728e-05,-0.000125399,-0.000753397,0.204042,0.000817565,0.434436,0,0,0,0,0,3.82161e-06,1.64977e-05,1.64908e-05,0.000110713,0.0296475,0.0296491,0.00615025,0.0477882,0.0477876,0.0227579,2.5644e-11,2.56322e-11,4.32083e-10,4.90091e-07,4.89958e-07,5e-08,0,0,0,0,0,0,0,0 +488000,0.983237,-0.00798439,-0.0137631,0.181638,0.00110872,-0.000522832,-0.0193987,7.58234e-05,-5.08941e-05,0.0276484,3.10173e-08,7.03823e-11,1.30798e-06,9.88709e-10,-8.61862e-10,4.18262e-08,0.203491,2.14204e-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.00801869,-0.0140022,0.181405,0.000687493,-0.000158842,-0.0369435,3.62432e-05,-2.13265e-05,0.0160397,4.30389e-08,9.0767e-12,1.81317e-06,3.65825e-09,-3.44534e-09,1.24343e-07,0.203491,2.14204e-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.0080714,-0.0143697,0.181816,0.00323886,-0.000530403,-0.0477349,0.000245389,-4.10207e-05,0.017733,4.76024e-09,-4.60119e-10,2.426e-07,3.75363e-10,-6.24777e-10,-1.16492e-08,0.203491,2.14204e-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.00805452,-0.0146151,0.182046,0.00575477,0.00207038,-0.0592733,0.000629231,5.19046e-05,0.0143143,-3.06321e-08,-5.10886e-10,-1.18023e-06,-1.29545e-09,8.06925e-10,-8.05869e-08,0.203491,2.14204e-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.00808492,-0.0149511,0.1822,0.00607745,0.00409991,-0.0743197,0.000573118,0.000278496,0.00366363,-8.03376e-08,-6.15501e-09,-3.07296e-06,1.60081e-08,-8.28157e-09,2.31536e-07,0.203491,2.14204e-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.00802233,-0.0152529,0.18307,0.0092751,0.00704688,-0.0910266,0.00138443,0.000777644,-0.00913315,-3.06643e-07,-1.06685e-08,-1.19551e-05,2.93032e-08,-1.96428e-08,7.75945e-07,0.203491,2.14204e-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.00812395,-0.0154388,0.182703,0.0155355,0.00526197,-0.10627,0.00142515,0.000771486,-0.0228124,-1.88334e-07,-5.50281e-08,-7.64761e-06,1.03963e-07,-2.45919e-08,1.45274e-06,0.203491,2.14204e-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.00808172,-0.0157372,0.182237,0.0220568,0.00480342,-0.108038,0.00335615,0.00128929,-0.019894,-3.70028e-08,-4.31913e-08,-1.91252e-06,1.18862e-08,5.24941e-08,-2.21987e-06,0.203491,2.14204e-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.00800237,-0.0159855,0.181242,0.025736,0.00430202,-0.121864,0.00324797,0.000817736,-0.0299464,3.09923e-07,-3.04292e-07,1.12404e-05,2.47392e-07,5.36677e-08,-2.5238e-06,0.203491,2.14204e-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.00801276,-0.0162328,0.180724,0.0349227,0.00524994,-0.120987,0.00643702,0.0013266,-0.0263017,4.56157e-07,-2.78845e-07,1.65063e-05,9.26654e-08,1.81855e-07,-8.61093e-06,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.71222e-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.00797386,-0.0162371,0.181101,0.0335707,0.00426548,-0.131496,0.00548233,0.000985125,-0.0369321,1.05077e-07,-1.23855e-06,9.65334e-06,7.46595e-07,7.96604e-08,-9.11575e-06,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.66711e-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.00804971,-0.0165743,0.181071,0.0415842,0.00471983,-0.142765,0.00940019,0.0013932,-0.0470266,9.59548e-08,-1.22598e-06,9.2259e-06,6.93453e-07,1.23058e-07,-1.11669e-05,0.203491,2.14204e-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.00809788,-0.01648,0.181055,0.0393025,0.00549171,-0.149375,0.00742383,0.00108418,-0.0523702,-4.02133e-07,-3.43865e-06,9.1477e-06,1.82761e-06,-6.21905e-08,-1.57976e-05,0.203491,2.14204e-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.00820576,-0.0167599,0.181102,0.0503197,0.00604139,-0.149728,0.0121627,0.00166968,-0.0542257,-4.45523e-07,-3.37864e-06,7.05299e-06,1.61964e-06,1.07121e-07,-2.38058e-05,0.203491,2.14204e-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.0440244,0.00698042,-0.152468,0.00907234,0.00127994,-0.0601209,-1.20676e-06,-7.36992e-06,1.34251e-05,3.32484e-06,-2.08473e-07,-2.93907e-05,0.203491,2.14204e-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.0525927,0.00800163,-0.153894,0.0141524,0.0020077,-0.0623208,-1.15325e-06,-7.29244e-06,1.47449e-05,3.09533e-06,-1.69347e-08,-3.85305e-05,0.203491,2.14204e-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.04222,0.00563504,-0.153465,0.00968689,0.00135361,-0.0614483,-2.5787e-06,-1.27938e-05,8.11116e-06,4.87476e-06,-2.49697e-07,-5.00242e-05,0.203491,2.14204e-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.0497315,0.00624444,-0.154829,0.0144915,0.00203063,-0.0650098,-2.60145e-06,-1.2709e-05,6.33621e-06,4.63811e-06,-5.18096e-08,-5.95876e-05,0.203491,2.14204e-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.0370215,0.00462984,-0.149222,0.00924731,0.0012845,-0.0618825,-3.77545e-06,-1.87264e-05,1.50075e-05,6.07594e-06,-1.51771e-07,-7.42128e-05,0.203491,2.14204e-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.0449227,0.00388731,-0.147752,0.0135672,0.00172301,-0.0590413,-3.76317e-06,-1.86022e-05,1.42826e-05,5.70257e-06,1.75175e-07,-9.01525e-05,0.203491,2.14204e-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.00826941,0.000997636,-0.061776,-4.98278e-06,-2.41905e-05,2.14743e-05,6.64418e-06,1.17821e-07,-0.000100992,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.06382e-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.0341018,0.00147043,-0.153918,0.0116122,0.00127244,-0.0681563,-4.98109e-06,-2.41289e-05,2.08744e-05,6.43828e-06,3.03064e-07,-0.000110164,0.203491,2.14204e-08,0.43426,0,0,0,0,0,3.00257e-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.00115583,-0.155464,0.0068302,0.000663298,-0.0712645,-6.16227e-06,-2.8561e-05,2.19797e-05,6.73016e-06,4.04115e-07,-0.000122485,0.203491,2.14204e-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.000193489,-0.151665,0.00959557,0.000758325,-0.0659179,-6.16985e-06,-2.84276e-05,1.99728e-05,6.22105e-06,8.69517e-07,-0.00014599,0.203491,2.14204e-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.74391e-08,2.51989e-06,2.51992e-06,2.26114e-06,0,0,0,0,0,0,0,0 +2888000,0.983761,-0.00821954,-0.0143738,0.17872,0.0201793,-0.0010975,-0.152249,0.0057077,0.000321785,-0.0650698,-7.21374e-06,-3.1829e-05,2.1248e-05,5.9752e-06,1.18872e-06,-0.000163737,0.203491,2.14204e-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.00822595,-0.0144923,0.178472,0.0228735,-0.00183761,-0.155301,0.00806159,0.000184178,-0.0694657,-7.17576e-06,-3.17829e-05,2.2333e-05,5.68218e-06,1.47413e-06,-0.000177897,0.203491,2.14204e-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.00817252,-0.0142217,0.17883,0.0183276,-0.00326086,-0.156326,0.004902,-5.32153e-05,-0.0707193,-8.27915e-06,-3.44192e-05,1.96451e-05,5.16966e-06,1.87352e-06,-0.000195745,0.203491,2.14204e-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.0218348,-0.00543699,-0.162884,0.00699315,-0.000570745,-0.0826116,-8.38334e-06,-3.43441e-05,1.38303e-05,5.03906e-06,1.96298e-06,-0.000201761,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.48605e-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.0240964,-0.00635158,-0.165897,0.00922334,-0.00119859,-0.090329,-8.3838e-06,-3.42987e-05,1.30425e-05,4.8144e-06,2.17638e-06,-0.000212958,0.203491,2.14204e-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.0172162,-0.0053036,-0.16723,0.00604117,-0.00111335,-0.0917314,-9.59554e-06,-3.63779e-05,9.75102e-06,4.06105e-06,2.76515e-06,-0.000235789,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.38874e-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.00794047,-0.0140882,0.180275,0.0220415,-0.00340687,-0.163336,0.00804656,-0.00152451,-0.0885223,-9.6331e-06,-3.62601e-05,6.04493e-06,3.51226e-06,3.28814e-06,-0.000264057,0.203491,2.14204e-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.0077464,-0.0137378,0.18033,0.0180844,-0.0032346,-0.169442,0.00558997,-0.00100294,-0.0963335,-1.07334e-05,-3.79995e-05,4.81378e-06,2.83676e-06,3.80328e-06,-0.000278504,0.203491,2.14204e-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.00779451,-0.0138022,0.179918,0.0196285,-0.00419468,-0.166633,0.00755631,-0.00136786,-0.0948663,-1.06561e-05,-3.79751e-05,7.44231e-06,2.2984e-06,4.34445e-06,-0.000306598,0.203491,2.14204e-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.00765257,-0.0136174,0.180013,0.0139549,4.58681e-05,-0.166737,0.00509544,-0.000743375,-0.0966469,-1.16232e-05,-3.95311e-05,6.39512e-06,1.33998e-06,5.1092e-06,-0.000331898,0.203491,2.14204e-08,0.43426,0,0,0,0,0,2.09521e-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.00762205,-0.0137068,0.179864,0.0148922,0.000487071,-0.16901,0.00656482,-0.000676504,-0.103455,-1.15893e-05,-3.9524e-05,7.58706e-06,1.0555e-06,5.3965e-06,-0.000346979,0.203491,2.14204e-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.00757984,-0.0135019,0.180404,0.0128418,0.00128407,-0.170028,0.00444787,-0.000291501,-0.105182,-1.23102e-05,-4.08202e-05,4.38708e-06,6.09849e-08,6.13804e-06,-0.00037374,0.203491,2.14204e-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.00754417,-0.0134528,0.180774,0.015101,0.00112682,-0.159037,0.00597655,-0.000184446,-0.0939399,-1.23223e-05,-4.0732e-05,2.25108e-06,-7.64082e-07,6.984e-06,-0.000419754,0.203491,2.14204e-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.00759553,-0.013188,0.180582,0.0116481,1.68796e-05,-0.159243,0.00411338,-6.04725e-05,-0.0977129,-1.27988e-05,-4.19588e-05,3.1373e-06,-1.70416e-06,7.6154e-06,-0.00044161,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.91204e-05,0.00173565,0.00173575,0.000560782,0.52568,0.525717,0.116402,0.149677,0.149682,0.149743,9.07437e-08,9.08148e-08,2.88136e-08,2.50775e-06,2.50779e-06,1.52543e-06,0,0,0,0,0,0,0,0 +4288000,0.983496,-0.00765223,-0.0132549,0.180279,0.0147911,0.000505332,-0.160715,0.00546124,-5.94032e-05,-0.10302,-1.27608e-05,-4.19646e-05,4.73909e-06,-2.02121e-06,7.94611e-06,-0.000459328,0.203491,2.14204e-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.67251e-08,2.50773e-06,2.50777e-06,1.4592e-06,0,0,0,0,0,0,0,0 +4392000,0.983578,-0.00756887,-0.0131026,0.179849,0.01325,-0.000690438,-0.153172,0.00398407,-8.6312e-05,-0.0951251,-1.31349e-05,-4.30492e-05,6.80816e-06,-3.30878e-06,8.93755e-06,-0.000501434,0.203491,2.14204e-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.3873e-08,7.39318e-08,2.48201e-08,2.50346e-06,2.5035e-06,1.39301e-06,0,0,0,0,0,0,0,0 +4488000,0.983558,-0.0076165,-0.0130836,0.17996,0.0145384,0.00115566,-0.152281,0.00538312,-1.39588e-05,-0.0964671,-1.31353e-05,-4.30251e-05,6.31218e-06,-3.70333e-06,9.35457e-06,-0.000524501,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.76205e-05,0.00166029,0.0016604,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.0125988,-0.000198085,-0.151651,0.0038703,7.60278e-06,-0.0999172,-1.35432e-05,-4.39888e-05,4.33017e-06,-4.62219e-06,9.94922e-06,-0.000546061,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.7136e-05,0.00135438,0.00135449,0.000505611,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.0131132,-0.000749558,-0.144994,0.00521026,8.8412e-06,-0.0966546,-1.34955e-05,-4.4005e-05,6.43907e-06,-5.13132e-06,1.04913e-05,-0.000576117,0.203491,2.14204e-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.04333e-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.00549473,-9.16145e-06,-0.143466,0.00340171,6.57316e-06,-0.0984897,-1.3846e-05,-4.48542e-05,5.19905e-06,-6.03053e-06,1.10926e-05,-0.000598637,0.203491,2.14204e-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.00590778,-0.00177195,-0.13695,0.00396772,-7.78752e-05,-0.0947777,-1.38293e-05,-4.48528e-05,5.7611e-06,-6.5029e-06,1.16037e-05,-0.000627552,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.62421e-05,0.00127576,0.00127587,0.000479709,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.00447908,-0.000495997,-0.130346,0.00254903,-9.99502e-05,-0.0908021,-1.40814e-05,-4.54253e-05,5.30573e-06,-7.36615e-06,1.22914e-05,-0.000657504,0.203491,2.14204e-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.00532118,-1.4615e-05,-0.125175,0.0030546,-0.000169542,-0.0865692,-1.4103e-05,-4.53932e-05,3.91225e-06,-7.78113e-06,1.2767e-05,-0.000684941,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.54513e-05,0.00111323,0.00111332,0.000457967,0.445252,0.445274,0.0996634,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.00106823,0.00293174,-0.12283,0.00192154,1.24048e-05,-0.0867285,-1.42648e-05,-4.58046e-05,4.12001e-06,-8.39893e-06,1.32462e-05,-0.000705937,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.50885e-05,0.000910179,0.000910252,0.000448845,0.342844,0.342861,0.0973586,0.121234,0.121236,0.142646,3.08188e-08,3.08437e-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.00296243,0.00432338,-0.113384,0.00217539,0.000362192,-0.0828551,-1.42585e-05,-4.58051e-05,4.32524e-06,-8.77261e-06,1.36629e-05,-0.000730306,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.50519e-05,0.000970284,0.000970362,0.000447033,0.404677,0.404699,0.0968191,0.158141,0.158144,0.145693,3.08186e-08,3.08435e-08,1.40831e-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.000360272,0.00661513,-0.109866,0.00133278,0.000539834,-0.079111,-1.4281e-05,-4.60861e-05,3.71903e-06,-9.34439e-06,1.40818e-05,-0.000754355,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.47036e-05,0.000796155,0.000796217,0.000438313,0.312693,0.312709,0.0943549,0.116367,0.116369,0.145006,2.46397e-08,2.46595e-08,1.32552e-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.00039039,0.00933499,-0.103531,0.00133442,0.00127799,-0.0748501,-1.4289e-05,-4.6076e-05,3.27748e-06,-9.66835e-06,1.4465e-05,-0.000776959,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.43743e-05,0.000845989,0.000846058,0.000427978,0.367529,0.367551,0.0913427,0.150747,0.15075,0.142735,2.46394e-08,2.46593e-08,1.24937e-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.000848774,0.0115007,-0.0962167,0.000811645,0.00141188,-0.0684493,-1.41234e-05,-4.62928e-05,2.67588e-06,-1.02059e-05,1.47534e-05,-0.000802297,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.40504e-05,0.00069755,0.000697607,0.000419965,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.000439525,0.0147604,-0.0934193,0.000704295,0.00260247,-0.0647366,-1.41419e-05,-4.62754e-05,1.79541e-06,-1.04608e-05,1.50781e-05,-0.000821409,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.37368e-05,0.000738859,0.000738923,0.00041044,0.333511,0.333534,0.0858443,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.00674759,-0.0125049,0.18041,-0.00070778,0.0149313,-0.0884846,0.000393617,0.00242716,-0.0604451,-1.37782e-05,-4.64895e-05,2.40877e-06,-1.09107e-05,1.51175e-05,-0.000841536,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.34425e-05,0.000612878,0.000612927,0.000403048,0.259722,0.259738,0.0833396,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.012571,0.180451,0.00150315,0.016302,-0.0870429,0.000426289,0.00397679,-0.0649808,-1.37813e-05,-4.64871e-05,2.28978e-06,-1.09819e-05,1.52099e-05,-0.000847023,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.34086e-05,0.000647145,0.000647199,0.000401523,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.00207561,0.0166291,-0.0809674,0.00063542,0.00569639,-0.0599449,-1.38015e-05,-4.64693e-05,1.40514e-06,-1.12166e-05,1.55358e-05,-0.000866186,0.203491,2.14204e-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.56573e-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.00140592,0.0145387,-0.0758703,0.000498177,0.00461679,-0.0551333,-1.33963e-05,-4.66632e-05,-3.20736e-07,-1.15976e-05,1.5441e-05,-0.000882924,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.28509e-05,0.000569011,0.000569061,0.000386001,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.00113985,0.0162831,-0.0732728,0.000713077,0.00623592,-0.0537236,-1.34136e-05,-4.66483e-05,-1.07203e-06,-1.17366e-05,1.5652e-05,-0.000895377,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.26497e-05,0.000600886,0.000600942,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.000485129,0.0144271,-0.0752754,0.000429641,0.00491865,-0.0586573,-1.29757e-05,-4.68721e-05,-1.27152e-06,-1.19713e-05,1.52994e-05,-0.00089835,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.23734e-05,0.000502664,0.000502709,0.000371567,0.249114,0.249127,0.0718369,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.00686997,-0.0125216,0.180937,0.000451765,0.0155153,-0.0738211,0.000389852,0.00647855,-0.0594463,-1.29684e-05,-4.68807e-05,-8.31578e-07,-1.20775e-05,1.54393e-05,-0.000907261,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.21779e-05,0.000529182,0.000529232,0.00036547,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.00693163,-0.0125241,0.180933,-0.00151355,0.0111854,-0.0707742,0.000173893,0.00486993,-0.057258,-1.25509e-05,-4.70653e-05,-1.19785e-06,-1.23738e-05,1.5221e-05,-0.000918567,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.21047e-05,0.000446415,0.000446453,0.000364181,0.226447,0.226457,0.0685411,0.119747,0.119749,0.135377,8.27629e-09,8.28264e-09,7.48103e-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.00238365,0.0122032,-0.0729343,-3.86635e-06,0.00600926,-0.0602089,-1.25679e-05,-4.70502e-05,-1.96902e-06,-1.24214e-05,1.53185e-05,-0.000924112,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.19139e-05,0.00046854,0.000468582,0.000358315,0.262174,0.262185,0.0662733,0.152491,0.152494,0.134174,8.27619e-09,8.28256e-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.00538796,0.0104073,-0.0731928,-0.000355421,0.00451334,-0.0582222,-1.22102e-05,-4.7174e-05,-2.47089e-06,-1.26504e-05,1.51305e-05,-0.000934855,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.1665e-05,0.00039875,0.000398782,0.000351297,0.206289,0.206296,0.0637685,0.114675,0.114677,0.131706,6.72243e-09,6.72747e-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.00696209,-0.0123916,0.181335,-0.00309377,0.0123022,-0.0710564,-0.000806771,0.00567061,-0.0597777,-1.22276e-05,-4.71588e-05,-3.24791e-06,-1.2707e-05,1.52483e-05,-0.000941681,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.14911e-05,0.000417269,0.000417305,0.000345823,0.237789,0.237798,0.0616402,0.145111,0.145113,0.130494,6.72235e-09,6.7274e-09,6.46799e-09,2.46974e-06,2.46967e-06,3.50079e-07,0,0,0,0,0,0,0,0 +6888000,0.983307,-0.00685321,-0.0122728,0.181409,-0.00293765,0.00870448,-0.0655419,-0.000734205,0.00423202,-0.0560637,-1.19043e-05,-4.72237e-05,-3.63692e-06,-1.28806e-05,1.50933e-05,-0.000953258,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.12605e-05,0.000358336,0.000358361,0.000339271,0.187981,0.187986,0.0593059,0.109936,0.109937,0.128085,5.48347e-09,5.48746e-09,6.17059e-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.00362048,0.00982104,-0.0627094,-0.00111288,0.0051868,-0.0550691,-1.19085e-05,-4.72216e-05,-3.76106e-06,-1.29539e-05,1.52248e-05,-0.000961684,0.203491,2.14204e-08,0.43426,0,0,0,0,0,1.10987e-05,0.000373892,0.000373919,0.000334155,0.215906,0.215912,0.0573203,0.138254,0.138256,0.126878,5.48341e-09,5.4874e-09,5.89177e-09,2.46846e-06,2.46839e-06,3.08645e-07,0,0,0,0,0,0,0,0 +7088000,0.9831,-0.00679115,-0.0121447,0.18254,-0.00374604,0.0112354,-0.0625643,-0.00099198,0.00410207,-0.0572131,-1.16226e-05,-4.726e-05,-3.91467e-06,-1.30275e-05,1.4984e-05,-0.000965825,0.204748,1.39698e-08,0.43476,0,0,0,0,0,7.56093e-05,0.000319438,0.000319257,0.00219372,0.162811,0.162817,0.0551549,0.105416,0.105417,0.124537,4.49278e-09,4.49591e-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.00672382,-0.0122169,0.182853,-0.00442049,0.012263,-0.0590952,-0.0014629,0.00539748,-0.055717,-1.16242e-05,-4.72604e-05,-3.91587e-06,-1.30945e-05,1.5109e-05,-0.000974104,0.204748,1.39698e-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.49283e-09,4.49596e-09,5.75776e-09,2.46737e-06,2.46729e-06,2.7256e-07,0,0,0,0,0,0,0,0 +7288000,0.983027,-0.00671882,-0.0121891,0.182932,-0.00283787,0.0129509,-0.0564523,-0.00122957,0.00437321,-0.0533413,-1.13459e-05,-4.72858e-05,-3.92324e-06,-1.31725e-05,1.50206e-05,-0.000982229,0.204748,1.39698e-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.72439e-09,3.72685e-09,5.75695e-09,2.46694e-06,2.46686e-06,2.60247e-07,0,0,0,0,0,0,0,0 +7392000,0.983133,-0.00664278,-0.0121604,0.182367,-0.00413345,0.0149595,-0.0535807,-0.00157578,0.00589357,-0.0498272,-1.13471e-05,-4.72869e-05,-3.89629e-06,-1.32436e-05,1.51565e-05,-0.000991425,0.204748,1.39698e-08,0.43476,0,0,0,0,0,3.59031e-05,0.000320829,0.000320762,0.00104123,0.134331,0.134336,0.0507205,0.11973,0.119732,0.123648,3.72444e-09,3.7269e-09,5.75603e-09,2.46694e-06,2.46686e-06,2.44828e-07,0,0,0,0,0,0,0,0 +7488000,0.983215,-0.00665918,-0.0121512,0.181922,-0.00215382,0.0153868,-0.0469738,-0.00124473,0.00497025,-0.0427423,-1.10748e-05,-4.73178e-05,-3.84947e-06,-1.33156e-05,1.54357e-05,-0.00100307,0.204748,1.39698e-08,0.43476,0,0,0,0,0,3.01908e-05,0.000319926,0.000319876,0.00087484,0.111892,0.111896,0.048825,0.0922028,0.0922037,0.121357,3.15364e-09,3.1556e-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.00187611,0.0166104,-0.0432338,-0.00145095,0.00659231,-0.0372021,-1.10762e-05,-4.73185e-05,-3.83342e-06,-1.33932e-05,1.55797e-05,-0.00101288,0.204748,1.39698e-08,0.43476,0,0,0,0,0,2.6067e-05,0.000320915,0.000320881,0.00075486,0.128826,0.128831,0.0472083,0.110204,0.110205,0.120144,3.15369e-09,3.15566e-09,5.7518e-09,2.46686e-06,2.46677e-06,2.17024e-07,0,0,0,0,0,0,0,0 +7688000,0.98323,-0.00678387,-0.0121456,0.181841,-0.0014401,0.0170538,-0.0425203,-0.00110469,0.00568949,-0.0322691,-1.08119e-05,-4.73624e-05,-3.85015e-06,-1.33452e-05,1.63598e-05,-0.00102132,0.204748,1.39698e-08,0.43476,0,0,0,0,0,2.29396e-05,0.00031666,0.000316633,0.00066422,0.117643,0.117647,0.0454653,0.0865958,0.0865966,0.117939,2.73546e-09,2.73705e-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.00666985,-0.0121542,0.181952,-0.000345111,0.0178058,-0.0436476,-0.00122323,0.00742454,-0.0368951,-1.08122e-05,-4.7362e-05,-3.86654e-06,-1.33434e-05,1.63577e-05,-0.00102111,0.204748,1.39698e-08,0.43476,0,0,0,0,0,2.05203e-05,0.000317534,0.000317512,0.000593615,0.140042,0.140048,0.0439781,0.103578,0.103579,0.116762,2.73551e-09,2.73711e-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.00674926,-0.0122011,0.182067,-0.00119996,0.0177555,-0.0435077,-0.000959457,0.00632359,-0.0390796,-1.05608e-05,-4.74157e-05,-3.87536e-06,-1.30465e-05,1.77914e-05,-0.00102285,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.90578e-05,0.000307636,0.000307618,0.000550529,0.13345,0.133456,0.04329,0.0830277,0.0830286,0.118057,2.43554e-09,2.43687e-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.006717,-0.0121095,0.182013,-0.00113431,0.0185722,-0.0406585,-0.00110241,0.00813713,-0.0381074,-1.05605e-05,-4.74165e-05,-3.83257e-06,-1.30921e-05,1.78579e-05,-0.00102755,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.74047e-05,0.0003082,0.000308189,0.000502131,0.160072,0.160079,0.0418856,0.100338,0.100339,0.116852,2.43559e-09,2.43692e-09,5.73373e-09,2.4549e-06,2.45481e-06,1.74208e-07,0,0,0,0,0,0,0,0 +8088000,0.983156,-0.00670239,-0.0120913,0.182245,0.000122146,0.0179082,-0.0388319,-0.000771955,0.006821,-0.0369311,-1.03371e-05,-4.74714e-05,-3.94576e-06,-1.25443e-05,2.02038e-05,-0.00103179,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.60087e-05,0.000291068,0.000291057,0.000461938,0.152609,0.152616,0.0403778,0.0816085,0.0816094,0.114728,2.23125e-09,2.2324e-09,5.72596e-09,2.43409e-06,2.434e-06,1.64528e-07,0,0,0,0,0,0,0,0 +8192000,0.983132,-0.0067788,-0.0119967,0.18238,0.000315492,0.0219438,-0.0341847,-0.000749578,0.00893454,-0.0305124,-1.03392e-05,-4.74697e-05,-4.00818e-06,-1.26448e-05,2.03329e-05,-0.00104042,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.48552e-05,0.000291235,0.000291231,0.000428415,0.181907,0.181916,0.0390897,0.100146,0.100147,0.113568,2.2313e-09,2.23245e-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.00686593,-0.0119476,0.182331,0.00257304,0.0199632,-0.031903,-0.000420243,0.00746252,-0.0295683,-1.01439e-05,-4.75316e-05,-4.00315e-06,-1.16413e-05,2.3615e-05,-0.00104368,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.38552e-05,0.000266949,0.000266946,0.000399763,0.169029,0.169037,0.0377074,0.0819086,0.0819096,0.111536,2.10486e-09,2.1059e-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.00682624,-0.0119336,0.182313,-0.000212542,0.0199412,-0.0310216,-0.000303278,0.00949674,-0.0281188,-1.01437e-05,-4.75318e-05,-3.98163e-06,-1.16893e-05,2.36693e-05,-0.00104742,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.30191e-05,0.00026675,0.00026675,0.000375443,0.199131,0.19914,0.0365261,0.102011,0.102013,0.110423,2.10491e-09,2.10595e-09,5.69389e-09,2.39935e-06,2.39927e-06,1.39142e-07,0,0,0,0,0,0,0,0 +8488000,0.983165,-0.00674891,-0.0119133,0.182208,-0.00117344,0.0226399,-0.0308337,-0.000342219,0.0114937,-0.0310521,-1.01412e-05,-4.75343e-05,-3.86089e-06,-1.16881e-05,2.36637e-05,-0.00104744,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.24966e-05,0.000266726,0.000266726,0.000360062,0.229375,0.229385,0.0359766,0.125597,0.1256,0.111528,2.10495e-09,2.10599e-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.00685437,-0.0119899,0.182109,-0.000341753,0.0195438,-0.0248416,-0.000330134,0.00959492,-0.0253089,-9.99351e-06,-4.75854e-05,-3.82696e-06,-1.04137e-05,2.76699e-05,-0.00105394,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.18346e-05,0.000237092,0.000237091,0.00034127,0.207112,0.20712,0.0348645,0.104554,0.104556,0.110399,2.0379e-09,2.03888e-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.00690922,-0.0120351,0.181973,-0.00119631,0.0193488,-0.0267457,-0.000437994,0.0114461,-0.0273578,-9.99185e-06,-4.75871e-05,-3.74519e-06,-1.04149e-05,2.76702e-05,-0.00105422,0.204748,1.39698e-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.03794e-09,2.03892e-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.000337985,0.0152717,-0.0268192,-0.000434957,0.0089646,-0.0242822,-9.89755e-06,-4.76177e-05,-3.78813e-06,-9.04653e-06,3.19692e-05,-0.0010584,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.07484e-05,0.000206109,0.000206108,0.000310265,0.204596,0.204603,0.0326536,0.106469,0.106471,0.107382,2.01005e-09,2.011e-09,5.63132e-09,2.29639e-06,2.2963e-06,1.13764e-07,0,0,0,0,0,0,0,0 +8888000,0.983239,-0.00709639,-0.0119756,0.181788,-0.00107558,0.0165884,-0.0225213,-0.0004904,0.0104999,-0.0177414,-9.89299e-06,-4.76215e-05,-3.57402e-06,-9.15648e-06,3.20601e-05,-0.00106474,0.204748,1.39698e-08,0.43476,0,0,0,0,0,1.03019e-05,0.000205814,0.000205815,0.000297342,0.230581,0.230589,0.0315613,0.132103,0.132105,0.105532,2.01009e-09,2.01104e-09,5.60988e-09,2.29639e-06,2.29631e-06,1.07999e-07,0,0,0,0,0,0,0,0 +8992000,0.983281,-0.00714045,-0.0118672,0.181568,-0.00246952,0.013385,-0.0200295,-0.00054173,0.00799747,-0.0185711,-9.84104e-06,-4.76427e-05,-3.25713e-06,-7.85464e-06,3.60229e-05,-0.00106561,0.204748,1.39698e-08,0.43476,0,0,0,0,0,9.91497e-06,0.000177579,0.000177579,0.00028625,0.192844,0.192849,0.030627,0.106949,0.10695,0.104502,2.0027e-09,2.00364e-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.00715472,-0.0119317,0.181329,-0.00222538,0.0147391,-0.0223031,-0.000770559,0.00930844,-0.021393,-9.83605e-06,-4.76477e-05,-3.0147e-06,-7.83683e-06,3.60032e-05,-0.00106507,0.204748,1.39698e-08,0.43476,0,0,0,0,0,9.68131e-06,0.000177414,0.000177413,0.000279657,0.215259,0.215265,0.0301941,0.132235,0.132237,0.105464,2.00274e-09,2.00368e-09,5.56719e-09,2.23938e-06,2.2393e-06,9.87428e-08,0,0,0,0,0,0,0,0 +9192000,0.983362,-0.00721651,-0.0119614,0.181117,0.000780308,0.0106368,-0.0202652,-0.000539427,0.00704861,-0.0207884,-9.82061e-06,-4.76556e-05,-2.75423e-06,-6.8655e-06,3.95023e-05,-0.00106688,0.204748,1.39698e-08,0.43476,0,0,0,0,0,9.36523e-06,0.000153959,0.000153957,0.000270785,0.175287,0.175291,0.0293151,0.105795,0.105796,0.104428,2.00235e-09,2.0033e-09,5.53971e-09,2.18623e-06,2.18615e-06,9.3884e-08,0,0,0,0,0,0,0,0 +9288000,0.98339,-0.00711485,-0.0118077,0.180983,0.00200483,0.0107764,-0.0175022,-0.000359669,0.008033,-0.0167807,-9.81547e-06,-4.76597e-05,-2.52419e-06,-6.9425e-06,3.95603e-05,-0.00107065,0.204748,1.39698e-08,0.43476,0,0,0,0,0,9.08124e-06,0.000154055,0.000154053,0.000262537,0.193903,0.193907,0.0283728,0.129965,0.129966,0.102672,2.00239e-09,2.00333e-09,5.50993e-09,2.18623e-06,2.18615e-06,8.93516e-08,0,0,0,0,0,0,0,0 +9392000,0.98338,-0.00707734,-0.0118265,0.181033,0.0019495,0.00696046,-0.0162487,-2.91637e-05,0.00588854,-0.0172088,-9.82838e-06,-4.76541e-05,-2.60601e-06,-6.0057e-06,4.23236e-05,-0.00107145,0.204748,1.39698e-08,0.43476,0,0,0,0,0,8.83528e-06,0.000136096,0.000136092,0.000255593,0.155153,0.155155,0.0275666,0.103248,0.103249,0.101684,2.00165e-09,2.00259e-09,5.47783e-09,2.14006e-06,2.13998e-06,8.50695e-08,0,0,0,0,0,0,0,0 +9488000,0.983412,-0.00712248,-0.0119086,0.180855,0.00140052,0.00645887,-0.0136372,0.000119735,0.00650765,-0.0137917,-9.82348e-06,-4.76579e-05,-2.38949e-06,-6.07356e-06,4.23727e-05,-0.00107447,0.204748,1.39698e-08,0.43476,0,0,0,0,0,8.60308e-06,0.000136538,0.000136534,0.000249025,0.170269,0.170271,0.0267013,0.125804,0.125805,0.100009,2.00168e-09,2.00263e-09,5.44338e-09,2.14006e-06,2.13998e-06,8.10714e-08,0,0,0,0,0,0,0,0 +9592000,0.98337,-0.00723744,-0.0118929,0.18108,0.00102444,0.00264906,-0.0126524,9.19708e-05,0.00451456,-0.0145692,-9.84886e-06,-4.76443e-05,-2.67574e-06,-5.28288e-06,4.43598e-05,-0.00107477,0.204748,1.39698e-08,0.43476,0,0,0,0,0,8.41674e-06,0.000123695,0.00012369,0.000243583,0.134959,0.13496,0.0259615,0.0997268,0.0997274,0.099068,1.99802e-09,1.99896e-09,5.40657e-09,2.10189e-06,2.10181e-06,7.72912e-08,0,0,0,0,0,0,0,0 +9688000,0.983382,-0.00723799,-0.0118239,0.18102,0.000552361,0.00146539,-0.00949115,0.000245932,0.00479329,-0.0124798,-9.84839e-06,-4.7644e-05,-2.66924e-06,-5.33423e-06,4.4399e-05,-0.00107669,0.204748,1.39698e-08,0.43476,0,0,0,0,0,8.22897e-06,0.000124521,0.000124517,0.000238332,0.147056,0.147057,0.0251662,0.12043,0.120431,0.0974697,1.99805e-09,1.99899e-09,5.36739e-09,2.1019e-06,2.10181e-06,7.37571e-08,0,0,0,0,0,0,0,0 +9792000,0.983356,-0.00723882,-0.011775,0.181163,0.00106315,-0.000191635,-0.00974538,0.000237956,0.0031844,-0.0120302,-9.87314e-06,-4.76293e-05,-2.98406e-06,-4.79723e-06,4.56886e-05,-0.00107759,0.204748,1.39698e-08,0.43476,0,0,0,0,0,8.0773e-06,0.000115916,0.000115911,0.000234096,0.116209,0.11621,0.0244868,0.0956393,0.0956396,0.0965734,1.99161e-09,1.99255e-09,5.32585e-09,2.07135e-06,2.07127e-06,7.04139e-08,0,0,0,0,0,0,0,0 +9888000,0.983373,-0.00723203,-0.0117536,0.18107,0.00209524,-0.00138999,-0.00871566,0.000351056,0.0030169,-0.013748,-9.86764e-06,-4.76348e-05,-2.71594e-06,-4.77834e-06,4.56681e-05,-0.00107711,0.204748,1.39698e-08,0.43476,0,0,0,0,0,8.01854e-06,0.000117136,0.000117132,0.000232343,0.125855,0.125856,0.0241733,0.114446,0.114447,0.0973775,1.99165e-09,1.99258e-09,5.29313e-09,2.07136e-06,2.07128e-06,6.80468e-08,0,0,0,0,0,0,0,0 +9992000,0.983343,-0.00727716,-0.0118113,0.181232,0.00328343,-0.00382469,-0.00774245,0.000441907,0.00173879,-0.014819,-9.88453e-06,-4.76228e-05,-2.97534e-06,-4.40711e-06,4.63009e-05,-0.00107701,0.204748,1.39698e-08,0.43476,0,0,0,0,0,7.90351e-06,0.000111809,0.000111804,0.000228989,0.0996042,0.0996052,0.0235336,0.0913073,0.0913075,0.0964815,1.98369e-09,1.98462e-09,5.24751e-09,2.04746e-06,2.04737e-06,6.50399e-08,0,0,0,0,0,0,0,0 +10088000,0.983327,-0.00723118,-0.0119424,0.181309,0.00184791,-0.00683342,-0.00665995,0.000701022,0.00117923,-0.0126148,-9.89009e-06,-4.76167e-05,-3.26002e-06,-4.46133e-06,4.63475e-05,-0.00107862,0.204748,1.39698e-08,0.43476,0,0,0,0,0,7.78015e-06,0.000113417,0.000113411,0.000225555,0.107328,0.107328,0.0228446,0.108292,0.108292,0.0949688,1.98372e-09,1.98465e-09,5.19961e-09,2.04746e-06,2.04738e-06,6.22201e-08,0,0,0,0,0,0,0,0 +10192000,0.983296,-0.00722047,-0.0118554,0.181483,-0.000682276,-0.0071658,-0.00529453,0.000509297,0.000245809,-0.0133778,-9.89972e-06,-4.76046e-05,-3.63709e-06,-4.24862e-06,4.64428e-05,-0.00107857,0.204748,1.39698e-08,0.43476,0,0,0,0,0,7.68995e-06,0.000110529,0.000110523,0.000222992,0.0853809,0.0853814,0.0222564,0.0869549,0.0869551,0.0941161,1.97567e-09,1.97659e-09,5.14947e-09,2.02905e-06,2.02897e-06,5.95508e-08,0,0,0,0,0,0,0,0 +10288000,0.983328,-0.00725904,-0.0117772,0.181314,-0.00014075,-0.00772403,-0.00574421,0.000445785,-0.00051922,-0.0118325,-9.89367e-06,-4.76097e-05,-3.36117e-06,-4.28147e-06,4.64582e-05,-0.00107967,0.204748,1.39698e-08,0.43476,0,0,0,0,0,7.5895e-06,0.000112508,0.000112503,0.000220245,0.091637,0.0916377,0.0216215,0.102259,0.102259,0.092672,1.9757e-09,1.97662e-09,5.09715e-09,2.02905e-06,2.02897e-06,5.70433e-08,0,0,0,0,0,0,0,0 +10392000,0.982994,-0.00724184,-0.0116975,0.183121,0.00691905,0.00130544,-0.0024762,0.000810474,-1.26172e-05,-0.0102291,-9.89337e-06,-4.76094e-05,-3.35887e-06,-4.31278e-06,4.64794e-05,-0.00108059,0.205039,0.000821557,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.0856759,1.97575e-09,1.97667e-09,5.09716e-09,2.02905e-06,2.02897e-06,5.48325e-08,0,0,0,0,0,0,0,0 +10488000,0.982895,-0.00715068,-0.0116477,0.183658,0.00730252,-0.000692963,-0.00135949,0.00148421,-3.80387e-06,-0.00765571,-9.89315e-06,-4.76087e-05,-3.36761e-06,-4.36269e-06,4.65134e-05,-0.00108204,0.205039,0.000821557,0.434373,0,0,0,0,0,4.97779e-05,0.00011351,0.0001134,0.00142649,0.0370056,0.0370056,0.0375232,0.12629,0.12629,0.0815567,1.9758e-09,1.97672e-09,5.09704e-09,2.02906e-06,2.02898e-06,5.34065e-08,0,0,0,0,0,0,0,0 +10592000,0.983025,-0.00711474,-0.0115705,0.182966,0.0047963,-0.00199187,-0.000192277,0.00112096,-4.60092e-05,-0.00397284,-9.88493e-06,-4.75923e-05,-3.33565e-06,-1.70838e-06,4.53925e-05,-0.00108391,0.205039,0.000821557,0.434373,0,0,0,0,0,3.94958e-05,0.000113312,0.000113228,0.00113048,0.0353711,0.0353711,0.0352268,0.0849825,0.0849825,0.0770606,1.97558e-09,1.9765e-09,5.09658e-09,2.02148e-06,2.0214e-06,5.17438e-08,0,0,0,0,0,0,0,0 +10688000,0.983045,-0.00707131,-0.0115878,0.182863,0.00585961,-0.00451242,-0.000224844,0.00165522,-0.000345016,-0.00283783,-9.88477e-06,-4.7592e-05,-3.33589e-06,-1.72911e-06,4.5406e-05,-0.00108449,0.205039,0.000821557,0.434373,0,0,0,0,0,3.27099e-05,0.000113818,0.00011375,0.000936584,0.0397889,0.0397887,0.0352034,0.0867792,0.0867792,0.0737233,1.97563e-09,1.97655e-09,5.09566e-09,2.02148e-06,2.0214e-06,5.03159e-08,0,0,0,0,0,0,0,0 +10792000,0.983059,-0.00707857,-0.0117062,0.182776,0.00572256,-0.00682652,0.000186607,0.00150484,-0.00104266,-0.000250266,-9.88891e-06,-4.75787e-05,-3.32931e-06,6.53293e-07,4.63185e-05,-0.00108578,0.205039,0.000821557,0.434373,0,0,0,0,0,2.79309e-05,0.000112414,0.000112354,0.000799933,0.0394629,0.0394628,0.0330585,0.0660561,0.0660561,0.071152,1.97488e-09,1.97581e-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.00705431,-0.0117318,0.182206,0.005626,-0.00746507,-0.000523885,0.00202008,-0.00177054,-0.0014714,-9.88705e-06,-4.75809e-05,-3.23115e-06,6.72119e-07,4.63035e-05,-0.00108521,0.205039,0.000821557,0.434373,0,0,0,0,0,2.44137e-05,0.000113245,0.000113193,0.000698401,0.0458772,0.0458771,0.032893,0.0686696,0.0686696,0.0694351,1.97493e-09,1.97586e-09,5.09206e-09,1.99334e-06,1.99327e-06,5e-08,0,0,0,0,0,0,0,0 +10992000,0.983135,-0.00702633,-0.0118196,0.182365,0.00372369,-0.00245411,0.00223478,0.00174286,-0.00144978,0.00344474,-9.87067e-06,-4.75749e-05,-3.26901e-06,1.54943e-06,4.2581e-05,-0.00108718,0.205039,0.000821557,0.434373,0,0,0,0,0,2.16836e-05,0.000110237,0.00011019,0.000620286,0.0451807,0.0451809,0.030867,0.0559893,0.0559893,0.0679688,1.97397e-09,1.9749e-09,5.08918e-09,1.94016e-06,1.94009e-06,5e-08,0,0,0,0,0,0,0,0 +11088000,0.98306,-0.00714393,-0.0117897,0.182767,0.00391903,-0.00045356,0.00411286,0.00207122,-0.00165488,0.00644574,-9.87219e-06,-4.75726e-05,-3.35951e-06,1.50817e-06,4.26086e-05,-0.00108833,0.205039,0.000821557,0.434373,0,0,0,0,0,2.00386e-05,0.000111395,0.000111355,0.000572932,0.0529823,0.0529829,0.0306788,0.0594925,0.0594925,0.0684158,1.97402e-09,1.97494e-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.007175,-0.0117799,0.183044,0.00404383,0.00175079,0.00752921,0.00263247,-0.00126247,0.00944293,-9.87552e-06,-4.75778e-05,-3.4633e-06,-1.12179e-06,4.31984e-05,-0.00108891,0.205039,0.000821557,0.434373,0,0,0,0,0,1.81764e-05,0.000107033,0.000106998,0.000520196,0.0506108,0.0506115,0.0287777,0.0505381,0.0505381,0.0675465,1.97329e-09,1.97421e-09,5.08205e-09,1.86632e-06,1.86625e-06,5.00008e-08,0,0,0,0,0,0,0,0 +11288000,0.982992,-0.00718666,-0.0118095,0.183128,0.00342557,0.000772457,0.00784785,0.00296656,-0.00109169,0.0100186,-9.87595e-06,-4.75775e-05,-3.48302e-06,-1.11895e-06,4.31977e-05,-0.00108886,0.205039,0.000821557,0.434373,0,0,0,0,0,1.66657e-05,0.000108514,0.000108483,0.000476663,0.0591539,0.0591547,0.0283726,0.0549468,0.0549469,0.0674521,1.97333e-09,1.97426e-09,5.07661e-09,1.86633e-06,1.86626e-06,5.00004e-08,0,0,0,0,0,0,0,0 +11392000,0.983003,-0.0070742,-0.011803,0.183074,0.00150877,0.00120385,0.00608958,0.00234034,-0.000839855,0.00715246,-9.87421e-06,-4.75738e-05,-3.46675e-06,1.10493e-06,4.25198e-05,-0.00108755,0.205039,0.000821557,0.434373,0,0,0,0,0,1.53983e-05,0.00010347,0.00010344,0.000440495,0.0545145,0.0545152,0.0265919,0.0477357,0.0477358,0.0669264,1.97304e-09,1.97396e-09,5.07007e-09,1.78206e-06,1.78199e-06,5.00004e-08,0,0,0,0,0,0,0,0 +11488000,0.983022,-0.00704604,-0.0117777,0.182975,-0.000545787,-0.000629323,0.00809909,0.00232139,-0.000775193,0.0108544,-9.87358e-06,-4.75735e-05,-3.45397e-06,1.06084e-06,4.25428e-05,-0.00108858,0.205039,0.000821557,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.97309e-09,1.97401e-09,5.06233e-09,1.78206e-06,1.782e-06,5e-08,0,0,0,0,0,0,0,0 +11592000,0.98301,-0.0071015,-0.0117739,0.183035,0.0012323,-0.000383978,0.00845391,0.00199912,-0.000624756,0.0112181,-9.8737e-06,-4.75724e-05,-3.49462e-06,1.14851e-06,4.21668e-05,-0.0010889,0.205039,0.000821557,0.434373,0,0,0,0,0,1.34028e-05,0.000100263,0.000100239,0.000383646,0.0564119,0.0564127,0.024446,0.0464623,0.0464624,0.0668169,1.97305e-09,1.97397e-09,5.05332e-09,1.69829e-06,1.69823e-06,5e-08,0,0,0,0,0,0,0,0 +11688000,0.983007,-0.00704309,-0.011754,0.183055,0.0014183,0.000378878,0.0102582,0.00214087,-0.000643785,0.011902,-9.87315e-06,-4.75729e-05,-3.4669e-06,1.15134e-06,4.21643e-05,-0.00108881,0.205039,0.000821557,0.434373,0,0,0,0,0,1.28322e-05,0.00010236,0.000102337,0.000367035,0.0648224,0.0648234,0.0240685,0.0523661,0.0523662,0.068401,1.9731e-09,1.97402e-09,5.0457e-09,1.69829e-06,1.69823e-06,5.00012e-08,0,0,0,0,0,0,0,0 +11792000,0.983047,-0.00712447,-0.0117358,0.182839,0.000164421,0.00024426,0.0111989,0.00166338,-0.00174586,0.0132188,-9.85975e-06,-4.75801e-05,-3.2973e-06,3.78577e-06,4.64363e-05,-0.00108885,0.205039,0.000821557,0.434373,0,0,0,0,0,1.21317e-05,9.79375e-05,9.79166e-05,0.000346898,0.0565029,0.0565038,0.0225569,0.0460258,0.0460259,0.0680605,1.9728e-09,1.97372e-09,5.03427e-09,1.62277e-06,1.62271e-06,5.00012e-08,0,0,0,0,0,0,0,0 +11888000,0.983047,-0.00720117,-0.0116695,0.182843,0.00163287,0.000787601,0.0103298,0.00172311,-0.00172515,0.0140939,-9.86053e-06,-4.75795e-05,-3.33382e-06,3.78855e-06,4.64358e-05,-0.0010888,0.205039,0.000821557,0.434373,0,0,0,0,0,1.15061e-05,0.000100315,0.000100298,0.000329102,0.0644046,0.0644058,0.0219833,0.0524145,0.0524147,0.0685508,1.97284e-09,1.97377e-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.00721125,-0.011751,0.182855,0.00370738,0.00463465,0.0105001,0.00269893,-1.34438e-05,0.0143063,-9.87057e-06,-4.75575e-05,-3.36221e-06,-5.38384e-07,4.39917e-05,-0.00108872,0.205039,0.000821557,0.434373,0,0,0,0,0,1.09666e-05,9.67225e-05,9.6706e-05,0.000313752,0.055279,0.0552801,0.0206144,0.0460032,0.0460033,0.0681862,1.97156e-09,1.97248e-09,5.00684e-09,1.55927e-06,1.55922e-06,5.00008e-08,0,0,0,0,0,0,0,0 +12088000,0.983017,-0.00713313,-0.0118029,0.182996,0.00444889,0.00425155,0.0129515,0.00308213,0.000382986,0.0185464,-9.87187e-06,-4.75553e-05,-3.43978e-06,-5.76654e-07,4.40108e-05,-0.00108948,0.205039,0.000821557,0.434373,0,0,0,0,0,1.04929e-05,9.93669e-05,9.93507e-05,0.000299952,0.0625501,0.0625515,0.020037,0.0527016,0.0527018,0.0686346,1.9716e-09,1.97253e-09,4.99072e-09,1.55928e-06,1.55922e-06,5.00004e-08,0,0,0,0,0,0,0,0 +12192000,0.982999,-0.00701793,-0.0118011,0.183098,0.00473551,0.00426691,0.012335,0.00247342,0.00159353,0.0207811,-9.89899e-06,-4.75577e-05,-3.60385e-06,6.45174e-07,4.10643e-05,-0.00108979,0.205039,0.000821557,0.434373,0,0,0,0,0,1.00696e-05,9.66513e-05,9.66355e-05,0.000288047,0.053245,0.0532461,0.018812,0.0461497,0.0461498,0.068213,1.96854e-09,1.96947e-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.00706464,-0.0117774,0.183202,0.00229185,0.00345452,0.0111968,0.00282265,0.00197816,0.0215819,-9.90191e-06,-4.7555e-05,-3.74244e-06,6.49527e-07,4.10657e-05,-0.00108972,0.205039,0.000821557,0.434373,0,0,0,0,0,9.68936e-06,9.95441e-05,9.95301e-05,0.000277188,0.059908,0.0599092,0.0182529,0.0530121,0.0530124,0.0685717,1.96858e-09,1.96951e-09,4.95335e-09,1.50845e-06,1.5084e-06,5e-08,0,0,0,0,0,0,0,0 +12392000,0.982973,-0.00710526,-0.0117257,0.18324,0.00125828,0.00136097,0.0111794,0.00229409,0.00146083,0.0195277,-9.89417e-06,-4.75662e-05,-3.84553e-06,2.13205e-06,4.19537e-05,-0.00108913,0.205039,0.000821557,0.434373,0,0,0,0,0,9.3577e-06,9.76157e-05,9.76029e-05,0.000267846,0.0508211,0.0508219,0.0171687,0.0463308,0.0463309,0.0680814,1.9629e-09,1.96382e-09,4.932e-09,1.46928e-06,1.46923e-06,5e-08,0,0,0,0,0,0,0,0 +12488000,0.982951,-0.00711198,-0.0117218,0.183354,0.00144404,0.00203985,0.014493,0.00242241,0.00160432,0.0208245,-9.89499e-06,-4.75654e-05,-3.88525e-06,2.13166e-06,4.19547e-05,-0.00108914,0.205039,0.000821557,0.434373,0,0,0,0,0,9.17413e-06,0.000100743,0.000100731,0.000262322,0.0569022,0.0569033,0.0168163,0.0532463,0.0532465,0.0695225,1.96294e-09,1.96386e-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.00715494,-0.0116613,0.18351,0.00472655,-0.00209514,0.0158835,0.00355865,-0.000321115,0.0234289,-9.81853e-06,-4.75379e-05,-4.01555e-06,1.27977e-06,4.60208e-05,-0.00108922,0.205039,0.000821557,0.434373,0,0,0,0,0,8.91566e-06,9.94722e-05,9.94615e-05,0.000254758,0.0483012,0.048302,0.0158577,0.0464805,0.0464806,0.0689455,1.9538e-09,1.95472e-09,4.89019e-09,1.43994e-06,1.43989e-06,5.00008e-08,0,0,0,0,0,0,0,0 +12688000,0.982918,-0.00710551,-0.0116676,0.183537,0.00486041,-0.00347165,0.0158569,0.00397598,-0.000590168,0.0251241,-9.81976e-06,-4.75367e-05,-4.07567e-06,1.27755e-06,4.6023e-05,-0.00108925,0.205039,0.000821557,0.434373,0,0,0,0,0,8.66709e-06,0.000102817,0.000102807,0.000247664,0.0539172,0.0539182,0.0153791,0.0533719,0.053372,0.0690854,1.95384e-09,1.95476e-09,4.86372e-09,1.43994e-06,1.4399e-06,5.00004e-08,0,0,0,0,0,0,0,0 +12792000,0.982965,-0.00721413,-0.01158,0.183289,0.00716262,-0.00577338,0.0171141,0.00602021,-0.00320878,0.0275288,-9.67537e-06,-4.7489e-05,-3.75534e-06,-1.31039e-07,5.04929e-05,-0.00108923,0.205039,0.000821557,0.434373,0,0,0,0,0,8.45326e-06,0.000102038,0.000102029,0.000241693,0.0459071,0.0459081,0.0145464,0.0465708,0.0465709,0.0684483,1.94034e-09,1.94126e-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.00723128,-0.0115111,0.183113,0.00699388,-0.00684535,0.0176318,0.00673917,-0.00380309,0.0296827,-9.67107e-06,-4.74929e-05,-3.55096e-06,-1.35842e-07,5.04899e-05,-0.0010893,0.205039,0.000821557,0.434373,0,0,0,0,0,8.24912e-06,0.000105585,0.000105578,0.000235986,0.0511321,0.0511333,0.0141193,0.0533879,0.053388,0.0684715,1.94038e-09,1.9413e-09,4.80502e-09,1.41864e-06,1.41859e-06,5e-08,0,0,0,0,0,0,0,0 +12992000,0.983034,-0.00722293,-0.0115128,0.182921,0.00651871,-0.004356,0.018284,0.00531574,-0.0028335,0.0320826,-9.7378e-06,-4.75316e-05,-3.33972e-06,1.22113e-06,4.81413e-05,-0.00108943,0.205039,0.000821557,0.434373,0,0,0,0,0,8.07725e-06,0.00010514,0.000105133,0.000231271,0.0437442,0.0437453,0.0134028,0.0465957,0.0465959,0.0677874,1.92164e-09,1.92255e-09,4.77277e-09,1.40363e-06,1.40359e-06,5e-08,0,0,0,0,0,0,0,0 +13088000,0.983045,-0.00721706,-0.0114119,0.18287,0.00733766,-0.00430725,0.0165829,0.00596446,-0.00320397,0.0315555,-9.73382e-06,-4.75361e-05,-3.13599e-06,1.24337e-06,4.81277e-05,-0.00108908,0.205039,0.000821557,0.434373,0,0,0,0,0,8.0045e-06,0.000108872,0.000108866,0.000229047,0.0486729,0.0486743,0.0131748,0.0533094,0.0533096,0.068879,1.92168e-09,1.92258e-09,4.74732e-09,1.40363e-06,1.40359e-06,5.00008e-08,0,0,0,0,0,0,0,0 +13192000,0.983052,-0.00722305,-0.0113641,0.182831,0.00501614,-0.00512215,0.0161123,0.00470811,-0.00392735,0.0333218,-9.71347e-06,-4.76266e-05,-2.92614e-06,3.0661e-06,4.78542e-05,-0.00108911,0.205039,0.000821557,0.434373,0,0,0,0,0,7.87723e-06,0.000108602,0.000108596,0.000225251,0.0418834,0.0418845,0.012556,0.0465601,0.0465602,0.0681372,1.89679e-09,1.89768e-09,4.71169e-09,1.39347e-06,1.39343e-06,5.00008e-08,0,0,0,0,0,0,0,0 +13288000,0.98305,-0.00725312,-0.0113525,0.182844,0.00505063,-0.00588561,0.0135831,0.00513588,-0.00442359,0.0324881,-9.7156e-06,-4.76256e-05,-3.01471e-06,3.08998e-06,4.78477e-05,-0.00108879,0.205039,0.000821557,0.434373,0,0,0,0,0,7.74204e-06,0.000112498,0.000112494,0.000221454,0.0465943,0.0465957,0.0122382,0.0531576,0.0531578,0.0679689,1.89682e-09,1.89772e-09,4.67417e-09,1.39348e-06,1.39344e-06,5.00004e-08,0,0,0,0,0,0,0,0 +13392000,0.983035,-0.00718935,-0.0114367,0.18292,0.00293456,-0.00398017,0.0128661,0.00399972,-0.00334221,0.0332247,-9.80392e-06,-4.76518e-05,-3.23961e-06,3.70984e-06,4.64357e-05,-0.00108869,0.205039,0.000821557,0.434373,0,0,0,0,0,7.63545e-06,0.000112254,0.000112249,0.000218499,0.0403449,0.0403462,0.0117154,0.0464745,0.0464746,0.0672077,1.86495e-09,1.86583e-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.00715793,-0.0114105,0.182926,0.00238521,-0.00244334,0.0129644,0.00424338,-0.00358582,0.0307005,-9.80362e-06,-4.76537e-05,-3.20067e-06,3.74811e-06,4.64209e-05,-0.00108817,0.205039,0.000821557,0.434373,0,0,0,0,0,7.53035e-06,0.000116292,0.000116287,0.000215429,0.0448904,0.0448922,0.0114525,0.0529542,0.0529545,0.0669663,1.86498e-09,1.86586e-09,4.59346e-09,1.38691e-06,1.38688e-06,5e-08,0,0,0,0,0,0,0,0 +13592000,0.983009,-0.00713668,-0.0114419,0.183064,0.00567302,-0.00287147,0.0140153,0.00632452,-0.00291373,0.0296504,-9.76719e-06,-4.74533e-05,-3.36438e-06,2.78608e-06,4.62563e-05,-0.00108777,0.205039,0.000821557,0.434373,0,0,0,0,0,7.45469e-06,0.000115938,0.000115934,0.000213142,0.039108,0.0391095,0.0110156,0.0463519,0.0463521,0.0661989,1.82549e-09,1.82635e-09,4.55036e-09,1.38287e-06,1.38284e-06,5e-08,0,0,0,0,0,0,0,0 +13688000,0.983037,-0.00706798,-0.0113515,0.182922,0.00524582,-0.00430679,0.0142447,0.00685486,-0.00324267,0.0329109,-9.76336e-06,-4.74561e-05,-3.19221e-06,2.7654e-06,4.6259e-05,-0.00108801,0.205039,0.000821557,0.434373,0,0,0,0,0,7.43442e-06,0.00012009,0.000120086,0.000212737,0.043566,0.0435676,0.0109213,0.0527201,0.0527204,0.0670121,1.82552e-09,1.82639e-09,4.51691e-09,1.38288e-06,1.38284e-06,5.00008e-08,0,0,0,0,0,0,0,0 +13792000,0.98302,-0.00702055,-0.0114547,0.183009,0.0107897,-0.00148978,0.0150278,0.0097373,-0.00115645,0.0318592,-9.83876e-06,-4.71138e-05,-3.38577e-06,2.20972e-06,4.56258e-05,-0.00108753,0.205039,0.000821557,0.434373,0,0,0,0,0,7.37184e-06,0.000119496,0.000119492,0.000210969,0.0381862,0.0381877,0.0105545,0.0462059,0.0462061,0.0662243,1.77793e-09,1.77878e-09,4.47074e-09,1.38048e-06,1.38044e-06,5.00008e-08,0,0,0,0,0,0,0,0 +13888000,0.983029,-0.00694634,-0.011424,0.182964,0.0113315,-0.000946779,0.0156129,0.0107715,-0.0012555,0.0335808,-9.83378e-06,-4.71183e-05,-3.14796e-06,2.20314e-06,4.56207e-05,-0.00108756,0.205039,0.000821557,0.434373,0,0,0,0,0,7.30507e-06,0.000123733,0.000123729,0.000208931,0.0425923,0.0425943,0.0103917,0.0524757,0.052476,0.0658835,1.77796e-09,1.77881e-09,4.42292e-09,1.38048e-06,1.38045e-06,5.00004e-08,0,0,0,0,0,0,0,0 +13992000,0.983039,-0.00697439,-0.0112076,0.182919,0.0108666,0.000186548,0.0147038,0.00867272,-0.00227356,0.0331807,-9.77168e-06,-4.73338e-05,-2.88276e-06,2.98101e-06,4.5274e-05,-0.0010873,0.205039,0.000821557,0.434373,0,0,0,0,0,7.26209e-06,0.000122774,0.000122771,0.000207611,0.0375469,0.037549,0.0100927,0.04605,0.0460502,0.0651116,1.72205e-09,1.72287e-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.00698779,-0.011156,0.183289,0.00842795,-0.00373086,0.0159157,0.00967831,-0.00247118,0.030554,-9.78931e-06,-4.7319e-05,-3.70527e-06,3.03704e-06,4.52786e-05,-0.00108676,0.205039,0.000821557,0.434373,0,0,0,0,0,7.20815e-06,0.000127063,0.000127061,0.000205964,0.0419322,0.0419343,0.00997591,0.0522377,0.052238,0.0647467,1.72208e-09,1.7229e-09,4.32251e-09,1.37899e-06,1.37895e-06,5e-08,0,0,0,0,0,0,0,0 +14192000,0.98293,-0.00695914,-0.0110876,0.183513,0.00543351,-0.00209785,0.0157045,0.00892379,-0.00184463,0.0306591,-9.86382e-06,-4.72892e-05,-4.1382e-06,3.64804e-06,4.50094e-05,-0.00108624,0.205039,0.000821557,0.434373,0,0,0,0,0,7.17776e-06,0.000125636,0.000125635,0.000205005,0.0371356,0.0371374,0.00973612,0.0458956,0.0458958,0.0639991,1.658e-09,1.65878e-09,4.27007e-09,1.37777e-06,1.37774e-06,5e-08,0,0,0,0,0,0,0,0 +14288000,0.982922,-0.0068982,-0.0110698,0.183562,0.0068745,-0.00233118,0.0144702,0.00941227,-0.0020954,0.0343039,-9.86369e-06,-4.72883e-05,-4.14979e-06,3.62378e-06,4.50178e-05,-0.00108656,0.205039,0.000821557,0.434373,0,0,0,0,0,7.20225e-06,0.000129944,0.000129943,0.000205599,0.0415549,0.0415571,0.00975721,0.0520193,0.0520196,0.0646572,1.65803e-09,1.65882e-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.00698508,-0.0110271,0.183547,0.0079052,-0.00452241,0.0145634,0.00901409,-0.00308504,0.0374962,-9.74861e-06,-4.73153e-05,-3.95626e-06,4.01274e-06,4.43349e-05,-0.00108667,0.205039,0.000821557,0.434373,0,0,0,0,0,7.18179e-06,0.000127954,0.000127953,0.000204913,0.0369391,0.0369409,0.00956475,0.045752,0.0457522,0.0639172,1.58617e-09,1.58692e-09,4.17512e-09,1.37633e-06,1.37631e-06,5.00012e-08,0,0,0,0,0,0,0,0 +14488000,0.982902,-0.00708253,-0.0109449,0.18367,0.00585843,-0.00437285,0.0183447,0.00963095,-0.00351622,0.0401366,-9.75635e-06,-4.73075e-05,-4.34161e-06,4.00526e-06,4.43474e-05,-0.00108685,0.205039,0.000821557,0.434373,0,0,0,0,0,7.14197e-06,0.000132244,0.000132245,0.000203807,0.0413585,0.0413607,0.00952716,0.0518299,0.0518303,0.0635361,1.5862e-09,1.58695e-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.00715848,-0.0107919,0.183776,0.00425956,-0.00428679,0.0164257,0.00653292,-0.00412718,0.0367385,-9.78775e-06,-4.76036e-05,-4.53085e-06,3.10006e-06,4.4081e-05,-0.00108601,0.205039,0.000821557,0.434373,0,0,0,0,0,7.1277e-06,0.000129648,0.00012965,0.000203349,0.0368633,0.0368652,0.00937959,0.0456267,0.0456269,0.0628339,1.50759e-09,1.5083e-09,4.062e-09,1.3743e-06,1.37427e-06,5.00008e-08,0,0,0,0,0,0,0,0 +14688000,0.98289,-0.00714345,-0.0108406,0.183733,0.00356678,-0.00453551,0.0168023,0.00687631,-0.00452508,0.0370918,-9.78566e-06,-4.76062e-05,-4.41636e-06,3.11472e-06,4.40739e-05,-0.00108579,0.205039,0.000821557,0.434373,0,0,0,0,0,7.09636e-06,0.000133886,0.000133888,0.000202432,0.0413283,0.0413305,0.00937639,0.0516756,0.051676,0.0624644,1.50761e-09,1.50833e-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.0071045,-0.0108443,0.183566,0.00544376,0.00241168,0.0157813,0.00573051,0.000422196,0.0399633,-1.03508e-05,-4.74791e-05,-3.95494e-06,4.09484e-06,4.7098e-05,-0.00108623,0.205039,0.000821557,0.434373,0,0,0,0,0,7.08507e-06,0.00013065,0.000130653,0.000202148,0.0369003,0.0369024,0.00926707,0.045524,0.0455243,0.0618037,1.42339e-09,1.42406e-09,3.94475e-09,1.37139e-06,1.37136e-06,5.00004e-08,0,0,0,0,0,0,0,0 +14888000,0.982954,-0.0070038,-0.0107796,0.1834,0.00389769,0.000517495,0.0178811,0.00614371,0.000559578,0.0403429,-1.03424e-05,-4.74876e-05,-3.5305e-06,4.1075e-06,4.70843e-05,-0.00108598,0.205039,0.000821557,0.434373,0,0,0,0,0,7.0568e-06,0.000134801,0.000134804,0.000201374,0.0413848,0.041387,0.00929433,0.0515591,0.0515596,0.0614544,1.42341e-09,1.42408e-09,3.88484e-09,1.37139e-06,1.37137e-06,5e-08,0,0,0,0,0,0,0,0 +14992000,0.982957,-0.00712622,-0.0106632,0.18339,0.00219788,-6.75489e-05,0.0201733,0.00497496,-0.000809656,0.0421536,-1.02085e-05,-4.76432e-05,-3.36662e-06,3.3756e-06,4.60928e-05,-0.00108541,0.205039,0.000821557,0.434373,0,0,0,0,0,7.05301e-06,0.000130937,0.00013094,0.000201212,0.0369537,0.0369556,0.0092171,0.0454456,0.0454459,0.060838,1.33509e-09,1.33571e-09,3.82416e-09,1.36744e-06,1.36742e-06,5e-08,0,0,0,0,0,0,0,0 +15088000,0.982947,-0.0070935,-0.0107491,0.183436,0.00126204,-4.60708e-05,0.0223242,0.00514552,-0.000849015,0.0435523,-1.02105e-05,-4.76417e-05,-3.45917e-06,3.38492e-06,4.60919e-05,-0.00108529,0.205039,0.000821557,0.434373,0,0,0,0,0,7.09614e-06,0.000134971,0.000134974,0.000202407,0.041455,0.0414572,0.00935114,0.0514771,0.0514776,0.0614495,1.33512e-09,1.33574e-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.00721597,-0.0108273,0.183511,-0.000613139,-0.000734884,0.0230472,0.00420571,-0.000803798,0.0452454,-1.02296e-05,-4.76783e-05,-3.64227e-06,3.2906e-06,4.60912e-05,-0.00108498,0.205039,0.000821557,0.434373,0,0,0,0,0,7.09312e-06,0.000130526,0.00013053,0.000202331,0.0370226,0.0370243,0.00929816,0.0453905,0.0453909,0.0608612,1.24441e-09,1.24499e-09,3.71651e-09,1.36242e-06,1.36239e-06,5.00008e-08,0,0,0,0,0,0,0,0 +15288000,0.982946,-0.00730254,-0.0108685,0.18343,-0.000698942,-0.00174849,0.0222815,0.00418559,-0.000899966,0.0423852,-1.02228e-05,-4.76869e-05,-3.25892e-06,3.35864e-06,4.60633e-05,-0.00108397,0.205039,0.000821557,0.434373,0,0,0,0,0,7.07603e-06,0.000134416,0.000134421,0.00020171,0.041536,0.041538,0.00937541,0.0514276,0.0514281,0.0605661,1.24444e-09,1.24501e-09,3.65436e-09,1.36242e-06,1.3624e-06,5.00004e-08,0,0,0,0,0,0,0,0 +15392000,0.982925,-0.00734659,-0.0109043,0.183538,0.000127503,0.00112956,0.0220886,0.00350348,-0.000585356,0.0424901,-1.02649e-05,-4.76899e-05,-3.35096e-06,3.51523e-06,4.62924e-05,-0.00108316,0.205039,0.000821557,0.434373,0,0,0,0,0,7.07943e-06,0.000129452,0.000129457,0.000201685,0.0370705,0.0370724,0.0093441,0.0453571,0.0453575,0.0600257,1.15296e-09,1.15349e-09,3.59181e-09,1.35633e-06,1.35631e-06,5.00004e-08,0,0,0,0,0,0,0,0 +15488000,0.982921,-0.00738502,-0.0108829,0.183557,-0.000162838,-0.0012777,0.0227284,0.00348186,-0.0005724,0.0431016,-1.02641e-05,-4.76914e-05,-3.29556e-06,3.53717e-06,4.62846e-05,-0.00108283,0.205039,0.000821557,0.434373,0,0,0,0,0,7.06223e-06,0.000133176,0.000133182,0.000201104,0.041567,0.0415689,0.00944114,0.0514048,0.0514053,0.0597674,1.15299e-09,1.15352e-09,3.52903e-09,1.35634e-06,1.35632e-06,5e-08,0,0,0,0,0,0,0,0 +15592000,0.982916,-0.00754607,-0.0109505,0.183575,0.00349428,-0.00501692,0.0223688,0.00562097,-0.00435565,0.0414586,-9.70108e-06,-4.75767e-05,-3.08279e-06,4.78551e-06,4.10863e-05,-0.00108185,0.205039,0.000821557,0.434373,0,0,0,0,0,7.0667e-06,0.000127778,0.000127779,0.000201102,0.0370541,0.0370559,0.00942673,0.0453412,0.0453416,0.0592745,1.06235e-09,1.06278e-09,3.46602e-09,1.34927e-06,1.34925e-06,5e-08,0,0,0,0,0,0,0,0 +15688000,0.98293,-0.00751356,-0.0109671,0.183498,0.0059405,-0.00762635,0.0230742,0.00605318,-0.00496447,0.0428392,-9.69798e-06,-4.75833e-05,-2.83381e-06,4.73087e-06,4.11452e-05,-0.00108166,0.205039,0.000821557,0.434373,0,0,0,0,0,7.11278e-06,0.000131321,0.00013132,0.00020241,0.0415162,0.0415184,0.00961692,0.0514009,0.0514016,0.0599446,1.06238e-09,1.0628e-09,3.41874e-09,1.34927e-06,1.34926e-06,5.00008e-08,0,0,0,0,0,0,0,0 +15792000,0.982956,-0.00752527,-0.0108798,0.183366,0.00330176,-0.00662477,0.0233246,0.00479846,-0.0039764,0.042665,-9.88407e-06,-4.76583e-05,-2.43556e-06,4.19731e-06,4.28477e-05,-0.0010806,0.205039,0.000821557,0.434373,0,0,0,0,0,7.11099e-06,0.00012559,0.000125589,0.000202421,0.0369575,0.0369592,0.00961366,0.0453383,0.0453387,0.0594845,9.73998e-10,9.74365e-10,3.35567e-09,1.3414e-06,1.34139e-06,5.00008e-08,0,0,0,0,0,0,0,0 +15888000,0.982928,-0.00759137,-0.0109141,0.18351,0.0028563,-0.00518822,0.0239497,0.00505029,-0.00455908,0.0435578,-9.88795e-06,-4.76509e-05,-2.72908e-06,4.30825e-06,4.27541e-05,-0.00108028,0.205039,0.000821557,0.434373,0,0,0,0,0,7.09358e-06,0.000128938,0.000128934,0.000201845,0.0413636,0.0413658,0.00974159,0.0514085,0.0514092,0.0593048,9.74038e-10,9.74369e-10,3.29269e-09,1.3414e-06,1.34139e-06,5.00004e-08,0,0,0,0,0,0,0,0 +15992000,0.982931,-0.00739617,-0.0108836,0.183502,0.00119201,-0.00433803,0.0212054,0.00409931,-0.00359294,0.0424377,-1.00179e-05,-4.76822e-05,-2.77411e-06,4.13927e-06,4.38877e-05,-0.00107849,0.205039,0.000821557,0.434373,0,0,0,0,0,7.08871e-06,0.000122983,0.000122976,0.000201846,0.0367827,0.0367845,0.00974706,0.0453432,0.0453437,0.0588904,8.8912e-10,8.894e-10,3.22984e-09,1.33289e-06,1.33288e-06,5.00004e-08,0,0,0,0,0,0,0,0 +16088000,0.982935,-0.00731842,-0.0108842,0.183484,0.000445487,-0.00523748,0.0189971,0.00414769,-0.00404729,0.0422675,-1.00234e-05,-4.76783e-05,-3.01633e-06,4.16096e-06,4.38902e-05,-0.00107799,0.205039,0.000821557,0.434373,0,0,0,0,0,7.0602e-06,0.00012613,0.000126123,0.000201265,0.0411319,0.0411339,0.00988552,0.0514212,0.0514219,0.0587526,8.89142e-10,8.89429e-10,3.16726e-09,1.3329e-06,1.33289e-06,5e-08,0,0,0,0,0,0,0,0 +16192000,0.982916,-0.00721839,-0.0107893,0.183595,-0.00274105,-0.00267595,0.0175737,0.00204098,-0.00308131,0.0383316,-1.02071e-05,-4.78101e-05,-3.33438e-06,2.8149e-06,4.56463e-05,-0.00107608,0.205039,0.000821557,0.434373,0,0,0,0,0,7.05692e-06,0.00012004,0.000120033,0.000201236,0.0365129,0.0365145,0.00989598,0.0453513,0.0453518,0.0583812,8.08536e-10,8.08792e-10,3.10496e-09,1.32391e-06,1.3239e-06,5e-08,0,0,0,0,0,0,0,0 +16288000,0.982907,-0.00722647,-0.0107029,0.183652,-0.0017986,-0.00400991,0.0170145,0.00179561,-0.0034387,0.0398503,-1.0206e-05,-4.78111e-05,-3.28254e-06,2.81912e-06,4.56429e-05,-0.00107603,0.205039,0.000821557,0.434373,0,0,0,0,0,7.10629e-06,0.000122984,0.000122978,0.000202486,0.0407655,0.0407673,0.0101201,0.051431,0.0514316,0.0591506,8.08565e-10,8.08827e-10,3.05852e-09,1.32391e-06,1.3239e-06,5.00008e-08,0,0,0,0,0,0,0,0 +16392000,0.98292,-0.0071609,-0.0107162,0.183582,0.000737684,-0.00284499,0.0174882,0.00293474,-0.00269888,0.0397,-1.02128e-05,-4.76371e-05,-2.89754e-06,4.98567e-06,4.56668e-05,-0.00107523,0.205039,0.000821557,0.434373,0,0,0,0,0,7.10661e-06,0.000116867,0.00011686,0.000202412,0.0361389,0.0361404,0.0101316,0.045358,0.0453584,0.0588088,7.33006e-10,7.33238e-10,2.99693e-09,1.31465e-06,1.31464e-06,5.00008e-08,0,0,0,0,0,0,0,0 +16488000,0.982909,-0.00727196,-0.0107449,0.183637,0.00292389,-0.00444396,0.0198344,0.0031021,-0.0030874,0.0439313,-1.02157e-05,-4.76338e-05,-3.05916e-06,4.94267e-06,4.56892e-05,-0.0010759,0.205039,0.000821557,0.434373,0,0,0,0,0,7.08355e-06,0.00011961,0.000119605,0.00020175,0.0402738,0.0402756,0.0102847,0.0514315,0.0514322,0.0587541,7.33029e-10,7.33267e-10,2.93585e-09,1.31465e-06,1.31465e-06,5.00004e-08,0,0,0,0,0,0,0,0 +16592000,0.982905,-0.00722417,-0.0107732,0.183654,0.00606173,-0.0045323,0.0231869,0.00273387,-0.00246402,0.0440819,-1.03185e-05,-4.76524e-05,-3.07076e-06,4.802e-06,4.67997e-05,-0.00107511,0.205039,0.000821557,0.434373,0,0,0,0,0,7.07855e-06,0.000113555,0.000113549,0.000201633,0.0356534,0.035655,0.0102952,0.0453585,0.0453589,0.0584493,6.62932e-10,6.63142e-10,2.87531e-09,1.30531e-06,1.3053e-06,5.00004e-08,0,0,0,0,0,0,0,0 +16688000,0.982913,-0.00724724,-0.0107245,0.183617,0.00753595,-0.00779071,0.0230296,0.00339328,-0.00304839,0.0445594,-1.03148e-05,-4.76561e-05,-2.87825e-06,4.83498e-06,4.67803e-05,-0.00107461,0.205039,0.000821557,0.434373,0,0,0,0,0,7.05619e-06,0.000116103,0.000116098,0.000200926,0.039677,0.0396787,0.0104511,0.0514175,0.0514181,0.0584328,6.62956e-10,6.63172e-10,2.81539e-09,1.30531e-06,1.30531e-06,5e-08,0,0,0,0,0,0,0,0 +16792000,0.982935,-0.00708339,-0.0106286,0.183512,0.00910035,-0.00788495,0.0213164,0.00276053,-0.00237652,0.0437911,-1.04835e-05,-4.77277e-05,-2.67138e-06,4.10062e-06,4.88025e-05,-0.00107318,0.205039,0.000821557,0.434373,0,0,0,0,0,7.04549e-06,0.000110184,0.000110178,0.000200761,0.0351243,0.0351256,0.010458,0.0453504,0.0453509,0.0581605,5.985e-10,5.98688e-10,2.75611e-09,1.29604e-06,1.29604e-06,5e-08,0,0,0,0,0,0,0,0 +16888000,0.982959,-0.00708115,-0.0107205,0.183374,0.00829803,-0.00807404,0.0235431,0.0035822,-0.00313013,0.0446363,-1.04769e-05,-4.77339e-05,-2.3382e-06,4.13069e-06,4.878e-05,-0.00107276,0.205039,0.000821557,0.434373,0,0,0,0,0,7.08279e-06,0.000112545,0.000112539,0.000201874,0.0390106,0.039012,0.0106972,0.0513879,0.0513885,0.0590421,5.98531e-10,5.98723e-10,2.71215e-09,1.29605e-06,1.29605e-06,5.00012e-08,0,0,0,0,0,0,0,0 +16992000,0.98295,-0.00714368,-0.0107791,0.183416,0.0101848,-0.00730608,0.0235729,0.00538447,-0.00239365,0.0431527,-1.05461e-05,-4.75659e-05,-2.22576e-06,6.46464e-06,4.95774e-05,-0.00107151,0.205039,0.000821557,0.434373,0,0,0,0,0,7.07901e-06,0.00010681,0.000106804,0.00020164,0.0345082,0.0345094,0.0106979,0.045331,0.0453314,0.0587906,5.39652e-10,5.39817e-10,2.65413e-09,1.28695e-06,1.28695e-06,5.00012e-08,0,0,0,0,0,0,0,0 +17088000,0.98295,-0.00722138,-0.0107354,0.183416,0.0130373,-0.00958712,0.0237397,0.00651255,-0.00323871,0.0424128,-1.05472e-05,-4.75658e-05,-2.25349e-06,6.51011e-06,4.95603e-05,-0.00107055,0.205039,0.000821557,0.434373,0,0,0,0,0,7.04953e-06,0.000108992,0.000108987,0.000200833,0.0382709,0.0382722,0.0108557,0.0513387,0.0513393,0.0588464,5.39677e-10,5.39848e-10,2.5969e-09,1.28695e-06,1.28696e-06,5.00008e-08,0,0,0,0,0,0,0,0 +17192000,0.982897,-0.0073031,-0.0106474,0.183702,0.0123511,-0.0133507,0.0245358,0.00638079,-0.00510785,0.0443236,-1.04834e-05,-4.7667e-05,-2.79603e-06,5.12994e-06,4.84473e-05,-0.00106997,0.205039,0.000821557,0.434373,0,0,0,0,0,7.04439e-06,0.00010348,0.000103475,0.000200541,0.0338466,0.0338473,0.0108489,0.0452986,0.045299,0.058619,4.8621e-10,4.86357e-10,2.54046e-09,1.27812e-06,1.27812e-06,5.00008e-08,0,0,0,0,0,0,0,0 +17288000,0.982869,-0.00726326,-0.0106533,0.183857,0.0135937,-0.0130187,0.0239663,0.00761504,-0.00631405,0.0441825,-1.0491e-05,-4.7661e-05,-3.15386e-06,5.15318e-06,4.84473e-05,-0.00106919,0.205039,0.000821557,0.434373,0,0,0,0,0,7.01626e-06,0.000105494,0.00010549,0.000199683,0.0374782,0.0374792,0.0110037,0.05127,0.0512705,0.0587032,4.86237e-10,4.86389e-10,2.48487e-09,1.27812e-06,1.27813e-06,5.00004e-08,0,0,0,0,0,0,0,0 +17392000,0.982909,-0.00715851,-0.0106415,0.183643,0.00963651,-0.0127426,0.0239092,0.00833923,-0.00369789,0.0438744,-1.07628e-05,-4.75281e-05,-2.82066e-06,7.22978e-06,5.20972e-05,-0.00106779,0.205039,0.000821557,0.434373,0,0,0,0,0,6.99548e-06,0.000100236,0.000100232,0.000199349,0.0331465,0.0331468,0.0109881,0.0452531,0.0452534,0.058495,4.37925e-10,4.38054e-10,2.43014e-09,1.26962e-06,1.26963e-06,5.00004e-08,0,0,0,0,0,0,0,0 +17488000,0.98289,-0.00716122,-0.0106818,0.183747,0.00842003,-0.013032,0.0242628,0.00915967,-0.00490787,0.0451315,-1.07673e-05,-4.75244e-05,-3.03813e-06,7.23779e-06,5.20994e-05,-0.00106744,0.205039,0.000821557,0.434373,0,0,0,0,0,6.9657e-06,0.000102094,0.000102089,0.000198444,0.0366391,0.0366394,0.0111384,0.051181,0.0511814,0.0586031,4.37953e-10,4.38086e-10,2.37631e-09,1.26963e-06,1.26964e-06,5e-08,0,0,0,0,0,0,0,0 +17592000,0.982887,-0.00711141,-0.0105547,0.18377,0.00398354,-0.00990949,0.023643,0.00482962,-0.00366876,0.0449214,-1.10548e-05,-4.78008e-05,-3.0063e-06,3.4681e-06,5.60286e-05,-0.00106613,0.205039,0.000821557,0.434373,0,0,0,0,0,6.95287e-06,9.71076e-05,9.71022e-05,0.000198044,0.0324148,0.0324151,0.0111132,0.0451937,0.0451939,0.0584095,3.94474e-10,3.94584e-10,2.32338e-09,1.26152e-06,1.26153e-06,5e-08,0,0,0,0,0,0,0,0 +17688000,0.982912,-0.00720995,-0.0104857,0.183634,0.00351686,-0.0103234,0.0239644,0.00522721,-0.00464634,0.0452599,-1.10537e-05,-4.78026e-05,-2.92705e-06,3.48544e-06,5.60291e-05,-0.00106545,0.205039,0.000821557,0.434373,0,0,0,0,0,6.97461e-06,9.88193e-05,9.88144e-05,0.000198912,0.0357696,0.03577,0.0113486,0.0510723,0.0510726,0.0594111,3.9451e-10,3.94619e-10,2.28429e-09,1.26152e-06,1.26153e-06,5.00008e-08,0,0,0,0,0,0,0,0 +17792000,0.982951,-0.00715135,-0.0104632,0.183431,0.00559894,-0.00796145,0.0248154,0.00557436,-0.00233367,0.050571,-1.12557e-05,-4.76784e-05,-2.8415e-06,5.32036e-06,5.8952e-05,-0.00106631,0.205039,0.000821557,0.434373,0,0,0,0,0,6.94379e-06,9.4113e-05,9.41066e-05,0.000198465,0.0316609,0.0316612,0.0113125,0.0451203,0.0451206,0.059222,3.55498e-10,3.55581e-10,2.23299e-09,1.25382e-06,1.25383e-06,5.00008e-08,0,0,0,0,0,0,0,0 +17888000,0.982959,-0.00710025,-0.0105584,0.183385,0.0068664,-0.0101652,0.023918,0.00623171,-0.00321619,0.0545126,-1.12525e-05,-4.76808e-05,-2.69312e-06,5.3059e-06,5.89531e-05,-0.00106685,0.205039,0.000821557,0.434373,0,0,0,0,0,6.90966e-06,9.56901e-05,9.56832e-05,0.000197462,0.0348917,0.034892,0.0114536,0.0509444,0.0509448,0.0593738,3.55527e-10,3.55615e-10,2.18266e-09,1.25382e-06,1.25384e-06,5.00004e-08,0,0,0,0,0,0,0,0 +17992000,0.982956,-0.00691672,-0.0105206,0.183407,0.00574465,-0.00435334,0.0237649,0.00500953,0.00147188,0.0554344,-1.16727e-05,-4.76256e-05,-2.71318e-06,6.22364e-06,6.51888e-05,-0.00106633,0.205039,0.000821557,0.434373,0,0,0,0,0,6.89127e-06,9.12621e-05,9.12545e-05,0.000196951,0.0309006,0.0309008,0.0114069,0.0450336,0.0450338,0.0591909,3.2059e-10,3.20662e-10,2.13328e-09,1.24654e-06,1.24656e-06,5.00004e-08,0,0,0,0,0,0,0,0 +18088000,0.982959,-0.00699763,-0.0104886,0.183394,0.00581562,-0.00424003,0.0225315,0.00559687,0.00101536,0.0536749,-1.16715e-05,-4.76275e-05,-2.62209e-06,6.27885e-06,6.51687e-05,-0.00106492,0.205039,0.000821557,0.434373,0,0,0,0,0,6.85643e-06,9.27145e-05,9.27078e-05,0.000195909,0.0339927,0.033993,0.0115407,0.0507992,0.0507995,0.0593539,3.2062e-10,3.20697e-10,2.08487e-09,1.24655e-06,1.24656e-06,5e-08,0,0,0,0,0,0,0,0 +18192000,0.982999,-0.0070338,-0.0105168,0.183174,0.00552383,-0.00383737,0.0231408,0.00572449,0.000937474,0.0514714,-1.16897e-05,-4.76105e-05,-2.15459e-06,6.84526e-06,6.55301e-05,-0.00106303,0.205039,0.000821557,0.434373,0,0,0,0,0,6.83265e-06,8.85643e-05,8.85571e-05,0.000195354,0.03012,0.0301202,0.0114835,0.044934,0.0449342,0.0591733,2.89397e-10,2.89461e-10,2.03743e-09,1.2397e-06,1.23972e-06,5e-08,0,0,0,0,0,0,0,0 +18288000,0.982992,-0.00708437,-0.0104785,0.183211,0.00603117,-0.00440265,0.0222803,0.00622485,0.000539301,0.0504373,-1.16893e-05,-4.76115e-05,-2.11369e-06,6.8876e-06,6.55161e-05,-0.00106185,0.205039,0.000821557,0.434373,0,0,0,0,0,6.85982e-06,8.99029e-05,8.98964e-05,0.000196032,0.0330825,0.0330826,0.0117072,0.0506359,0.0506362,0.0602419,2.89433e-10,2.89499e-10,2.00249e-09,1.23971e-06,1.23972e-06,5.00008e-08,0,0,0,0,0,0,0,0 +18392000,0.982962,-0.00701015,-0.0105034,0.183373,0.00611032,-0.00457177,0.0221641,0.00744363,0.000489056,0.0506236,-1.16918e-05,-4.75119e-05,-2.27029e-06,8.53682e-06,6.54726e-05,-0.00106109,0.205039,0.000821557,0.434373,0,0,0,0,0,6.84426e-06,8.60252e-05,8.60177e-05,0.000195413,0.0293468,0.0293467,0.0116388,0.0448219,0.0448221,0.0600548,2.61568e-10,2.61623e-10,1.95675e-09,1.2333e-06,1.23332e-06,5.00008e-08,0,0,0,0,0,0,0,0 +18488000,0.982972,-0.00707757,-0.0105058,0.183319,0.00857618,-0.00471317,0.021829,0.00822005,2.17671e-05,0.0519804,-1.16877e-05,-4.75157e-05,-2.05951e-06,8.55328e-06,6.54632e-05,-0.00106084,0.205039,0.000821557,0.434373,0,0,0,0,0,6.80706e-06,8.72595e-05,8.72527e-05,0.000194289,0.0321859,0.0321859,0.0117602,0.050458,0.0504583,0.0602384,2.616e-10,2.61659e-10,1.91199e-09,1.23331e-06,1.23332e-06,5.00004e-08,0,0,0,0,0,0,0,0 +18592000,0.982935,-0.00691799,-0.0103683,0.183529,0.00678843,-0.00503246,0.0218471,0.00665116,4.63694e-05,0.0542922,-1.17679e-05,-4.75982e-05,-2.30056e-06,7.24687e-06,6.66543e-05,-0.00106044,0.205039,0.000821557,0.434373,0,0,0,0,0,6.79083e-06,8.36414e-05,8.36338e-05,0.00019363,0.0285818,0.0285817,0.0116821,0.0446986,0.0446987,0.0600474,2.36743e-10,2.36793e-10,1.86818e-09,1.22732e-06,1.22734e-06,5.00004e-08,0,0,0,0,0,0,0,0 +18688000,0.982961,-0.00689801,-0.0103175,0.183396,0.00642264,-0.00391687,0.0206455,0.00729585,-0.000372012,0.0531847,-1.17628e-05,-4.76033e-05,-2.01986e-06,7.29168e-06,6.66362e-05,-0.00105927,0.205039,0.000821557,0.434373,0,0,0,0,0,6.74879e-06,8.47803e-05,8.47732e-05,0.000192484,0.0313013,0.0313013,0.0117956,0.050266,0.0502662,0.0602308,2.36776e-10,2.36829e-10,1.82535e-09,1.22733e-06,1.22734e-06,5e-08,0,0,0,0,0,0,0,0 +18792000,0.982958,-0.00687332,-0.0101998,0.183418,0.0056656,-0.00503216,0.0196572,0.00707357,-0.000363722,0.0501084,-1.17959e-05,-4.75981e-05,-2.01984e-06,7.52844e-06,6.71259e-05,-0.00105648,0.205039,0.000821557,0.434373,0,0,0,0,0,6.72463e-06,8.14091e-05,8.1402e-05,0.000191795,0.0278235,0.0278234,0.0117084,0.0445646,0.0445648,0.0600336,2.1461e-10,2.14654e-10,1.78346e-09,1.22174e-06,1.22176e-06,5e-08,0,0,0,0,0,0,0,0 +18888000,0.982947,-0.00682941,-0.010234,0.183479,0.00476366,-0.00449559,0.0189199,0.00754508,-0.000865763,0.048578,-1.17989e-05,-4.75961e-05,-2.15116e-06,7.5597e-06,6.71214e-05,-0.0010552,0.205039,0.000821557,0.434373,0,0,0,0,0,6.74294e-06,8.24617e-05,8.24542e-05,0.000192315,0.0304261,0.030426,0.0119175,0.0500612,0.0500614,0.0611392,2.14647e-10,2.14694e-10,1.75268e-09,1.22175e-06,1.22177e-06,5.00008e-08,0,0,0,0,0,0,0,0 +18992000,0.982933,-0.00678924,-0.0102282,0.183555,0.0027721,-0.00585861,0.0195362,0.0061993,-0.000715253,0.0510586,-1.1856e-05,-4.76434e-05,-2.12369e-06,6.8467e-06,6.8058e-05,-0.00105484,0.205039,0.000821557,0.434373,0,0,0,0,0,6.72246e-06,7.93269e-05,7.9319e-05,0.000191575,0.0270796,0.0270794,0.0118209,0.044421,0.0444212,0.0609276,1.94886e-10,1.94925e-10,1.71245e-09,1.21656e-06,1.21658e-06,5.00008e-08,0,0,0,0,0,0,0,0 +19088000,0.982941,-0.00688673,-0.0102406,0.183509,0.000597614,-0.00609197,0.0204472,0.00640587,-0.00125822,0.0471095,-1.18525e-05,-4.76474e-05,-1.91006e-06,6.90976e-06,6.80405e-05,-0.00105266,0.205039,0.000821557,0.434373,0,0,0,0,0,6.68309e-06,8.02998e-05,8.02927e-05,0.000190366,0.0295642,0.0295639,0.0119222,0.0498456,0.0498457,0.0611125,1.9492e-10,1.94962e-10,1.67314e-09,1.21656e-06,1.21658e-06,5.00004e-08,0,0,0,0,0,0,0,0 +19192000,0.982906,-0.00679075,-0.0103547,0.183689,-0.00141583,-0.0060478,0.020354,0.00528705,-0.00101602,0.0468457,-1.1916e-05,-4.76491e-05,-2.33232e-06,6.83097e-06,6.89555e-05,-0.00105176,0.205039,0.000821557,0.434373,0,0,0,0,0,6.65571e-06,7.73886e-05,7.73802e-05,0.000189604,0.0263463,0.026346,0.0118183,0.0442688,0.0442689,0.0608913,1.77299e-10,1.77333e-10,1.63475e-09,1.21175e-06,1.21177e-06,5.00004e-08,0,0,0,0,0,0,0,0 +19288000,0.982912,-0.00674924,-0.0103312,0.183664,-0.00223225,-0.00593589,0.0205796,0.00514117,-0.00159312,0.0462634,-1.19167e-05,-4.76488e-05,-2.35724e-06,6.85256e-06,6.89526e-05,-0.00105081,0.205039,0.000821557,0.434373,0,0,0,0,0,6.61026e-06,7.82894e-05,7.82813e-05,0.000188386,0.0287323,0.0287321,0.0119127,0.04962,0.0496201,0.0610681,1.77334e-10,1.77371e-10,1.59727e-09,1.21176e-06,1.21178e-06,5e-08,0,0,0,0,0,0,0,0 +19392000,0.982903,-0.00685039,-0.0102315,0.183712,-0.00278059,-0.00302313,0.0214897,0.00434717,3.79901e-05,0.0444126,-1.20208e-05,-4.76142e-05,-2.48894e-06,7.50413e-06,7.06972e-05,-0.0010489,0.205039,0.000821557,0.434373,0,0,0,0,0,6.58104e-06,7.55842e-05,7.55771e-05,0.000187601,0.0256332,0.0256331,0.0118024,0.0441084,0.0441084,0.0608365,1.61609e-10,1.6164e-10,1.56067e-09,1.2073e-06,1.20732e-06,5e-08,0,0,0,0,0,0,0,0 +19488000,0.982867,-0.00688371,-0.010129,0.183911,-0.00351376,-0.0029739,0.0218702,0.00403093,-0.000226868,0.04524,-1.2025e-05,-4.76106e-05,-2.6993e-06,7.5077e-06,7.07014e-05,-0.00104841,0.205039,0.000821557,0.434373,0,0,0,0,0,6.60193e-06,7.64193e-05,7.64131e-05,0.000187977,0.0279207,0.0279206,0.0119978,0.0493854,0.0493855,0.0619535,1.61648e-10,1.61681e-10,1.53383e-09,1.2073e-06,1.20733e-06,5.00012e-08,0,0,0,0,0,0,0,0 +19592000,0.98285,-0.00683412,-0.010243,0.183996,-0.00464619,-0.0061125,0.0236889,0.00445711,-0.00141797,0.0461758,-1.19637e-05,-4.75588e-05,-2.75759e-06,8.46616e-06,6.95673e-05,-0.00104757,0.205039,0.000821557,0.434373,0,0,0,0,0,6.57686e-06,7.39082e-05,7.3901e-05,0.000187151,0.024943,0.0249428,0.0118806,0.043941,0.043941,0.0617034,1.47606e-10,1.47633e-10,1.49877e-09,1.20317e-06,1.2032e-06,5.00012e-08,0,0,0,0,0,0,0,0 +19688000,0.982865,-0.00684159,-0.0102614,0.183914,-0.00616177,-0.00482433,0.0230349,0.00394981,-0.00194242,0.0468182,-1.19605e-05,-4.75619e-05,-2.58409e-06,8.48482e-06,6.95619e-05,-0.00104695,0.205039,0.000821557,0.434373,0,0,0,0,0,6.53226e-06,7.46838e-05,7.4677e-05,0.000185894,0.0271392,0.027139,0.0119654,0.0491443,0.0491443,0.0618694,1.47642e-10,1.47672e-10,1.46456e-09,1.20318e-06,1.2032e-06,5.00008e-08,0,0,0,0,0,0,0,0 +19792000,0.982844,-0.00691044,-0.0103143,0.184019,-0.00693125,-0.00337884,0.020557,0.00444664,-0.00153238,0.0415874,-1.19676e-05,-4.74745e-05,-2.78559e-06,1.00985e-05,6.95824e-05,-0.00104384,0.205039,0.000821557,0.434373,0,0,0,0,0,6.50336e-06,7.23514e-05,7.23446e-05,0.000185055,0.024284,0.0242838,0.0118439,0.0437679,0.0437679,0.0616082,1.35091e-10,1.35115e-10,1.43118e-09,1.19936e-06,1.19938e-06,5.00008e-08,0,0,0,0,0,0,0,0 +19888000,0.982828,-0.00694217,-0.0103931,0.184101,-0.00670055,-0.00316785,0.0209039,0.00373062,-0.00180909,0.0405444,-1.19694e-05,-4.74732e-05,-2.86567e-06,1.01178e-05,6.95835e-05,-0.00104271,0.205039,0.000821557,0.434373,0,0,0,0,0,6.46266e-06,7.30728e-05,7.30661e-05,0.000183789,0.0263872,0.0263871,0.0119235,0.0488982,0.0488982,0.0617619,1.35128e-10,1.35154e-10,1.39863e-09,1.19936e-06,1.19939e-06,5.00004e-08,0,0,0,0,0,0,0,0 +19992000,0.982846,-0.00694952,-0.0105724,0.183994,-0.00592289,-0.00311661,0.0179732,0.00431572,-0.000377275,0.0372029,-1.20127e-05,-4.7374e-05,-2.78264e-06,1.20522e-05,7.03872e-05,-0.00103988,0.205039,0.000821557,0.434373,0,0,0,0,0,6.42756e-06,7.09067e-05,7.08994e-05,0.000182941,0.0236461,0.0236459,0.0117987,0.0435903,0.0435903,0.0614899,1.23897e-10,1.23918e-10,1.36689e-09,1.19583e-06,1.19585e-06,5.00004e-08,0,0,0,0,0,0,0,0 +20088000,0.982856,-0.00693868,-0.010568,0.183943,-0.00545449,-0.00500617,0.0173994,0.00376108,-0.000774417,0.0393905,-1.20127e-05,-4.7374e-05,-2.78481e-06,1.20488e-05,7.03874e-05,-0.00104005,0.205039,0.000821557,0.434373,0,0,0,0,0,6.3797e-06,7.15783e-05,7.15714e-05,0.000181681,0.0256713,0.0256711,0.0118737,0.0486483,0.0486483,0.0616307,1.23934e-10,1.23958e-10,1.33594e-09,1.19583e-06,1.19586e-06,5e-08,0,0,0,0,0,0,0,0 +20192000,0.98283,-0.00691609,-0.0106487,0.184074,-0.00521217,-0.00299965,0.0184723,0.00315817,-0.000573193,0.040509,-1.20399e-05,-4.73449e-05,-3.06624e-06,1.25268e-05,7.07915e-05,-0.0010395,0.205039,0.000821557,0.434373,0,0,0,0,0,6.34933e-06,6.95624e-05,6.95548e-05,0.000180817,0.0230298,0.0230296,0.0117465,0.0434086,0.0434086,0.0613486,1.13869e-10,1.13888e-10,1.30576e-09,1.19255e-06,1.19257e-06,5e-08,0,0,0,0,0,0,0,0 +20288000,0.982836,-0.00691076,-0.0106866,0.184043,-0.00856727,-0.0038885,0.0188149,0.00253069,-0.000861612,0.0418167,-1.204e-05,-4.73449e-05,-3.06712e-06,1.25297e-05,7.07917e-05,-0.00103933,0.205039,0.000821557,0.434373,0,0,0,0,0,6.35555e-06,7.01892e-05,7.01817e-05,0.000181055,0.0249723,0.024972,0.0119267,0.0483948,0.0483947,0.0624413,1.1391e-10,1.13931e-10,1.28363e-09,1.19255e-06,1.19257e-06,5.00008e-08,0,0,0,0,0,0,0,0 +20392000,0.982831,-0.00685644,-0.0106621,0.184074,-0.00971624,-0.0028209,0.0181943,0.00208607,-0.000645398,0.040781,-1.20456e-05,-4.73095e-05,-2.86153e-06,1.33236e-05,7.09666e-05,-0.00103749,0.205039,0.000821557,0.434373,0,0,0,0,0,6.33251e-06,6.83145e-05,6.83066e-05,0.000180161,0.0224354,0.0224351,0.0117961,0.0432237,0.0432236,0.0621406,1.04882e-10,1.04899e-10,1.25476e-09,1.18951e-06,1.18953e-06,5.00008e-08,0,0,0,0,0,0,0,0 +20488000,0.982849,-0.00687714,-0.0106342,0.183979,-0.0124241,-0.0035743,0.0182809,0.00100084,-0.000911037,0.0391834,-1.20455e-05,-4.73099e-05,-2.84383e-06,1.33446e-05,7.09687e-05,-0.00103623,0.205039,0.000821557,0.434373,0,0,0,0,0,6.28186e-06,6.88997e-05,6.88924e-05,0.000178891,0.0243011,0.0243007,0.011866,0.0481386,0.0481386,0.0622645,1.0492e-10,1.04939e-10,1.22663e-09,1.18951e-06,1.18954e-06,5.00004e-08,0,0,0,0,0,0,0,0 +20592000,0.98288,-0.00685905,-0.0106515,0.183813,-0.0119729,-0.0049119,0.0180759,0.000870099,-0.000802603,0.0374765,-1.20376e-05,-4.72569e-05,-2.52103e-06,1.45262e-05,7.09252e-05,-0.00103445,0.205039,0.000821557,0.434373,0,0,0,0,0,6.24894e-06,6.71562e-05,6.71486e-05,0.000178001,0.0218616,0.0218612,0.0117346,0.0430358,0.0430357,0.0619552,9.68136e-11,9.68284e-11,1.19921e-09,1.1867e-06,1.18672e-06,5.00004e-08,0,0,0,0,0,0,0,0 +20688000,0.982873,-0.00678606,-0.0106471,0.183849,-0.0140372,-0.00446187,0.0188883,-0.000328327,-0.00120735,0.0375587,-1.20404e-05,-4.72545e-05,-2.65908e-06,1.45318e-05,7.09306e-05,-0.00103382,0.205039,0.000821557,0.434373,0,0,0,0,0,6.20248e-06,6.7704e-05,6.76966e-05,0.000176733,0.0236561,0.0236556,0.0118016,0.0478805,0.0478804,0.0620662,9.68526e-11,9.68694e-11,1.17249e-09,1.1867e-06,1.18673e-06,5e-08,0,0,0,0,0,0,0,0 +20792000,0.982898,-0.00618986,-0.0105552,0.183741,-0.0160898,-0.00184643,0.00442409,-0.000393128,-0.000979028,0.0366271,-1.2038e-05,-4.71938e-05,-2.54919e-06,1.57824e-05,7.0922e-05,-0.00103255,0.205039,0.000821557,0.434373,0,0,0,0,0,6.16622e-06,6.60814e-05,6.60716e-05,0.000175845,0.0213429,0.0213425,0.0116702,0.0428458,0.0428457,0.0617494,8.95623e-11,8.95753e-11,1.14645e-09,1.1841e-06,1.18412e-06,5e-08,0,0,0,0,0,0,0,0 +20888000,0.982955,0.00260953,-0.00685658,0.183702,-0.0223961,0.00976136,-0.106542,-0.00229774,-0.000583745,0.0319802,-1.2037e-05,-4.71947e-05,-2.49615e-06,1.57947e-05,7.09211e-05,-0.00103239,0.205039,0.000821557,0.434373,0,0,0,0,0,6.1645e-06,6.65876e-05,6.65694e-05,0.000176031,0.0233374,0.0233371,0.0118449,0.0476333,0.0476333,0.0628247,8.96043e-11,8.96179e-11,1.12736e-09,1.1841e-06,1.18413e-06,5.00008e-08,0,0,0,0,0,0,0,0 +20992000,0.982945,0.00631303,-0.00321408,0.183766,-0.0330607,0.0281469,-0.252857,-0.00237784,0.000314091,0.0170344,-1.19629e-05,-4.71179e-05,-2.48376e-06,1.73749e-05,6.92884e-05,-0.00103584,0.205039,0.000821557,0.434373,0,0,0,0,0,6.13596e-06,6.49911e-05,6.49807e-05,0.000175125,0.0213551,0.021355,0.0117119,0.0426767,0.0426767,0.0624912,8.29642e-11,8.29738e-11,1.10247e-09,1.18133e-06,1.18136e-06,5.00008e-08,0,0,0,0,0,0,0,0 +21088000,0.982887,0.00481452,-0.00353235,0.184112,-0.0456239,0.0430477,-0.365326,-0.00614599,0.00377529,-0.0120802,-1.19634e-05,-4.71174e-05,-2.50847e-06,1.73808e-05,6.92846e-05,-0.001036,0.205039,0.000821557,0.434373,0,0,0,0,0,6.11237e-06,6.54745e-05,6.54627e-05,0.000173828,0.0233196,0.0233195,0.0117771,0.0474488,0.0474488,0.0625864,8.3005e-11,8.30141e-11,1.07822e-09,1.18133e-06,1.18136e-06,5.00004e-08,0,0,0,0,0,0,0,0 +21192000,0.982833,0.00182663,-0.00522048,0.184416,-0.0490434,0.0483872,-0.494459,-0.00540046,0.00343246,-0.0448317,-1.17228e-05,-4.70017e-05,-2.40539e-06,2.01736e-05,6.31402e-05,-0.00104613,0.205039,0.000821557,0.434373,0,0,0,0,0,6.10306e-06,6.38538e-05,6.38403e-05,0.000172887,0.0212903,0.0212901,0.0116453,0.0425417,0.0425418,0.0622476,7.68986e-11,7.69079e-11,1.05458e-09,1.17802e-06,1.17805e-06,5.00004e-08,0,0,0,0,0,0,0,0 +21288000,0.982777,-0.000274156,-0.00652115,0.184683,-0.049296,0.0521352,-0.618906,-0.0101329,0.00828572,-0.100672,-1.17284e-05,-4.69964e-05,-2.69163e-06,2.02621e-05,6.31561e-05,-0.00104527,0.205039,0.000821557,0.434373,0,0,0,0,0,6.06759e-06,6.43071e-05,6.42931e-05,0.000171612,0.0232399,0.0232394,0.0117094,0.0472944,0.0472945,0.0623317,7.6939e-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.982739,-0.00184435,-0.00725858,0.184844,-0.0453811,0.0489088,-0.748057,-0.0104511,0.011006,-0.164553,-1.1616e-05,-4.68961e-05,-2.59202e-06,2.31057e-05,5.99424e-05,-0.00105254,0.205039,0.000821557,0.434373,0,0,0,0,0,6.04974e-06,6.2655e-05,6.26427e-05,0.000170687,0.021192,0.0211916,0.0115791,0.042429,0.0424291,0.0619887,7.13407e-11,7.13524e-11,1.00911e-09,1.17416e-06,1.17418e-06,5e-08,0,0,0,0,0,0,0,0 +21488000,0.982708,-0.00264665,-0.00769634,0.184985,-0.0410967,0.046708,-0.877632,-0.0146816,0.0156387,-0.245032,-1.16142e-05,-4.68979e-05,-2.49696e-06,2.31026e-05,5.99481e-05,-0.0010516,0.205039,0.000821557,0.434373,0,0,0,0,0,6.06564e-06,6.30756e-05,6.3064e-05,0.00017076,0.0231092,0.0231086,0.0117522,0.0471603,0.0471604,0.063046,7.13836e-11,7.13959e-11,9.92675e-10,1.17416e-06,1.17419e-06,5.00008e-08,0,0,0,0,0,0,0,0 +21592000,0.982715,-0.0030999,-0.00769042,0.184937,-0.0341068,0.0434461,-1.00536,-0.0161864,0.0182022,-0.334072,-1.15696e-05,-4.68743e-05,-2.29244e-06,2.38786e-05,5.86694e-05,-0.00106056,0.205039,0.000821557,0.434373,0,0,0,0,0,6.03632e-06,6.14019e-05,6.13924e-05,0.000169841,0.021053,0.0210524,0.0116216,0.0423303,0.0423304,0.0626891,6.62653e-11,6.62789e-11,9.71234e-10,1.16977e-06,1.16979e-06,5.00008e-08,0,0,0,0,0,0,0,0 +21688000,0.982711,-0.00340986,-0.00756662,0.184958,-0.0324687,0.0399442,-1.1329,-0.0193697,0.0222126,-0.442878,-1.1566e-05,-4.6878e-05,-2.09726e-06,2.388e-05,5.86958e-05,-0.00105827,0.205039,0.000821557,0.434373,0,0,0,0,0,5.99946e-06,6.17916e-05,6.17837e-05,0.000168586,0.0229145,0.0229138,0.0116862,0.0470378,0.0470378,0.0627611,6.63065e-11,6.63209e-11,9.50342e-10,1.16977e-06,1.16979e-06,5.00004e-08,0,0,0,0,0,0,0,0 +21792000,0.982727,-0.00373467,-0.00773501,0.184863,-0.0273933,0.0355555,-1.2664,-0.0181849,0.0246475,-0.562815,-1.15403e-05,-4.67953e-05,-1.83558e-06,2.69647e-05,5.82503e-05,-0.00106531,0.205039,0.000821557,0.434373,0,0,0,0,0,5.96923e-06,6.01139e-05,6.01073e-05,0.000167674,0.0208693,0.0208686,0.0115576,0.0422393,0.0422393,0.0624023,6.16427e-11,6.16576e-11,9.29987e-10,1.16492e-06,1.16492e-06,5.00004e-08,0,0,0,0,0,0,0,0 +21888000,0.982718,-0.00402525,-0.00785712,0.1849,-0.0240365,0.0317159,-1.38123,-0.0206558,0.0279065,-0.696616,-1.15426e-05,-4.67934e-05,-1.94554e-06,2.69833e-05,5.83078e-05,-0.00106299,0.205039,0.000821557,0.434373,0,0,0,0,0,5.92421e-06,6.04762e-05,6.04702e-05,0.000166444,0.0226493,0.0226485,0.011622,0.0469198,0.0469198,0.0624657,6.16842e-11,6.17e-11,9.10151e-10,1.16492e-06,1.16493e-06,5e-08,0,0,0,0,0,0,0,0 +21992000,0.982733,-0.00465798,-0.00809601,0.184796,-0.0242038,0.0279052,-1.36594,-0.0234773,0.0294747,-0.83607,-1.15859e-05,-4.6849e-05,-1.80354e-06,2.47511e-05,6.07463e-05,-0.00106853,0.205039,0.000821557,0.434373,0,0,0,0,0,5.89017e-06,5.88133e-05,5.88092e-05,0.000165543,0.0202879,0.020287,0.0114953,0.0421409,0.0421409,0.062106,5.74495e-11,5.74647e-11,8.90825e-10,1.15972e-06,1.15972e-06,5e-08,0,0,0,0,0,0,0,0 +22088000,0.982726,-0.005383,-0.008853,0.184778,-0.0219011,0.0244134,-1.34885,-0.0257399,0.0319332,-0.97164,-1.15826e-05,-4.68524e-05,-1.62756e-06,2.47493e-05,6.08054e-05,-0.00106641,0.205039,0.000821557,0.434373,0,0,0,0,0,5.8971e-06,5.91507e-05,5.91465e-05,0.000165574,0.021695,0.021694,0.0116684,0.0467471,0.0467471,0.0631483,5.74932e-11,5.7509e-11,8.7667e-10,1.15972e-06,1.15972e-06,5.00012e-08,0,0,0,0,0,0,0,0 +22192000,0.982751,-0.00578687,-0.00923923,0.184613,-0.00939113,0.0213705,-1.36397,-0.0114202,0.0328077,-1.11873,-1.15428e-05,-4.66709e-05,-1.40106e-06,2.90123e-05,6.16117e-05,-0.00106398,0.205039,0.000821557,0.434373,0,0,0,0,0,5.86164e-06,5.76521e-05,5.76487e-05,0.00016467,0.0195306,0.0195296,0.0115418,0.0420057,0.0420057,0.0627771,5.37273e-11,5.37417e-11,8.58198e-10,1.15528e-06,1.15527e-06,5.00012e-08,0,0,0,0,0,0,0,0 +22288000,0.982734,-0.00648611,-0.00948861,0.184668,-0.00436152,0.016408,-1.3617,-0.0120975,0.034641,-1.25548,-1.15448e-05,-4.66694e-05,-1.49296e-06,2.89965e-05,6.16987e-05,-0.00106186,0.205039,0.000821557,0.434373,0,0,0,0,0,5.81928e-06,5.79642e-05,5.7963e-05,0.000163454,0.020909,0.0209079,0.0116076,0.0465324,0.0465322,0.0628329,5.37696e-11,5.37849e-11,8.40194e-10,1.15529e-06,1.15527e-06,5.00008e-08,0,0,0,0,0,0,0,0 +22392000,0.982859,-0.00683876,-0.00971075,0.183974,0.00381948,0.00946434,-1.36456,-0.000965923,0.0319935,-1.40779,-1.14874e-05,-4.66112e-05,-1.61381e-06,2.9144e-05,6.12713e-05,-0.00105677,0.203935,0.000817121,0.434565,0,0,0,0,0,8.01266e-05,5.67667e-05,5.66577e-05,0.00230551,0.0185465,0.0185455,0.011483,0.0418372,0.0418371,0.0624627,5.04027e-11,5.04149e-11,8.27002e-10,1.1514e-06,1.15137e-06,5.00008e-08,0,0,0,0,0,0,0,0 +22488000,0.98265,-0.00701445,-0.0101315,0.185058,0.00811765,0.00340758,-1.36931,-0.000390521,0.0325965,-1.54308,-1.14875e-05,-4.66113e-05,-1.6139e-06,2.91275e-05,6.13447e-05,-0.00105528,0.203935,0.000817121,0.434565,0,0,0,0,0,5.62778e-05,5.67612e-05,5.66693e-05,0.00161888,0.0185478,0.0185465,0.0115479,0.046179,0.0461788,0.0625122,5.04519e-11,5.0464e-11,8.27049e-10,1.1514e-06,1.15138e-06,5.00004e-08,0,0,0,0,0,0,0,0 +22592000,0.982779,-0.00683947,-0.0107225,0.184347,0.0180738,-0.00283718,-1.36857,0.0131431,0.030913,-1.69165,-1.14621e-05,-4.64842e-05,-1.60897e-06,3.33456e-05,5.88735e-05,-0.00105239,0.203935,0.000817121,0.434565,0,0,0,0,0,4.3425e-05,5.67137e-05,5.66254e-05,0.00124739,0.0164832,0.0164819,0.0114252,0.0414714,0.0414712,0.0621435,4.7653e-11,4.76625e-11,8.27092e-10,1.1501e-06,1.15007e-06,5.00004e-08,0,0,0,0,0,0,0,0 +22688000,0.982652,-0.0067636,-0.0109346,0.185013,0.0203022,-0.00644274,-1.37214,0.0150082,0.0304298,-1.82885,-1.14624e-05,-4.64843e-05,-1.61393e-06,3.33146e-05,5.89868e-05,-0.00105035,0.203935,0.000817121,0.434565,0,0,0,0,0,3.53722e-05,5.6738e-05,5.66622e-05,0.00101462,0.0180461,0.0180446,0.0114909,0.0454477,0.0454475,0.0621874,4.77021e-11,4.77117e-11,8.27122e-10,1.15011e-06,1.15007e-06,5e-08,0,0,0,0,0,0,0,0 +22792000,0.982591,-0.00663913,-0.011282,0.18532,0.0253363,-0.0107222,-1.37632,0.0236465,0.0279716,-1.98281,-1.14718e-05,-4.64663e-05,-1.61787e-06,4.10055e-05,5.11824e-05,-0.00104552,0.203935,0.000817121,0.434565,0,0,0,0,0,2.97535e-05,5.62938e-05,5.62219e-05,0.000855222,0.0178437,0.0178423,0.0113712,0.0408834,0.0408832,0.0618208,4.54794e-11,4.54868e-11,8.2714e-10,1.1473e-06,1.14725e-06,5e-08,0,0,0,0,0,0,0,0 +22888000,0.982752,-0.00681614,-0.0115968,0.184439,0.0284516,-0.0149668,-1.37771,0.0262245,0.0267964,-2.1205,-1.14718e-05,-4.64666e-05,-1.60531e-06,4.09676e-05,5.13056e-05,-0.00104353,0.203935,0.000817121,0.434565,0,0,0,0,0,2.65386e-05,5.6333e-05,5.62658e-05,0.000765227,0.0208312,0.0208296,0.0115448,0.0446443,0.0446439,0.062837,4.55286e-11,4.55359e-11,8.27154e-10,1.1473e-06,1.14726e-06,5.00008e-08,0,0,0,0,0,0,0,0 +22992000,0.982901,-0.00668052,-0.0118524,0.183633,0.030627,-0.0172138,-1.38246,0.0333293,0.023973,-2.27846,-1.14821e-05,-4.64658e-05,-1.58838e-06,5.39624e-05,3.84187e-05,-0.00103761,0.203935,0.000817121,0.434565,0,0,0,0,0,2.31962e-05,5.52051e-05,5.51399e-05,0.00067111,0.0217307,0.0217294,0.0114257,0.0402849,0.0402846,0.0624617,4.37803e-11,4.37859e-11,8.27143e-10,1.13732e-06,1.13727e-06,5.00008e-08,0,0,0,0,0,0,0,0 +23088000,0.982945,-0.00665085,-0.0121686,0.183376,0.0346837,-0.0204891,-1.38057,0.036483,0.0221364,-2.4149,-1.14823e-05,-4.6466e-05,-1.5903e-06,5.39351e-05,3.85107e-05,-0.00103621,0.203935,0.000817121,0.434565,0,0,0,0,0,2.05858e-05,5.52383e-05,5.5176e-05,0.000597696,0.0259457,0.0259446,0.0114948,0.0440351,0.0440346,0.0625033,4.38294e-11,4.38351e-11,8.27109e-10,1.13733e-06,1.13728e-06,5.00004e-08,0,0,0,0,0,0,0,0 +23192000,0.982934,-0.00657299,-0.0122578,0.183433,0.0358944,-0.0190724,-1.38345,0.0435698,0.0184478,-2.5671,-1.1465e-05,-4.64537e-05,-1.60087e-06,6.87343e-05,2.70082e-05,-0.00103222,0.203935,0.000817121,0.434565,0,0,0,0,0,1.85056e-05,5.32989e-05,5.32402e-05,0.000538856,0.0270831,0.027083,0.0113783,0.0398887,0.0398883,0.0621315,4.24948e-11,4.24991e-11,8.27054e-10,1.11661e-06,1.11656e-06,5.00004e-08,0,0,0,0,0,0,0,0 +23288000,0.982971,-0.00703875,-0.0123651,0.183211,0.0393004,-0.0228303,-1.37968,0.0471426,0.0164014,-2.7058,-1.14652e-05,-4.6454e-05,-1.59604e-06,6.86856e-05,2.71599e-05,-0.00103,0.203935,0.000817121,0.434565,0,0,0,0,0,1.68249e-05,5.3324e-05,5.32739e-05,0.00049061,0.0322471,0.032247,0.0114483,0.0438414,0.043841,0.0621697,4.25439e-11,4.25482e-11,8.26971e-10,1.11662e-06,1.11656e-06,5e-08,0,0,0,0,0,0,0,0 +23392000,0.982934,-0.00687651,-0.0123849,0.183414,0.0389296,-0.0207277,-1.38175,0.0540341,0.0162693,-2.85282,-1.14769e-05,-4.64162e-05,-1.62162e-06,7.68293e-05,5.38789e-06,-0.00102866,0.203935,0.000817121,0.434565,0,0,0,0,0,1.54128e-05,5.06497e-05,5.06032e-05,0.000450413,0.0327351,0.032735,0.0113344,0.0398408,0.0398404,0.0618019,4.1568e-11,4.15713e-11,8.26861e-10,1.0845e-06,1.08443e-06,5e-08,0,0,0,0,0,0,0,0 +23488000,0.982965,-0.00697489,-0.0126899,0.183224,0.0413978,-0.0215891,-1.38299,0.0578827,0.0142061,-2.98958,-1.14768e-05,-4.64165e-05,-1.60934e-06,7.67911e-05,5.48729e-06,-0.00102716,0.203935,0.000817121,0.434565,0,0,0,0,0,1.45225e-05,5.06733e-05,5.06271e-05,0.000424462,0.0385326,0.0385329,0.0115115,0.0441669,0.0441665,0.0628137,4.16171e-11,4.16205e-11,8.2677e-10,1.0845e-06,1.08444e-06,5.00008e-08,0,0,0,0,0,0,0,0 +23592000,0.982988,-0.00722079,-0.0125148,0.183102,0.0376512,-0.0229823,-1.3822,0.0617465,0.00994484,-3.14083,-1.14528e-05,-4.64072e-05,-1.60007e-06,9.62547e-05,-1.78599e-06,-0.00102468,0.203935,0.000817121,0.434565,0,0,0,0,0,1.34811e-05,4.75116e-05,4.74713e-05,0.000394185,0.037653,0.0376535,0.0113978,0.0401757,0.0401754,0.0624387,4.09344e-11,4.09371e-11,8.26605e-10,1.04326e-06,1.04319e-06,5.00008e-08,0,0,0,0,0,0,0,0 +23688000,0.983004,-0.00784013,-0.0130276,0.182955,0.0344996,-0.0239315,-1.28624,0.0652256,0.00765132,-3.27485,-1.14527e-05,-4.64076e-05,-1.57942e-06,9.62111e-05,-1.68333e-06,-0.00102304,0.203935,0.000817121,0.434565,0,0,0,0,0,1.25954e-05,4.75311e-05,4.74931e-05,0.000367976,0.0433449,0.0433451,0.0114706,0.0449615,0.0449612,0.0624784,4.09835e-11,4.09862e-11,8.26402e-10,1.04326e-06,1.04319e-06,5.00004e-08,0,0,0,0,0,0,0,0 +23792000,0.982971,-0.00966893,-0.0158704,0.182821,0.0265319,-0.0176677,-0.95091,0.0704605,0.00778565,-3.40175,-1.14414e-05,-4.63787e-05,-1.5598e-06,9.81309e-05,-1.56962e-05,-0.00101842,0.203935,0.000817121,0.434565,0,0,0,0,0,1.18254e-05,4.43069e-05,4.42547e-05,0.000345123,0.039808,0.039808,0.0113583,0.0407984,0.0407981,0.0621081,4.05198e-11,4.05221e-11,8.26164e-10,9.96764e-07,9.96688e-07,5.00004e-08,0,0,0,0,0,0,0,0 +23888000,0.982878,-0.0129089,-0.019828,0.182734,0.0206078,-0.0168483,-0.537407,0.0727326,0.00616975,-3.47617,-1.14416e-05,-4.63787e-05,-1.56335e-06,9.81171e-05,-1.56229e-05,-0.00101734,0.203935,0.000817121,0.434565,0,0,0,0,0,1.11351e-05,4.4359e-05,4.42898e-05,0.000324975,0.0442866,0.044287,0.0114308,0.0459523,0.0459519,0.062146,4.05688e-11,4.05711e-11,8.25883e-10,9.96769e-07,9.96691e-07,5e-08,0,0,0,0,0,0,0,0 +23992000,0.98281,-0.0151529,-0.0223525,0.182634,0.0218851,-0.0157321,-0.142936,0.0781821,0.0054202,-3.54692,-1.14296e-05,-4.63607e-05,-1.562e-06,9.42344e-05,-1.90842e-05,-0.000991006,0.203935,0.000817121,0.434565,0,0,0,0,0,1.0514e-05,4.16296e-05,4.1553e-05,0.000307189,0.0398071,0.0398081,0.0113201,0.0415251,0.0415249,0.0617806,4.02534e-11,4.02555e-11,8.25562e-10,9.4735e-07,9.47268e-07,5e-08,0,0,0,0,0,0,0,0 +24088000,0.982839,-0.0147164,-0.0213318,0.182637,0.026204,-0.0227555,0.0841165,0.0804651,0.00359399,-3.55036,-1.143e-05,-4.63605e-05,-1.57868e-06,9.42462e-05,-1.90442e-05,-0.000990145,0.203935,0.000817121,0.434565,0,0,0,0,0,1.00939e-05,4.16321e-05,4.15667e-05,0.0002953,0.0446104,0.0446121,0.0114998,0.0469582,0.046958,0.0627923,4.03025e-11,4.03046e-11,8.25302e-10,9.47354e-07,9.47271e-07,5.00008e-08,0,0,0,0,0,0,0,0 +24192000,0.982932,-0.0118128,-0.0175308,0.182751,0.0372537,-0.0298255,0.0714822,0.0863325,-0.000415903,-3.56746,-1.1425e-05,-4.63508e-05,-1.56845e-06,9.375e-05,-1.46545e-05,-0.000969205,0.203935,0.000817121,0.434565,0,0,0,0,0,9.59777e-06,3.92994e-05,3.92548e-05,0.000280787,0.0405728,0.0405747,0.0113901,0.0422688,0.0422687,0.0624205,4.00804e-11,4.00823e-11,8.249e-10,8.98184e-07,8.98098e-07,5.00008e-08,0,0,0,0,0,0,0,0 +24288000,0.983016,-0.00948694,-0.0142468,0.182719,0.0388008,-0.0315351,0.0492254,0.0900623,-0.00340762,-3.56503,-1.14251e-05,-4.6351e-05,-1.56376e-06,9.37466e-05,-1.46028e-05,-0.000968196,0.203935,0.000817121,0.434565,0,0,0,0,0,9.14291e-06,3.9294e-05,3.92666e-05,0.00026767,0.0457615,0.0457637,0.0114667,0.0480125,0.0480125,0.062462,4.01293e-11,4.01313e-11,8.24446e-10,8.98189e-07,8.98102e-07,5.00004e-08,0,0,0,0,0,0,0,0 +24392000,0.983083,-0.00857113,-0.0131952,0.182485,0.0339671,-0.0254784,0.0660746,0.0959891,-0.00333549,-3.55968,-1.14196e-05,-4.63542e-05,-1.52103e-06,8.61855e-05,-2.05308e-05,-0.000967913,0.203935,0.000817121,0.434565,0,0,0,0,0,8.73432e-06,3.72297e-05,3.7207e-05,0.000255838,0.0407333,0.0407349,0.0113586,0.0430022,0.0430022,0.0620955,3.99598e-11,3.99617e-11,8.23943e-10,8.53667e-07,8.53577e-07,5.00004e-08,0,0,0,0,0,0,0,0 +24488000,0.983112,-0.00879744,-0.0132636,0.182314,0.0274989,-0.021092,0.0638427,0.098937,-0.00556516,-3.55281,-1.14185e-05,-4.63551e-05,-1.46309e-06,8.61515e-05,-2.05615e-05,-0.000968119,0.203935,0.000817121,0.434565,0,0,0,0,0,8.37451e-06,3.72563e-05,3.72358e-05,0.000245018,0.0454616,0.0454635,0.0114353,0.0489723,0.0489724,0.0621362,4.00087e-11,4.00107e-11,8.23383e-10,8.53672e-07,8.53581e-07,5e-08,0,0,0,0,0,0,0,0 +24592000,0.983066,-0.0095135,-0.0134533,0.182512,0.0280681,-0.0168711,0.0590994,0.105111,-0.00404687,-3.54802,-1.14187e-05,-4.63756e-05,-1.47022e-06,7.35494e-05,-2.40967e-05,-0.00096671,0.203935,0.000817121,0.434565,0,0,0,0,0,8.05585e-06,3.55045e-05,3.54871e-05,0.000235206,0.039949,0.0399504,0.0113287,0.0436602,0.0436602,0.0617751,3.98671e-11,3.98691e-11,8.22769e-10,8.1491e-07,8.14819e-07,5e-08,0,0,0,0,0,0,0,0 +24688000,0.983046,-0.00998304,-0.013236,0.182609,0.0239289,-0.015043,0.0591131,0.107645,-0.00551043,-3.54026,-1.14188e-05,-4.63755e-05,-1.47513e-06,7.35474e-05,-2.41266e-05,-0.000967436,0.203935,0.000817121,0.434565,0,0,0,0,0,7.83656e-06,3.55376e-05,3.5524e-05,0.000228562,0.0442244,0.0442261,0.0115117,0.0497636,0.0497638,0.0627907,3.99161e-11,3.99181e-11,8.22281e-10,8.14914e-07,8.14823e-07,5.00012e-08,0,0,0,0,0,0,0,0 +24792000,0.98306,-0.0101091,-0.0126065,0.182573,0.021889,-0.0158057,0.0508194,0.110056,-0.0055699,-3.53815,-1.14245e-05,-4.63906e-05,-1.4768e-06,6.96656e-05,-2.49568e-05,-0.000966698,0.203935,0.000817121,0.434565,0,0,0,0,0,7.54578e-06,3.40825e-05,3.40729e-05,0.000220194,0.0385096,0.0385107,0.0114044,0.0441986,0.0441987,0.0624236,3.97898e-11,3.97918e-11,8.21563e-10,7.82184e-07,7.82095e-07,5.00012e-08,0,0,0,0,0,0,0,0 +24888000,0.983057,-0.00991582,-0.0121385,0.182628,0.0178775,-0.0171125,0.0412372,0.112008,-0.007147,-3.53483,-1.14242e-05,-4.63909e-05,-1.45833e-06,6.96496e-05,-2.49349e-05,-0.000966304,0.203935,0.000817121,0.434565,0,0,0,0,0,7.28945e-06,3.4123e-05,3.41148e-05,0.000212426,0.0423536,0.0423548,0.0114834,0.0503508,0.050351,0.0624697,3.98387e-11,3.98407e-11,8.20779e-10,7.82188e-07,7.82099e-07,5.00008e-08,0,0,0,0,0,0,0,0 +24992000,0.983037,-0.00971723,-0.0119383,0.182761,0.0135134,-0.0144863,0.0330938,0.114913,-0.00545356,-3.53318,-1.14259e-05,-4.64198e-05,-1.45803e-06,6.14252e-05,-2.78393e-05,-0.000965731,0.203935,0.000817121,0.434565,0,0,0,0,0,7.05688e-06,3.2942e-05,3.29336e-05,0.000205334,0.036678,0.036679,0.0113772,0.0445995,0.0445996,0.0621079,3.97225e-11,3.97245e-11,8.19934e-10,7.55122e-07,7.55036e-07,5.00008e-08,0,0,0,0,0,0,0,0 +25088000,0.983025,-0.0100684,-0.0119737,0.182805,0.00908398,-0.0125024,0.030252,0.11595,-0.00680189,-3.5341,-1.14263e-05,-4.64197e-05,-1.47416e-06,6.14763e-05,-2.78164e-05,-0.00096431,0.203935,0.000817121,0.434565,0,0,0,0,0,6.83075e-06,3.29933e-05,3.2986e-05,0.000198722,0.0400819,0.0400831,0.0114562,0.0507301,0.0507303,0.0621537,3.97713e-11,3.97734e-11,8.19018e-10,7.55126e-07,7.5504e-07,5.00004e-08,0,0,0,0,0,0,0,0 +25192000,0.982969,-0.0103668,-0.0118528,0.183095,0.00849927,-0.0124206,0.0292863,0.119939,-0.00795327,-3.53306,-1.14483e-05,-4.64553e-05,-1.51327e-06,5.25765e-05,-2.33473e-05,-0.000962657,0.203935,0.000817121,0.434565,0,0,0,0,0,6.63706e-06,3.20497e-05,3.20438e-05,0.000192661,0.0346111,0.0346122,0.0113508,0.0448612,0.0448613,0.0617971,3.96642e-11,3.96663e-11,8.18037e-10,7.32986e-07,7.32903e-07,5.00004e-08,0,0,0,0,0,0,0,0 +25288000,0.982916,-0.0104702,-0.0112136,0.183417,0.00244827,-0.0130185,0.0237858,0.120459,-0.00915934,-3.53105,-1.14496e-05,-4.64541e-05,-1.58549e-06,5.26483e-05,-2.33756e-05,-0.000962501,0.203935,0.000817121,0.434565,0,0,0,0,0,6.45217e-06,3.21071e-05,3.21044e-05,0.000186973,0.0376321,0.0376336,0.0114297,0.0509146,0.0509149,0.0618424,3.9713e-11,3.97151e-11,8.16981e-10,7.3299e-07,7.32908e-07,5e-08,0,0,0,0,0,0,0,0 +25392000,0.982914,-0.0106523,-0.0110549,0.183423,-0.00157657,-0.010542,0.0220747,0.121034,-0.00722418,-3.53149,-1.14538e-05,-4.64857e-05,-1.58255e-06,4.65422e-05,-2.52527e-05,-0.00096068,0.203935,0.000817121,0.434565,0,0,0,0,0,6.27412e-06,3.1362e-05,3.13604e-05,0.000181772,0.0324821,0.0324834,0.0113252,0.0449921,0.0449923,0.0614908,3.96159e-11,3.9618e-11,8.15856e-10,7.14997e-07,7.14917e-07,5e-08,0,0,0,0,0,0,0,0 +25488000,0.982918,-0.0106763,-0.0107498,0.183422,-0.00777933,-0.00920675,0.0218886,0.120559,-0.00818293,-3.53046,-1.14537e-05,-4.64858e-05,-1.58007e-06,4.65532e-05,-2.52495e-05,-0.000960298,0.203935,0.000817121,0.434565,0,0,0,0,0,6.15546e-06,3.14298e-05,3.14294e-05,0.000178307,0.0351484,0.0351501,0.011509,0.0509289,0.0509291,0.0625024,3.96647e-11,3.96669e-11,8.14972e-10,7.15001e-07,7.14922e-07,5.00008e-08,0,0,0,0,0,0,0,0 +25592000,0.982886,-0.0109278,-0.010583,0.183588,-0.00894514,-0.0133994,0.022742,0.121347,-0.0117214,-3.52949,-1.1488e-05,-4.65105e-05,-1.63615e-06,4.2482e-05,-1.83763e-05,-0.000959554,0.203935,0.000817121,0.434565,0,0,0,0,0,6.00149e-06,3.0848e-05,3.08487e-05,0.00017373,0.0303678,0.0303692,0.0114031,0.0450065,0.0450067,0.0621446,3.9579e-11,3.95811e-11,8.13714e-10,7.00412e-07,7.00336e-07,5.00008e-08,0,0,0,0,0,0,0,0 +25688000,0.982894,-0.0103957,-0.0102901,0.183592,-0.0102628,-0.011665,0.0116246,0.120452,-0.0129455,-3.52991,-1.14879e-05,-4.65107e-05,-1.62782e-06,4.25074e-05,-1.83767e-05,-0.000958778,0.203935,0.000817121,0.434565,0,0,0,0,0,5.85313e-06,3.09247e-05,3.09241e-05,0.000169384,0.0327426,0.032744,0.0114832,0.0507991,0.0507993,0.0621956,3.96277e-11,3.96299e-11,8.12377e-10,7.00416e-07,7.0034e-07,5.00004e-08,0,0,0,0,0,0,0,0 +25792000,0.982906,-0.0102091,-0.00960385,0.183572,-0.0159401,-0.00853127,0.0109766,0.121064,-0.0128415,-3.53234,-1.15065e-05,-4.65408e-05,-1.64112e-06,3.70937e-05,-1.62412e-05,-0.000957058,0.203935,0.000817121,0.434565,0,0,0,0,0,5.71312e-06,3.04719e-05,3.04729e-05,0.000165416,0.0283461,0.0283476,0.0113779,0.04492,0.0449202,0.0618426,3.95549e-11,3.9557e-11,8.10962e-10,6.88626e-07,6.88553e-07,5.00004e-08,0,0,0,0,0,0,0,0 +25888000,0.98287,-0.0102608,-0.00966412,0.183761,-0.021935,-0.00577227,0.0130323,0.119193,-0.0135066,-3.53152,-1.15082e-05,-4.65391e-05,-1.73981e-06,3.71615e-05,-1.62726e-05,-0.000956933,0.203935,0.000817121,0.434565,0,0,0,0,0,5.58368e-06,3.05578e-05,3.05585e-05,0.000161613,0.0304413,0.030443,0.0114576,0.0505505,0.0505507,0.061893,3.96035e-11,3.96057e-11,8.09464e-10,6.8863e-07,6.88557e-07,5e-08,0,0,0,0,0,0,0,0 +25992000,0.982874,-0.0103632,-0.00984424,0.183722,-0.0272653,-0.00508837,0.006001,0.115341,-0.0147638,-3.53061,-1.15273e-05,-4.6546e-05,-1.73815e-06,3.73348e-05,-1.38783e-05,-0.000956319,0.203935,0.000817121,0.434565,0,0,0,0,0,5.46278e-06,3.02141e-05,3.0214e-05,0.000158146,0.0264326,0.026434,0.0113528,0.044748,0.0447481,0.0615445,3.95446e-11,3.95467e-11,8.07885e-10,6.79077e-07,6.79006e-07,5e-08,0,0,0,0,0,0,0,0 +26088000,0.982899,-0.0101084,-0.00980212,0.183606,-0.0325771,-0.00399343,0.00511256,0.112451,-0.0152091,-3.53104,-1.15265e-05,-4.65467e-05,-1.693e-06,3.73268e-05,-1.38714e-05,-0.000955954,0.203935,0.000817121,0.434565,0,0,0,0,0,5.38414e-06,3.0308e-05,3.0307e-05,0.00015592,0.028302,0.0283036,0.0115374,0.0502061,0.0502063,0.0625627,3.95933e-11,3.95955e-11,8.06657e-10,6.79081e-07,6.79011e-07,5.00008e-08,0,0,0,0,0,0,0,0 +26192000,0.982892,-0.0101094,-0.0103643,0.183613,-0.0326485,-0.00429146,0.000206426,0.113487,-0.018389,-3.53474,-1.15629e-05,-4.65719e-05,-1.65342e-06,3.27423e-05,-7.19124e-06,-0.00095416,0.203935,0.000817121,0.434565,0,0,0,0,0,5.28303e-06,3.00496e-05,3.00461e-05,0.000152835,0.0246493,0.0246507,0.011431,0.0445045,0.0445047,0.0622076,3.9549e-11,3.95511e-11,8.04931e-10,6.71356e-07,6.71286e-07,5.00008e-08,0,0,0,0,0,0,0,0 +26288000,0.982884,-0.0101283,-0.0106454,0.183638,-0.0354596,-0.00266202,-0.00509345,0.110218,-0.0187543,-3.53553,-1.15638e-05,-4.65711e-05,-1.70635e-06,3.2776e-05,-7.21465e-06,-0.000953982,0.203935,0.000817121,0.434565,0,0,0,0,0,5.17808e-06,3.01521e-05,3.01474e-05,0.000149854,0.0263258,0.0263272,0.0115114,0.0497849,0.0497851,0.0622632,3.95976e-11,3.95997e-11,8.03118e-10,6.71359e-07,6.7129e-07,5.00004e-08,0,0,0,0,0,0,0,0 +26392000,0.982903,-0.0095893,-0.0105833,0.183572,-0.0453825,-0.00161626,-0.00102682,0.0909746,-0.0211568,-3.5364,-1.1588e-05,-4.65643e-05,-1.75917e-06,4.0782e-05,-6.20559e-06,-0.000954027,0.203935,0.000817121,0.434565,0,0,0,0,0,5.07787e-06,2.99597e-05,2.99531e-05,0.000147163,0.0230015,0.0230024,0.0114053,0.0442025,0.0442026,0.0619123,3.95682e-11,3.95701e-11,8.01218e-10,6.65113e-07,6.65043e-07,5.00004e-08,0,0,0,0,0,0,0,0 +26488000,0.982909,-0.00936405,-0.0104763,0.183555,-0.0493867,0.00131979,0.00871697,0.0864047,-0.0211952,-3.53412,-1.15883e-05,-4.65639e-05,-1.77731e-06,4.07535e-05,-6.18866e-06,-0.000954744,0.203935,0.000817121,0.434565,0,0,0,0,0,4.98559e-06,3.00687e-05,3.00617e-05,0.00014453,0.0244972,0.0244982,0.011485,0.0493031,0.0493033,0.061967,3.96167e-11,3.96187e-11,7.99229e-10,6.65116e-07,6.65047e-07,5e-08,0,0,0,0,0,0,0,0 +26592000,0.98289,-0.00882917,-0.0107291,0.183668,-0.0509031,0.00437835,0.00889063,0.0746804,-0.0230587,-3.53486,-1.16178e-05,-4.65759e-05,-1.83812e-06,4.23359e-05,-3.2303e-06,-0.000953144,0.203935,0.000817121,0.434565,0,0,0,0,0,4.90644e-06,2.99333e-05,2.99237e-05,0.000142156,0.0214862,0.0214866,0.011379,0.0438526,0.0438527,0.0616201,3.96016e-11,3.96035e-11,7.97152e-10,6.60028e-07,6.59957e-07,5e-08,0,0,0,0,0,0,0,0 +26688000,0.982878,-0.00871111,-0.0104089,0.183757,-0.052982,0.00842154,0.00771786,0.0696661,-0.0224411,-3.53297,-1.16194e-05,-4.65743e-05,-1.93235e-06,4.23486e-05,-3.25012e-06,-0.000953549,0.203935,0.000817121,0.434565,0,0,0,0,0,4.8562e-06,3.0049e-05,3.00402e-05,0.000140731,0.022846,0.022846,0.011564,0.0487756,0.0487757,0.0626446,3.96503e-11,3.96521e-11,7.95548e-10,6.60032e-07,6.59961e-07,5.00008e-08,0,0,0,0,0,0,0,0 +26792000,0.982893,-0.00852449,-0.00987299,0.183716,-0.0578402,0.00747461,0.00650246,0.0593485,-0.025131,-3.53582,-1.16491e-05,-4.658e-05,-1.95087e-06,4.39036e-05,7.63159e-07,-0.00095177,0.203935,0.000817121,0.434565,0,0,0,0,0,4.78071e-06,2.99551e-05,2.99477e-05,0.000138622,0.0201157,0.0201156,0.0114563,0.0434651,0.0434652,0.0622906,3.96492e-11,3.96508e-11,7.93312e-10,6.55907e-07,6.55832e-07,5.00008e-08,0,0,0,0,0,0,0,0 +26888000,0.982906,-0.00790204,-0.00997056,0.183666,-0.0636899,0.010742,0.00122085,0.0534961,-0.0242439,-3.53661,-1.16483e-05,-4.65808e-05,-1.90373e-06,4.39121e-05,7.59856e-07,-0.000951332,0.203935,0.000817121,0.434565,0,0,0,0,0,4.70975e-06,3.00794e-05,3.00701e-05,0.000136527,0.0213548,0.0213548,0.0115364,0.0482152,0.0482153,0.0623497,3.96976e-11,3.96993e-11,7.90985e-10,6.5591e-07,6.55836e-07,5.00004e-08,0,0,0,0,0,0,0,0 +26992000,0.982896,-0.00733839,-0.0104555,0.18372,-0.067972,0.0146071,0.00038711,0.0446034,-0.0242324,-3.54008,-1.16668e-05,-4.65887e-05,-1.92796e-06,4.37555e-05,3.05448e-06,-0.000949505,0.203935,0.000817121,0.434565,0,0,0,0,0,4.64816e-06,3.00241e-05,3.00119e-05,0.000134665,0.0188772,0.0188769,0.011429,0.0430491,0.0430492,0.0619994,3.97093e-11,3.97108e-11,7.88566e-10,6.52571e-07,6.52492e-07,5.00004e-08,0,0,0,0,0,0,0,0 +27088000,0.982895,-0.00718015,-0.0107745,0.183709,-0.0700332,0.0211047,0.00381269,0.0379406,-0.0225237,-3.54479,-1.16669e-05,-4.65886e-05,-1.93791e-06,4.38579e-05,2.94686e-06,-0.000947655,0.203935,0.000817121,0.434565,0,0,0,0,0,4.58409e-06,3.01556e-05,3.01422e-05,0.000132804,0.0200059,0.0200051,0.0115082,0.0476321,0.0476321,0.062057,3.97576e-11,3.97593e-11,7.86055e-10,6.52574e-07,6.52495e-07,5e-08,0,0,0,0,0,0,0,0 +27192000,0.9829,-0.00721086,-0.0106942,0.183686,-0.0745444,0.0235406,0.00564908,0.0304054,-0.021585,-3.54807,-1.16813e-05,-4.65946e-05,-1.96479e-06,4.31458e-05,5.23529e-06,-0.000946147,0.203935,0.000817121,0.434565,0,0,0,0,0,4.52622e-06,3.01275e-05,3.01149e-05,0.00013117,0.0177552,0.0177544,0.0114009,0.042612,0.042612,0.0617102,3.97806e-11,3.97823e-11,7.83449e-10,6.49866e-07,6.49782e-07,5e-08,0,0,0,0,0,0,0,0 +27288000,0.982902,-0.00733954,-0.011637,0.183617,-0.0810174,0.02911,0.110651,0.0229746,-0.0190569,-3.5436,-1.16812e-05,-4.65947e-05,-1.9629e-06,4.31373e-05,5.24556e-06,-0.000946321,0.203935,0.000817121,0.434565,0,0,0,0,0,4.49448e-06,3.02676e-05,3.0252e-05,0.000130292,0.0187353,0.0187343,0.0115856,0.0470327,0.0470327,0.0627402,3.98291e-11,3.98309e-11,7.81449e-10,6.4987e-07,6.49785e-07,5.00012e-08,0,0,0,0,0,0,0,0 +27392000,0.982853,-0.00877033,-0.0142464,0.183633,-0.0814016,0.0334907,0.442186,0.020608,-0.01562,-3.52378,-1.16898e-05,-4.66109e-05,-1.94948e-06,3.90015e-05,7.01253e-06,-0.000941051,0.203935,0.000817121,0.434565,0,0,0,0,0,4.44929e-06,3.02791e-05,3.02565e-05,0.000128825,0.0165322,0.0165313,0.0114759,0.042151,0.042151,0.0623859,3.98609e-11,3.98628e-11,7.78681e-10,6.47566e-07,6.47476e-07,5.00012e-08,0,0,0,0,0,0,0,0 +27488000,0.982799,-0.0100874,-0.0160592,0.183701,-0.0844975,0.0386758,0.744957,0.0126228,-0.0121297,-3.46793,-1.16915e-05,-4.66094e-05,-2.04203e-06,3.89938e-05,6.9765e-06,-0.000940258,0.203935,0.000817121,0.434565,0,0,0,0,0,4.40028e-06,3.04285e-05,3.04015e-05,0.000127328,0.0173488,0.0173476,0.0115549,0.0463884,0.0463884,0.0624469,3.99091e-11,3.99112e-11,7.75821e-10,6.47568e-07,6.47478e-07,5.00008e-08,0,0,0,0,0,0,0,0 +27592000,0.98282,-0.0100085,-0.0149145,0.183693,-0.0761599,0.039992,0.845113,0.00997024,-0.0114201,-3.40551,-1.17022e-05,-4.66191e-05,-2.04052e-06,3.61081e-05,1.03561e-05,-0.000923194,0.203935,0.000817121,0.434565,0,0,0,0,0,4.35529e-06,3.04823e-05,3.04614e-05,0.000126055,0.0154989,0.0154972,0.0114459,0.0416584,0.0416583,0.0620959,3.99452e-11,3.99475e-11,7.72866e-10,6.45027e-07,6.44932e-07,5.00008e-08,0,0,0,0,0,0,0,0 +27688000,0.98288,-0.0088765,-0.0121083,0.183632,-0.0724215,0.0363961,0.750546,0.00287075,-0.00770167,-3.33176,-1.17017e-05,-4.66196e-05,-2.01531e-06,3.61721e-05,1.02731e-05,-0.000921907,0.203935,0.000817121,0.434565,0,0,0,0,0,4.30617e-06,3.06241e-05,3.0612e-05,0.000124744,0.0164204,0.0164186,0.0115244,0.0457418,0.0457416,0.062155,3.99935e-11,3.99957e-11,7.69823e-10,6.4503e-07,6.44933e-07,5.00004e-08,0,0,0,0,0,0,0,0 +27792000,0.982906,-0.00745463,-0.0105115,0.183659,-0.0693462,0.0331618,0.741959,0.00145601,-0.0078921,-3.2545,-1.17079e-05,-4.66252e-05,-1.98007e-06,3.29034e-05,1.51607e-05,-0.000923847,0.203935,0.000817121,0.434565,0,0,0,0,0,4.27009e-06,3.06944e-05,3.06851e-05,0.000123628,0.0147763,0.0147747,0.0114156,0.0411674,0.0411672,0.0618072,4.00364e-11,4.00385e-11,7.66685e-10,6.42911e-07,6.42807e-07,5.00004e-08,0,0,0,0,0,0,0,0 +27888000,0.982898,-0.00710867,-0.0106026,0.183709,-0.075232,0.0388739,0.780125,-0.00547313,-0.00448506,-3.18384,-1.17078e-05,-4.66252e-05,-1.97893e-06,3.29641e-05,1.50723e-05,-0.000922743,0.203935,0.000817121,0.434565,0,0,0,0,0,4.23286e-06,3.08514e-05,3.08413e-05,0.000122447,0.0155998,0.0155979,0.0114933,0.0451198,0.0451195,0.0618643,4.00844e-11,4.00867e-11,7.63458e-10,6.42914e-07,6.42808e-07,5e-08,0,0,0,0,0,0,0,0 +27992000,0.982891,-0.00755771,-0.0109899,0.183707,-0.072692,0.0404882,0.767406,-0.00507517,-0.00467513,-3.10847,-1.17084e-05,-4.6628e-05,-1.95699e-06,2.93818e-05,1.94709e-05,-0.000918759,0.203935,0.000817121,0.434565,0,0,0,0,0,4.2014e-06,3.09388e-05,3.09287e-05,0.000121465,0.0140999,0.014098,0.0113849,0.0406874,0.0406871,0.0615195,4.0131e-11,4.01334e-11,7.60136e-10,6.41135e-07,6.41022e-07,5e-08,0,0,0,0,0,0,0,0 +28088000,0.982901,-0.0078427,-0.0109946,0.183639,-0.0764491,0.0408894,0.773763,-0.0122164,-0.000752794,-3.0344,-1.1707e-05,-4.66294e-05,-1.87643e-06,2.93631e-05,1.95089e-05,-0.000918833,0.203935,0.000817121,0.434565,0,0,0,0,0,4.18964e-06,3.11017e-05,3.1092e-05,0.000121086,0.0148982,0.0148963,0.0115675,0.0445159,0.0445155,0.0625424,4.01794e-11,4.01818e-11,7.57598e-10,6.41139e-07,6.41024e-07,5.00008e-08,0,0,0,0,0,0,0,0 +28192000,0.982902,-0.00727605,-0.0113048,0.183637,-0.0741962,0.0378332,0.779897,-0.012695,-0.00158551,-2.95707,-1.17017e-05,-4.66287e-05,-1.85914e-06,2.683e-05,2.3443e-05,-0.000916534,0.203935,0.000817121,0.434565,0,0,0,0,0,4.16162e-06,3.1197e-05,3.11855e-05,0.000120222,0.0135176,0.0135159,0.0114572,0.0402192,0.0402189,0.0621899,4.02265e-11,4.0229e-11,7.54118e-10,6.39686e-07,6.39563e-07,5.00008e-08,0,0,0,0,0,0,0,0 +28288000,0.982919,-0.00677823,-0.0115468,0.183552,-0.0797089,0.0407079,0.779925,-0.0200506,0.00223316,-2.88474,-1.16996e-05,-4.66305e-05,-1.75175e-06,2.69196e-05,2.33432e-05,-0.000915578,0.203935,0.000817121,0.434565,0,0,0,0,0,4.13049e-06,3.13666e-05,3.13538e-05,0.000119277,0.0142885,0.0142868,0.011535,0.0439331,0.0439327,0.0622496,4.02743e-11,4.02772e-11,7.50552e-10,6.39689e-07,6.39564e-07,5.00004e-08,0,0,0,0,0,0,0,0 +28392000,0.982902,-0.00678713,-0.012187,0.183603,-0.07768,0.0429316,0.780627,-0.0179667,0.0030185,-2.80901,-1.16881e-05,-4.66235e-05,-1.66711e-06,2.32593e-05,2.6479e-05,-0.000913098,0.203935,0.000817121,0.434565,0,0,0,0,0,4.11159e-06,3.14674e-05,3.14529e-05,0.000118519,0.0130239,0.0130222,0.0114252,0.0397654,0.039765,0.0619001,4.03181e-11,4.03213e-11,7.46893e-10,6.38508e-07,6.38376e-07,5.00004e-08,0,0,0,0,0,0,0,0 +28488000,0.982899,-0.00706622,-0.0126857,0.183571,-0.0786747,0.0462612,0.7817,-0.0254364,0.00728899,-2.73783,-1.16876e-05,-4.66238e-05,-1.64763e-06,2.33417e-05,2.6352e-05,-0.000911713,0.203935,0.000817121,0.434565,0,0,0,0,0,4.08337e-06,3.16432e-05,3.16279e-05,0.000117678,0.0137721,0.0137701,0.011502,0.043375,0.0433744,0.0619575,4.03659e-11,4.03695e-11,7.43152e-10,6.38511e-07,6.38376e-07,5e-08,0,0,0,0,0,0,0,0 +28592000,0.982925,-0.00709528,-0.0126603,0.183434,-0.0701591,0.0428887,0.780376,-0.0232562,0.00491664,-2.65761,-1.16639e-05,-4.66153e-05,-1.60013e-06,2.07682e-05,3.04508e-05,-0.000910868,0.203935,0.000817121,0.434565,0,0,0,0,0,4.05769e-06,3.17441e-05,3.17296e-05,0.000117033,0.0126097,0.0126078,0.0113923,0.0393292,0.0393288,0.0616109,4.04024e-11,4.04064e-11,7.3932e-10,6.37566e-07,6.37424e-07,5e-08,0,0,0,0,0,0,0,0 +28688000,0.982914,-0.00687943,-0.0120203,0.183546,-0.0701958,0.0438614,0.780962,-0.0300025,0.00911162,-2.58483,-1.16642e-05,-4.6615e-05,-1.61999e-06,2.08047e-05,3.03793e-05,-0.000910062,0.203935,0.000817121,0.434565,0,0,0,0,0,4.05817e-06,3.19229e-05,3.19106e-05,0.000116909,0.0133429,0.0133408,0.0115745,0.0428445,0.0428438,0.0626367,4.04505e-11,4.04547e-11,7.36406e-10,6.37569e-07,6.37425e-07,5.00008e-08,0,0,0,0,0,0,0,0 +28792000,0.982931,-0.00615454,-0.0117496,0.183497,-0.0765333,0.0446272,0.778632,-0.0547976,0.00974908,-2.51114,-1.16417e-05,-4.6593e-05,-1.5289e-06,2.58879e-05,2.95479e-05,-0.0009063,0.203935,0.000817121,0.434565,0,0,0,0,0,4.0403e-06,3.20226e-05,3.20106e-05,0.000116344,0.0122691,0.0122671,0.0114633,0.0389134,0.0389128,0.0622821,4.04751e-11,4.04799e-11,7.32427e-10,6.36826e-07,6.36675e-07,5.00008e-08,0,0,0,0,0,0,0,0 +28888000,0.982955,-0.00600257,-0.0114856,0.183391,-0.0801743,0.0457831,0.777295,-0.0622871,0.0140735,-2.43973,-1.16396e-05,-4.65947e-05,-1.42547e-06,2.59828e-05,2.94207e-05,-0.000905082,0.203935,0.000817121,0.434565,0,0,0,0,0,4.01664e-06,3.2208e-05,3.21969e-05,0.000115674,0.0129935,0.0129915,0.0115403,0.0423443,0.0423435,0.0623416,4.05228e-11,4.05278e-11,7.28371e-10,6.36829e-07,6.36676e-07,5.00004e-08,0,0,0,0,0,0,0,0 +28992000,0.982934,-0.00572516,-0.0117067,0.183498,-0.0737372,0.0430399,0.776348,-0.0545158,0.0124652,-2.36622,-1.16036e-05,-4.65676e-05,-1.41802e-06,2.26446e-05,3.22059e-05,-0.00090117,0.203935,0.000817121,0.434565,0,0,0,0,0,4.00583e-06,3.23049e-05,3.22933e-05,0.000115184,0.0119974,0.0119957,0.0114294,0.0385206,0.03852,0.06199,4.05308e-11,4.05364e-11,7.2423e-10,6.36256e-07,6.36095e-07,5.00004e-08,0,0,0,0,0,0,0,0 +29088000,0.982934,-0.00558749,-0.0117739,0.183499,-0.0765401,0.0446901,0.77652,-0.0617802,0.0166367,-2.29301,-1.16031e-05,-4.6568e-05,-1.3953e-06,2.26772e-05,3.21555e-05,-0.000900664,0.203935,0.000817121,0.434565,0,0,0,0,0,3.98686e-06,3.24964e-05,3.24847e-05,0.000114586,0.0127169,0.0127151,0.0115055,0.0418772,0.0418763,0.0620469,4.05785e-11,4.05843e-11,7.20015e-10,6.36259e-07,6.36096e-07,5e-08,0,0,0,0,0,0,0,0 +29192000,0.982958,-0.00550152,-0.0119682,0.183357,-0.0703302,0.0436737,0.771224,-0.0535406,0.0156357,-2.22043,-1.156e-05,-4.653e-05,-1.27754e-06,1.98946e-05,3.41935e-05,-0.000896245,0.203935,0.000817121,0.434565,0,0,0,0,0,3.97121e-06,3.25867e-05,3.25749e-05,0.000114176,0.0117918,0.0117902,0.0113952,0.0381537,0.038153,0.0616982,4.05649e-11,4.05713e-11,7.15718e-10,6.35825e-07,6.35655e-07,5e-08,0,0,0,0,0,0,0,0 +29288000,0.982937,-0.00575031,-0.0119909,0.183464,-0.0719182,0.0494345,0.773561,-0.0603362,0.0201448,-2.14597,-1.15598e-05,-4.65302e-05,-1.26475e-06,1.98912e-05,3.42042e-05,-0.000896373,0.203935,0.000817121,0.434565,0,0,0,0,0,3.97949e-06,3.27831e-05,3.2772e-05,0.000114236,0.0125108,0.0125088,0.0115773,0.0414461,0.0414452,0.0627262,4.06128e-11,4.06195e-11,7.12462e-10,6.35828e-07,6.35656e-07,5.00008e-08,0,0,0,0,0,0,0,0 +29392000,0.98294,-0.00617902,-0.0114512,0.183464,-0.0658243,0.0478911,0.775589,-0.0537074,0.0195058,-2.0681,-1.15166e-05,-4.64952e-05,-1.1905e-06,1.78672e-05,3.59e-05,-0.000894692,0.203935,0.000817121,0.434565,0,0,0,0,0,3.97023e-06,3.28622e-05,3.28542e-05,0.000113882,0.0116417,0.01164,0.0114653,0.037815,0.0378143,0.0623694,4.05724e-11,4.05797e-11,7.08034e-10,6.35505e-07,6.35327e-07,5.00008e-08,0,0,0,0,0,0,0,0 +29488000,0.982955,-0.00617769,-0.0113553,0.183393,-0.0685739,0.048475,0.776951,-0.0601287,0.0241605,-1.99388,-1.15135e-05,-4.6498e-05,-1.02533e-06,1.79191e-05,3.58733e-05,-0.000894587,0.203935,0.000817121,0.434565,0,0,0,0,0,3.95645e-06,3.30633e-05,3.30559e-05,0.000113401,0.0123646,0.012363,0.0115419,0.0410529,0.0410519,0.0624282,4.062e-11,4.06276e-11,7.03539e-10,6.35508e-07,6.35327e-07,5.00004e-08,0,0,0,0,0,0,0,0 +29592000,0.982974,-0.00604872,-0.0113387,0.183292,-0.0629571,0.0466403,0.77856,-0.0535775,0.0222845,-1.91416,-1.14568e-05,-4.64614e-05,-8.79569e-07,1.63895e-05,3.73055e-05,-0.000894243,0.203935,0.000817121,0.434565,0,0,0,0,0,3.94717e-06,3.31323e-05,3.31252e-05,0.000113107,0.011547,0.0115456,0.0114305,0.0375067,0.0375059,0.0620745,4.05477e-11,4.05559e-11,6.98969e-10,6.3527e-07,6.35084e-07,5.00004e-08,0,0,0,0,0,0,0,0 +29688000,0.982991,-0.00613174,-0.0111484,0.183211,-0.0669092,0.0460038,0.773649,-0.0597838,0.0267643,-1.8432,-1.14541e-05,-4.64637e-05,-7.48411e-07,1.64918e-05,3.71721e-05,-0.000892923,0.203935,0.000817121,0.434565,0,0,0,0,0,3.9334e-06,3.33376e-05,3.33315e-05,0.000112679,0.0122807,0.0122795,0.0115063,0.0406998,0.0406989,0.0621307,4.05951e-11,4.06037e-11,6.94337e-10,6.35274e-07,6.35085e-07,5e-08,0,0,0,0,0,0,0,0 +29792000,0.982997,-0.00590414,-0.0116237,0.183158,-0.0626063,0.0401031,0.770479,-0.0534715,0.0250098,-1.76723,-1.13978e-05,-4.64189e-05,-5.86355e-07,1.55416e-05,3.79723e-05,-0.000890398,0.203935,0.000817121,0.434565,0,0,0,0,0,3.92848e-06,3.33926e-05,3.33853e-05,0.000112432,0.0115072,0.0115064,0.0113955,0.0372309,0.0372302,0.0617799,4.04857e-11,4.04948e-11,6.89635e-10,6.35097e-07,6.34904e-07,5e-08,0,0,0,0,0,0,0,0 +29888000,0.982996,-0.0054285,-0.011974,0.183157,-0.0635268,0.0406956,0.76703,-0.059463,0.0288579,-1.69679,-1.13959e-05,-4.64205e-05,-4.92187e-07,1.56261e-05,3.78552e-05,-0.000889185,0.203935,0.000817121,0.434565,0,0,0,0,0,3.93896e-06,3.36035e-05,3.35947e-05,0.000112628,0.0122507,0.0122498,0.0115773,0.0403891,0.0403882,0.0628096,4.05335e-11,4.05429e-11,6.86084e-10,6.35101e-07,6.34906e-07,5.00012e-08,0,0,0,0,0,0,0,0 +29992000,0.982993,-0.00548812,-0.0120243,0.183169,-0.0581375,0.0373677,0.764324,-0.0538306,0.0254301,-1.6244,-1.1325e-05,-4.63824e-05,-4.3839e-07,1.50324e-05,3.80759e-05,-0.000885246,0.203935,0.000817121,0.434565,0,0,0,0,0,3.93469e-06,3.36394e-05,3.3631e-05,0.000112423,0.0115103,0.0115097,0.0114651,0.0369894,0.0369886,0.0624509,4.03819e-11,4.03918e-11,6.81272e-10,6.34964e-07,6.34765e-07,5.00012e-08,0,0,0,0,0,0,0,0 +30088000,0.982982,-0.0055944,-0.0121491,0.183216,-0.0583771,0.0387381,0.762542,-0.0594523,0.029096,-1.55343,-1.13279e-05,-4.63796e-05,-5.98186e-07,1.50385e-05,3.80145e-05,-0.000884385,0.203935,0.000817121,0.434565,0,0,0,0,0,3.92074e-06,3.38532e-05,3.3845e-05,0.000112081,0.0122654,0.0122647,0.0115413,0.0401216,0.0401207,0.0625088,4.04293e-11,4.04394e-11,6.76407e-10,6.34968e-07,6.34766e-07,5.00008e-08,0,0,0,0,0,0,0,0 +30192000,0.982946,-0.0055268,-0.0121173,0.183413,-0.0531891,0.0366039,0.762299,-0.0536792,0.0283435,-1.47883,-1.1291e-05,-4.63232e-05,-7.56094e-07,1.47964e-05,3.83568e-05,-0.000881975,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91943e-06,3.38684e-05,3.38607e-05,0.000111913,0.0115507,0.0115501,0.0114297,0.0367828,0.0367821,0.0621531,4.02311e-11,4.02417e-11,6.7148e-10,6.34851e-07,6.34647e-07,5.00008e-08,0,0,0,0,0,0,0,0 +30288000,0.982929,-0.00553957,-0.012113,0.183503,-0.051945,0.0370944,0.761365,-0.0586839,0.0318993,-1.41219,-1.129e-05,-4.63239e-05,-7.16106e-07,1.49233e-05,3.81553e-05,-0.000879579,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91416e-06,3.40852e-05,3.4078e-05,0.000111598,0.0123182,0.0123177,0.0115052,0.0398976,0.0398968,0.0622085,4.02784e-11,4.02892e-11,6.66503e-10,6.34854e-07,6.34648e-07,5.00004e-08,0,0,0,0,0,0,0,0 +30392000,0.982923,-0.00548404,-0.0119891,0.183544,-0.0458246,0.0337047,0.758618,-0.0514607,0.0300069,-1.34193,-1.12279e-05,-4.62594e-05,-5.25418e-07,1.53571e-05,3.78806e-05,-0.000875202,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91719e-06,3.40776e-05,3.40712e-05,0.000111461,0.0116238,0.0116234,0.0113943,0.0366116,0.0366109,0.061856,4.00299e-11,4.00411e-11,6.6147e-10,6.34741e-07,6.34534e-07,5.00004e-08,0,0,0,0,0,0,0,0 +30488000,0.982946,-0.00547077,-0.012122,0.183414,-0.0493116,0.0338838,0.76001,-0.0560134,0.0332868,-1.27229,-1.12252e-05,-4.62619e-05,-3.88324e-07,1.5446e-05,3.77743e-05,-0.00087396,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90641e-06,3.42975e-05,3.42911e-05,0.000111182,0.0124058,0.0124055,0.0114692,0.039717,0.0397163,0.0619089,4.00772e-11,4.00887e-11,6.56392e-10,6.34745e-07,6.34535e-07,5e-08,0,0,0,0,0,0,0,0 +30592000,0.982952,-0.00576236,-0.0123838,0.183354,-0.0455917,0.0316129,0.759629,-0.0498674,0.0305196,-1.19793,-1.1157e-05,-4.62059e-05,-2.8763e-07,1.5885e-05,3.72836e-05,-0.000871456,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90398e-06,3.42658e-05,3.42595e-05,0.00011108,0.0117236,0.0117234,0.011359,0.0364756,0.036475,0.0615594,3.97754e-11,3.97871e-11,6.51264e-10,6.3462e-07,6.34409e-07,5e-08,0,0,0,0,0,0,0,0 +30688000,0.982967,-0.00611358,-0.0125773,0.183249,-0.0436146,0.0304824,0.759139,-0.0542134,0.0335185,-1.12813,-1.11563e-05,-4.62064e-05,-2.56161e-07,1.59472e-05,3.71962e-05,-0.000870304,0.203935,0.000817121,0.434565,0,0,0,0,0,3.9121e-06,3.44881e-05,3.44823e-05,0.000111396,0.0125236,0.0125234,0.0115392,0.039579,0.0395784,0.0625789,3.98231e-11,3.9835e-11,6.47401e-10,6.34624e-07,6.34412e-07,5.00008e-08,0,0,0,0,0,0,0,0 +30792000,0.982995,-0.00578714,-0.0122179,0.183137,-0.0376537,0.0258497,0.757053,-0.0493778,0.0331045,-1.05465,-1.11402e-05,-4.61545e-05,-2.24006e-07,1.65124e-05,3.75487e-05,-0.000867554,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90549e-06,3.44284e-05,3.44235e-05,0.000111324,0.0118492,0.0118491,0.0114276,0.036374,0.0363735,0.0622216,3.94656e-11,3.94775e-11,6.42198e-10,6.34474e-07,6.34262e-07,5.00008e-08,0,0,0,0,0,0,0,0 +30888000,0.982973,-0.00512476,-0.0121225,0.183277,-0.0374391,0.0234324,0.755484,-0.0529101,0.0354896,-0.986853,-1.11421e-05,-4.61526e-05,-3.30238e-07,1.65722e-05,3.74361e-05,-0.000865807,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90039e-06,3.46521e-05,3.46467e-05,0.000111087,0.0126665,0.0126665,0.0115031,0.0394825,0.039482,0.0622764,3.95128e-11,3.95249e-11,6.36958e-10,6.34478e-07,6.34264e-07,5.00004e-08,0,0,0,0,0,0,0,0 +30992000,0.982965,-0.00524992,-0.0120286,0.183324,-0.0317274,0.0197515,0.757324,-0.0467627,0.0312851,-0.914459,-1.10697e-05,-4.60993e-05,-3.38567e-07,1.72946e-05,3.64239e-05,-0.000862935,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90057e-06,3.45641e-05,3.45596e-05,0.000111028,0.0119889,0.0119889,0.0113923,0.0363059,0.0363054,0.0619224,3.90981e-11,3.911e-11,6.31678e-10,6.34292e-07,6.34079e-07,5.00004e-08,0,0,0,0,0,0,0,0 +31088000,0.982927,-0.00539758,-0.0121241,0.183516,-0.0306507,0.0176666,0.756159,-0.0497021,0.0330091,-0.844858,-1.10704e-05,-4.60986e-05,-3.78287e-07,1.73387e-05,3.63575e-05,-0.000861808,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90052e-06,3.47891e-05,3.4785e-05,0.000110803,0.0128232,0.0128232,0.0114672,0.039425,0.0394245,0.0619747,3.91453e-11,3.91574e-11,6.26366e-10,6.34295e-07,6.34082e-07,5e-08,0,0,0,0,0,0,0,0 +31192000,0.982936,-0.00554959,-0.0122093,0.18346,-0.027974,0.0153509,0.759098,-0.0445608,0.0304065,-0.770256,-1.1028e-05,-4.60543e-05,-2.0974e-07,1.80678e-05,3.5978e-05,-0.000860185,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90187e-06,3.46722e-05,3.46684e-05,0.000110761,0.0121407,0.0121407,0.0113571,0.036269,0.0362686,0.061624,3.86735e-11,3.86852e-11,6.21021e-10,6.34066e-07,6.33854e-07,5e-08,0,0,0,0,0,0,0,0 +31288000,0.98295,-0.00580245,-0.0123018,0.183369,-0.0253455,0.0138875,0.762164,-0.0470836,0.0318628,-0.700706,-1.10263e-05,-4.60558e-05,-1.27571e-07,1.81411e-05,3.59009e-05,-0.000858919,0.203935,0.000817121,0.434565,0,0,0,0,0,3.9135e-06,3.48979e-05,3.48946e-05,0.000111125,0.0129868,0.0129868,0.0115375,0.0394036,0.0394033,0.062645,3.87212e-11,3.8733e-11,6.17005e-10,6.3407e-07,6.33858e-07,5.00008e-08,0,0,0,0,0,0,0,0 +31392000,0.982962,-0.00551971,-0.0120522,0.18333,-0.02114,0.00843037,0.761029,-0.0426897,0.0284251,-0.624563,-1.09883e-05,-4.60265e-05,-1.99354e-07,1.84682e-05,3.54782e-05,-0.000856799,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90897e-06,3.47514e-05,3.47485e-05,0.000111104,0.0122995,0.0122993,0.0114261,0.0362608,0.0362605,0.0622865,3.81937e-11,3.82049e-11,6.11611e-10,6.33797e-07,6.33585e-07,5.00008e-08,0,0,0,0,0,0,0,0 +31488000,0.982935,-0.00528064,-0.0123827,0.183461,-0.0216787,0.00622352,0.756974,-0.0447693,0.0290752,-0.555333,-1.09892e-05,-4.60255e-05,-2.52725e-07,1.85154e-05,3.54156e-05,-0.000855494,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90694e-06,3.49778e-05,3.49738e-05,0.000110907,0.0131687,0.0131685,0.0115018,0.0394156,0.0394154,0.0623409,3.82409e-11,3.82522e-11,6.06193e-10,6.338e-07,6.33589e-07,5.00004e-08,0,0,0,0,0,0,0,0 +31592000,0.982952,-0.00513819,-0.0128082,0.183344,-0.0204967,0.00474588,0.76043,-0.0393651,0.0266195,-0.480346,-1.09608e-05,-4.59708e-05,-1.25452e-07,1.97147e-05,3.51833e-05,-0.000853304,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90549e-06,3.48018e-05,3.47966e-05,0.000110893,0.0124624,0.0124621,0.0113911,0.0362789,0.0362788,0.0619858,3.76589e-11,3.76693e-11,6.00752e-10,6.33472e-07,6.33262e-07,5.00004e-08,0,0,0,0,0,0,0,0 +31688000,0.982977,-0.00511928,-0.0133109,0.183173,-0.0230414,0.00418854,0.756726,-0.0414752,0.0269956,-0.413467,-1.09575e-05,-4.59739e-05,4.36107e-08,1.98382e-05,3.5079e-05,-0.000851067,0.203935,0.000817121,0.434565,0,0,0,0,0,3.89723e-06,3.5028e-05,3.50215e-05,0.000110711,0.0133452,0.0133448,0.0114662,0.0394569,0.0394568,0.0620379,3.7706e-11,3.77166e-11,5.95292e-10,6.33476e-07,6.33266e-07,5e-08,0,0,0,0,0,0,0,0 +31792000,0.98299,-0.00535758,-0.0139464,0.183051,-0.016004,0.00325365,0.756413,-0.036264,0.026877,-0.339446,-1.09695e-05,-4.59008e-05,1.77285e-07,2.16507e-05,3.58127e-05,-0.000848769,0.203935,0.000817121,0.434565,0,0,0,0,0,3.89621e-06,3.4823e-05,3.48153e-05,0.000110704,0.0126258,0.0126252,0.0113562,0.0363201,0.03632,0.0616863,3.70732e-11,3.70825e-11,5.89815e-10,6.33095e-07,6.32888e-07,5e-08,0,0,0,0,0,0,0,0 +31888000,0.982985,-0.00506949,-0.0137163,0.183101,-0.0125157,0.00208679,0.755091,-0.0376274,0.0270772,-0.27272,-1.09682e-05,-4.59019e-05,2.39035e-07,2.17515e-05,3.57319e-05,-0.000846631,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91351e-06,3.50466e-05,3.50394e-05,0.00011109,0.0135196,0.0135188,0.011537,0.039524,0.0395239,0.0627092,3.71208e-11,3.71303e-11,5.8571e-10,6.33099e-07,6.32892e-07,5.00008e-08,0,0,0,0,0,0,0,0 +31992000,0.982961,-0.00530216,-0.0132446,0.183261,-0.00688468,0.00249968,0.752803,-0.0325911,0.0255133,-0.203046,-1.09673e-05,-4.5848e-05,1.44771e-07,2.30597e-05,3.59493e-05,-0.000842727,0.203935,0.000817121,0.434565,0,0,0,0,0,3.9173e-06,3.48105e-05,3.48054e-05,0.000111085,0.012781,0.0127802,0.0114257,0.036381,0.0363809,0.0623499,3.6441e-11,3.6449e-11,5.8021e-10,6.32667e-07,6.32462e-07,5.00008e-08,0,0,0,0,0,0,0,0 +32088000,0.982973,-0.00567158,-0.0129086,0.18321,-0.00660604,-0.000531284,0.754678,-0.033261,0.025663,-0.135144,-1.09669e-05,-4.58484e-05,1.69247e-07,2.31314e-05,3.59e-05,-0.000841083,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90965e-06,3.50321e-05,3.50291e-05,0.000110913,0.0136836,0.0136826,0.0115016,0.0396121,0.039612,0.0624042,3.64881e-11,3.64963e-11,5.74699e-10,6.32671e-07,6.32467e-07,5.00004e-08,0,0,0,0,0,0,0,0 +32192000,0.982963,-0.00584946,-0.0131227,0.183242,-0.00524076,-0.00377729,0.755405,-0.0295439,0.0254775,-0.0645033,-1.10052e-05,-4.58057e-05,1.15075e-07,2.42385e-05,3.71962e-05,-0.000837296,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90991e-06,3.47708e-05,3.47677e-05,0.000110915,0.0129207,0.0129195,0.0113911,0.0364575,0.0364574,0.0620484,3.57664e-11,3.57731e-11,5.69181e-10,6.32191e-07,6.3199e-07,5.00004e-08,0,0,0,0,0,0,0,0 +32288000,0.98298,-0.00581252,-0.0133781,0.183132,-0.00469436,-0.00660128,0.752958,-0.0300397,0.0249591,0.00179821,-1.10033e-05,-4.58076e-05,2.17112e-07,2.43503e-05,3.714e-05,-0.000835022,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90244e-06,3.49918e-05,3.4988e-05,0.000110745,0.0138377,0.0138362,0.0114664,0.0397161,0.0397159,0.0621005,3.58135e-11,3.58204e-11,5.63657e-10,6.32195e-07,6.31994e-07,5e-08,0,0,0,0,0,0,0,0 +32392000,0.982957,-0.00591664,-0.0135482,0.183241,0.00385711,-0.00762476,0.751774,-0.0133919,0.0234695,0.0772213,-1.0993e-05,-4.56941e-05,1.47759e-07,2.67134e-05,3.73745e-05,-0.000832675,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90541e-06,3.47055e-05,3.47018e-05,0.000110745,0.0130557,0.013054,0.0113566,0.0365461,0.0365459,0.0617482,3.50557e-11,3.50606e-11,5.5813e-10,6.31672e-07,6.31474e-07,5e-08,0,0,0,0,0,0,0,0 +32488000,0.982963,-0.00801249,-0.0119821,0.18324,0.0248225,-0.0528807,0.0447954,-0.0115462,0.0190943,0.0942565,-1.09942e-05,-4.56929e-05,8.51095e-08,2.67134e-05,3.73745e-05,-0.000832675,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91701e-06,3.49199e-05,3.49255e-05,0.000111144,0.0152374,0.0152332,0.0112412,0.0398879,0.0398876,0.06276,3.51034e-11,3.51082e-11,5.53998e-10,0,0,0,0,0,0,0,0,0,0,0 +32592000,0.982965,-0.00800395,-0.0119743,0.18323,0.028128,-0.053635,0.0394254,0.00399193,0.0163382,0.0871146,-1.10597e-05,-4.55989e-05,1.52696e-07,2.67134e-05,3.73745e-05,-0.000832675,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91825e-06,3.43741e-05,3.43796e-05,0.000111145,0.0149584,0.0149541,0.010726,0.036725,0.0367247,0.0623477,3.42375e-11,3.42391e-11,5.4847e-10,0,0,0,0,0,0,0,0,0,0,0 +32688000,0.982961,-0.00797038,-0.0118633,0.183256,0.0246619,-0.0576911,0.0377214,0.00653201,0.0109814,0.0857607,-1.10607e-05,-4.55981e-05,1.06533e-07,2.67134e-05,3.73745e-05,-0.000832675,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91211e-06,3.45868e-05,3.45928e-05,0.000110974,0.0167575,0.0167526,0.0104282,0.0401695,0.040169,0.062289,3.42845e-11,3.42864e-11,5.42947e-10,0,0,0,0,0,0,0,0,0,0,0 +32792000,0.982959,-0.00784112,-0.0119224,0.183268,0.0266399,-0.0562085,0.0329989,0.0195446,0.00945459,0.0790587,-1.11484e-05,-4.55119e-05,1.96029e-07,2.67134e-05,3.73745e-05,-0.000832675,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91466e-06,3.3664e-05,3.36688e-05,0.000110972,0.0166237,0.0166189,0.00996768,0.0369724,0.036972,0.0618194,3.33557e-11,3.33539e-11,5.37428e-10,0,0,0,0,0,0,0,0,0,0,0 +32888000,0.98297,-0.0078024,-0.0120069,0.18321,0.02672,-0.0610746,0.0308805,0.0221478,0.00383719,0.0761701,-1.11481e-05,-4.55123e-05,2.16063e-07,2.67134e-05,3.73745e-05,-0.000832675,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90681e-06,3.38695e-05,3.38743e-05,0.0001108,0.01877,0.0187645,0.0096959,0.0405398,0.040539,0.061672,3.34027e-11,3.34013e-11,5.31917e-10,6.31674e-07,6.31476e-07,5.00021e-08,0,0,0,0,0,0,0,0 +32992000,0.982979,-0.00769834,-0.012009,0.183162,0.0265917,-0.0584288,0.0289732,0.032928,0.00187512,0.071564,-1.12234e-05,-4.54497e-05,3.36133e-07,2.67785e-05,3.67296e-05,-0.000832661,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90739e-06,3.2533e-05,3.25365e-05,0.000110796,0.0187632,0.0187581,0.00929779,0.0372972,0.0372965,0.0611598,3.24357e-11,3.24304e-11,5.26415e-10,6.31655e-07,6.31458e-07,5.00073e-08,0,0,0,0,0,0,0,0 +33088000,0.98297,-0.00764319,-0.0119984,0.183215,0.0237228,-0.0616215,0.0301885,0.0353646,-0.00386675,0.0753103,-1.12249e-05,-4.54484e-05,2.62712e-07,2.67778e-05,3.67303e-05,-0.000832663,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90146e-06,3.27283e-05,3.27319e-05,0.000110619,0.0215093,0.0215037,0.00907716,0.0410322,0.0410311,0.0609393,3.24827e-11,3.24778e-11,5.20925e-10,6.3166e-07,6.31463e-07,5.00122e-08,0,0,0,0,0,0,0,0 +33192000,0.982965,-0.00751906,-0.0119394,0.183249,0.0227333,-0.0595674,0.0279074,0.0442326,-0.00534272,0.0747625,-1.12991e-05,-4.53911e-05,1.86987e-07,2.69012e-05,3.29441e-05,-0.000832585,0.203935,0.000817121,0.434565,0,0,0,0,0,3.89991e-06,3.09956e-05,3.09976e-05,0.000110612,0.0216104,0.0216054,0.00875512,0.0377238,0.0377228,0.0603982,3.15113e-11,3.15023e-11,5.15448e-10,6.30456e-07,6.30259e-07,5.00138e-08,0,0,0,0,0,0,0,0 +33288000,0.982986,-0.00758038,-0.0119234,0.183138,0.0202093,-0.0599098,0.0269697,0.0462444,-0.0110782,0.0768665,-1.12964e-05,-4.53936e-05,3.25898e-07,2.69016e-05,3.29437e-05,-0.000832581,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91253e-06,3.1179e-05,3.11813e-05,0.000110997,0.0249021,0.0248969,0.00866664,0.0416824,0.041681,0.0610428,3.15588e-11,3.15502e-11,5.11362e-10,6.30461e-07,6.30264e-07,5.00187e-08,0,0,0,0,0,0,0,0 +33392000,0.982994,-0.00739464,-0.0119981,0.183098,0.0183703,-0.0515637,0.0259683,0.053392,-0.00842903,0.0734729,-1.14144e-05,-4.53256e-05,3.69717e-07,2.53311e-05,2.33878e-05,-0.000832249,0.203935,0.000817121,0.434565,0,0,0,0,0,3.91085e-06,2.91267e-05,2.91269e-05,0.000110984,0.0247599,0.0247558,0.00840916,0.0382731,0.038272,0.0604688,3.06232e-11,3.06109e-11,5.05913e-10,6.26673e-07,6.26478e-07,5.00113e-08,0,0,0,0,0,0,0,0 +33488000,0.982987,-0.00740214,-0.0119834,0.183132,0.0157041,-0.052106,0.0252461,0.0549916,-0.0133671,0.0718266,-1.14142e-05,-4.53259e-05,3.83485e-07,2.53444e-05,2.33776e-05,-0.000832203,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90608e-06,2.9297e-05,2.92975e-05,0.000110795,0.0284483,0.0284441,0.00829061,0.0425066,0.042505,0.060146,3.06702e-11,3.06583e-11,5.00484e-10,6.26678e-07,6.26483e-07,5.00156e-08,0,0,0,0,0,0,0,0 +33592000,0.983008,-0.00723035,-0.0119634,0.183031,0.014222,-0.0482112,0.0249092,0.0608602,-0.011856,0.0693899,-1.14884e-05,-4.52774e-05,4.96298e-07,2.39399e-05,1.48196e-05,-0.000831977,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90339e-06,2.70533e-05,2.70517e-05,0.000110778,0.0277709,0.0277676,0.0080948,0.0389444,0.0389431,0.0595685,2.98114e-11,2.97962e-11,4.95074e-10,6.19561e-07,6.1937e-07,5.00039e-08,0,0,0,0,0,0,0,0 +33688000,0.983015,-0.00721922,-0.0119441,0.182995,0.0104737,-0.0497276,0.0214231,0.0620962,-0.0165791,0.0673768,-1.14878e-05,-4.52781e-05,5.30892e-07,2.39694e-05,1.47977e-05,-0.000831871,0.203935,0.000817121,0.434565,0,0,0,0,0,3.896e-06,2.72106e-05,2.72092e-05,0.000110585,0.0317124,0.0317091,0.0080234,0.0434826,0.0434809,0.0592204,2.98583e-11,2.98436e-11,4.89688e-10,6.19566e-07,6.19375e-07,5.00068e-08,0,0,0,0,0,0,0,0 +33792000,0.983025,-0.00706775,-0.0119199,0.182946,0.00725773,-0.0442486,0.0233624,0.0668059,-0.014158,0.0643811,-1.1559e-05,-4.52284e-05,4.79326e-07,2.13305e-05,5.07618e-06,-0.000831478,0.203935,0.000817121,0.434565,0,0,0,0,0,3.89073e-06,2.49245e-05,2.49211e-05,0.000110563,0.0302964,0.0302941,0.00788207,0.0397089,0.0397076,0.0586507,2.91079e-11,2.90904e-11,4.84324e-10,6.09063e-07,6.08878e-07,5.00021e-08,0,0,0,0,0,0,0,0 +33888000,0.983033,-0.00709868,-0.0118844,0.182907,0.00369308,-0.0427324,0.022338,0.0672733,-0.0183636,0.0642993,-1.15573e-05,-4.523e-05,5.68276e-07,2.13528e-05,5.06111e-06,-0.000831393,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90427e-06,2.50697e-05,2.50666e-05,0.000110927,0.0343261,0.034324,0.00791965,0.0445518,0.0445501,0.0591581,2.91555e-11,2.91383e-11,4.8033e-10,6.09067e-07,6.08883e-07,5.00037e-08,0,0,0,0,0,0,0,0 +33992000,0.983021,-0.00692159,-0.0120268,0.182969,0.00390332,-0.0334657,0.0221691,0.0724137,-0.0131026,0.0633963,-1.16315e-05,-4.51637e-05,5.21475e-07,1.399e-05,-7.28314e-06,-0.00083096,0.203935,0.000817121,0.434565,0,0,0,0,0,3.90362e-06,2.28809e-05,2.28756e-05,0.000110891,0.0321264,0.0321252,0.00782355,0.0405172,0.040516,0.0585894,2.85308e-11,2.85115e-11,4.75012e-10,5.95683e-07,5.95506e-07,5.00008e-08,0,0,0,0,0,0,0,0 +34088000,0.983016,-0.00690471,-0.0120345,0.182995,0.00159733,-0.035353,0.022329,0.072707,-0.0164277,0.0645477,-1.16324e-05,-4.51629e-05,4.75105e-07,1.40059e-05,-7.29512e-06,-0.000830906,0.203935,0.000817121,0.434565,0,0,0,0,0,3.89616e-06,2.30156e-05,2.30104e-05,0.000110684,0.0361169,0.0361157,0.00783428,0.0456365,0.045635,0.0582267,2.85778e-11,2.8559e-11,4.69722e-10,5.95687e-07,5.9551e-07,5.00004e-08,0,0,0,0,0,0,0,0 +34192000,0.98301,-0.00681867,-0.0120589,0.183029,-0.00156079,-0.0277037,0.0211956,0.0758829,-0.0123135,0.0629193,-1.1681e-05,-4.51241e-05,5.4589e-07,9.46051e-06,-1.74686e-05,-0.000829898,0.203935,0.000817121,0.434565,0,0,0,0,0,3.89736e-06,2.10262e-05,2.10195e-05,0.000110639,0.0331899,0.0331895,0.00778002,0.0413126,0.0413114,0.0576847,2.80808e-11,2.80603e-11,4.64462e-10,5.80255e-07,5.80086e-07,5.00004e-08,0,0,0,0,0,0,0,0 +34288000,0.983009,-0.0066914,-0.0121164,0.183033,-0.00243858,-0.0284998,0.0199913,0.075717,-0.0150152,0.0608102,-1.168e-05,-4.5125e-05,5.95935e-07,9.53504e-06,-1.75167e-05,-0.000829623,0.203935,0.000817121,0.434565,0,0,0,0,0,3.8913e-06,2.11525e-05,2.11456e-05,0.000110423,0.0370426,0.0370424,0.00782651,0.0466588,0.0466574,0.0573365,2.81278e-11,2.81078e-11,4.59232e-10,5.80258e-07,5.80091e-07,5e-08,0,0,0,0,0,0,0,0 +34392000,0.983025,-0.00660371,-0.0121352,0.182953,-0.00356489,-0.0210408,0.0210093,0.0787181,-0.010847,0.058658,-1.17163e-05,-4.50913e-05,6.05644e-07,4.4078e-06,-2.61779e-05,-0.000829302,0.203935,0.000817121,0.434565,0,0,0,0,0,3.88582e-06,1.94221e-05,1.94138e-05,0.000110376,0.0335304,0.0335308,0.00780794,0.042045,0.042044,0.056828,2.77485e-11,2.77275e-11,4.54035e-10,5.6369e-07,5.63532e-07,5e-08,0,0,0,0,0,0,0,0 +34488000,0.983019,-0.00667379,-0.0120852,0.182981,-0.005531,-0.021597,0.0208119,0.0783063,-0.0129282,0.0590571,-1.17146e-05,-4.50928e-05,6.91376e-07,4.44183e-06,-2.61962e-05,-0.000829169,0.203935,0.000817121,0.434565,0,0,0,0,0,3.9012e-06,1.95419e-05,1.9534e-05,0.000110712,0.0371737,0.0371743,0.00794503,0.0475573,0.0475562,0.0573173,2.77961e-11,2.77754e-11,4.5017e-10,5.63693e-07,5.63537e-07,5.00008e-08,0,0,0,0,0,0,0,0 +34592000,0.983022,-0.00658935,-0.0118785,0.182987,-0.00378299,-0.017963,0.812835,0.0810424,-0.0104868,0.0894353,-1.17326e-05,-4.50674e-05,6.82209e-07,1.78262e-07,-3.0956e-05,-0.000828557,0.203935,0.000817121,0.434565,0,0,0,0,0,3.89842e-06,1.80899e-05,1.80813e-05,0.000110653,0.0318375,0.0318386,0.00795295,0.0426362,0.0426354,0.0568341,2.75179e-11,2.74966e-11,4.45032e-10,5.46799e-07,5.46653e-07,5.00008e-08,0,0,0,0,0,0,0,0 +34688000,0.983025,-0.00657239,-0.0115999,0.182989,-0.00420102,-0.0174998,1.76169,0.0806538,-0.012169,0.203656,-1.17327e-05,-4.50673e-05,6.73964e-07,4.33585e-07,-3.11196e-05,-0.000827589,0.203935,0.000817121,0.434565,0,0,0,0,0,3.88991e-06,1.82048e-05,1.81971e-05,0.000110423,0.0334864,0.0334881,0.00805708,0.04805,0.0480492,0.0565376,2.75649e-11,2.75441e-11,4.39927e-10,5.46801e-07,5.46657e-07,5.00004e-08,0,0,0,0,0,0,0,0 +34792000,0.983031,-0.00651671,-0.0113535,0.182973,-0.00384246,-0.0131026,2.76151,0.0826855,-0.00946103,0.3724,-1.17385e-05,-4.50426e-05,7.10082e-07,5.06645e-06,-4.13876e-05,-0.000792797,0.203935,0.000817121,0.434565,0,0,0,0,0,3.8868e-06,1.72168e-05,1.7209e-05,0.000110356,0.0288117,0.0288137,0.00808908,0.0429655,0.0429649,0.056098,2.73898e-11,2.73687e-11,4.34861e-10,5.28096e-07,5.27964e-07,5.00004e-08,0,0,0,0,0,0,0,0 +34888000,0.983034,-0.00649894,-0.0110772,0.182972,-0.00443789,-0.012478,3.70407,0.0822563,-0.0106193,0.651733,-1.1738e-05,-4.50423e-05,7.09197e-07,6.05765e-06,-4.20168e-05,-0.000788914,0.203935,0.000817121,0.434565,0,0,0,0,0,3.87801e-06,1.73301e-05,1.7323e-05,0.000110118,0.0305401,0.0305427,0.00821755,0.0481625,0.0481619,0.055841,2.74368e-11,2.74163e-11,4.29829e-10,5.28097e-07,5.27967e-07,5e-08,0,0,0,0,0,0,0,0 diff --git a/test/test_EKF_basics.cpp b/test/test_EKF_basics.cpp index ac36b61fa5..a1d989959e 100644 --- a/test/test_EKF_basics.cpp +++ b/test/test_EKF_basics.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2019 ECL Development Team. All rights reserved. + * Copyright (c) 2019-2020 ECL Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -51,7 +51,7 @@ class EkfBasicsTest : public ::testing::Test { // Duration of initalization with only providing baro,mag and IMU - const uint32_t _init_duration_s{2}; + const uint32_t _init_duration_s{3}; // Setup the Ekf with synthetic measurements void SetUp() override @@ -166,7 +166,7 @@ TEST_F(EkfBasicsTest, gpsFusion) TEST_F(EkfBasicsTest, accleBiasEstimation) { - // GIVEN: initialized EKF with default IMU, baro and mag input for 2s + // GIVEN: initialized EKF with default IMU, baro and mag input for 3s // WHEN: Added more sensor measurements with accel bias and gps measurements Vector3f accel_bias_sim = {0.0f,0.0f,0.1f}; @@ -181,8 +181,8 @@ TEST_F(EkfBasicsTest, accleBiasEstimation) Vector3f zero{0.0f, 0.0f, 0.0f}; // THEN: EKF should stay or converge to zero - EXPECT_TRUE(matrix::isEqual(pos, zero, 0.001f)); - EXPECT_TRUE(matrix::isEqual(vel, zero, 0.001f)); + EXPECT_TRUE(matrix::isEqual(pos, zero, 0.01f)); + EXPECT_TRUE(matrix::isEqual(vel, zero, 0.005f)); EXPECT_TRUE(matrix::isEqual(accel_bias, accel_bias_sim, 0.001f)); EXPECT_TRUE(matrix::isEqual(gyro_bias, zero, 0.001f)); }