EKF: allow initialising without mag depending on configuration

- reduce initial number of required mag and baro samples before init
This commit is contained in:
Daniel Agar
2020-11-02 17:13:14 -05:00
committed by Paul Riseborough
parent 1237087d70
commit 398fe159ce
6 changed files with 762 additions and 760 deletions
+19 -17
View File
@@ -158,37 +158,40 @@ bool Ekf::initialiseFilter()
// Sum the magnetometer measurements
if (_mag_buffer.pop_first_older_than(_imu_sample_delayed.time_us, &_mag_sample_delayed)) {
if (_mag_sample_delayed.time_us != 0) {
_mag_counter ++;
// wait for all bad initial data to be flushed
if (_mag_counter <= uint8_t(_obs_buffer_length + 1)) {
if (_mag_counter == 0) {
_mag_lpf.reset(_mag_sample_delayed.mag);
} else {
_mag_lpf.update(_mag_sample_delayed.mag);
}
_mag_counter++;
}
}
// accumulate enough height measurements to be confident in the quality of the data
if (_baro_buffer.pop_first_older_than(_imu_sample_delayed.time_us, &_baro_sample_delayed)) {
if (_baro_sample_delayed.time_us != 0) {
_baro_counter ++;
// wait for all bad initial data to be flushed
if (_baro_counter <= uint8_t(_obs_buffer_length + 1)) {
if (_baro_counter == 0) {
_baro_hgt_offset = _baro_sample_delayed.hgt;
} else if (_baro_counter > (uint8_t)(_obs_buffer_length + 1)) {
} else {
_baro_hgt_offset = 0.9f * _baro_hgt_offset + 0.1f * _baro_sample_delayed.hgt;
}
_baro_counter++;
}
}
const bool not_enough_baro_samples_accumulated = _baro_counter <= 2u * _obs_buffer_length;
const bool not_enough_mag_samples_accumulated = _mag_counter <= 2u * _obs_buffer_length;
if (_params.mag_fusion_type <= MAG_FUSE_TYPE_3D) {
if (_mag_counter < _obs_buffer_length) {
// not enough mag samples accumulated
return false;
}
}
if (not_enough_baro_samples_accumulated || not_enough_mag_samples_accumulated) {
if (_baro_counter < _obs_buffer_length) {
// not enough baro samples accumulated
return false;
}
@@ -233,8 +236,8 @@ bool Ekf::initialiseTilt()
const float accel_norm = _accel_lpf.getState().norm();
const float gyro_norm = _gyro_lpf.getState().norm();
if (accel_norm < 0.9f * CONSTANTS_ONE_G ||
accel_norm > 1.1f * CONSTANTS_ONE_G ||
if (accel_norm < 0.8f * CONSTANTS_ONE_G ||
accel_norm > 1.2f * CONSTANTS_ONE_G ||
gyro_norm > math::radians(15.0f)) {
return false;
}
@@ -244,8 +247,7 @@ bool Ekf::initialiseTilt()
const float pitch = asinf(gravity_in_body(0));
const float roll = atan2f(-gravity_in_body(1), -gravity_in_body(2));
const Eulerf euler_init(roll, pitch, 0.0f);
_state.quat_nominal = Quatf(euler_init);
_state.quat_nominal = Quatf{Eulerf{roll, pitch, 0.0f}};
_R_to_earth = Dcmf(_state.quat_nominal);
return true;
@@ -505,7 +507,7 @@ void Ekf::applyCorrectionToVerticalOutputBuffer(float vert_vel_correction)
* The vel and pos state history are corrected individually so they track the EKF states at
* the fusion time horizon. This option provides the most accurate tracking of EKF states.
*/
void Ekf::applyCorrectionToOutputBuffer(const Vector3f& vel_correction, const Vector3f& pos_correction)
void Ekf::applyCorrectionToOutputBuffer(const Vector3f &vel_correction, const Vector3f &pos_correction)
{
// loop through the output filter state history and apply the corrections to the velocity and position states
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
+3 -2
View File
@@ -347,9 +347,10 @@ void Ekf::resetHeight()
// align output filter states to match EKF states at the fusion time horizon
void Ekf::alignOutputFilter()
{
const outputSample output_delayed = _output_buffer.get_oldest();
const outputSample &output_delayed = _output_buffer.get_oldest();
// calculate the quaternion rotation delta from the EKF to output observer states at the EKF fusion time horizon
Quatf q_delta = _state.quat_nominal * output_delayed.quat_nominal.inversed();
Quatf q_delta{_state.quat_nominal * output_delayed.quat_nominal.inversed()};
q_delta.normalize();
// calculate the velocity and position deltas between the output and EKF at the EKF fusion time horizon
+1 -2
View File
@@ -50,8 +50,7 @@ void EstimatorInterface::setIMUData(const imuSample &imu_sample)
{
// TODO: resolve misplaced responsibility
if (!_initialised) {
init(imu_sample.time_us);
_initialised = true;
_initialised = init(imu_sample.time_us);
}
const float dt = math::constrain((imu_sample.time_us - _time_last_imu) / 1e6f, 1.0e-4f, 0.02f);
+388 -388
View File
@@ -1,391 +1,391 @@
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
15000,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
85000,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
185000,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
285000,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
385000,0.989603,-0.00857216,-0.0119078,0.143073,0.000133666,-0.000277178,-0.00414673,9.49438e-07,-2.44198e-06,-6.03039e-05,0,0,0,0,0,0,0.152965,0.00147309,0.410088,0,0,0,0,0,0.000102935,0.00248519,0.0024849,0.00489915,25.0004,25.0004,0.562573,0.259374,0.259374,4.00051,1e-06,1e-06,1e-06,0,0,4e-06,0,0,0,0,0,0,0,0
485000,0.873043,-0.00536963,-0.0150435,0.487382,0.0032852,-0.00268215,-0.0560697,0.000172131,-0.000145157,-0.0022496,2.10632e-08,2.20741e-06,-9.68587e-05,0,0,-1.10347e-09,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000100385,0.00250732,0.00250648,0.00321251,25.009,25.009,0.563297,0.609397,0.609397,0.802449,1e-06,1e-06,9.99306e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
585000,0.824127,-0.00455437,-0.0165729,0.566144,0.00699165,-0.00309858,-0.143324,0.000215882,-0.000108838,-0.0115127,1.22864e-07,7.37986e-06,-0.000290141,0,0,-3.82915e-08,0.145057,0.00139693,0.412416,0,0,0,0,0,8.31666e-05,0.00257636,0.00257509,0.00215765,7.81318,7.81318,0.564696,0.228164,0.228164,0.451649,1e-06,9.99996e-07,9.94631e-07,0,0,4e-06,0,0,0,0,0,0,0,0
685000,0.795498,-0.00413653,-0.0176833,0.605685,0.0171541,-0.00419003,-0.237402,0.00162021,-0.000502731,-0.0283793,3.22707e-07,1.41331e-05,-0.000523548,0,0,-3.07404e-07,0.145057,0.00139693,0.412416,0,0,0,0,0,9.50057e-05,0.0026951,0.00269348,0.00166608,7.85164,7.85165,0.564631,0.486038,0.486038,0.322081,1e-06,9.99986e-07,9.82817e-07,0,0,3.99989e-06,0,0,0,0,0,0,0,0
785000,0.776637,-0.0037867,-0.0186074,0.629662,0.0184876,-0.00234201,-0.31876,0.000927229,-0.000187065,-0.0544486,5.98717e-07,2.11077e-05,-0.000752349,0,0,-9.39324e-07,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000126298,0.00285709,0.00285512,0.00138078,2.59846,2.59847,0.565093,0.195718,0.195718,0.277167,9.99947e-07,9.99914e-07,9.61995e-07,0,0,3.99965e-06,0,0,0,0,0,0,0,0
885000,0.761537,-0.00356561,-0.0193954,0.647821,0.0309543,0.000136874,-0.394552,0.00363055,-0.000258594,-0.0989389,9.84626e-07,2.83689e-05,-0.000980539,0,0,-1.02684e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000172615,0.00307433,0.00307199,0.00119368,2.66011,2.66014,0.575936,0.329464,0.329464,0.30756,9.99947e-07,9.99882e-07,9.30419e-07,0,0,3.99966e-06,0,0,0,0,0,0,0,0
985000,0.750605,-0.00332776,-0.0200672,0.660438,0.0442467,0.00297509,-0.448454,0.0076697,-2.24434e-06,-0.148863,1.32346e-06,3.37909e-05,-0.00114481,0,0,-1.07041e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000237131,0.00334084,0.00333813,0.00110676,2.74789,2.74795,0.589654,0.517242,0.517244,0.349642,9.99947e-07,9.99848e-07,8.99523e-07,0,0,3.99967e-06,0,0,0,0,0,0,0,0
1085000,0.738766,-0.00312073,-0.0207373,0.673636,0.0469934,0.00631671,-0.502946,0.00644321,0.000519088,-0.206395,1.55343e-06,4.00967e-05,-0.00133222,0,0,-1.11788e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000303816,0.00362807,0.00362491,0.000998511,1.28895,1.28902,0.605335,0.244167,0.244168,0.403746,9.99313e-07,9.99157e-07,8.49714e-07,0,0,3.99968e-06,0,0,0,0,0,0,0,0
1185000,0.728138,-0.00293566,-0.0213864,0.68509,0.0619802,0.0103432,-0.544385,0.012204,0.0015029,-0.266853,1.94941e-06,4.54893e-05,-0.00148444,0,0,-1.13815e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000373673,0.00399142,0.00398771,0.000912053,1.41199,1.41211,0.623813,0.351605,0.351609,0.470375,9.99313e-07,9.99085e-07,7.92293e-07,0,0,3.99969e-06,0,0,0,0,0,0,0,0
1285000,0.718913,-0.00263894,-0.0218149,0.694753,0.0623883,0.0132016,-0.573057,0.0100819,0.00168317,-0.327915,1.31663e-06,4.88296e-05,-0.00158775,0,0,-1.18406e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000442006,0.00430784,0.00430363,0.000839067,0.88672,0.886854,0.64532,0.196911,0.196914,0.550125,9.95822e-07,9.95513e-07,7.29291e-07,0,0,3.99969e-06,0,0,0,0,0,0,0,0
1385000,0.710664,-0.00248824,-0.0223633,0.703171,0.077594,0.0194662,-0.593152,0.0172375,0.0034496,-0.389065,1.52808e-06,5.13907e-05,-0.00165592,0,0,-1.18834e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000504887,0.00476305,0.00475815,0.000775431,1.05403,1.05423,0.669981,0.273433,0.273443,0.643692,9.95821e-07,9.9542e-07,6.63746e-07,0,0,3.9997e-06,0,0,0,0,0,0,0,0
1485000,0.703484,-0.00215002,-0.0224526,0.710353,0.0746768,0.0216206,-0.610058,0.0138393,0.00326718,-0.450268,-1.08398e-06,5.13457e-05,-0.00168925,0,0,-1.27411e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000560261,0.0050028,0.00499758,0.000718738,0.81848,0.818678,0.697829,0.171176,0.171183,0.75185,9.83423e-07,9.82944e-07,5.98938e-07,0,0,3.9997e-06,0,0,0,0,0,0,0,0
1585000,0.697385,-0.00197633,-0.0228396,0.71633,0.0883755,0.0280848,-0.623672,0.0219981,0.00573443,-0.511978,-1.07812e-06,5.14128e-05,-0.00169099,0,0,-1.27415e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000629453,0.00553687,0.00553094,0.000692817,1.03667,1.03695,0.728778,0.237839,0.237856,0.875451,9.83423e-07,9.82875e-07,5.5197e-07,0,0,3.99971e-06,0,0,0,0,0,0,0,0
1685000,0.693162,-0.00146275,-0.0223927,0.720433,0.0810576,0.0296606,-0.635863,0.0168264,0.00492085,-0.575307,-7.04487e-06,4.68718e-05,-0.00164827,0,0,-1.42489e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000667764,0.00552227,0.00551657,0.000643773,0.882656,0.882892,0.762581,0.159426,0.159437,1.01538,9.51599e-07,9.51006e-07,4.92619e-07,0,0,3.9997e-06,0,0,0,0,0,0,0,0
1785000,0.688801,-0.0012436,-0.0227101,0.724593,0.0949689,0.0378508,-0.651971,0.0254986,0.00819823,-0.640843,-7.14823e-06,4.55646e-05,-0.0016127,0,0,-1.42454e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000696221,0.00610853,0.00610208,0.000599744,1.14829,1.14861,0.799277,0.226764,0.226788,1.17259,9.51598e-07,9.50932e-07,4.38039e-07,0,0,3.99971e-06,0,0,0,0,0,0,0,0
1885000,0.684729,-0.000443559,-0.0216395,0.728476,0.0788938,0.0367569,-0.669842,0.0183086,0.00659167,-0.709709,-1.68846e-05,3.90306e-05,-0.00157486,0,0,-1.63824e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000716372,0.00566002,0.00565468,0.000558894,0.971056,0.971275,0.838384,0.156213,0.156226,1.34801,8.9045e-07,8.89804e-07,3.88834e-07,0,0,3.9997e-06,0,0,0,0,0,0,0,0
1985000,0.681947,-0.000266737,-0.0218138,0.731076,0.0893574,0.0446547,-0.692518,0.0265368,0.0106216,-0.78457,-1.70013e-05,3.70254e-05,-0.00151333,0,0,-1.63922e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000728971,0.00625746,0.00625151,0.000522792,1.26603,1.26632,0.879927,0.228245,0.228272,1.54267,8.9045e-07,8.89758e-07,3.44909e-07,0,0,3.99971e-06,0,0,0,0,0,0,0,0
2085000,0.680376,0.000644228,-0.0202761,0.732582,0.0666931,0.0377439,-0.72217,0.017395,0.00772231,-0.867867,-2.91839e-05,2.7456e-05,-0.00143551,0,0,-1.87274e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000735499,0.00535096,0.00534671,0.000488751,1.01071,1.01088,0.923402,0.156001,0.156013,1.75747,8.00793e-07,8.00185e-07,3.061e-07,0,0,3.99969e-06,0,0,0,0,0,0,0,0
2185000,0.678162,0.00086873,-0.0207403,0.734619,0.0760968,0.0486686,-0.751552,0.0249739,0.0127309,-0.953968,-2.77314e-05,2.79212e-05,-0.0013773,0,0,-1.90259e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000736905,0.00591738,0.00591035,0.000459,1.30832,1.30845,0.969067,0.231498,0.231514,1.99361,8.00704e-07,8.00061e-07,2.71967e-07,0,0,3.9997e-06,0,0,0,0,0,0,0,0
2285000,0.67637,0.0016509,-0.0198491,0.736292,0.0578561,0.0471775,-0.785207,0.0169127,0.0104879,-1.04757,-3.49864e-05,2.40597e-05,-0.00131793,0,0,-2.23399e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00076091,0.00474262,0.00473467,0.000442516,0.980676,0.980576,1.0171,0.154526,0.154524,2.25259,6.96344e-07,6.95866e-07,2.48965e-07,0,0,3.9997e-06,0,0,0,0,0,0,0,0
2385000,0.674997,0.00190538,-0.0208074,0.737524,0.0715387,0.0643129,-0.820814,0.0253434,0.0183526,-1.14865,-2.99038e-05,2.87089e-05,-0.00125678,0,0,-2.36882e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000754766,0.00525084,0.00523782,0.00041633,1.25711,1.25677,1.06644,0.229664,0.229641,2.53466,6.96157e-07,6.9571e-07,2.21911e-07,0,0,3.99971e-06,0,0,0,0,0,0,0,0
2485000,0.673831,0.00247058,-0.0193836,0.738627,0.0489537,0.0531012,-0.859331,0.0159946,0.0129955,-1.2581,-3.82934e-05,2.01397e-05,-0.00119881,0,0,-2.66523e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00074613,0.00405847,0.00404952,0.00039186,0.90194,0.90167,1.11688,0.150391,0.150377,2.841,5.93715e-07,5.93485e-07,1.98329e-07,0,0,3.99971e-06,0,0,0,0,0,0,0,0
2585000,0.67405,0.00270029,-0.0202287,0.738403,0.0591248,0.0693035,-0.912298,0.0231822,0.0211813,-1.3864,-3.34327e-05,2.34881e-05,-0.00112301,0,0,-2.83052e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000735856,0.00450115,0.00448976,0.000370633,1.147,1.14655,1.16912,0.221802,0.221765,3.17313,5.9363e-07,5.93445e-07,1.77739e-07,0,0,3.99972e-06,0,0,0,0,0,0,0,0
2685000,0.673166,0.00303506,-0.0186818,0.739249,0.0365361,0.0527507,-0.956886,0.0138935,0.013784,-1.5129,-4.14168e-05,1.27258e-05,-0.00107217,0,0,-3.03108e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000723504,0.00344478,0.00343813,0.000350862,0.807576,0.807311,1.22223,0.144248,0.144233,3.53164,5.0222e-07,5.02173e-07,1.59679e-07,0,0,3.99972e-06,0,0,0,0,0,0,0,0
2785000,0.673236,0.0033343,-0.0192003,0.739171,0.0426704,0.0650539,-1.01101,0.0188759,0.020817,-1.65732,-3.83548e-05,1.40911e-05,-0.00101102,0,0,-3.14948e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000711001,0.00382697,0.00381912,0.00033346,1.02014,1.01976,1.27693,0.210221,0.210187,3.91832,5.02181e-07,5.02165e-07,1.43921e-07,0,0,3.99973e-06,0,0,0,0,0,0,0,0
2885000,0.672047,0.00342885,-0.0178013,0.740287,0.0239806,0.0477436,-1.05215,0.0109054,0.0130033,-1.79343,-4.48691e-05,3.58368e-06,-0.000974493,0,0,-3.24004e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00071867,0.00294694,0.00294259,0.000324621,0.717308,0.717097,1.33456,0.137218,0.137205,4.33665,4.2379e-07,4.23828e-07,1.3334e-07,0,0,3.99974e-06,0,0,0,0,0,0,0,0
2985000,0.672029,0.00366362,-0.0180856,0.740295,0.0262658,0.0581709,-1.10972,0.0139879,0.0189646,-1.95383,-4.28147e-05,4.03277e-06,-0.000923281,0,0,-3.32156e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000704067,0.00327739,0.00327241,0.000309483,0.902317,0.902016,1.39173,0.197428,0.197399,4.78303,4.2377e-07,4.23827e-07,1.20747e-07,0,0,3.99975e-06,0,0,0,0,0,0,0,0
3085000,0.672519,0.00386688,-0.0184229,0.739841,0.0293609,0.0681637,-1.17314,0.0175458,0.0261732,-2.13121,-4.05722e-05,4.56187e-06,-0.000869679,0,0,-3.40309e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000689255,0.0036289,0.00362324,0.000295657,1.12185,1.12144,1.44986,0.282398,0.282345,5.26086,4.23751e-07,4.23826e-07,1.0963e-07,0,0,3.99976e-06,0,0,0,0,0,0,0,0
3185000,0.672636,0.00377716,-0.0172142,0.739763,0.0123418,0.0505563,-1.23388,0.00968653,0.016983,-2.3112,-4.48912e-05,-5.05414e-06,-0.000826235,0,0,-3.4305e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00067372,0.00284128,0.0028381,0.000282826,0.802527,0.802299,1.50871,0.185026,0.185003,5.771,3.56999e-07,3.57083e-07,9.97812e-08,0,0,3.99977e-06,0,0,0,0,0,0,0,0
3285000,0.672686,0.00396283,-0.0174048,0.739713,0.0127302,0.0593761,-1.29365,0.0113083,0.022939,-2.50031,-4.34474e-05,-4.95429e-06,-0.000785643,0,0,-3.47666e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000659075,0.00314584,0.00314228,0.000271159,0.995069,0.994764,1.56875,0.261925,0.261883,6.31539,3.56988e-07,3.57083e-07,9.10672e-08,0,0,3.99978e-06,0,0,0,0,0,0,0,0
3385000,0.673281,0.00385424,-0.0164498,0.739194,0.0019349,0.0440225,-1.36316,0.00581985,0.0150133,-2.70991,-4.56688e-05,-1.31079e-05,-0.000742195,0,0,-3.46299e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00064399,0.00248962,0.00248755,0.000260301,0.720692,0.720523,1.62944,0.173713,0.173695,6.89463,2.99793e-07,2.99876e-07,8.32982e-08,0,0,3.99979e-06,0,0,0,0,0,0,0,0
3485000,0.674003,0.00404082,-0.0166142,0.738531,0.00178498,0.0517378,-1.43517,0.00625674,0.0201685,-2.93352,-4.43192e-05,-1.31993e-05,-0.000699927,0,0,-3.4945e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000629805,0.0027539,0.00275158,0.000250398,0.89154,0.89132,1.69127,0.243704,0.243672,7.51063,2.99786e-07,2.99876e-07,7.63928e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
3585000,0.673473,0.00381202,-0.0158731,0.739032,-0.0043401,0.0377591,-1.48621,0.00282433,0.0131368,-3.13438,-4.54648e-05,-2.00601e-05,-0.000675457,0,0,-3.44807e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000631129,0.00219541,0.00219401,0.000245431,0.653596,0.653479,1.75731,0.163654,0.163641,8.1721,2.5043e-07,2.50502e-07,7.16654e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
3685000,0.674036,0.00397304,-0.0159874,0.738515,-0.00509734,0.0440246,-1.55893,0.00248277,0.0175182,-3.37604,-4.43947e-05,-2.02243e-05,-0.000639127,0,0,-3.46319e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000616849,0.0024243,0.00242273,0.000236562,0.806662,0.806512,1.82096,0.22781,0.227786,8.86575,2.50425e-07,2.50501e-07,6.59746e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
3785000,0.674842,0.00367256,-0.0155035,0.73779,-0.00757749,0.0331376,-1.63529,0.00073607,0.0115664,-3.63464,-4.40305e-05,-2.60436e-05,-0.000603184,0,0,-3.41564e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000602528,0.00193924,0.00193822,0.000228266,0.597218,0.59714,1.8852,0.154758,0.154747,9.59968,2.07729e-07,2.07786e-07,6.08491e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
3885000,0.675562,0.00385368,-0.0154905,0.73713,-0.0103391,0.0370677,-1.71012,-8.54303e-05,0.0153019,-3.8997,-4.31137e-05,-2.62207e-05,-0.000570974,0,0,-3.41947e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000589028,0.00213653,0.0021354,0.000220645,0.734947,0.734846,1.95043,0.213938,0.213921,10.3756,2.07725e-07,2.07786e-07,5.62515e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
3985000,0.676076,0.00361358,-0.0150409,0.73667,-0.0124243,0.0286208,-1.78135,-0.000858018,0.010098,-4.169,-4.21982e-05,-3.11085e-05,-0.000542874,0,0,-3.36729e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000575491,0.00170941,0.00170864,0.000213436,0.548215,0.54816,2.0162,0.146832,0.146824,11.1944,1.7093e-07,1.70974e-07,5.20768e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
4085000,0.676733,0.00369168,-0.0150365,0.736066,-0.0146068,0.0332205,-1.85517,-0.00219148,0.0133897,-4.45371,-4.14169e-05,-3.12986e-05,-0.000515045,0,0,-3.36189e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000562839,0.0018783,0.00187744,0.000206779,0.672175,0.672105,2.08284,0.201677,0.201665,12.058,1.70927e-07,1.70974e-07,4.83236e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
4185000,0.676679,0.00338446,-0.0147014,0.736124,-0.0141219,0.025778,-1.91293,-0.00211361,0.00893692,-4.7177,-4.01867e-05,-3.53782e-05,-0.000496504,0,0,-3.31429e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000562545,0.0015,0.00149939,0.000203546,0.50398,0.503943,2.15478,0.139678,0.139673,12.982,1.39502e-07,1.39533e-07,4.57232e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
4285000,0.677471,0.00350782,-0.0147428,0.735393,-0.0185235,0.0294048,-1.98963,-0.00369886,0.0118777,-5.02731,-3.94678e-05,-3.55753e-05,-0.000470546,0,0,-3.30301e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000550124,0.00164347,0.00164278,0.000197523,0.615433,0.615384,2.22293,0.190644,0.190635,13.9401,1.395e-07,1.39533e-07,4.25535e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
4385000,0.67843,0.00320133,-0.0145229,0.734515,-0.0180995,0.0221424,-2.07311,-0.0031214,0.00800394,-5.35801,-3.76293e-05,-3.91136e-05,-0.000444182,0,0,-3.25554e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000537829,0.00130879,0.00130828,0.000191787,0.46302,0.462993,2.29167,0.133124,0.13312,14.9466,1.12991e-07,1.13011e-07,3.96521e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
4485000,0.678847,0.0033097,-0.0145121,0.734129,-0.0210447,0.0245552,-2.14364,-0.00509011,0.0104889,-5.6742,-3.70707e-05,-3.92788e-05,-0.000424061,0,0,-3.24206e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000526291,0.00142972,0.00142915,0.000186435,0.563061,0.563028,2.3613,0.180532,0.180525,16.0039,1.12989e-07,1.13011e-07,3.70229e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
4585000,0.679696,0.00295496,-0.014398,0.733347,-0.0186622,0.0196752,-2.22542,-0.00393227,0.00709342,-6.02296,-3.50454e-05,-4.22469e-05,-0.000401298,0,0,-3.20017e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000514875,0.00113538,0.00113493,0.000181344,0.42475,0.424732,2.4314,0.127043,0.12704,17.1125,9.09303e-08,9.09433e-08,3.46059e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
4685000,0.680583,0.00301114,-0.0143872,0.732523,-0.0202887,0.0221621,-2.30705,-0.00588814,0.00937948,-6.38377,-3.44384e-05,-4.24383e-05,-0.000379542,0,0,-3.18098e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000504097,0.00123661,0.00123611,0.000176603,0.513937,0.513916,2.50231,0.171148,0.171143,18.2748,9.09287e-08,9.09432e-08,3.24066e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
4785000,0.680992,0.00264364,-0.0143127,0.732146,-0.0171015,0.0167532,-2.37557,-0.00429667,0.00633029,-6.72678,-3.25319e-05,-4.48974e-05,-0.000363356,0,0,-3.14504e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000493473,0.000979857,0.000979469,0.000172072,0.388659,0.388649,2.57373,0.12135,0.121348,19.4914,7.28172e-08,7.28244e-08,3.03777e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
4885000,0.681257,0.00269074,-0.0143351,0.731899,-0.0184823,0.0187656,-2.43901,-0.0060845,0.0082642,-7.06867,-3.21386e-05,-4.50273e-05,-0.000349277,0,0,-3.13032e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00049268,0.00106412,0.00106368,0.000170022,0.467971,0.467959,2.6515,0.162353,0.16235,20.7894,7.28162e-08,7.28244e-08,2.89698e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
4985000,0.681765,0.00245219,-0.0142384,0.731429,-0.0158401,0.0149598,-2.50951,-0.00430745,0.00562811,-7.43485,-3.03498e-05,-4.70806e-05,-0.000333984,0,0,-3.09296e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000482393,0.000842151,0.000841811,0.000165857,0.354845,0.354838,2.72425,0.11599,0.115988,22.1215,5.81213e-08,5.81241e-08,2.72172e-08,0,0,3.9998e-06,0,0,0,0,0,0,0,0
5085000,0.682549,0.00247674,-0.0142814,0.730696,-0.0178727,0.0163651,-2.59012,-0.00598819,0.00736801,-7.83341,-2.98653e-05,-4.72601e-05,-0.000316654,0,0,-3.07141e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000472642,0.000912001,0.000911617,0.00016193,0.425065,0.425056,2.79779,0.154082,0.15408,23.5135,5.81201e-08,5.8124e-08,2.56104e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
5185000,0.683383,0.00251131,-0.014262,0.729916,-0.019224,0.0185348,-2.67124,-0.00779792,0.00931152,-8.24667,-2.93849e-05,-4.74249e-05,-0.000299795,0,0,-3.04927e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000463195,0.000984755,0.000984327,0.000158199,0.505162,0.50515,2.87186,0.203981,0.203978,24.9665,5.8119e-08,5.8124e-08,2.41257e-08,0,0,3.99982e-06,0,0,0,0,0,0,0,0
5285000,0.684196,0.00227379,-0.0142075,0.729156,-0.0163739,0.0124089,-2.75125,-0.00569043,0.00644643,-8.66705,-2.77315e-05,-4.91776e-05,-0.000284213,0,0,-3.00532e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00045391,0.000779433,0.0007791,0.000154631,0.385225,0.385219,2.94645,0.146294,0.146292,26.4813,4.63126e-08,4.63134e-08,2.27471e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
5385000,0.684549,0.00240329,-0.0142048,0.728824,-0.0178114,0.0122244,-2.81623,-0.00739156,0.00779035,-9.06342,-2.74018e-05,-4.93081e-05,-0.000272628,0,0,-2.98733e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000445101,0.000839494,0.000839124,0.000151252,0.455695,0.455689,3.02182,0.192334,0.192331,28.0611,4.63116e-08,4.63133e-08,2.14771e-08,0,0,3.99982e-06,0,0,0,0,0,0,0,0
5485000,0.684711,0.00222181,-0.014148,0.728674,-0.0145457,0.00794831,-2.87212,-0.00537066,0.0051244,-9.4489,-2.60773e-05,-5.06334e-05,-0.000263399,0,0,-2.95134e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000444003,0.000665095,0.000664809,0.000149755,0.348643,0.348639,3.10384,0.138971,0.13897,29.7421,3.68972e-08,3.68957e-08,2.05812e-08,0,0,3.99981e-06,0,0,0,0,0,0,0,0
5585000,0.685244,0.00225001,-0.014113,0.728174,-0.0163413,0.00865131,-2.94143,-0.00691855,0.00607097,-9.87277,-2.57504e-05,-5.07776e-05,-0.000251889,0,0,-2.93089e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000435446,0.000714624,0.000714307,0.000146625,0.410516,0.410511,3.18045,0.181429,0.181427,31.4568,3.68964e-08,3.68956e-08,1.94659e-08,0,0,3.99982e-06,0,0,0,0,0,0,0,0
5685000,0.685589,0.0021151,-0.0140507,0.72785,-0.0144422,0.00520435,-3.00682,-0.00508099,0.0040031,-10.2944,-2.45466e-05,-5.17811e-05,-0.000241854,0,0,-2.89389e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000427094,0.000567284,0.000567041,0.000143587,0.315452,0.315448,3.25753,0.132105,0.132104,33.2397,2.94278e-08,2.9425e-08,1.84254e-08,0,0,3.99982e-06,0,0,0,0,0,0,0,0
5785000,0.685971,0.0021878,-0.0140129,0.727491,-0.017225,0.00546744,-0.00307082,-0.00663488,0.00461389,-365.429,-2.42774e-05,-5.19113e-05,-0.00023238,0,0,-2.8746e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000419096,0.000608134,0.000607866,0.000140723,0.369673,0.369667,9.99881,0.171265,0.171263,2.00225,2.94271e-08,2.94249e-08,1.74605e-08,0,0,3.99983e-06,0,0,0,0,0,0,0,0
5885000,0.686391,0.0020374,-0.0140071,0.727095,-0.0148974,0.00371742,-0.00663697,-0.00499634,0.00304435,-365.42,-2.31925e-05,-5.26527e-05,-0.000223035,0,0,-2.86764e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.00041127,0.000484106,0.0004839,0.000137961,0.285283,0.285277,9.74018,0.125684,0.125683,0.709952,2.35201e-08,2.35165e-08,1.65582e-08,0,0,3.99983e-06,0,0,0,0,0,0,0,0
5985000,0.686838,0.00208672,-0.0140049,0.726673,-0.0180418,0.00383239,0.001181,-0.00665473,0.00350939,-365.403,-2.29297e-05,-5.27882e-05,-0.000213766,0,0,-2.95092e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000403782,0.000517838,0.000517612,0.000135331,0.332928,0.33292,8.84143,0.16181,0.161809,0.518932,2.35196e-08,2.35165e-08,1.57192e-08,0,0,3.99982e-06,0,0,0,0,0,0,0,0
6085000,0.6875,0.00195993,-0.0140139,0.726046,-0.0162914,0.00296948,-0.0178643,-0.00515058,0.00235926,-365.405,-2.18709e-05,-5.33722e-05,-0.000203461,0,0,-2.89253e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000396449,0.000413668,0.000413494,0.000132797,0.258195,0.258188,7.29172,0.11969,0.119689,0.482378,1.8854e-08,1.885e-08,1.4933e-08,0,0,3.99973e-06,0,0,0,0,0,0,0,0
6185000,0.687679,0.00191575,-0.013985,0.725877,-0.0192131,0.00269257,-0.0197431,-0.00691727,0.00271576,-365.402,-2.16994e-05,-5.34641e-05,-0.000197396,0,0,-3.04775e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000395352,0.000441583,0.000441391,0.000131782,0.3,0.299991,5.97241,0.153046,0.153045,0.538038,1.88536e-08,1.885e-08,1.43778e-08,0,0,3.99958e-06,0,0,0,0,0,0,0,0
6285000,0.688282,0.00177952,-0.0140432,0.725305,-0.0161119,0.00242873,-0.0199419,-0.00534824,0.00186943,-365.397,-2.07085e-05,-5.39168e-05,-0.000188315,0,0,-3.27844e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000388239,0.000354168,0.00035402,0.000129406,0.233927,0.233919,4.38238,0.114107,0.114106,0.517119,1.51678e-08,1.51636e-08,1.36775e-08,0,0,3.99922e-06,0,0,0,0,0,0,0,0
6385000,0.68893,0.00183978,-0.0139509,0.724691,-0.0179162,0.00275739,-0.0551852,-0.00703114,0.00221778,-365.409,-2.04489e-05,-5.40631e-05,-0.000179138,0,0,-2.91488e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.0003814,0.000377325,0.000377165,0.000127133,0.270687,0.270677,3.16523,0.144941,0.14494,0.486049,1.51674e-08,1.51635e-08,1.30228e-08,0,0,3.99868e-06,0,0,0,0,0,0,0,0
6485000,0.689452,0.00175066,-0.0140663,0.724192,-0.015116,0.00191415,-0.0617157,-0.00537219,0.00155968,-365.41,-1.95459e-05,-5.4432e-05,-0.000171206,0,0,-3.29939e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000374704,0.000303954,0.00030383,0.000124939,0.212189,0.21218,2.28878,0.108913,0.108912,0.448584,1.22515e-08,1.22473e-08,1.24071e-08,0,0,3.99788e-06,0,0,0,0,0,0,0,0
6585000,0.689751,0.00175025,-0.0140708,0.723908,-0.0160327,0.00181654,-0.103523,-0.00686866,0.00180366,-365.433,-1.93814e-05,-5.45276e-05,-0.000165411,0,0,-2.27038e-06,0.145057,0.00139693,0.412416,0,0,0,0,0,0.000368189,0.00032323,0.000323094,0.000122852,0.24457,0.24456,1.6784,0.137451,0.13745,0.410712,1.22511e-08,1.22473e-08,1.18286e-08,0,0,3.99679e-06,0,0,0,0,0,0,0,0
6685000,0.704438,0.0013807,-0.0141441,0.709623,-0.0126404,0.00144579,-0.0877564,-0.00516254,0.00124274,-365.422,-1.8654e-05,-5.47813e-05,-0.000160794,0,0,-4.38969e-06,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00144739,0.000260445,0.000259909,0.00121714,0.190139,0.19013,1.25898,0.104083,0.104082,0.376614,9.93918e-09,9.93512e-09,1.14158e-08,0,0,3.99532e-06,0,0,0,0,0,0,0,0
6785000,0.704885,0.00137156,-0.014111,0.70918,-0.0140215,0.000900028,-0.122135,-0.00649166,0.00137702,-365.447,-1.8649e-05,-5.4784e-05,-0.000160689,0,0,-2.86484e-06,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00109915,0.000260667,0.000260259,0.0009244,0.191922,0.191912,1.02818,0.129598,0.129596,0.379444,9.93927e-09,9.93521e-09,1.14121e-08,0,0,3.99392e-06,0,0,0,0,0,0,0,0
6885000,0.704136,0.00138548,-0.0140415,0.709924,-0.0136586,0.000177781,-0.128743,-0.00499294,0.000899876,-365.453,-1.81348e-05,-5.49054e-05,-0.000160729,0,0,-3.60625e-06,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00083927,0.000261063,0.000260751,0.000706747,0.137222,0.137215,0.79864,0.0979423,0.0979413,0.347412,8.16361e-09,8.15934e-09,1.14051e-08,0,0,3.9915e-06,0,0,0,0,0,0,0,0
6985000,0.703424,0.00145336,-0.0140073,0.710631,-0.0140832,0.000640705,-0.135016,-0.00639625,0.000963651,-365.46,-1.81382e-05,-5.49037e-05,-0.000160808,0,0,-4.75233e-06,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000684073,0.000262057,0.000261801,0.000576955,0.144019,0.144012,0.633741,0.118779,0.118778,0.319461,8.16369e-09,8.15944e-09,1.13973e-08,0,0,3.98828e-06,0,0,0,0,0,0,0,0
7085000,0.702308,0.0014451,-0.0139916,0.711734,-0.0123993,-0.000647408,-0.131771,-0.00500258,0.000608756,-365.458,-1.76978e-05,-5.49773e-05,-0.000161031,0,0,-7.6544e-06,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000581021,0.00026167,0.000261451,0.000490833,0.111855,0.11185,0.514682,0.0908423,0.0908413,0.295665,6.85774e-09,6.85341e-09,1.13875e-08,0,0,3.98415e-06,0,0,0,0,0,0,0,0
7185000,0.701912,0.0014537,-0.0139377,0.712126,-0.0145538,-0.00119025,-0.151432,-0.00634285,0.000532112,-365.476,-1.76951e-05,-5.49786e-05,-0.000160966,0,0,-6.6746e-06,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000507619,0.000262991,0.000262799,0.000429679,0.12282,0.122816,0.426916,0.108384,0.108382,0.274884,6.85782e-09,6.85351e-09,1.13764e-08,0,0,3.97879e-06,0,0,0,0,0,0,0,0
7285000,0.7017,0.00147235,-0.0138803,0.712336,-0.0162872,-0.00137467,-0.151912,-0.00788352,0.0003876,-365.477,-1.76971e-05,-5.49774e-05,-0.000160945,0,0,-1.07183e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00045279,0.000264661,0.000264489,0.000384053,0.136303,0.136299,0.362166,0.128725,0.128723,0.257075,6.8579e-09,6.8536e-09,1.13636e-08,0,0,3.97204e-06,0,0,0,0,0,0,0,0
7385000,0.70137,0.00146212,-0.0138616,0.712661,-0.014355,-0.000682973,-0.161798,-0.00658226,0.000170294,-365.489,-1.72942e-05,-5.50174e-05,-0.000160884,0,0,-1.24342e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000410296,0.000261246,0.000261089,0.000348797,0.118413,0.118413,0.313697,0.100086,0.100085,0.241455,5.90074e-09,5.89645e-09,1.13483e-08,0,0,3.9635e-06,0,0,0,0,0,0,0,0
7485000,0.701247,0.00152335,-0.0137933,0.712784,-0.0162934,-0.000839486,-0.167818,-0.00812962,0.000108627,-365.497,-1.72908e-05,-5.50194e-05,-0.000160714,0,0,-1.58442e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000384636,0.000262866,0.000262719,0.00032753,0.135199,0.135201,0.288934,0.118551,0.118549,0.241776,5.90082e-09,5.89655e-09,1.13354e-08,0,0,3.95572e-06,0,0,0,0,0,0,0,0
7585000,0.701215,0.00149016,-0.0137452,0.712816,-0.0158046,-0.000321018,-0.171899,-0.00684865,2.35484e-05,-365.503,-1.69185e-05,-5.50461e-05,-0.00016043,0,0,-2.1388e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000355681,0.00025474,0.000254606,0.000303665,0.123715,0.12372,0.260044,0.0943152,0.0943142,0.228517,5.1993e-09,5.19509e-09,1.13159e-08,0,0,3.94325e-06,0,0,0,0,0,0,0,0
7685000,0.700892,0.00156641,-0.0136774,0.713135,-0.017965,-0.000244637,-0.1681,-0.00855498,9.25826e-07,-365.499,-1.6922e-05,-5.50455e-05,-0.000160383,0,0,-3.31519e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000331759,0.000256094,0.000255968,0.000284051,0.143102,0.143109,0.23878,0.112202,0.112201,0.217154,5.19937e-09,5.19518e-09,1.12939e-08,0,0,3.92824e-06,0,0,0,0,0,0,0,0
7785000,0.700359,0.00153733,-0.0137302,0.713657,-0.016668,0.000294973,-0.166576,-0.00731456,3.32299e-06,-365.498,-1.65928e-05,-5.50596e-05,-0.000160516,0,0,-4.43513e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000311647,0.000241902,0.000241785,0.000267691,0.133409,0.133419,0.223131,0.0909311,0.0909308,0.207244,4.69304e-09,4.68895e-09,1.12685e-08,0,0,3.91006e-06,0,0,0,0,0,0,0,0
7885000,0.700227,0.00155643,-0.0137322,0.713787,-0.0194186,0.00147926,-0.164808,-0.00912385,9.89445e-05,-365.495,-1.65878e-05,-5.50641e-05,-0.000160186,0,0,-5.88925e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000294502,0.000242871,0.000242759,0.000253874,0.154511,0.154524,0.211835,0.109114,0.109114,0.198625,4.69311e-09,4.68904e-09,1.12399e-08,0,0,3.88837e-06,0,0,0,0,0,0,0,0
7985000,0.700087,0.00152408,-0.0137601,0.713924,-0.018015,0.0020018,-0.171152,-0.00782371,0.00020131,-365.502,-1.62692e-05,-5.50923e-05,-0.000159693,0,0,-6.65339e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000279728,0.000222226,0.000222123,0.000242059,0.143191,0.143205,0.204034,0.0894533,0.0894539,0.191306,4.34195e-09,4.338e-09,1.12077e-08,0,0,3.86303e-06,0,0,0,0,0,0,0,0
8085000,0.699924,0.00151132,-0.0137498,0.714083,-0.019857,0.00273893,-0.183199,-0.00973548,0.000459462,-365.518,-1.62517e-05,-5.51025e-05,-0.000159074,0,0,-6.85521e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000270514,0.000222782,0.000222682,0.000234794,0.164947,0.164964,0.204647,0.108381,0.108382,0.194116,4.34202e-09,4.33809e-09,1.11812e-08,0,0,3.84145e-06,0,0,0,0,0,0,0,0
8185000,0.699519,0.0014276,-0.0137787,0.714479,-0.018676,0.00345243,-0.188425,-0.00816942,0.000576049,-365.526,-1.5983e-05,-5.51334e-05,-0.000158905,0,0,-7.94094e-05,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000258846,0.000196701,0.000196609,0.000225641,0.149701,0.149718,0.201091,0.0891759,0.0891776,0.188308,4.11447e-09,4.11066e-09,1.11422e-08,0,0,3.80879e-06,0,0,0,0,0,0,0,0
8285000,0.699264,0.00146217,-0.0138254,0.714728,-0.019942,0.00358094,-0.184673,-0.0101674,0.000944614,-365.523,-1.59746e-05,-5.514e-05,-0.000158497,0,0,-0.000102378,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000248507,0.000196903,0.000196814,0.000217626,0.171067,0.171087,0.199012,0.108889,0.108892,0.18338,4.11453e-09,4.11075e-09,1.10989e-08,0,0,3.77159e-06,0,0,0,0,0,0,0,0
8385000,0.699055,0.0014328,-0.0138719,0.714932,-0.0175171,0.00383804,-0.182319,-0.00834807,0.000957637,-365.521,-1.57414e-05,-5.51848e-05,-0.000157769,0,0,-0.00012503,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000239291,0.000167709,0.000167631,0.000210528,0.150993,0.151011,0.198094,0.0893233,0.0893259,0.179353,3.98068e-09,3.977e-09,1.10513e-08,0,0,3.73007e-06,0,0,0,0,0,0,0,0
8485000,0.698712,0.00142104,-0.0138806,0.715267,-0.0188761,0.00459043,-0.179339,-0.0102555,0.00137268,-365.52,-1.57284e-05,-5.51937e-05,-0.000157252,0,0,-0.000148862,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000231001,0.00016769,0.000167613,0.00020421,0.170993,0.171015,0.197814,0.109536,0.109541,0.175989,3.98073e-09,3.97709e-09,1.09989e-08,0,0,3.68398e-06,0,0,0,0,0,0,0,0
8585000,0.698377,0.00136009,-0.013899,0.715594,-0.016556,0.00563078,-0.177416,-0.0082619,0.00131149,-365.52,-1.55597e-05,-5.52315e-05,-0.000156812,0,0,-0.000172116,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000223473,0.000138308,0.000138244,0.000198567,0.146723,0.146741,0.197984,0.089237,0.0892402,0.173312,3.91141e-09,3.90787e-09,1.09419e-08,0,0,3.63382e-06,0,0,0,0,0,0,0,0
8685000,0.698347,0.00140618,-0.0138521,0.715624,-0.0189073,0.00613671,-0.169542,-0.0100868,0.00190363,-365.513,-1.55221e-05,-5.52548e-05,-0.00015547,0,0,-0.00020609,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000216623,0.000138231,0.000138169,0.000193471,0.164683,0.164704,0.198194,0.109481,0.109487,0.171103,3.91146e-09,3.90796e-09,1.08799e-08,0,0,3.57955e-06,0,0,0,0,0,0,0,0
8785000,0.697901,0.00125287,-0.0138762,0.716058,-0.0161308,0.00653713,-0.165173,-0.00805508,0.00173621,-365.511,-1.54101e-05,-5.52856e-05,-0.000155183,0,0,-0.000231824,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000212642,0.000111244,0.000111193,0.000190721,0.137861,0.137876,0.203511,0.0885189,0.0885225,0.176877,3.88115e-09,3.87772e-09,1.08299e-08,0,0,3.53626e-06,0,0,0,0,0,0,0,0
8885000,0.697667,0.00128774,-0.0138838,0.716287,-0.0172077,0.00680158,-0.163548,-0.00977927,0.00243726,-365.512,-1.53855e-05,-5.53006e-05,-0.000154331,0,0,-0.00025533,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000206779,0.00011127,0.00011122,0.00018643,0.153449,0.153467,0.203304,0.1083,0.108305,0.175319,3.88119e-09,3.8778e-09,1.07588e-08,0,0,3.47595e-06,0,0,0,0,0,0,0,0
8985000,0.697398,0.00124372,-0.0139036,0.716548,-0.0142891,0.00561456,-0.15447,-0.00768514,0.00205229,-365.504,-1.53011e-05,-5.53324e-05,-0.000153494,0,0,-0.000290075,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000201389,8.82923e-05,8.82548e-05,0.000182501,0.126073,0.126086,0.202731,0.0870468,0.0870505,0.174111,3.87081e-09,3.86749e-09,1.06825e-08,0,0,3.41335e-06,0,0,0,0,0,0,0,0
9085000,0.697124,0.00128353,-0.0139276,0.716814,-0.0154167,0.00575223,-0.155345,-0.00918227,0.00261095,-365.508,-1.52722e-05,-5.53496e-05,-0.000152502,0,0,-0.000306964,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00019643,8.85515e-05,8.85142e-05,0.000178876,0.139245,0.139261,0.201555,0.105955,0.105961,0.173043,3.87084e-09,3.86757e-09,1.06007e-08,0,0,3.34873e-06,0,0,0,0,0,0,0,0
9185000,0.697166,0.00122948,-0.0139795,0.716772,-0.0121536,0.00492832,-0.155689,-0.00712334,0.00213737,-365.512,-1.51851e-05,-5.53915e-05,-0.000150421,0,0,-0.000326688,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000191833,7.0159e-05,7.01325e-05,0.000175532,0.112997,0.113007,0.199713,0.0848989,0.0849025,0.172037,3.86856e-09,3.86536e-09,1.05134e-08,0,0,3.28267e-06,0,0,0,0,0,0,0,0
9285000,0.69701,0.00121145,-0.0140198,0.716924,-0.0120057,0.00525283,-0.152745,-0.00837461,0.00265907,-365.511,-1.51416e-05,-5.54171e-05,-0.000148941,0,0,-0.000352593,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000187616,7.07395e-05,7.07126e-05,0.000172443,0.123985,0.123997,0.197342,0.102663,0.102668,0.171158,3.86859e-09,3.86543e-09,1.04209e-08,0,0,3.21663e-06,0,0,0,0,0,0,0,0
9385000,0.696772,0.00117061,-0.0139628,0.717156,-0.0119052,0.00658904,-0.154398,-0.00959896,0.00325291,-365.516,-1.51117e-05,-5.54347e-05,-0.000147926,0,0,-0.000369312,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000185604,7.15131e-05,7.14855e-05,0.000171224,0.135487,0.135501,0.199946,0.123705,0.123712,0.177924,3.86863e-09,3.86551e-09,1.03481e-08,0,0,3.16731e-06,0,0,0,0,0,0,0,0
9485000,0.69674,0.00110707,-0.0140144,0.717186,-0.00920687,0.00537996,-0.15161,-0.00731195,0.0027177,-365.518,-1.50439e-05,-5.54699e-05,-0.000145813,0,0,-0.000390219,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000181969,5.76944e-05,5.76757e-05,0.00016854,0.109044,0.109053,0.196268,0.0987328,0.0987373,0.176929,3.8685e-09,3.86544e-09,1.02461e-08,0,0,3.10215e-06,0,0,0,0,0,0,0,0
9585000,0.696658,0.00112287,-0.0139982,0.717266,-0.0103143,0.00578248,-0.147691,-0.00834798,0.00327615,-365.517,-1.49889e-05,-5.55019e-05,-0.000143939,0,0,-0.000414492,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000178628,5.88408e-05,5.88214e-05,0.000166054,0.118547,0.118557,0.19198,0.118088,0.118094,0.17579,3.86851e-09,3.86551e-09,1.01388e-08,0,0,3.03832e-06,0,0,0,0,0,0,0,0
9685000,0.696398,0.00113429,-0.0140275,0.717518,-0.00803226,0.00622521,-0.141029,-0.00641589,0.00273605,-365.513,-1.49573e-05,-5.55178e-05,-0.000142773,0,0,-0.000441707,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000175572,4.88473e-05,4.88352e-05,0.00016376,0.0953444,0.0953504,0.18727,0.0944612,0.0944651,0.174611,3.86837e-09,3.86543e-09,1.00266e-08,0,0,2.97675e-06,0,0,0,0,0,0,0,0
9785000,0.696397,0.00112702,-0.0139765,0.71752,-0.00666722,0.00748069,-0.131935,-0.00720051,0.00341987,-365.506,-1.48918e-05,-5.5556e-05,-0.000140548,0,0,-0.000472068,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000172772,5.03913e-05,5.03783e-05,0.000161643,0.103246,0.103253,0.182073,0.112134,0.112139,0.173248,3.86837e-09,3.8655e-09,9.90938e-09,0,0,2.9175e-06,0,0,0,0,0,0,0,0
9885000,0.696237,0.00108647,-0.0139178,0.717676,-0.00477259,0.00688529,-0.130748,-0.0053618,0.00295168,-365.509,-1.48452e-05,-5.55796e-05,-0.000138745,0,0,-0.000487589,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00017024,4.34888e-05,4.34817e-05,0.000159684,0.0833416,0.083345,0.176606,0.090091,0.0900941,0.171821,3.86795e-09,3.86514e-09,9.78757e-09,0,0,2.86127e-06,0,0,0,0,0,0,0,0
9985000,0.696046,0.00112585,-0.0139358,0.717861,-0.0047242,0.00657869,-0.125677,-0.00587554,0.00363089,-365.506,-1.47993e-05,-5.56064e-05,-0.000137192,0,0,-0.000510134,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000167932,4.54375e-05,4.54286e-05,0.000157881,0.0900321,0.0900356,0.170834,0.106173,0.106177,0.170204,3.86795e-09,3.86521e-09,9.66111e-09,0,0,2.80795e-06,0,0,0,0,0,0,0,0
10085000,0.695925,0.00111825,-0.0139319,0.717979,-0.00258346,0.00480048,-0.126139,-0.00434069,0.00298773,-365.51,-1.47543e-05,-5.56282e-05,-0.000135522,0,0,-0.000522234,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000167419,4.0937e-05,4.09318e-05,0.000157696,0.0732397,0.0732412,0.169909,0.0857993,0.0858017,0.175933,3.86764e-09,3.86495e-09,9.56338e-09,0,0,2.76995e-06,0,0,0,0,0,0,0,0
10185000,0.695676,0.00111391,-0.0139917,0.718219,-0.00237022,0.00640248,-0.126497,-0.00459062,0.00351096,-365.514,-1.47186e-05,-5.56488e-05,-0.000134301,0,0,-0.00053416,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000165492,4.32857e-05,4.32783e-05,0.000156151,0.0790574,0.0790585,0.163643,0.100435,0.100438,0.173912,3.86763e-09,3.86501e-09,9.42952e-09,0,0,2.7222e-06,0,0,0,0,0,0,0,0
10285000,0.695527,0.00105745,-0.0139725,0.718363,-0.000546491,0.00478271,-0.115454,-0.00335293,0.00288296,-365.502,-1.46704e-05,-5.56737e-05,-0.000132714,0,0,-0.000563502,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000163748,4.06011e-05,4.05969e-05,0.00015475,0.0650473,0.0650471,0.157393,0.0817081,0.0817099,0.171841,3.86752e-09,3.86498e-09,9.29208e-09,0,0,2.67789e-06,0,0,0,0,0,0,0,0
10385000,0.695439,0.00102611,-0.0139197,0.718449,0.0113944,-0.0203235,0.00395206,0.000951113,-0.00180988,-365.489,-1.46067e-05,-5.57103e-05,-0.000130525,0,0,-0.000581462,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000162274,4.33385e-05,4.33323e-05,0.000153548,0.0347254,0.0347253,0.0376514,0.12528,0.12528,0.149194,3.86751e-09,3.86505e-09,9.15109e-09,0,0,2.64074e-06,0,0,0,0,0,0,0,0
10485000,0.695267,0.00104904,-0.0139219,0.718616,0.0121846,-0.0199027,-0.000794477,0.00211183,-0.00382334,-365.474,-1.45576e-05,-5.57386e-05,-0.000128851,0,0,-0.000600041,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000161082,4.62695e-05,4.62608e-05,0.000152612,0.0353241,0.035324,0.0383423,0.126252,0.126252,0.131539,3.86749e-09,3.86511e-09,9.00693e-09,0,0,2.61293e-06,0,0,0,0,0,0,0,0
10585000,0.695247,0.0010811,-0.0139732,0.718634,0.0126651,-0.017033,-0.00437551,0.00251857,-0.00372231,-365.466,-1.45014e-05,-5.56983e-05,-0.000126581,0,0,-0.000610657,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000160074,4.92771e-05,4.92658e-05,0.000151853,0.0317308,0.0317305,0.0368,0.0848584,0.0848584,0.118582,3.8632e-09,3.86091e-09,8.86018e-09,0,0,2.59057e-06,0,0,0,0,0,0,0,0
10685000,0.695111,0.00111479,-0.013967,0.718766,0.0127454,-0.0180157,-0.00982359,0.00382799,-0.00548902,-365.462,-1.44521e-05,-5.57263e-05,-0.000124868,0,0,-0.000618188,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000160605,5.25877e-05,5.25731e-05,0.00015251,0.0330327,0.0330321,0.0380193,0.0865672,0.0865671,0.11252,3.86321e-09,3.86099e-09,8.74854e-09,0,0,2.57694e-06,0,0,0,0,0,0,0,0
10785000,0.695098,0.00110558,-0.013995,0.718778,0.0125456,-0.0167377,-0.0145644,0.00394682,-0.00500968,-365.46,-1.44111e-05,-5.56186e-05,-0.00012255,0,0,-0.000623328,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000159817,5.55841e-05,5.55673e-05,0.000151925,0.0304781,0.0304773,0.0368422,0.0656909,0.0656909,0.104598,3.84565e-09,3.84352e-09,8.59746e-09,0,0,2.55977e-06,0,0,0,0,0,0,0,0
10885000,0.695085,0.00104238,-0.0139554,0.718792,0.0131617,-0.0171198,-0.021463,0.00521381,-0.00668624,-365.461,-1.43491e-05,-5.56534e-05,-0.000120372,0,0,-0.000625516,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000159156,5.92492e-05,5.92298e-05,0.000151471,0.0325365,0.0325353,0.0381869,0.067955,0.0679549,0.0995395,3.84563e-09,3.84358e-09,8.44442e-09,0,0,2.54653e-06,0,0,0,0,0,0,0,0
10985000,0.695213,0.00106388,-0.0139893,0.718667,0.012601,-0.0144151,-0.0272705,0.00569318,-0.00774586,-365.459,-1.41944e-05,-5.53843e-05,-0.000117467,0,0,-0.000632205,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000158499,6.18681e-05,6.18474e-05,0.00015099,0.0306309,0.0306294,0.0371409,0.0551273,0.0551273,0.0945432,3.80515e-09,3.80323e-09,8.28969e-09,0,0,2.53217e-06,0,0,0,0,0,0,0,0
11085000,0.695343,0.00105966,-0.0139281,0.718542,0.0131492,-0.0139242,-0.03101,0.00701136,-0.00920767,-365.454,-1.411e-05,-5.5432e-05,-0.000114515,0,0,-0.000640992,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000157969,6.58455e-05,6.58221e-05,0.000150638,0.0334824,0.0334802,0.0385905,0.0578973,0.0578972,0.0921173,3.80512e-09,3.80329e-09,8.13375e-09,0,0,2.52195e-06,0,0,0,0,0,0,0,0
11185000,0.695259,0.00109167,-0.0139753,0.718622,0.0151749,-0.0113406,-0.0372693,0.00748475,-0.00931783,-365.458,-1.39685e-05,-5.50922e-05,-0.000112565,0,0,-0.000642102,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000157398,6.76532e-05,6.76297e-05,0.00015018,0.0318909,0.0318886,0.0375738,0.0489544,0.0489543,0.0886902,3.73262e-09,3.73094e-09,7.97661e-09,0,0,2.50883e-06,0,0,0,0,0,0,0,0
11285000,0.695154,0.00116236,-0.0140009,0.718724,0.016082,-0.0108071,-0.0423446,0.00905915,-0.0104186,-365.459,-1.39264e-05,-5.51161e-05,-0.000111089,0,0,-0.000646477,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000156943,7.18788e-05,7.18519e-05,0.000149886,0.0355487,0.0355456,0.0390759,0.0522326,0.0522323,0.0878644,3.7326e-09,3.731e-09,7.81901e-09,0,0,2.50048e-06,0,0,0,0,0,0,0,0
11385000,0.695004,0.00127594,-0.0139978,0.718868,0.0142027,-0.00846435,-0.0461921,0.00783319,-0.00878408,-365.46,-1.42345e-05,-5.48795e-05,-0.000109752,0,0,-0.000651677,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000157708,7.24349e-05,7.24088e-05,0.000150654,0.0339454,0.0339423,0.0383837,0.0453555,0.0453552,0.0871594,3.62147e-09,3.62003e-09,7.69999e-09,0,0,2.48966e-06,0,0,0,0,0,0,0,0
11485000,0.694879,0.00128156,-0.0140192,0.718989,0.0133456,-0.00755507,-0.0509602,0.00921872,-0.00958582,-365.462,-1.41928e-05,-5.49035e-05,-0.000108271,0,0,-0.000654988,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000157301,7.68234e-05,7.6794e-05,0.000150372,0.0383719,0.0383677,0.0399509,0.0491613,0.0491608,0.087342,3.62144e-09,3.62009e-09,7.54178e-09,0,0,2.4825e-06,0,0,0,0,0,0,0,0
11585000,0.694801,0.00134032,-0.0140634,0.719063,0.00939458,-0.0043671,-0.054537,0.00776025,-0.00801147,-365.463,-1.44824e-05,-5.47141e-05,-0.00010647,0,0,-0.000661158,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000156766,7.57727e-05,7.57465e-05,0.000149885,0.036438,0.0364338,0.0388561,0.0433946,0.0433941,0.0851559,3.46948e-09,3.46833e-09,7.38327e-09,0,0,2.46989e-06,0,0,0,0,0,0,0,0
11685000,0.694796,0.00131503,-0.0140675,0.719068,0.00779862,-0.00267606,-0.0604784,0.00861013,-0.00839893,-365.469,-1.44306e-05,-5.47441e-05,-0.000104587,0,0,-0.000661284,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000156374,8.02268e-05,8.01976e-05,0.000149612,0.0415502,0.0415446,0.0404159,0.0477418,0.0477411,0.0859919,3.46946e-09,3.46839e-09,7.22555e-09,0,0,2.46365e-06,0,0,0,0,0,0,0,0
11785000,0.694851,0.00144819,-0.0140846,0.719014,0.00251796,-0.000169466,-0.0630016,0.0061438,-0.00605815,-365.468,-1.48655e-05,-5.44111e-05,-0.000102393,0,0,-0.000669822,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000155818,7.73969e-05,7.73729e-05,0.000149097,0.0390017,0.0389966,0.0392425,0.0425116,0.042511,0.0840403,3.2802e-09,3.27935e-09,7.0677e-09,0,0,2.45114e-06,0,0,0,0,0,0,0,0
11885000,0.694785,0.00145295,-0.014075,0.719079,0.00291652,0.000328636,-0.0669277,0.00645022,-0.00605449,-365.471,-1.48205e-05,-5.44379e-05,-0.00010075,0,0,-0.000673619,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000155436,8.18173e-05,8.17905e-05,0.000148804,0.0446749,0.0446687,0.0407783,0.0473941,0.0473931,0.0852733,3.28019e-09,3.27941e-09,6.91148e-09,0,0,2.44558e-06,0,0,0,0,0,0,0,0
11985000,0.694793,0.00160308,-0.01404,0.719071,-0.00034581,0.00304317,-0.0704423,0.00427983,-0.00394518,-365.474,-1.51465e-05,-5.41632e-05,-9.87766e-05,0,0,-0.00067925,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000156173,7.72655e-05,7.72454e-05,0.000149464,0.0413134,0.0413083,0.0400017,0.0423279,0.0423272,0.0852316,3.06226e-09,3.06166e-09,6.79441e-09,0,0,2.43447e-06,0,0,0,0,0,0,0,0
12085000,0.694981,0.00162396,-0.014051,0.718889,-0.000422612,0.00463728,-0.0781835,0.00425926,-0.00357882,-365.483,-1.50721e-05,-5.42091e-05,-9.59632e-05,0,0,-0.000678863,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000155771,8.15623e-05,8.15395e-05,0.00014915,0.0473991,0.0473929,0.041546,0.0477126,0.0477115,0.0867578,3.06225e-09,3.06172e-09,6.64015e-09,0,0,2.42945e-06,0,0,0,0,0,0,0,0
12185000,0.69499,0.00157592,-0.0140734,0.71888,0.000259155,0.00639042,-0.0733913,0.00475009,-0.0030108,-365.475,-1.47742e-05,-5.43477e-05,-9.39522e-05,0,0,-0.000695791,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000155178,7.556e-05,7.55456e-05,0.000148543,0.043147,0.0431419,0.0401956,0.0425697,0.0425689,0.0848784,2.82734e-09,2.827e-09,6.48658e-09,0,0,2.41714e-06,0,0,0,0,0,0,0,0
12285000,0.695078,0.00155557,-0.0140862,0.718795,-0.00150354,0.00782645,-0.0755756,0.00473153,-0.00228166,-365.475,-1.47146e-05,-5.43853e-05,-9.16924e-05,0,0,-0.000702404,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00015476,7.96615e-05,7.96447e-05,0.000148197,0.0494694,0.0494631,0.0416861,0.0483979,0.0483966,0.0865253,2.82734e-09,2.82706e-09,6.33543e-09,0,0,2.41256e-06,0,0,0,0,0,0,0,0
12385000,0.695086,0.00147604,-0.0141064,0.718787,-7.32354e-05,0.00832706,-0.0721657,0.00524763,-0.00205086,-365.469,-1.44084e-05,-5.46108e-05,-8.99891e-05,0,0,-0.000716977,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000154133,7.26178e-05,7.26101e-05,0.000147563,0.0443824,0.0443777,0.0402641,0.0430368,0.0430359,0.0846437,2.58771e-09,2.58759e-09,6.18535e-09,0,0,2.40055e-06,0,0,0,0,0,0,0,0
12485000,0.695039,0.00144974,-0.01413,0.718832,-0.000869334,0.010527,-0.0770605,0.0052312,-0.00110993,-365.473,-1.43724e-05,-5.46342e-05,-8.85825e-05,0,0,-0.000719901,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00015369,7.6476e-05,7.64662e-05,0.000147183,0.050798,0.0507922,0.0416933,0.0492332,0.0492319,0.0863352,2.58771e-09,2.58765e-09,6.03796e-09,0,0,2.39632e-06,0,0,0,0,0,0,0,0
12585000,0.695049,0.00155194,-0.0140034,0.718824,-0.00676615,0.0110151,-0.0806043,0.000428274,-0.00116162,-365.478,-1.51431e-05,-5.49232e-05,-8.67214e-05,0,0,-0.00072572,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000153048,6.88342e-05,6.88337e-05,0.000146505,0.0450204,0.0450161,0.0402092,0.0435895,0.0435886,0.0844344,2.35374e-09,2.3538e-09,5.89201e-09,0,0,2.3847e-06,0,0,0,0,0,0,0,0
12685000,0.694982,0.00159697,-0.0139636,0.71889,-0.006825,0.0130499,-0.0857697,-0.000248249,4.15681e-05,-365.486,-1.51104e-05,-5.49456e-05,-8.53929e-05,0,0,-0.000726432,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000153857,7.24239e-05,7.24213e-05,0.000147279,0.0513921,0.0513871,0.0421128,0.0500718,0.0500705,0.0880163,2.35378e-09,2.35387e-09,5.78437e-09,0,0,2.38176e-06,0,0,0,0,0,0,0,0
12785000,0.695072,0.00169012,-0.0138246,0.718806,-0.0117324,0.0115606,-0.0860284,-0.00408074,-0.000374765,-365.486,-1.56499e-05,-5.52999e-05,-8.33572e-05,0,0,-0.000736543,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000153172,6.45855e-05,6.4592e-05,0.000146571,0.0451058,0.0451022,0.0405347,0.0441377,0.0441368,0.086008,2.13293e-09,2.13311e-09,5.64235e-09,0,0,2.37051e-06,0,0,0,0,0,0,0,0
12885000,0.69516,0.00164543,-0.0138672,0.71872,-0.0123095,0.0118938,-0.0877696,-0.0052697,0.000778518,-365.486,-1.5603e-05,-5.53326e-05,-8.14422e-05,0,0,-0.00074253,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000152661,6.79002e-05,6.79052e-05,0.000146118,0.0513495,0.0513454,0.0418456,0.0508255,0.0508243,0.0877324,2.13295e-09,2.13317e-09,5.50336e-09,0,0,2.36689e-06,0,0,0,0,0,0,0,0
12985000,0.695384,0.00144833,-0.0139932,0.718501,-0.00482726,0.0104322,-0.0843951,0.000826252,0.000162521,-365.484,-1.46026e-05,-5.56911e-05,-7.88997e-05,0,0,-0.000756367,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000151944,6.01773e-05,6.01907e-05,0.000145395,0.0447413,0.0447385,0.0402187,0.0446285,0.0446277,0.0857048,1.92956e-09,1.92984e-09,5.3663e-09,0,0,2.3562e-06,0,0,0,0,0,0,0,0
13085000,0.695279,0.00145983,-0.0139447,0.718603,-0.00531773,0.0112329,-0.0863389,0.000332588,0.0012534,-365.487,-1.45754e-05,-5.57105e-05,-7.77641e-05,0,0,-0.00076026,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000151412,6.32236e-05,6.32361e-05,0.000144889,0.0507789,0.0507757,0.041428,0.0514487,0.0514476,0.0873524,1.92959e-09,1.9299e-09,5.23214e-09,0,0,2.3528e-06,0,0,0,0,0,0,0,0
13185000,0.695364,0.0012955,-0.0139918,0.718521,0.00110737,0.0110431,-0.0801976,0.00527027,0.000656174,-365.478,-1.38534e-05,-5.60248e-05,-7.58674e-05,0,0,-0.000777816,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000150681,5.58351e-05,5.58553e-05,0.000144143,0.0440386,0.0440365,0.0397687,0.0450364,0.0450357,0.0853151,1.74555e-09,1.74589e-09,5.10034e-09,0,0,2.34273e-06,0,0,0,0,0,0,0,0
13285000,0.695456,0.00131002,-0.0139949,0.718431,0.000922163,0.0124984,-0.0802287,0.00539059,0.00184023,-365.475,-1.38112e-05,-5.60556e-05,-7.40769e-05,0,0,-0.000784541,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000151354,5.86305e-05,5.86493e-05,0.000144787,0.0498409,0.0498386,0.0414446,0.0519281,0.0519272,0.0888456,1.7456e-09,1.74596e-09,5.00354e-09,0,0,2.34036e-06,0,0,0,0,0,0,0,0
13385000,0.695658,0.00117982,-0.0139309,0.718237,0.000948407,0.0115298,-0.0742492,0.00399744,0.00101567,-365.464,-1.37126e-05,-5.6387e-05,-7.18267e-05,0,0,-0.000800279,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000150584,5.17027e-05,5.17285e-05,0.000144024,0.0431031,0.0431016,0.03972,0.0453539,0.0453533,0.0867167,1.58088e-09,1.58126e-09,4.87641e-09,0,0,2.33084e-06,0,0,0,0,0,0,0,0
13485000,0.695839,0.001211,-0.0139296,0.718062,0.000385368,0.0121965,-0.0752476,0.00411184,0.00220182,-365.462,-1.36645e-05,-5.64234e-05,-6.9725e-05,0,0,-0.00080567,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000149968,5.42662e-05,5.42912e-05,0.000143466,0.0486471,0.0486454,0.0407681,0.0522679,0.0522671,0.0882909,1.58092e-09,1.58132e-09,4.75226e-09,0,0,2.32789e-06,0,0,0,0,0,0,0,0
13585000,0.695892,0.00115452,-0.013875,0.718012,0.000215043,0.0122138,-0.0743712,0.00292308,0.00136763,-365.462,-1.35757e-05,-5.6721e-05,-6.83313e-05,0,0,-0.000813628,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000149182,4.78607e-05,4.78917e-05,0.000142695,0.0420126,0.0420114,0.0390326,0.0455837,0.0455832,0.0861724,1.43444e-09,1.43484e-09,4.63068e-09,0,0,2.31905e-06,0,0,0,0,0,0,0,0
13685000,0.696083,0.00113269,-0.0138455,0.717827,0.000868977,0.0146683,-0.07985,0.00295961,0.00269387,-365.468,-1.35273e-05,-5.67593e-05,-6.61403e-05,0,0,-0.000814624,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000148547,5.02146e-05,5.02451e-05,0.000142106,0.0472965,0.0472953,0.0399811,0.0524816,0.052481,0.0876669,1.43448e-09,1.4349e-09,4.51204e-09,0,0,2.31629e-06,0,0,0,0,0,0,0,0
13785000,0.696148,0.00105255,-0.0137529,0.717765,0.00103775,0.0104693,-0.0788725,0.00382173,0.000146131,-365.468,-1.33447e-05,-5.72858e-05,-6.45676e-05,0,0,-0.000823055,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000147756,4.43441e-05,4.43799e-05,0.000141323,0.0408444,0.0408436,0.0382498,0.0457338,0.0457333,0.0855684,1.30457e-09,1.30498e-09,4.39604e-09,0,0,2.30813e-06,0,0,0,0,0,0,0,0
13885000,0.696223,0.00100861,-0.0137842,0.717692,0.00137256,0.0110656,-0.0840698,0.00393883,0.00121888,-365.475,-1.33102e-05,-5.73136e-05,-6.29837e-05,0,0,-0.000823993,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000147099,4.65105e-05,4.65457e-05,0.000140709,0.0458665,0.0458658,0.0390975,0.0525876,0.052587,0.086983,1.30462e-09,1.30504e-09,4.28293e-09,0,0,2.30554e-06,0,0,0,0,0,0,0,0
13985000,0.69637,0.000964608,-0.0137313,0.717551,0.0013041,0.00849048,-0.0817903,0.00462503,-0.000898567,-365.473,-1.31478e-05,-5.77428e-05,-6.13037e-05,0,0,-0.000833359,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000147471,4.11608e-05,4.11999e-05,0.000141043,0.0396405,0.03964,0.0378683,0.0458148,0.0458145,0.0867538,1.18946e-09,1.18986e-09,4.19972e-09,0,0,2.29862e-06,0,0,0,0,0,0,0,0
14085000,0.696529,0.000944464,-0.0137454,0.717397,0.00118775,0.00901719,-0.0844303,0.00473111,-2.9911e-05,-365.479,-1.31086e-05,-5.77749e-05,-5.94798e-05,0,0,-0.000834851,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000146778,4.31593e-05,4.31982e-05,0.000140405,0.0444031,0.0444027,0.0386392,0.052604,0.0526035,0.0881475,1.18951e-09,1.18993e-09,4.09137e-09,0,0,2.29623e-06,0,0,0,0,0,0,0,0
14185000,0.696723,0.000843552,-0.0137321,0.717209,0.00414946,0.00791787,-0.0839947,0.00672631,-0.000406482,-365.48,-1.27826e-05,-5.79722e-05,-5.74936e-05,0,0,-0.000841391,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000145952,3.82972e-05,3.83399e-05,0.000139614,0.0384319,0.0384317,0.0369089,0.0458378,0.0458375,0.0860217,1.08727e-09,1.08767e-09,3.98567e-09,0,0,2.2893e-06,0,0,0,0,0,0,0,0
14285000,0.696892,0.000847509,-0.0136961,0.717045,0.00457853,0.00916658,-0.0849875,0.00716751,0.000432142,-365.481,-1.27468e-05,-5.80016e-05,-5.58276e-05,0,0,-0.000845063,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000145235,4.01461e-05,4.01886e-05,0.000138968,0.0429609,0.0429608,0.0375849,0.0525481,0.0525477,0.0873329,1.08732e-09,1.08773e-09,3.88273e-09,0,0,2.28707e-06,0,0,0,0,0,0,0,0
14385000,0.697145,0.000757359,-0.0136636,0.7168,0.00605447,0.00922616,-0.0848675,0.00852979,2.56151e-05,-365.482,-1.25131e-05,-5.81989e-05,-5.37522e-05,0,0,-0.000851423,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000144395,3.57294e-05,3.57751e-05,0.000138184,0.0372546,0.0372547,0.0358852,0.0458126,0.0458124,0.0852314,9.96284e-10,9.96667e-10,3.78228e-09,0,0,2.28074e-06,0,0,0,0,0,0,0,0
14485000,0.697244,0.000750959,-0.0136102,0.716704,0.00588737,0.0111666,-0.0892035,0.0091306,0.00105341,-365.491,-1.24816e-05,-5.82258e-05,-5.22416e-05,0,0,-0.000851276,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000143676,3.7445e-05,3.74907e-05,0.000137513,0.0415626,0.0415627,0.0364699,0.0524354,0.0524351,0.086461,9.96341e-10,9.96736e-10,3.68463e-09,0,0,2.27866e-06,0,0,0,0,0,0,0,0
14585000,0.697226,0.000708053,-0.0134304,0.716725,0.00299286,0.00920759,-0.0877076,0.00595267,-0.000870504,-365.493,-1.27737e-05,-5.85642e-05,-5.14641e-05,0,0,-0.000858449,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000143965,3.34298e-05,3.34779e-05,0.000137792,0.0361154,0.0361157,0.0352785,0.0457489,0.0457487,0.0862465,9.14998e-10,9.15363e-10,3.61304e-09,0,0,2.2734e-06,0,0,0,0,0,0,0,0
14685000,0.697447,0.000677681,-0.0134211,0.716511,0.00450698,0.00692931,-0.0872931,0.00636859,-4.03669e-05,-365.493,-1.27336e-05,-5.85979e-05,-4.95623e-05,0,0,-0.000862582,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000143217,3.50267e-05,3.50747e-05,0.000137107,0.0402173,0.0402178,0.035797,0.0522786,0.0522784,0.0874478,9.15058e-10,9.15433e-10,3.51985e-09,0,0,2.27147e-06,0,0,0,0,0,0,0,0
14785000,0.697555,0.000668695,-0.0132939,0.716408,0.00193559,0.00470482,-0.0827129,0.00376793,-0.00161534,-365.486,-1.29569e-05,-5.88589e-05,-4.82145e-05,0,0,-0.000873025,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000142363,3.13699e-05,3.14202e-05,0.000136321,0.0350298,0.0350304,0.0341596,0.0456545,0.0456544,0.0853589,8.42089e-10,8.42433e-10,3.42907e-09,0,0,2.26622e-06,0,0,0,0,0,0,0,0
14885000,0.697737,0.000659611,-0.0132537,0.716231,0.00291116,0.00631458,-0.0868092,0.00400155,-0.00107078,-365.492,-1.29234e-05,-5.88879e-05,-4.65904e-05,0,0,-0.000874195,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000141605,3.28599e-05,3.29102e-05,0.00013563,0.0389501,0.038951,0.0346002,0.0520892,0.052089,0.086479,8.42152e-10,8.42505e-10,3.34087e-09,0,0,2.26443e-06,0,0,0,0,0,0,0,0
14985000,0.697777,0.000613935,-0.0132373,0.716193,0.00218905,0.00536299,-0.0819647,0.00319978,-0.00108794,-365.487,-1.2971e-05,-5.89832e-05,-4.54979e-05,0,0,-0.000883876,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000140758,2.95203e-05,2.95723e-05,0.000134847,0.0340029,0.0340036,0.0330225,0.0455365,0.0455364,0.0844482,7.76418e-10,7.76739e-10,3.255e-09,0,0,2.25968e-06,0,0,0,0,0,0,0,0
15085000,0.697902,0.000549099,-0.0132143,0.716071,0.00232611,0.00550745,-0.0853677,0.00342624,-0.000552215,-365.496,-1.29479e-05,-5.90035e-05,-4.43646e-05,0,0,-0.000883535,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000139988,3.09142e-05,3.09663e-05,0.000134161,0.0377413,0.0377422,0.0333873,0.0518753,0.0518752,0.0854898,7.76483e-10,7.76812e-10,3.1716e-09,0,0,2.25802e-06,0,0,0,0,0,0,0,0
15185000,0.69802,0.000517842,-0.0131825,0.715957,0.00188655,0.0057531,-0.081753,0.0027584,-0.000581622,-365.493,-1.29763e-05,-5.90913e-05,-4.31881e-05,0,0,-0.000891835,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000139135,2.7856e-05,2.79095e-05,0.000133399,0.033028,0.0330289,0.0318751,0.0454006,0.0454006,0.0835189,7.17056e-10,7.17354e-10,3.09045e-09,0,0,2.25374e-06,0,0,0,0,0,0,0,0
15285000,0.698126,0.000490116,-0.0132207,0.715852,0.00225734,0.00638615,-0.0832667,0.00298163,2.5996e-05,-365.494,-1.29545e-05,-5.91099e-05,-4.21403e-05,0,0,-0.000894625,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000139414,2.91637e-05,2.92167e-05,0.000133692,0.0366122,0.0366133,0.0326069,0.0516447,0.0516447,0.0863078,7.17132e-10,7.17435e-10,3.0311e-09,0,0,2.25259e-06,0,0,0,0,0,0,0,0
15385000,0.698399,0.00046223,-0.0131721,0.715587,0.00206348,0.00617334,-0.0798755,0.000560163,-0.000132269,-365.49,-1.30334e-05,-5.922e-05,-4.03228e-05,0,0,-0.000902037,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000138554,2.63531e-05,2.64073e-05,0.000132926,0.0321158,0.0321169,0.0311294,0.0452515,0.0452515,0.0843152,6.63192e-10,6.63465e-10,2.95387e-09,0,0,2.24869e-06,0,0,0,0,0,0,0,0
15485000,0.698396,0.000480042,-0.013178,0.71559,0.00312033,0.00598519,-0.0811926,0.000816452,0.000457692,-365.496,-1.30217e-05,-5.92302e-05,-3.97522e-05,0,0,-0.000902634,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000137772,2.75811e-05,2.76353e-05,0.000132222,0.0355445,0.0355459,0.0313806,0.0514027,0.0514028,0.0852467,6.63261e-10,6.63541e-10,2.87888e-09,0,0,2.24727e-06,0,0,0,0,0,0,0,0
15585000,0.698418,0.000460738,-0.0131367,0.71557,0.00154487,0.00542695,-0.0782144,-0.0013042,0.000186476,-365.496,-1.31116e-05,-5.93181e-05,-3.89671e-05,0,0,-0.000908289,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000136926,2.49902e-05,2.50453e-05,0.000131462,0.0312479,0.0312491,0.0299729,0.045093,0.045093,0.0833192,6.14148e-10,6.14398e-10,2.80597e-09,0,0,2.24375e-06,0,0,0,0,0,0,0,0
15685000,0.698518,0.00046992,-0.0131615,0.715472,0.00174218,0.00561706,-0.0803813,-0.00115832,0.000745068,-365.5,-1.30915e-05,-5.93357e-05,-3.79816e-05,0,0,-0.000909544,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000136144,2.6146e-05,2.62011e-05,0.000130756,0.0345471,0.0345485,0.0301665,0.0511537,0.0511539,0.0841607,6.14219e-10,6.14475e-10,2.73512e-09,0,0,2.24243e-06,0,0,0,0,0,0,0,0
15785000,0.698623,0.000431131,-0.0131802,0.715368,0.00222204,0.00335811,-0.0804873,-0.00096147,-0.000820818,-365.504,-1.30882e-05,-5.95302e-05,-3.70099e-05,0,0,-0.000913219,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000135302,2.37491e-05,2.38048e-05,0.000130013,0.0304428,0.030444,0.0288318,0.044928,0.0449281,0.0822989,5.69353e-10,5.69581e-10,2.66631e-09,0,0,2.23926e-06,0,0,0,0,0,0,0,0
15885000,0.69862,0.000388497,-0.0131811,0.715371,0.00318639,0.00333888,-0.0817568,-0.000661345,-0.000496013,-365.508,-1.30765e-05,-5.95404e-05,-3.64353e-05,0,0,-0.000914503,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000135513,2.48388e-05,2.48942e-05,0.000130235,0.0336145,0.0336161,0.0293699,0.0509019,0.0509021,0.0848499,5.69433e-10,5.69665e-10,2.61604e-09,0,0,2.23836e-06,0,0,0,0,0,0,0,0
15985000,0.698823,0.000307465,-0.0131737,0.715174,0.00319422,0.00186444,-0.0773149,-0.000617319,-0.00173975,-365.502,-1.30774e-05,-5.97092e-05,-3.48764e-05,0,0,-0.000921744,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000134679,2.26133e-05,2.26693e-05,0.00012948,0.029684,0.0296853,0.0280776,0.0447595,0.0447597,0.0829762,5.28333e-10,5.28538e-10,2.55063e-09,0,0,2.23547e-06,0,0,0,0,0,0,0,0
16085000,0.698997,0.000308229,-0.0131936,0.715003,0.00466736,0.00207817,-0.0766579,-0.000221717,-0.00156228,-365.5,-1.30526e-05,-5.97306e-05,-3.36688e-05,0,0,-0.000925194,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000133893,2.36415e-05,2.36976e-05,0.000128772,0.0327428,0.0327444,0.0281923,0.0506499,0.0506502,0.0837131,5.28408e-10,5.28617e-10,2.48708e-09,0,0,2.23435e-06,0,0,0,0,0,0,0,0
16185000,0.699177,0.000300031,-0.0131554,0.714828,0.00489952,0.00195609,-0.0740028,-0.000324601,-0.00138547,-365.496,-1.30762e-05,-5.97686e-05,-3.23609e-05,0,0,-0.000931432,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000133065,2.15682e-05,2.16246e-05,0.000128037,0.0289744,0.0289758,0.0269723,0.0445895,0.0445897,0.0819073,4.90665e-10,4.90848e-10,2.42539e-09,0,0,2.23176e-06,0,0,0,0,0,0,0,0
16285000,0.699426,0.000313594,-0.013173,0.714584,0.00671146,0.0016541,-0.0764785,0.000270144,-0.00118705,-365.501,-1.30476e-05,-5.9794e-05,-3.09393e-05,0,0,-0.000931945,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000132284,2.25398e-05,2.25963e-05,0.000127337,0.0319259,0.0319276,0.0270509,0.0504,0.0504003,0.0825793,4.90741e-10,4.90929e-10,2.36546e-09,0,0,2.23072e-06,0,0,0,0,0,0,0,0
16385000,0.699475,0.000271217,-0.0131771,0.714536,0.00594947,0.000570128,-0.0746054,6.80717e-05,-0.00103798,-365.499,-1.31019e-05,-5.98132e-05,-3.0299e-05,0,0,-0.000937431,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000131464,2.06026e-05,2.06594e-05,0.000126619,0.0283053,0.0283067,0.0259005,0.0444194,0.0444196,0.0808402,4.56009e-10,4.56172e-10,2.30727e-09,0,0,2.22838e-06,0,0,0,0,0,0,0,0
16485000,0.699552,0.000273836,-0.013129,0.714461,0.0050905,0.00129895,-0.0784057,0.000596383,-0.000941249,-365.506,-1.3087e-05,-5.98264e-05,-2.95555e-05,0,0,-0.000937399,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000130695,2.15212e-05,2.15781e-05,0.000125926,0.0311584,0.03116,0.0259488,0.0501533,0.0501537,0.0814512,4.56086e-10,4.56254e-10,2.25075e-09,0,0,2.22742e-06,0,0,0,0,0,0,0,0
16585000,0.699707,0.000412812,-0.0130764,0.71431,0.00236102,0.00255164,-0.078973,-0.00201834,0.00159293,-365.505,-1.33009e-05,-5.96565e-05,-2.8599e-05,0,0,-0.000941308,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00013079,1.97061e-05,1.97629e-05,0.000126075,0.0276777,0.027679,0.0251851,0.0442505,0.0442507,0.0814005,4.24078e-10,4.24223e-10,2.20944e-09,0,0,2.22554e-06,0,0,0,0,0,0,0,0
16685000,0.69974,0.000412153,-0.0130659,0.714278,0.00271479,0.00307726,-0.0782812,-0.00174963,0.00187981,-365.503,-1.32911e-05,-5.96645e-05,-2.81405e-05,0,0,-0.000945146,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000130013,2.05759e-05,2.06328e-05,0.000125384,0.0304379,0.0304394,0.0252127,0.0499114,0.0499118,0.0819772,4.24156e-10,4.24306e-10,2.15572e-09,0,0,2.22466e-06,0,0,0,0,0,0,0,0
16785000,0.69984,0.000448129,-0.0130335,0.71418,-6.74756e-06,0.00422397,-0.0769606,-0.00391672,0.00385253,-365.5,-1.34669e-05,-5.95311e-05,-2.73878e-05,0,0,-0.000949612,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000129206,1.88702e-05,1.89272e-05,0.00012468,0.0270803,0.0270816,0.0241719,0.0440836,0.0440839,0.0803003,3.94603e-10,3.94732e-10,2.10358e-09,0,0,2.22275e-06,0,0,0,0,0,0,0,0
16885000,0.699872,0.000461469,-0.0129819,0.71415,-0.000237618,0.00522412,-0.0769538,-0.00391343,0.00428825,-365.499,-1.3454e-05,-5.9542e-05,-2.67682e-05,0,0,-0.000952598,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000128451,1.96939e-05,1.9751e-05,0.000123988,0.0297522,0.0297536,0.0241767,0.0496743,0.0496747,0.0808212,3.94683e-10,3.94816e-10,2.05292e-09,0,0,2.22193e-06,0,0,0,0,0,0,0,0
16985000,0.699886,0.00040717,-0.0129054,0.714138,5.81336e-05,0.00310717,-0.0757767,-0.00440293,0.00231352,-365.498,-1.35145e-05,-5.96962e-05,-2.63531e-05,0,0,-0.000955743,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000127659,1.80879e-05,1.81451e-05,0.000123294,0.0265101,0.0265114,0.0231945,0.0439191,0.0439194,0.0791955,3.67378e-10,3.67493e-10,2.00369e-09,0,0,2.22021e-06,0,0,0,0,0,0,0,0
17085000,0.699998,0.000373067,-0.0129949,0.714026,0.000874377,0.00396353,-0.0767932,-0.00436107,0.00264688,-365.502,-1.34992e-05,-5.97096e-05,-2.55946e-05,0,0,-0.000956544,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000126908,1.88694e-05,1.89266e-05,0.000122619,0.0290949,0.0290964,0.0231795,0.0494421,0.0494425,0.0796639,3.67459e-10,3.67578e-10,1.95592e-09,0,0,2.21946e-06,0,0,0,0,0,0,0,0
17185000,0.700107,0.000373151,-0.012937,0.71392,0.00135925,0.00413155,-0.0774255,-0.00475761,0.00104126,-365.507,-1.35574e-05,-5.98513e-05,-2.48932e-05,0,0,-0.000957787,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000126974,1.73549e-05,1.74118e-05,0.000122737,0.0259632,0.0259645,0.0225434,0.043757,0.0437573,0.0796708,3.4222e-10,3.4232e-10,1.921e-09,0,0,2.21808e-06,0,0,0,0,0,0,0,0
17285000,0.700168,0.000345042,-0.0129079,0.713861,0.00356562,0.00518211,-0.0751206,-0.00450789,0.00149884,-365.502,-1.35441e-05,-5.98625e-05,-2.42573e-05,0,0,-0.000961773,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000126228,1.80955e-05,1.81525e-05,0.000122057,0.0284712,0.0284728,0.0225167,0.0492147,0.0492151,0.0801078,3.42302e-10,3.42406e-10,1.87559e-09,0,0,2.21738e-06,0,0,0,0,0,0,0,0
17385000,0.700309,0.000317067,-0.0128539,0.713724,0.00420906,0.00452158,-0.072437,-0.00377815,5.99869e-05,-365.498,-1.35405e-05,-6.00036e-05,-2.35075e-05,0,0,-0.000966768,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00012545,1.66639e-05,1.67209e-05,0.000121383,0.0254456,0.0254469,0.0216346,0.0435977,0.043598,0.0785466,3.18947e-10,3.19036e-10,1.83145e-09,0,0,2.21596e-06,0,0,0,0,0,0,0,0
17485000,0.700408,0.000316597,-0.0128583,0.713627,0.0048287,0.00414323,-0.0721325,-0.00334643,0.000492533,-365.498,-1.3527e-05,-6.00153e-05,-2.28452e-05,0,0,-0.000968698,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000124714,1.73669e-05,1.74239e-05,0.000120719,0.0278778,0.0278793,0.0215946,0.0489928,0.0489933,0.0789368,3.1903e-10,3.19122e-10,1.7886e-09,0,0,2.21532e-06,0,0,0,0,0,0,0,0
17585000,0.700487,0.000245829,-0.0128349,0.713549,0.00590885,0.00282347,-0.0665637,-0.00282877,-0.000796712,-365.489,-1.35364e-05,-6.01365e-05,-2.21557e-05,0,0,-0.00097494,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000123962,1.60119e-05,1.60689e-05,0.000120049,0.0249464,0.0249477,0.0207675,0.0434412,0.0434415,0.0774379,2.97413e-10,2.97491e-10,1.74695e-09,0,0,2.21403e-06,0,0,0,0,0,0,0,0
17685000,0.700588,0.000210093,-0.0128205,0.71345,0.00709285,0.00354296,-0.0684163,-0.00217013,-0.000477627,-365.492,-1.3522e-05,-6.01491e-05,-2.14394e-05,0,0,-0.000975859,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000123243,1.66792e-05,1.67362e-05,0.000119393,0.0273096,0.0273112,0.0207178,0.0487758,0.0487763,0.0777849,2.97497e-10,2.97578e-10,1.70651e-09,0,0,2.21343e-06,0,0,0,0,0,0,0,0
17785000,0.700813,0.000129807,-0.0128217,0.713229,0.00907765,0.00318311,-0.0680458,-0.00141495,-0.000486093,-365.494,-1.3444e-05,-6.0198e-05,-2.02728e-05,0,0,-0.000978179,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000122506,1.5395e-05,1.5452e-05,0.000118737,0.0244699,0.0244713,0.0199432,0.0432874,0.0432878,0.076346,2.77483e-10,2.77551e-10,1.66719e-09,0,0,2.21226e-06,0,0,0,0,0,0,0,0
17885000,0.700873,0.000138442,-0.0128113,0.713171,0.0106645,0.00256612,-0.069129,-0.000438568,-0.000171134,-365.497,-1.34351e-05,-6.02068e-05,-1.98017e-05,0,0,-0.000979081,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00012257,1.6029e-05,1.60858e-05,0.000118828,0.0267635,0.0267651,0.0201349,0.0485636,0.0485641,0.0781509,2.77573e-10,2.77641e-10,1.63847e-09,0,0,2.21185e-06,0,0,0,0,0,0,0,0
17985000,0.701032,8.32411e-05,-0.012799,0.713015,0.0121377,0.000476838,-0.0666199,-1.49526e-05,-0.000274746,-365.495,-1.34022e-05,-6.02361e-05,-1.91283e-05,0,0,-0.000982789,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000121826,1.48106e-05,1.48672e-05,0.000118186,0.0240088,0.0240101,0.0193941,0.0431364,0.0431368,0.0767154,2.59043e-10,2.59096e-10,1.60106e-09,0,0,2.21077e-06,0,0,0,0,0,0,0,0
18085000,0.701007,8.48627e-05,-0.0128128,0.713039,0.0127987,0.000282852,-0.066218,0.0012337,-0.000281268,-365.492,-1.3399e-05,-6.02391e-05,-1.89684e-05,0,0,-0.000985482,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000121122,1.54129e-05,1.54695e-05,0.000117548,0.0262393,0.0262408,0.0193318,0.048356,0.0483565,0.0769969,2.59132e-10,2.59181e-10,1.56474e-09,0,0,2.21026e-06,0,0,0,0,0,0,0,0
18185000,0.701169,4.20295e-05,-0.012781,0.712881,0.0133795,0.000763104,-0.064108,0.00197879,-0.000215056,-365.489,-1.34102e-05,-6.02528e-05,-1.82226e-05,0,0,-0.000988974,0.208824,0.00201103,0.434169,0,0,0,0,0,0.0001204,1.42557e-05,1.43122e-05,0.000116914,0.0235663,0.0235675,0.0186382,0.042988,0.0429884,0.0756194,2.41973e-10,2.42007e-10,1.52942e-09,0,0,2.20929e-06,0,0,0,0,0,0,0,0
18285000,0.701255,-2.07853e-05,-0.0127381,0.712797,0.0135538,0.000305133,-0.0643757,0.00331531,-0.000162761,-365.489,-1.34039e-05,-6.02595e-05,-1.78791e-05,0,0,-0.000990517,0.208824,0.00201103,0.434169,0,0,0,0,0,0.0001197,1.48279e-05,1.48845e-05,0.000116296,0.025733,0.0257344,0.0185681,0.0481526,0.048153,0.0758548,2.42062e-10,2.42094e-10,1.49509e-09,0,0,2.20881e-06,0,0,0,0,0,0,0,0
18385000,0.701456,-2.26624e-05,-0.0127555,0.712599,0.0148173,0.00167603,-0.0623832,0.00379132,-6.81337e-05,-365.485,-1.34258e-05,-6.02754e-05,-1.7074e-05,0,0,-0.000994194,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000118991,1.37284e-05,1.37847e-05,0.000115678,0.0231379,0.0231391,0.0179189,0.0428421,0.0428424,0.0745332,2.26173e-10,2.26192e-10,1.46171e-09,0,0,2.20792e-06,0,0,0,0,0,0,0,0
18485000,0.701553,4.15687e-06,-0.0127444,0.712503,0.015897,0.00192767,-0.0642955,0.00536709,0.000104625,-365.486,-1.34161e-05,-6.02856e-05,-1.65434e-05,0,0,-0.000995307,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000119032,1.4273e-05,1.43291e-05,0.000115748,0.0252475,0.0252488,0.018068,0.0479532,0.0479536,0.0761719,2.26265e-10,2.26283e-10,1.43733e-09,0,0,2.20759e-06,0,0,0,0,0,0,0,0
18585000,0.701729,-2.0575e-05,-0.0126725,0.712331,0.015174,0.00176594,-0.0643185,0.0043803,3.22818e-05,-365.487,-1.35214e-05,-6.03103e-05,-1.58146e-05,0,0,-0.000997548,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000118332,1.32268e-05,1.32827e-05,0.000115132,0.0227249,0.022726,0.0174474,0.0426983,0.0426987,0.0748548,2.1155e-10,2.11557e-10,1.40556e-09,0,0,2.20677e-06,0,0,0,0,0,0,0,0
18685000,0.701779,-6.682e-05,-0.0126954,0.712281,0.0155873,0.00133024,-0.0672119,0.00591545,0.000220175,-365.495,-1.35142e-05,-6.03179e-05,-1.5413e-05,0,0,-0.000997066,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000117662,1.3745e-05,1.38009e-05,0.000114519,0.0247743,0.0247755,0.0173732,0.0477573,0.0477578,0.0750377,2.1164e-10,2.11646e-10,1.37466e-09,0,0,2.20636e-06,0,0,0,0,0,0,0,0
18785000,0.701817,-5.30234e-05,-0.0126709,0.712245,0.0144443,0.00114713,-0.0658912,0.00483857,0.00019333,-365.495,-1.36241e-05,-6.03285e-05,-1.51279e-05,0,0,-0.000999646,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000116979,1.27496e-05,1.28054e-05,0.000113915,0.0223195,0.0223206,0.0167916,0.0425566,0.0425569,0.0737741,1.98016e-10,1.98014e-10,1.34463e-09,0,0,2.20561e-06,0,0,0,0,0,0,0,0
18885000,0.701998,-5.05171e-05,-0.0126486,0.712067,0.0151874,0.00180308,-0.0666923,0.00630795,0.000365724,-365.495,-1.36093e-05,-6.03437e-05,-1.43228e-05,0,0,-0.00100091,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000116323,1.32428e-05,1.32985e-05,0.000113315,0.0243149,0.024316,0.0167167,0.0475643,0.0475648,0.0739302,1.98107e-10,1.98103e-10,1.31541e-09,0,0,2.20523e-06,0,0,0,0,0,0,0,0
18985000,0.702092,-4.53294e-05,-0.0126461,0.711974,0.0161509,0.00237069,-0.0674722,0.00731979,0.000296304,-365.496,-1.3595e-05,-6.03662e-05,-1.37471e-05,0,0,-0.00100265,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000115662,1.22952e-05,1.23508e-05,0.000112718,0.0219294,0.0219303,0.0161723,0.0424163,0.0424167,0.0727177,1.85494e-10,1.85484e-10,1.287e-09,0,0,2.20454e-06,0,0,0,0,0,0,0,0
19085000,0.702188,-6.79405e-05,-0.0125935,0.71188,0.016979,0.00306618,-0.0653955,0.00895076,0.000589842,-365.492,-1.3585e-05,-6.03761e-05,-1.32144e-05,0,0,-0.00100516,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000115022,1.27649e-05,1.28204e-05,0.00011213,0.0238693,0.0238704,0.0160972,0.047374,0.0473745,0.0728498,1.85585e-10,1.85574e-10,1.25936e-09,0,0,2.20419e-06,0,0,0,0,0,0,0,0
19185000,0.702233,-6.6168e-05,-0.0124892,0.711838,0.0166591,0.002951,-0.0663602,0.00951948,0.000474912,-365.493,-1.35939e-05,-6.04008e-05,-1.2881e-05,0,0,-0.00100673,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000115031,1.18623e-05,1.19174e-05,0.000112178,0.0215475,0.0215484,0.0157689,0.0422775,0.0422779,0.0729941,1.73912e-10,1.73897e-10,1.23914e-09,0,0,2.20364e-06,0,0,0,0,0,0,0,0
19285000,0.702231,-3.31694e-05,-0.0124379,0.711841,0.0170243,0.00238119,-0.0653113,0.0111697,0.000744195,-365.489,-1.35903e-05,-6.04041e-05,-1.27015e-05,0,0,-0.00100924,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000114395,1.23099e-05,1.2365e-05,0.000111595,0.0234377,0.0234386,0.0156949,0.047186,0.0471865,0.0731085,1.74004e-10,1.73987e-10,1.21279e-09,0,0,2.20332e-06,0,0,0,0,0,0,0,0
19385000,0.702346,-5.64474e-05,-0.0123801,0.711728,0.0150285,0.00129492,-0.060999,0.00928122,0.000578917,-365.482,-1.37089e-05,-6.04253e-05,-1.21761e-05,0,0,-0.00101294,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000113752,1.14503e-05,1.15052e-05,0.00011102,0.0211737,0.0211745,0.0152061,0.0421398,0.0421402,0.07195,1.63198e-10,1.63178e-10,1.18716e-09,0,0,2.20273e-06,0,0,0,0,0,0,0,0
19485000,0.70252,-4.28683e-05,-0.0123955,0.711556,0.0143196,0.000297879,-0.0648167,0.0107217,0.000639502,-365.488,-1.36967e-05,-6.04376e-05,-1.15111e-05,0,0,-0.0010126,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000113127,1.18775e-05,1.19323e-05,0.000110453,0.0230158,0.0230166,0.0151336,0.0469998,0.0470003,0.0720442,1.6329e-10,1.63269e-10,1.16222e-09,0,0,2.20242e-06,0,0,0,0,0,0,0,0
19585000,0.702673,7.71625e-07,-0.0123071,0.711407,0.0125291,-0.000782291,-0.0647099,0.00896289,0.00047532,-365.489,-1.37914e-05,-6.0453e-05,-1.07968e-05,0,0,-0.00101425,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000112503,1.10583e-05,1.11129e-05,0.000109885,0.0208133,0.020814,0.0146736,0.0420031,0.0420034,0.0709227,1.5329e-10,1.53267e-10,1.13793e-09,0,0,2.20188e-06,0,0,0,0,0,0,0,0
19685000,0.702691,-8.91074e-06,-0.0123491,0.711388,0.0133002,-0.00314915,-0.0640855,0.0102456,0.000279009,-365.49,-1.37884e-05,-6.04559e-05,-1.06421e-05,0,0,-0.00101534,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000111892,1.14662e-05,1.15207e-05,0.000109331,0.0226032,0.0226039,0.0146021,0.0468154,0.0468158,0.0709988,1.53382e-10,1.53359e-10,1.1143e-09,0,0,2.2016e-06,0,0,0,0,0,0,0,0
19785000,0.702762,4.27016e-05,-0.0123409,0.711318,0.0108002,-0.00425144,-0.063609,0.00856005,0.000182456,-365.49,-1.38785e-05,-6.04464e-05,-1.03378e-05,0,0,-0.00101722,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000111888,1.06861e-05,1.07403e-05,0.000109369,0.0204582,0.0204588,0.0143334,0.0418671,0.0418674,0.0711752,1.44133e-10,1.44107e-10,1.09701e-09,0,0,2.20117e-06,0,0,0,0,0,0,0,0
19885000,0.702963,-3.23091e-06,-0.0122824,0.71112,0.00985662,-0.00461077,-0.0632787,0.00960537,-0.000274078,-365.491,-1.38644e-05,-6.04602e-05,-9.58182e-06,0,0,-0.00101807,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000111286,1.10753e-05,1.11294e-05,0.000108817,0.0222025,0.0222031,0.014264,0.0466323,0.0466327,0.0712372,1.44225e-10,1.44199e-10,1.07446e-09,0,0,2.2009e-06,0,0,0,0,0,0,0,0
19985000,0.703149,-4.3428e-05,-0.0122708,0.710936,0.00738411,-0.00559686,-0.0608006,0.00801275,-0.00030909,-365.487,-1.3927e-05,-6.04501e-05,-8.90317e-06,0,0,-0.00102053,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000110678,1.03317e-05,1.03856e-05,0.000108272,0.020112,0.0201124,0.0138506,0.0417316,0.0417319,0.0701658,1.35665e-10,1.35637e-10,1.05249e-09,0,0,2.20044e-06,0,0,0,0,0,0,0,0
20085000,0.703386,-6.74623e-05,-0.012241,0.710703,0.00716654,-0.00736569,-0.0611394,0.00874538,-0.000940182,-365.486,-1.39104e-05,-6.04662e-05,-8.01766e-06,0,0,-0.00102164,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000110092,1.07037e-05,1.07576e-05,0.00010773,0.0218137,0.0218143,0.0137839,0.0464503,0.0464507,0.0702127,1.35758e-10,1.3573e-10,1.03111e-09,0,0,2.20019e-06,0,0,0,0,0,0,0,0
20185000,0.7035,2.1982e-05,-0.0122242,0.71059,0.00516792,-0.00827666,-0.0580926,0.00633228,-0.000849558,-365.481,-1.40048e-05,-6.04372e-05,-7.52234e-06,0,0,-0.00102453,0.208824,0.00201103,0.434169,0,0,0,0,0,0.0001095,9.99488e-06,1.00485e-05,0.000107195,0.0197765,0.0197769,0.0133957,0.0415966,0.0415968,0.0691837,1.27837e-10,1.27808e-10,1.01028e-09,0,0,2.19975e-06,0,0,0,0,0,0,0,0
20285000,0.703619,-1.01397e-05,-0.0122054,0.710472,0.00433775,-0.00995076,-0.0606378,0.00680011,-0.00176448,-365.485,-1.39965e-05,-6.04452e-05,-7.08113e-06,0,0,-0.00102474,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000108925,1.03509e-05,1.04044e-05,0.000106669,0.0214363,0.0214368,0.0133318,0.0462697,0.04627,0.0692175,1.2793e-10,1.27901e-10,9.90006e-10,0,0,2.19952e-06,0,0,0,0,0,0,0,0
20385000,0.703687,-3.63353e-06,-0.012248,0.710404,0.00173626,-0.0108765,-0.057671,0.00469223,-0.00154112,-365.479,-1.40714e-05,-6.03988e-05,-6.85772e-06,0,0,-0.00102791,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000108342,9.67513e-06,9.72851e-06,0.000106151,0.0194514,0.0194517,0.012967,0.0414621,0.0414623,0.0682288,1.206e-10,1.2057e-10,9.70239e-10,0,0,2.19912e-06,0,0,0,0,0,0,0,0
20485000,0.703759,3.34153e-05,-0.0122585,0.710333,0.00150653,-0.011862,-0.0589446,0.00484299,-0.00267403,-365.483,-1.40672e-05,-6.04028e-05,-6.63748e-06,0,0,-0.00102808,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000108337,1.00162e-05,1.00694e-05,0.000106181,0.0210677,0.0210681,0.0130484,0.0460901,0.0460904,0.0694358,1.20695e-10,1.20666e-10,9.55778e-10,0,0,2.19896e-06,0,0,0,0,0,0,0,0
20585000,0.703764,5.52011e-05,-0.0123198,0.710327,0.0015338,-0.011993,-0.0611083,0.00409159,-0.00231849,-365.486,-1.40848e-05,-6.03485e-05,-6.53719e-06,0,0,-0.00102891,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000107764,9.37183e-06,9.42482e-06,0.000105664,0.0191352,0.0191356,0.0126989,0.0413281,0.0413283,0.0684524,1.13911e-10,1.13882e-10,9.36889e-10,0,0,2.19858e-06,0,0,0,0,0,0,0,0
20685000,0.703876,7.43758e-05,-0.0123398,0.710216,0.00176867,-0.0134501,-0.0608738,0.00425382,-0.00356883,-365.484,-1.40781e-05,-6.0354e-05,-6.20793e-06,0,0,-0.00103046,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000107203,9.69858e-06,9.7515e-06,0.000105158,0.0207133,0.0207137,0.0126403,0.0459119,0.0459122,0.0684647,1.14004e-10,1.13976e-10,9.18499e-10,0,0,2.19838e-06,0,0,0,0,0,0,0,0
20785000,0.703971,9.82836e-05,-0.0123285,0.710122,0.000371716,-0.0125886,-0.0601958,0.00355783,-0.00302454,-365.484,-1.40888e-05,-6.0297e-05,-5.88509e-06,0,0,-0.00103193,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000106642,9.0835e-06,9.13628e-06,0.000104656,0.0188266,0.0188269,0.012311,0.0411945,0.0411947,0.0675195,1.07723e-10,1.07697e-10,9.00561e-10,0,0,2.19803e-06,0,0,0,0,0,0,0,0
20885000,0.704144,8.21981e-05,-0.012319,0.70995,6.94866e-05,-0.0151616,-0.0614726,0.00359283,-0.00440407,-365.487,-1.40784e-05,-6.03057e-05,-5.36809e-06,0,0,-0.00103227,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000106095,9.39679e-06,9.4495e-06,0.000104159,0.0203661,0.0203664,0.012254,0.0457347,0.045735,0.0675147,1.07816e-10,1.07792e-10,8.83082e-10,0,0,2.19784e-06,0,0,0,0,0,0,0,0
20985000,0.70421,8.90125e-05,-0.0123436,0.709885,-0.000425406,-0.0159445,-0.0601554,0.00473075,-0.0038227,-365.486,-1.40513e-05,-6.02413e-05,-5.09658e-06,0,0,-0.00103404,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00010555,8.81e-06,8.86259e-06,0.000103666,0.0185259,0.0185262,0.0119439,0.0410614,0.0410616,0.066606,1.02001e-10,1.01977e-10,8.66041e-10,0,0,2.19751e-06,0,0,0,0,0,0,0,0
21085000,0.704358,7.38275e-05,-0.0123386,0.709738,-0.000247448,-0.0185608,-0.0606056,0.00468606,-0.00554863,-365.488,-1.40443e-05,-6.02472e-05,-4.74784e-06,0,0,-0.00103463,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000105537,9.11097e-06,9.16332e-06,0.000103692,0.0200281,0.0200283,0.0120188,0.0455584,0.0455586,0.0677288,1.02096e-10,1.02074e-10,8.53574e-10,0,0,2.19738e-06,0,0,0,0,0,0,0,0
21185000,0.704402,0.000105193,-0.0123475,0.709694,0.000108643,-0.017748,-0.0604632,0.00570505,-0.00477776,-365.491,-1.40209e-05,-6.0168e-05,-4.60687e-06,0,0,-0.00103567,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000104995,8.55086e-06,8.60315e-06,0.000103206,0.0182334,0.0182336,0.011721,0.0409285,0.0409287,0.0668249,9.67112e-11,9.6689e-11,8.3727e-10,0,0,2.19707e-06,0,0,0,0,0,0,0,0
21285000,0.704608,0.000137119,-0.0123084,0.70949,-0.000503822,-0.0198387,-0.0598446,0.00568648,-0.00664409,-365.489,-1.4011e-05,-6.01763e-05,-4.11939e-06,0,0,-0.0010369,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000104462,8.83983e-06,8.89203e-06,0.00010273,0.0197006,0.0197007,0.0116698,0.0453831,0.0453833,0.0668051,9.68047e-11,9.67845e-11,8.21375e-10,0,0,2.1969e-06,0,0,0,0,0,0,0,0
21385000,0.704605,0.000178318,-0.0123112,0.709492,-0.00147599,-0.0195591,-0.058931,0.00477557,-0.00481277,-365.49,-1.40198e-05,-6.00567e-05,-4.01522e-06,0,0,-0.00103814,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000103938,8.30508e-06,8.35723e-06,0.00010225,0.0179495,0.0179496,0.011389,0.0407961,0.0407963,0.0659357,9.18163e-11,9.1796e-11,8.05872e-10,0,0,2.19661e-06,0,0,0,0,0,0,0,0
21485000,0.70472,0.000187693,-0.012289,0.709379,-0.00180256,-0.0209257,-0.0596828,0.0045801,-0.00682169,-365.492,-1.40128e-05,-6.00627e-05,-3.66715e-06,0,0,-0.00103871,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000103424,8.58313e-06,8.6352e-06,0.000101778,0.0193831,0.0193833,0.011341,0.0452088,0.0452091,0.0659099,9.19102e-11,9.18916e-11,7.90755e-10,0,0,2.19645e-06,0,0,0,0,0,0,0,0
21585000,0.704758,0.000188803,-0.0122663,0.709341,-0.00274742,-0.0182966,-0.0591462,0.00380764,-0.00492811,-365.494,-1.40131e-05,-5.99467e-05,-3.52856e-06,0,0,-0.00103974,0.208824,0.00201103,0.434169,0,0,0,0,0,0.00010291,8.07228e-06,8.12433e-06,0.000101313,0.0176747,0.0176749,0.0110761,0.0406642,0.0406643,0.0650733,8.7287e-11,8.72682e-11,7.76007e-10,0,0,2.19618e-06,0,0,0,0,0,0,0,0
21685000,0.704811,0.000185725,-0.0123032,0.709288,-0.00253758,-0.0197306,-0.0580984,0.00353934,-0.00684451,-365.495,-1.40086e-05,-5.99505e-05,-3.3096e-06,0,0,-0.00104049,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000102411,8.34027e-06,8.39224e-06,0.00010085,0.019074,0.0190741,0.011031,0.0450357,0.0450359,0.0650427,8.73812e-11,8.7364e-11,7.61622e-10,0,0,2.19603e-06,0,0,0,0,0,0,0,0
21785000,0.70481,0.000186714,-0.0123096,0.70929,-0.00334907,-0.0152906,-0.0588635,0.00202997,-0.00307859,-365.499,-1.40384e-05,-5.97771e-05,-3.28272e-06,0,0,-0.00104106,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000102392,7.85245e-06,7.90427e-06,0.000100863,0.0174077,0.0174078,0.0108906,0.0405327,0.0405329,0.0652857,8.30962e-11,8.30784e-11,7.51079e-10,0,0,2.19581e-06,0,0,0,0,0,0,0,0
21885000,0.704881,0.000188307,-0.0122609,0.709219,-0.00295138,-0.0156702,-0.058616,0.00171332,-0.00462167,-365.502,-1.40354e-05,-5.97796e-05,-3.13591e-06,0,0,-0.0010415,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000101893,8.11048e-06,8.16221e-06,0.00010041,0.0187763,0.0187764,0.0108482,0.0448639,0.0448641,0.0652498,8.31907e-11,8.31743e-11,7.37298e-10,0,0,2.19567e-06,0,0,0,0,0,0,0,0
21985000,0.704967,0.000201427,-0.0123098,0.709133,-0.00380169,-0.0134143,-0.0574144,0.000514542,-0.00129182,-365.503,-1.40533e-05,-5.96339e-05,-2.89806e-06,-1.62879e-11,1.58225e-11,-0.00104258,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000101396,7.64419e-06,7.69597e-06,9.99594e-05,0.0171847,0.0171849,0.0106073,0.0404019,0.0404021,0.0644486,7.92142e-11,7.91977e-11,7.23847e-10,4e-06,4e-06,2.19542e-06,0,0,0,0,0,0,0,0
22085000,0.705021,0.000210126,-0.0122971,0.70908,-0.0039799,-0.012685,-0.0594155,0.000147636,-0.00258509,-365.506,-1.40503e-05,-5.96365e-05,-2.74704e-06,-1.03547e-09,1.00589e-09,-0.00104293,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000100912,7.89334e-06,7.94506e-06,9.95139e-05,0.0191662,0.0191663,0.0105686,0.0446959,0.0446961,0.0644092,7.93089e-11,7.92938e-11,7.10722e-10,4.00001e-06,4.00001e-06,2.19529e-06,0,0,0,0,0,0,0,0
22185000,0.705101,0.000192579,-0.0122755,0.709,-0.00382299,-0.0115975,-0.0577274,9.47774e-05,-0.00225686,-365.507,-1.40349e-05,-5.95974e-05,-2.53026e-06,-2.76197e-06,9.07748e-07,-0.00104415,0.208824,0.00201103,0.434169,0,0,0,0,0,0.000100427,7.44828e-06,7.50005e-06,9.90727e-05,0.0188341,0.0188341,0.0103405,0.0402786,0.0402787,0.063631,7.5624e-11,7.56088e-11,6.979e-10,3.98838e-06,3.98838e-06,2.19506e-06,0,0,0,0,0,0,0,0
22285000,0.705104,0.000228279,-0.0123102,0.708997,-0.00510452,-0.0124877,-0.0581571,-0.000348747,-0.00346638,-365.51,-1.40335e-05,-5.95986e-05,-2.46116e-06,-2.7727e-06,9.18226e-07,-0.00104458,0.208824,0.00201103,0.434169,0,0,0,0,0,9.99565e-05,7.68919e-06,7.7409e-06,9.86345e-05,0.0222919,0.0222919,0.0103054,0.0445866,0.0445867,0.0635888,7.5719e-11,7.5705e-11,6.85395e-10,3.98839e-06,3.98839e-06,2.19492e-06,0,0,0,0,0,0,0,0
22385000,0.705145,0.000214669,-0.0123069,0.708956,-0.0058768,-0.0115126,-0.0562673,-0.000365091,-0.00303582,-365.508,-1.40142e-05,-5.95603e-05,-2.27974e-06,-9.13711e-06,3.77942e-06,-0.00104631,0.208824,0.00201103,0.434169,0,0,0,0,0,9.9939e-05,7.27436e-06,7.326e-06,9.86408e-05,0.0227892,0.0227891,0.010191,0.0402177,0.0402178,0.0638486,7.23572e-11,7.2343e-11,6.76229e-10,3.92483e-06,3.92483e-06,2.19474e-06,0,0,0,0,0,0,0,0
22485000,0.705214,0.000222742,-0.012273,0.708888,-0.00631716,-0.0114185,-0.0554022,-0.00096942,-0.00420697,-365.506,-1.40103e-05,-5.95638e-05,-2.08419e-06,-9.20578e-06,3.84652e-06,-0.0010476,0.208824,0.00201103,0.434169,0,0,0,0,0,9.94724e-05,7.50738e-06,7.55895e-06,9.82093e-05,0.0275237,0.0275235,0.0101594,0.0446589,0.044659,0.063803,7.24524e-11,7.24393e-11,6.64234e-10,3.92484e-06,3.92484e-06,2.19462e-06,0,0,0,0,0,0,0,0
22585000,0.70529,0.000195997,-0.012251,0.708813,-0.00584474,-0.00988571,-0.0555487,-0.00159774,-0.00266104,-365.507,-1.39857e-05,-5.95049e-05,-1.87403e-06,-2.51683e-05,1.54059e-05,-0.00104862,0.208824,0.00201103,0.434169,0,0,0,0,0,9.90054e-05,7.14175e-06,7.19337e-06,9.77814e-05,0.028047,0.0280468,0.00995254,0.0403104,0.0403105,0.0630571,6.9493e-11,6.94801e-11,6.52511e-10,3.78292e-06,3.78292e-06,2.19441e-06,0,0,0,0,0,0,0,0
22685000,0.705364,0.000234229,-0.0122781,0.708739,-0.00685839,-0.00974077,-0.0547416,-0.00221396,-0.00364634,-365.507,-1.39815e-05,-5.95087e-05,-1.66296e-06,-2.52559e-05,1.54927e-05,-0.00104943,0.208824,0.00201103,0.434169,0,0,0,0,0,9.85501e-05,7.36859e-06,7.42016e-06,9.73589e-05,0.0337563,0.033756,0.0099243,0.0450232,0.0450233,0.0630102,6.95884e-11,6.95766e-11,6.41072e-10,3.78293e-06,3.78293e-06,2.19429e-06,0,0,0,0,0,0,0,0
22785000,0.705288,0.000218855,-0.0122596,0.708815,-0.00704193,-0.0075004,-0.0531268,-0.00359141,-0.00301375,-365.503,-1.39895e-05,-5.94762e-05,-1.89535e-06,-3.48997e-05,2.09686e-05,-0.00105169,0.208824,0.00201103,0.434169,0,0,0,0,0,9.80919e-05,7.0755e-06,7.12711e-06,9.69429e-05,0.0334795,0.0334791,0.0097283,0.0406205,0.0406206,0.0622913,6.71202e-11,6.71087e-11,6.2989e-10,3.55842e-06,3.55842e-06,2.19409e-06,0,0,0,0,0,0,0,0
22885000,0.705348,0.000231472,-0.0122367,0.708755,-0.00809997,-0.00715915,-0.0519585,-0.00433617,-0.00374258,-365.502,-1.39875e-05,-5.94782e-05,-1.79238e-06,-3.50525e-05,2.11164e-05,-0.00105266,0.208824,0.00201103,0.434169,0,0,0,0,0,9.76447e-05,7.29746e-06,7.349e-06,9.65329e-05,0.0397924,0.0397919,0.00970318,0.045712,0.0457121,0.0622436,6.72159e-11,6.72054e-11,6.18977e-10,3.55843e-06,3.55842e-06,2.19397e-06,0,0,0,0,0,0,0,0
22985000,0.705405,0.000219545,-0.0122238,0.708699,-0.00777917,-0.00644932,-0.0501863,-0.005285,-0.00309559,-365.498,-1.39826e-05,-5.94612e-05,-1.65506e-06,-4.334e-05,2.88868e-05,-0.00105448,0.208824,0.00201103,0.434169,0,0,0,0,0,9.7199e-05,7.09366e-06,7.14518e-06,9.61245e-05,0.0381117,0.0381113,0.00951675,0.0411466,0.0411466,0.0615503,6.52827e-11,6.52727e-11,6.08307e-10,3.26864e-06,3.26864e-06,2.19379e-06,0,0,0,0,0,0,0,0
23085000,0.705415,0.000181529,-0.0121762,0.70869,-0.00808459,-0.00624929,-0.0509233,-0.0060758,-0.00371035,-365.497,-1.39819e-05,-5.94622e-05,-1.61248e-06,-4.35683e-05,2.91051e-05,-0.00105557,0.208824,0.00201103,0.434169,0,0,0,0,0,9.71841e-05,7.31301e-06,7.3643e-06,9.61296e-05,0.0446495,0.0446489,0.00958538,0.0466603,0.0466603,0.0624628,6.53795e-11,6.53703e-11,6.00492e-10,3.26865e-06,3.26864e-06,2.19371e-06,0,0,0,0,0,0,0,0
23185000,0.705465,0.000232204,-0.0121419,0.708641,-0.0115916,-0.0059897,-0.048861,-0.0102456,-0.00302201,-365.492,-1.40215e-05,-5.94486e-05,-1.52659e-06,-5.18446e-05,6.20277e-06,-0.0010576,0.208824,0.00201103,0.434169,0,0,0,0,0,9.67426e-05,7.20274e-06,7.25395e-06,9.57267e-05,0.0413559,0.0413553,0.00940434,0.0418255,0.0418256,0.0617729,6.39587e-11,6.39501e-11,5.90244e-10,2.94348e-06,2.94348e-06,2.19353e-06,0,0,0,0,0,0,0,0
23285000,0.705493,0.000166433,-0.0121557,0.708612,-0.0120803,-0.00718765,-0.0487263,-0.011421,-0.00368616,-365.494,-1.40191e-05,-5.94509e-05,-1.40342e-06,-5.1972e-05,6.32777e-06,-0.00105809,0.208824,0.00201103,0.434169,0,0,0,0,0,9.63159e-05,7.42155e-06,7.47269e-06,9.53247e-05,0.0477903,0.0477897,0.00938438,0.0477371,0.0477371,0.0617235,6.40548e-11,6.4047e-11,5.80238e-10,2.94348e-06,2.94348e-06,2.19342e-06,0,0,0,0,0,0,0,0
23385000,0.705558,0.000230719,-0.0121133,0.708549,-0.0146988,-0.00622682,-0.0493573,-0.0147584,-0.00291151,-365.496,-1.40361e-05,-5.94399e-05,-1.29262e-06,-6.0889e-05,-1.11602e-05,-0.00105876,0.208824,0.00201103,0.434169,0,0,0,0,0,9.58849e-05,7.39706e-06,7.44806e-06,9.49308e-05,0.0430552,0.0430546,0.00921149,0.0425655,0.0425655,0.0610576,6.30702e-11,6.3063e-11,5.70451e-10,2.61345e-06,2.61345e-06,2.19325e-06,0,0,0,0,0,0,0,0
23485000,0.705652,0.00236412,-0.00994815,0.708484,-0.021495,-0.00689338,-0.0816976,-0.0165025,-0.00356254,-365.498,-1.40316e-05,-5.94444e-05,-1.051e-06,-6.10876e-05,-1.09657e-05,-0.00105933,0.208824,0.00201103,0.434169,0,0,0,0,0,9.54718e-05,7.6107e-06,7.6604e-06,9.45469e-05,0.0491681,0.0491673,0.00919554,0.0488019,0.0488019,0.0610033,6.31664e-11,6.316e-11,5.60886e-10,2.61345e-06,2.61345e-06,2.19315e-06,0,0,0,0,0,0,0,0
23585000,0.705276,0.00769787,-0.00231594,0.708887,-0.0294683,-0.0033721,-0.112659,-0.0147614,-0.00135392,-365.499,-1.40002e-05,-5.94291e-05,-1.04112e-06,-7.95938e-05,7.06788e-06,-0.00106118,0.208824,0.00201103,0.434169,0,0,0,0,0,9.51044e-05,7.64566e-06,7.68756e-06,9.41394e-05,0.0433899,0.0433888,0.00903167,0.0432808,0.0432808,0.0603608,6.25166e-11,6.25105e-11,5.51534e-10,2.30182e-06,2.30182e-06,2.193e-06,0,0,0,0,0,0,0,0
23685000,0.704658,0.00754414,0.0039297,0.709496,-0.0599138,-0.0111757,-0.162192,-0.0191178,-0.00199448,-365.51,-1.39988e-05,-5.9431e-05,-9.53141e-07,-7.97356e-05,7.20007e-06,-0.00106155,0.208824,0.00201103,0.434169,0,0,0,0,0,9.51681e-05,7.86691e-06,7.89294e-06,9.40812e-05,0.04903,0.0490302,0.00910128,0.0497487,0.0497485,0.0612373,6.2614e-11,6.26081e-11,5.44686e-10,2.30182e-06,2.30182e-06,2.19293e-06,0,0,0,0,0,0,0,0
23785000,0.704381,0.00470269,0.000972266,0.709806,-0.078436,-0.0199229,-0.21522,-0.0161564,-0.000278692,-365.519,-1.395e-05,-5.94242e-05,-8.184e-07,-0.00010232,6.36216e-05,-0.00106315,0.208824,0.00201103,0.434169,0,0,0,0,0,9.47911e-05,7.96508e-06,7.99626e-06,9.36573e-05,0.0426462,0.0426479,0.00894496,0.043911,0.0439109,0.0605981,6.2203e-11,6.21975e-11,5.35693e-10,2.02206e-06,2.02208e-06,2.19283e-06,0,0,0,0,0,0,0,0
23885000,0.704259,0.00202476,-0.0051025,0.709922,-0.0951437,-0.0288531,-0.268852,-0.0249425,-0.0027536,-365.541,-1.39468e-05,-5.94277e-05,-6.42405e-07,-0.00010244,6.37306e-05,-0.00106338,0.208824,0.00201103,0.434169,0,0,0,0,0,9.43981e-05,8.19696e-06,8.2384e-06,9.32449e-05,0.0477505,0.0477531,0.00893583,0.0505108,0.0505107,0.0605463,6.22995e-11,6.22944e-11,5.26902e-10,2.02206e-06,2.02208e-06,2.19275e-06,0,0,0,0,0,0,0,0
23985000,0.704202,0.000582864,-0.00982684,0.709931,-0.0939153,-0.031636,-0.321065,-0.028195,-0.00584517,-365.563,-1.39168e-05,-5.94387e-05,-5.53778e-07,-0.000108927,8.60986e-05,-0.00106404,0.208824,0.00201103,0.434169,0,0,0,0,0,9.39837e-05,8.3487e-06,8.39463e-06,9.28486e-05,0.0411545,0.041156,0.00879099,0.0444202,0.04442,0.0599295,6.2051e-11,6.20466e-11,5.183e-10,1.77919e-06,1.77922e-06,2.19267e-06,0,0,0,0,0,0,0,0
24085000,0.704267,0.00178118,-0.0087971,0.709878,-0.0952397,-0.0314357,-0.369437,-0.0376042,-0.0089777,-365.589,-1.39132e-05,-5.94442e-05,-3.15166e-07,-0.0001094,8.65438e-05,-0.00106513,0.208824,0.00201103,0.434169,0,0,0,0,0,9.35919e-05,8.57693e-06,8.62185e-06,9.24796e-05,0.0457186,0.0457197,0.00878639,0.0510612,0.051061,0.0598804,6.21476e-11,6.21439e-11,5.09892e-10,1.77919e-06,1.77922e-06,2.19261e-06,0,0,0,0,0,0,0,0
24185000,0.704292,0.00290646,-0.0064028,0.709876,-0.0949421,-0.0310701,-0.416458,-0.0386713,-0.0107252,-365.613,-1.38805e-05,-5.94539e-05,-1.73918e-07,-0.000119792,0.000112434,-0.00106546,0.208824,0.00201103,0.434169,0,0,0,0,0,9.31987e-05,8.74135e-06,8.78348e-06,9.2118e-05,0.0392087,0.0392091,0.00864917,0.0447944,0.0447941,0.0592851,6.20067e-11,6.20035e-11,5.01665e-10,1.57263e-06,1.57266e-06,2.19255e-06,0,0,0,0,0,0,0,0
24285000,0.704215,0.00342361,-0.0054877,0.709957,-0.104895,-0.0348194,-0.471759,-0.0486415,-0.0140178,-365.655,-1.38814e-05,-5.94539e-05,-2.00901e-07,-0.000119947,0.00011256,-0.00106578,0.208824,0.00201103,0.434169,0,0,0,0,0,9.28181e-05,8.97569e-06,9.01644e-06,9.1752e-05,0.0432633,0.0432636,0.00864868,0.051403,0.0514027,0.0592388,6.21034e-11,6.21006e-11,4.9362e-10,1.57262e-06,1.57266e-06,2.19251e-06,0,0,0,0,0,0,0,0
24385000,0.704178,0.00354592,-0.00574822,0.709992,-0.112784,-0.0457663,-0.523364,-0.0555005,-0.0278853,-365.697,-1.38631e-05,-5.94874e-05,-1.50492e-07,-9.10184e-05,0.000118843,-0.00106537,0.208824,0.00201103,0.434169,0,0,0,0,0,9.27948e-05,9.16781e-06,9.20832e-06,9.17454e-05,0.0370314,0.0370315,0.00859489,0.045035,0.0450347,0.0595374,6.20335e-11,6.20309e-11,4.87719e-10,1.39906e-06,1.3991e-06,2.19246e-06,0,0,0,0,0,0,0,0
24485000,0.704225,0.00437618,-0.00177671,0.709961,-0.125435,-0.0505768,-0.574587,-0.0673312,-0.0326426,-365.745,-1.38635e-05,-5.94892e-05,-1.17198e-07,-9.13699e-05,0.000119139,-0.00106596,0.208824,0.00201103,0.434169,0,0,0,0,0,9.24149e-05,9.40329e-06,9.4377e-06,9.13998e-05,0.0406226,0.0406227,0.00859672,0.0515556,0.0515552,0.0594931,6.21303e-11,6.2128e-11,4.79975e-10,1.39906e-06,1.3991e-06,2.19243e-06,0,0,0,0,0,0,0,0
24585000,0.704352,0.00492857,0.00205839,0.709831,-0.137214,-0.0631403,-0.623782,-0.0705142,-0.042885,-365.796,-1.38385e-05,-5.95122e-05,1.28688e-07,-8.07877e-05,0.000145126,-0.00106369,0.208824,0.00201103,0.434169,0,0,0,0,0,9.20237e-05,9.60879e-06,9.63515e-06,9.10542e-05,0.0347777,0.0347783,0.00847143,0.0451523,0.045152,0.0589214,6.21057e-11,6.21034e-11,4.72393e-10,1.25412e-06,1.25415e-06,2.19235e-06,0,0,0,0,0,0,0,0
24685000,0.704411,0.00497559,0.00312904,0.709768,-0.161429,-0.0765661,-0.703894,-0.0853986,-0.0498537,-365.858,-1.38349e-05,-5.95169e-05,3.44896e-07,-8.09306e-05,0.0001453,-0.00106379,0.208824,0.00201103,0.434169,0,0,0,0,0,9.16512e-05,9.85533e-06,9.87896e-06,9.07014e-05,0.037952,0.0379539,0.00848508,0.0515447,0.0515443,0.0588808,6.22027e-11,6.22007e-11,4.64977e-10,1.25412e-06,1.25415e-06,2.19235e-06,0,0,0,0,0,0,0,0
24785000,0.704354,0.00472834,0.00192048,0.70983,-0.176428,-0.0876361,-0.791218,-0.0922133,-0.0599205,-365.927,-1.38238e-05,-5.95551e-05,3.08515e-07,-9.54201e-05,0.000172291,-0.00106212,0.208824,0.00201103,0.434169,0,0,0,0,0,9.12644e-05,1.00767e-05,1.01024e-05,9.03455e-05,0.0325373,0.0325397,0.00837955,0.0451606,0.0451602,0.0583248,6.22098e-11,6.22076e-11,4.5771e-10,1.13354e-06,1.13357e-06,2.19221e-06,0,0,0,0,0,0,0,0
24885000,0.704325,0.00637177,0.00345234,0.709841,-0.197512,-0.0986156,-0.814518,-0.110852,-0.0691991,-366.004,-1.3824e-05,-5.95561e-05,3.25785e-07,-9.55858e-05,0.000172426,-0.00106222,0.208824,0.00201103,0.434169,0,0,0,0,0,9.08969e-05,1.03297e-05,1.03526e-05,9.00015e-05,0.0353611,0.0353645,0.008377,0.051398,0.0513976,0.0582892,6.2307e-11,6.2305e-11,4.50606e-10,1.13354e-06,1.13358e-06,2.19221e-06,0,0,0,0,0,0,0,0
24985000,0.704265,0.00829955,0.00541568,0.709868,-0.210796,-0.103526,-0.869701,-0.112441,-0.0753107,-366.08,-1.38202e-05,-5.95906e-05,2.45314e-07,-0.000125078,0.000223834,-0.00105827,0.208824,0.00201103,0.434169,0,0,0,0,0,9.08587e-05,1.05635e-05,1.05827e-05,8.99976e-05,0.0303999,0.0304044,0.00833832,0.0450746,0.0450742,0.0586029,6.23362e-11,6.23341e-11,4.45393e-10,1.0331e-06,1.03313e-06,2.19201e-06,0,0,0,0,0,0,0,0
25085000,0.70425,0.00869337,0.00492078,0.709882,-0.240444,-0.114113,-0.920426,-0.135004,-0.086163,-366.164,-1.38209e-05,-5.95922e-05,2.62543e-07,-0.00012536,0.000224053,-0.00105827,0.208824,0.00201103,0.434169,0,0,0,0,0,9.04937e-05,1.08219e-05,1.08422e-05,8.96542e-05,0.0329053,0.0329124,0.00834866,0.0511378,0.0511375,0.0585702,6.24336e-11,6.24316e-11,4.38547e-10,1.0331e-06,1.03313e-06,2.19202e-06,0,0,0,0,0,0,0,0
25185000,0.704284,0.00821891,0.00339467,0.709863,-0.265043,-0.129788,-0.969985,-0.156112,-0.114098,-366.249,-1.3807e-05,-5.9633e-05,3.86327e-07,-0.000102361,0.000226867,-0.00105479,0.208824,0.00201103,0.434169,0,0,0,0,0,9.01114e-05,1.10641e-05,1.10868e-05,8.9307e-05,0.0283814,0.0283889,0.0082397,0.044908,0.0449077,0.0580357,6.24786e-11,6.24764e-11,4.31831e-10,9.49343e-07,9.49362e-07,2.19174e-06,0,0,0,0,0,0,0,0
25285000,0.704355,0.0100211,0.0098549,0.709709,-0.293015,-0.138988,-1.02487,-0.183915,-0.127463,-366.342,-1.38062e-05,-5.96369e-05,5.02759e-07,-0.000102663,0.000227147,-0.00105451,0.208824,0.00201103,0.434169,0,0,0,0,0,8.97478e-05,1.13322e-05,1.13401e-05,8.89851e-05,0.0306163,0.0306264,0.00825419,0.0507872,0.0507872,0.0580076,6.2576e-11,6.25739e-11,4.25269e-10,9.49341e-07,9.49366e-07,2.19174e-06,0,0,0,0,0,0,0,0
25385000,0.704437,0.0115014,0.0166403,0.709478,-0.320791,-0.159332,-1.07341,-0.195955,-0.148198,-366.438,-1.37992e-05,-5.96686e-05,6.29559e-07,-0.000101771,0.000265565,-0.00104819,0.208824,0.00201103,0.434169,0,0,0,0,0,8.93526e-05,1.1597e-05,1.15843e-05,8.86562e-05,0.0265035,0.0265157,0.00815004,0.0446747,0.0446746,0.0574913,6.26339e-11,6.26317e-11,4.18827e-10,8.79356e-07,8.79367e-07,2.19136e-06,0,0,0,0,0,0,0,0
25485000,0.704494,0.0117962,0.0181509,0.70938,-0.368761,-0.182756,-1.12709,-0.230422,-0.165273,-366.547,-1.37961e-05,-5.96718e-05,7.93083e-07,-0.000101732,0.000265617,-0.00104803,0.208824,0.00201103,0.434169,0,0,0,0,0,8.89979e-05,1.18699e-05,1.18526e-05,8.83278e-05,0.0285074,0.0285264,0.0081658,0.0503653,0.0503659,0.0574677,6.27311e-11,6.27293e-11,4.12535e-10,8.79354e-07,8.79373e-07,2.19135e-06,0,0,0,0,0,0,0,0
25585000,0.704609,0.0113228,0.0161772,0.709321,-0.408792,-0.214739,-1.18191,-0.259077,-0.20478,-366.658,-1.37832e-05,-5.97167e-05,9.17692e-07,-8.26061e-05,0.000279767,-0.00104447,0.208824,0.00201103,0.434169,0,0,0,0,0,8.86203e-05,1.21247e-05,1.21142e-05,8.79966e-05,0.0247744,0.0247951,0.00806858,0.0443866,0.044387,0.0569687,6.27997e-11,6.27978e-11,4.06347e-10,8.20754e-07,8.20759e-07,2.19085e-06,0,0,0,0,0,0,0,0
25685000,0.704566,0.0147117,0.0224799,0.70913,-0.456173,-0.23504,-1.23505,-0.302218,-0.22723,-366.779,-1.37818e-05,-5.97178e-05,9.84476e-07,-8.25498e-05,0.000279768,-0.00104445,0.208824,0.00201103,0.434169,0,0,0,0,0,8.85809e-05,1.24211e-05,1.23918e-05,8.79883e-05,0.0265808,0.0266092,0.00815354,0.0498883,0.04989,0.0577728,6.28977e-11,6.28962e-11,4.01831e-10,8.20754e-07,8.20766e-07,2.19082e-06,0,0,0,0,0,0,0,0
25785000,0.704512,0.0175736,0.0293275,0.708868,-0.498519,-0.26063,-1.282,-0.318031,-0.255635,-366.898,-1.37845e-05,-5.97596e-05,1.15896e-06,-9.57638e-05,0.000341236,-0.00103806,0.208824,0.00201103,0.434169,0,0,0,0,0,8.81767e-05,1.27209e-05,1.26667e-05,8.76392e-05,0.0231949,0.0232286,0.00805618,0.0440544,0.0440556,0.0572762,6.29753e-11,6.29738e-11,3.95852e-10,7.71612e-07,7.71608e-07,2.19019e-06,0,0,0,0,0,0,0,0
25885000,0.711586,0.018271,0.0298283,0.701728,-0.568851,-0.28921,-1.33231,-0.371397,-0.283154,-367.027,-1.37848e-05,-5.976e-05,1.15827e-06,-9.58354e-05,0.000341278,-0.00103786,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000907149,1.43032e-05,1.33082e-05,0.000934441,0.0250694,0.0251275,0.00796736,0.0493685,0.0493718,0.0572455,6.30751e-11,6.30735e-11,3.95951e-10,7.71612e-07,7.71615e-07,2.19013e-06,0,0,0,0,0,0,0,0
25985000,0.710523,0.0172662,0.02657,0.70296,-0.622475,-0.327381,-1.38778,-0.412239,-0.340748,-367.16,-1.37858e-05,-5.98119e-05,1.15901e-06,-7.44503e-05,0.000371609,-0.00103849,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000695764,1.37391e-05,1.3177e-05,0.000715536,0.0223857,0.0224761,0.00863776,0.0436855,0.0436881,0.0567229,6.31376e-11,6.31349e-11,3.96011e-10,7.27314e-07,7.27302e-07,2.19e-06,0,0,0,0,0,0,0,0
26085000,0.705234,0.0218323,0.0359739,0.707725,-0.687779,-0.353683,-1.41477,-0.477649,-0.374785,-367.299,-1.37863e-05,-5.98124e-05,1.15201e-06,-7.46285e-05,0.000371604,-0.00103838,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000570796,1.42558e-05,1.33593e-05,0.000576535,0.0244946,0.0246392,0.0103064,0.0488253,0.0488314,0.0566417,6.32374e-11,6.32345e-11,3.96108e-10,7.27315e-07,7.27309e-07,2.18998e-06,0,0,0,0,0,0,0,0
26185000,0.703039,0.0244735,0.046011,0.709239,-0.735817,-0.386159,-1.38352,-0.500518,-0.416882,-367.432,-1.38675e-05,-5.99125e-05,1.14595e-06,-9.617e-05,0.000463239,-0.00105279,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000483696,1.48163e-05,1.34406e-05,0.000484658,0.0222155,0.0224024,0.0125395,0.0432986,0.0433034,0.0561515,6.32301e-11,6.32256e-11,3.96175e-10,6.8398e-07,6.83956e-07,2.18596e-06,0,0,0,0,0,0,0,0
26285000,0.702681,0.0254755,0.0486901,0.70938,-0.828113,-0.427116,-1.37233,-0.578652,-0.457549,-367.569,-1.38678e-05,-5.9913e-05,1.14135e-06,-9.63354e-05,0.000463216,-0.00105287,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000433844,1.48857e-05,1.34961e-05,0.000435206,0.0244964,0.0247909,0.0158877,0.0483018,0.048314,0.0569896,6.333e-11,6.33254e-11,3.9627e-10,6.83981e-07,6.83965e-07,2.18595e-06,0,0,0,0,0,0,0,0
26385000,0.703562,0.0245822,0.0451126,0.708775,-0.908211,-0.485465,-1.37655,-0.646189,-0.545464,-367.703,-1.38428e-05,-5.9997e-05,1.12605e-06,-6.22011e-05,0.000481504,-0.00105075,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000381153,1.44231e-05,1.34135e-05,0.000383811,0.022479,0.0228075,0.0194804,0.0429244,0.0429338,0.0566643,6.32322e-11,6.32256e-11,3.96342e-10,6.41693e-07,6.41638e-07,2.17162e-06,0,0,0,0,0,0,0,0
26485000,0.703678,0.0320856,0.0599683,0.707256,-1.00147,-0.523632,-1.38084,-0.741433,-0.595941,-367.839,-1.38432e-05,-5.99981e-05,1.11943e-06,-6.2502e-05,0.00048145,-0.00105143,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000339942,1.53167e-05,1.37349e-05,0.000344254,0.0248948,0.0253234,0.0243103,0.0478338,0.047856,0.0570599,6.33321e-11,6.33253e-11,3.9643e-10,6.41682e-07,6.41646e-07,2.17124e-06,0,0,0,0,0,0,0,0
26585000,0.703185,0.0387911,0.0768185,0.70578,-1.08983,-0.575297,-1.36882,-0.783005,-0.661224,-367.972,-1.40169e-05,-6.01878e-05,1.08681e-06,-8.92433e-05,0.000589056,-0.00106238,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000305635,1.63415e-05,1.39809e-05,0.000311367,0.0229928,0.0234868,0.028594,0.0425902,0.0426073,0.0570606,6.31379e-11,6.31294e-11,3.96503e-10,6.00833e-07,6.00707e-07,2.14139e-06,0,0,0,0,0,0,0,0
26685000,0.704121,0.0402449,0.0802667,0.70438,-1.23522,-0.636065,-1.35857,-0.899233,-0.721747,-368.108,-1.4017e-05,-6.01879e-05,1.08844e-06,-8.91943e-05,0.000589085,-0.00106291,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000279287,1.64107e-05,1.40575e-05,0.000285962,0.0255326,0.026223,0.034578,0.0474462,0.0474854,0.0580677,6.32378e-11,6.32289e-11,3.96584e-10,6.00806e-07,6.00712e-07,2.13982e-06,0,0,0,0,0,0,0,0
26785000,0.705006,0.0383351,0.0744649,0.704239,-1.35473,-0.721066,-1.36141,-0.994692,-0.853316,-368.245,-1.40632e-05,-6.02533e-05,1.03732e-06,-3.33236e-05,0.000633361,-0.00105995,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000256397,1.56409e-05,1.38534e-05,0.000263335,0.0236406,0.0243639,0.0388231,0.042315,0.0423448,0.0584574,6.29541e-11,6.29444e-11,3.96654e-10,5.61993e-07,5.61721e-07,2.09164e-06,0,0,0,0,0,0,0,0
26885000,0.704552,0.0468241,0.0950203,0.701701,-1.49818,-0.77815,-1.37409,-1.13703,-0.928127,-368.383,-1.40632e-05,-6.02529e-05,1.03939e-06,-3.32425e-05,0.000633401,-0.00105921,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000237204,1.70132e-05,1.42843e-05,0.000244717,0.0262473,0.0271547,0.0456756,0.0471534,0.0472172,0.0602635,6.30541e-11,6.30437e-11,3.96727e-10,5.6194e-07,5.6172e-07,2.08786e-06,0,0,0,0,0,0,0,0
26985000,0.703818,0.0540117,0.117597,0.698494,-1.61883,-0.853443,-1.34827,-1.195,-1.02627,-368.517,-1.45195e-05,-6.05178e-05,9.95114e-07,-6.00733e-05,0.000804013,-0.00109256,0.216913,0.00208893,0.427651,0,0,0,0,0,0.000221978,1.85392e-05,1.45677e-05,0.00023025,0.0242939,0.0252802,0.0490556,0.042109,0.0421581,0.0619052,6.26971e-11,6.26885e-11,3.96799e-10,5.25798e-07,5.25241e-07,2.02355e-06,0,0,0,0,0,0,0,0
27085000,0.704456,0.0552057,0.122529,0.696908,-1.82308,-0.943109,-1.3201,-1.36704,-1.11607,-368.647,-1.45193e-05,-6.05183e-05,9.93428e-07,-6.01135e-05,0.00080389,-0.001096,0.213385,0.00204254,0.429843,-0.00188059,0.0039054,0.00110385,0,0,0.000221138,1.91069e-05,1.4754e-05,0.000230519,0.0269874,0.0284045,0.0560294,0.0469582,0.0470675,0.0646437,6.27971e-11,6.27884e-11,3.96898e-10,5.25807e-07,5.25243e-07,2.01734e-06,0.00139139,1.86108e-05,0.0013943,0.000554898,0.00139003,0.00138818,0,0
27185000,0.706572,0.0520049,0.112534,0.696698,-2.02291,-1.00349,-1.3014,-1.5633,-1.19227,-368.774,-1.44765e-05,-6.07952e-05,9.83893e-07,-0.000120135,0.000794429,-0.00109783,0.213731,0.00204324,0.429892,-0.00223744,0.00358796,0.00122433,0,0,0.000218665,1.79429e-05,1.44349e-05,0.000228508,0.0269278,0.0285171,0.057524,0.0495089,0.0496193,0.0654425,6.24183e-11,6.24175e-11,3.96994e-10,5.0359e-07,5.02376e-07,1.93899e-06,0.00132629,1.84754e-05,0.0013294,0.000344982,0.00132461,0.00132249,0,0
27285000,0.708082,0.0463619,0.0974785,0.697832,-2.18556,-1.0714,-1.29135,-1.77404,-1.29615,-368.904,-1.44765e-05,-6.07952e-05,9.83759e-07,-0.000120136,0.000794415,-0.00109814,0.213326,0.00204124,0.430332,-0.00192503,0.00385903,0.00174723,0,0,0.000219285,1.6861e-05,1.42583e-05,0.000229308,0.0296849,0.0316754,0.0643252,0.0551955,0.0554134,0.0689623,6.25181e-11,6.25174e-11,3.97093e-10,5.03599e-07,5.02366e-07,1.92973e-06,0.00130129,1.83521e-05,0.00130436,0.000265289,0.00129957,0.00129776,0,0
27385000,0.709614,0.0401533,0.0813765,0.698722,-2.2765,-1.08607,-1.28141,-1.96142,-1.36546,-369.032,-1.49162e-05,-6.12432e-05,9.70962e-07,-0.000214078,0.000886921,-0.00112712,0.212947,0.00203565,0.430173,-0.00225152,0.00429191,0.00191714,0,0,0.000216661,1.55652e-05,1.38798e-05,0.000226242,0.0290543,0.0309147,0.0638407,0.0576508,0.0578459,0.0695276,6.21084e-11,6.21258e-11,3.97188e-10,4.82215e-07,4.79873e-07,1.84501e-06,0.00128375,1.8232e-05,0.00128593,0.000222152,0.00128213,0.00127986,0,0
27485000,0.710186,0.0343738,0.0662803,0.700043,-2.36274,-1.12299,-1.26728,-2.19366,-1.47605,-369.162,-1.49171e-05,-6.12431e-05,9.72309e-07,-0.000214105,0.000887155,-0.00112303,0.2127,0.00203248,0.430026,-0.00233105,0.004443,0.00214326,0,0,0.000217304,1.48955e-05,1.38077e-05,0.000226488,0.0317177,0.0337477,0.0699397,0.0641673,0.064506,0.0736138,6.22078e-11,6.22258e-11,3.97287e-10,4.82224e-07,4.79845e-07,1.83314e-06,0.00126637,1.81133e-05,0.00126699,0.000195791,0.00126483,0.00126144,0,0
27585000,0.710944,0.0296593,0.0536904,0.700569,-2.44741,-1.13285,-1.28317,-2.46428,-1.57602,-369.301,-1.4621e-05,-6.13686e-05,9.51331e-07,-0.00023931,0.000826936,-0.00107121,0.212688,0.00202864,0.430255,-0.00262999,0.00400464,0.00199258,0,0,0.000214541,1.41928e-05,1.35739e-05,0.000223095,0.0305652,0.0322335,0.0682099,0.0663955,0.0666791,0.0751073,6.1791e-11,6.1837e-11,3.97379e-10,4.62238e-07,4.58397e-07,1.75219e-06,0.00125202,1.80253e-05,0.00125076,0.000180674,0.00125052,0.0012455,0,0
27685000,0.710776,0.0287447,0.0514766,0.700943,-2.48598,-1.14649,-1.28412,-2.71102,-1.68999,-369.429,-1.4621e-05,-6.13686e-05,9.51279e-07,-0.000239311,0.000826931,-0.0010713,0.212605,0.00202658,0.430177,-0.00276506,0.00399167,0.00212497,0,0,0.000214683,1.42542e-05,1.36855e-05,0.000222952,0.0331377,0.0348163,0.0735682,0.0737021,0.0741409,0.0796669,6.18902e-11,6.19369e-11,3.97478e-10,4.62247e-07,4.58352e-07,1.73927e-06,0.00123351,1.79089e-05,0.0012299,0.000166527,0.00123203,0.00122488,0,0
27785000,0.710988,0.0292283,0.0533919,0.700565,-2.53724,-1.1482,-1.28793,-2.97817,-1.78739,-369.561,-1.44852e-05,-6.15202e-05,9.18216e-07,-0.000269163,0.000799891,-0.00104841,0.212504,0.00202198,0.429864,-0.00326708,0.00406427,0.00232739,0,0,0.000211928,1.41602e-05,1.35959e-05,0.000219911,0.0316078,0.0329113,0.0696233,0.0755966,0.0759553,0.0791218,6.14875e-11,6.15682e-11,3.97563e-10,4.43923e-07,4.3842e-07,1.66094e-06,0.00122045,1.77951e-05,0.00121509,0.000155126,0.001219,0.00121024,0,0
27885000,0.711029,0.0286042,0.0516625,0.700679,-2.57486,-1.16297,-1.29047,-3.2339,-1.90301,-369.695,-1.44876e-05,-6.15204e-05,9.20369e-07,-0.000269287,0.000800463,-0.00104051,0.212629,0.00202401,0.429808,-0.00324822,0.00416707,0.002203,0,0,0.000211956,1.42521e-05,1.3724e-05,0.000219888,0.0341198,0.0354129,0.0739264,0.083637,0.0841458,0.083728,6.15862e-11,6.16682e-11,3.97662e-10,4.4393e-07,4.38358e-07,1.6473e-06,0.0012106,1.76836e-05,0.00120411,0.000147073,0.00120919,0.00119933,0,0
27985000,0.711411,0.027604,0.0477341,0.70061,-2.64229,-1.17094,-1.29917,-3.54185,-2.0171,-369.828,-1.41044e-05,-6.15307e-05,8.83059e-07,-0.000271057,0.000725513,-0.00101172,0.212583,0.00202286,0.429546,-0.00335282,0.00419603,0.00234596,0,0,0.00020992,1.40027e-05,1.36121e-05,0.000217603,0.0323011,0.033278,0.0689919,0.0851215,0.0855353,0.0825219,6.12148e-11,6.13323e-11,3.97736e-10,4.27436e-07,4.20286e-07,1.57789e-06,0.00120133,1.75737e-05,0.00119349,0.000139798,0.00119993,0.00118879,0,0
28085000,0.710933,0.0330703,0.0601792,0.699899,-2.6786,-1.18224,-1.31191,-3.80767,-2.13468,-369.959,-1.41045e-05,-6.15308e-05,8.83078e-07,-0.000271064,0.000725532,-0.00101148,0.21259,0.00202131,0.429517,-0.00356783,0.00415773,0.00240131,0,0,0.000209616,1.45452e-05,1.38745e-05,0.000217416,0.0347408,0.0356944,0.0723396,0.0938312,0.0943813,0.086961,6.13132e-11,6.14323e-11,3.97835e-10,4.27441e-07,4.20213e-07,1.56441e-06,0.00119563,1.74659e-05,0.00118703,0.00013461,0.00119427,0.00118237,0,0
28185000,0.710784,0.0385506,0.0744156,0.698399,-2.74655,-1.19658,-1.07578,-4.1124,-2.24774,-370.09,-1.38671e-05,-6.15646e-05,8.45392e-07,-0.000277492,0.000679623,-0.000996122,0.212637,0.00202121,0.429486,-0.00365367,0.00411507,0.00235135,0,0,0.000207456,1.49781e-05,1.3934e-05,0.00021561,0.0325025,0.0332252,0.0661662,0.0948579,0.0953084,0.0851628,6.09858e-11,6.11389e-11,3.97896e-10,4.12844e-07,4.04177e-07,1.50505e-06,0.00119414,1.73605e-05,0.00118535,0.000129752,0.0011928,0.00118079,0,0
28285000,0.712703,0.0314857,0.0588677,0.698282,-2.7459,-1.20799,-0.218058,-4.38714,-2.36799,-370.156,-1.38674e-05,-6.15646e-05,8.45536e-07,-0.000277507,0.000679681,-0.000995432,0.212687,0.00202057,0.429543,-0.00376237,0.00401985,0.00238242,0,0,0.000207442,1.45386e-05,1.39227e-05,0.000216594,0.0340484,0.0346661,0.0671091,0.104135,0.104704,0.0911759,6.10844e-11,6.12388e-11,3.97995e-10,4.12849e-07,4.04121e-07,1.49556e-06,0.00119303,1.72825e-05,0.00118422,0.000127076,0.00119172,0.00117968,0,0
28385000,0.715112,0.0154512,0.0277144,0.698289,-2.77526,-1.21372,0.641418,-4.72085,-2.48906,-370.143,-1.34734e-05,-6.15549e-05,8.02533e-07,-0.00027558,0.000606368,-0.000960363,0.212389,0.0020152,0.429649,-0.0038281,0.00351504,0.00248284,0,0,0.000206676,1.38631e-05,1.37121e-05,0.000216758,0.031361,0.0317471,0.0669295,0.104726,0.105197,0.0950242,6.07564e-11,6.09352e-11,3.98055e-10,3.98962e-07,3.89246e-07,1.4795e-06,0.00118328,1.71777e-05,0.0011738,0.000123264,0.00118199,0.00116911,0,0
28485000,0.715457,0.00584394,0.00844385,0.698581,-2.73311,-1.20562,0.97149,-4.99669,-2.61024,-370.06,-1.34759e-05,-6.15555e-05,8.03523e-07,-0.000275737,0.000606892,-0.000954357,0.211528,0.00200375,0.429617,-0.0037931,0.0027695,0.00287124,0,0,0.000206745,1.40126e-05,1.38735e-05,0.000216832,0.0331869,0.0334485,0.0677771,0.114452,0.115011,0.0985985,6.08538e-11,6.1035e-11,3.98155e-10,3.98962e-07,3.8914e-07,1.46423e-06,0.00115464,1.707e-05,0.00114319,0.000120209,0.00115319,0.00113798,0,0
28585000,0.71481,0.00408359,0.00481784,0.699291,-2.70246,-1.18482,0.863885,-5.33242,-2.73082,-369.977,-1.30586e-05,-6.1539e-05,7.55786e-07,-0.000272709,0.000531448,-0.000919202,0.211835,0.00200704,0.430033,-0.00376709,0.00271438,0.00229311,0,0,0.000206799,1.4095e-05,1.39308e-05,0.000216004,0.0312416,0.0313265,0.0691543,0.114648,0.115131,0.101936,6.05263e-11,6.07255e-11,3.98205e-10,3.856e-07,3.75105e-07,1.44581e-06,0.00112184,1.69625e-05,0.00110814,0.00011714,0.00112017,0.00110238,0,0
28685000,0.713822,0.00333977,0.00382037,0.700309,-2.63253,-1.16612,0.859864,-5.59922,-2.84839,-369.899,-1.30628e-05,-6.15403e-05,7.57034e-07,-0.00027299,0.000532325,-0.000909392,0.211709,0.00200592,0.429681,-0.00374961,0.00276333,0.00263228,0,0,0.000207367,1.42809e-05,1.41094e-05,0.000215563,0.0332294,0.0332362,0.069841,0.124845,0.125369,0.105026,6.0623e-11,6.08252e-11,3.98304e-10,3.85595e-07,3.74974e-07,1.42814e-06,0.00109281,1.6857e-05,0.00107715,0.000114772,0.00109086,0.00107097,0,0
28785000,0.713199,0.00316389,0.00363656,0.700945,-2.60647,-1.1466,0.864564,-5.92995,-2.96118,-369.817,-1.26672e-05,-6.15479e-05,6.81328e-07,-0.000274503,0.000459824,-0.000885294,0.211583,0.00200294,0.429894,-0.00381929,0.00233863,0.00245355,0,0,0.000207543,1.43323e-05,1.41564e-05,0.000214929,0.0311466,0.0311235,0.0628005,0.124581,0.125074,0.0999488,6.03584e-11,6.0574e-11,3.98316e-10,3.73734e-07,3.62678e-07,1.3696e-06,0.00106799,1.67535e-05,0.00105065,0.000112516,0.00106576,0.00104421,0,0
28885000,0.712693,0.00311522,0.00381405,0.701459,-2.54069,-1.12962,0.850404,-6.18732,-3.07501,-369.737,-1.26702e-05,-6.15488e-05,6.8209e-07,-0.0002747,0.000460429,-0.000878618,0.211472,0.00200191,0.42958,-0.00378921,0.00238459,0.00276214,0,0,0.00020797,1.45146e-05,1.43398e-05,0.000214847,0.0330815,0.0330657,0.0643539,0.135188,0.135682,0.10534,6.04563e-11,6.06738e-11,3.98416e-10,3.73734e-07,3.62599e-07,1.35882e-06,0.00105181,1.66772e-05,0.00103345,0.000111124,0.00104937,0.00102682,0,0
28985000,0.712446,0.00343704,0.00438796,0.701705,-2.53159,-1.11634,0.843341,-6.53062,-3.19194,-369.656,-1.22182e-05,-6.15173e-05,5.93364e-07,-0.000269093,0.00037628,-0.000852993,0.211092,0.00199583,0.429547,-0.00381666,0.001767,0.00293338,0,0,0.000208132,1.45574e-05,1.43865e-05,0.000214651,0.0309833,0.0310125,0.0582142,0.134497,0.135002,0.100478,6.0257e-11,6.04768e-11,3.98386e-10,3.63286e-07,3.52187e-07,1.31316e-06,0.00103313,1.65766e-05,0.00101359,0.000109366,0.00103045,0.0010068,0,0
29085000,0.712291,0.0035501,0.00474729,0.701859,-2.4723,-1.10046,0.832525,-6.78084,-3.30279,-369.577,-1.22207e-05,-6.15181e-05,5.93922e-07,-0.00026926,0.000376787,-0.000847428,0.210972,0.0019943,0.429255,-0.00382457,0.00178251,0.00323146,0,0,0.000208399,1.47463e-05,1.45771e-05,0.000214761,0.0328504,0.0329546,0.0584158,0.145464,0.145937,0.102876,6.03546e-11,6.05766e-11,3.98486e-10,3.63285e-07,3.52099e-07,1.30126e-06,0.00101718,1.64774e-05,0.00099671,0.000107867,0.0010143,0.000989769,0,0
29185000,0.712247,0.00377694,0.00514497,0.7019,-2.44101,-1.08748,0.820699,-7.07301,-3.41672,-369.503,-1.2023e-05,-6.14972e-05,5.50152e-07,-0.000265438,0.000339107,-0.000825459,0.211378,0.00200011,0.429481,-0.00374648,0.00195148,0.00281658,0,0,0.000208461,1.47896e-05,1.46263e-05,0.000214736,0.0307431,0.0309198,0.0531707,0.144376,0.144898,0.0984408,6.0216e-11,6.04324e-11,3.98414e-10,3.54203e-07,3.43392e-07,1.26586e-06,0.00100341,1.638e-05,0.000982129,0.000106495,0.00100035,0.000975096,0,0
29285000,0.712178,0.00406931,0.0059139,0.701962,-2.38734,-1.07435,0.842875,-7.31447,-3.52484,-369.427,-1.20261e-05,-6.14982e-05,5.50708e-07,-0.000265643,0.000339718,-0.000818709,0.211329,0.00199936,0.42937,-0.00376516,0.0019528,0.00291711,0,0,0.000208727,1.49831e-05,1.48243e-05,0.00021494,0.032515,0.0328151,0.0531548,0.155654,0.156116,0.10049,6.0314e-11,6.05322e-11,3.98514e-10,3.54204e-07,3.4332e-07,1.25593e-06,0.000991522,1.62841e-05,0.000969598,0.000105296,0.0009883,0.000962459,0,0
29385000,0.712202,0.0046108,0.00737777,0.701921,-2.37433,-1.0669,0.849737,-7.6183,-3.64214,-369.35,-1.17858e-05,-6.14587e-05,4.98095e-07,-0.000258063,0.000292429,-0.000791825,0.211523,0.00200099,0.429343,-0.0038441,0.00191892,0.00283925,0,0,0.000208676,1.50211e-05,1.48765e-05,0.000214899,0.0304029,0.0307658,0.0486367,0.154205,0.154752,0.0964308,6.02277e-11,6.04357e-11,3.98403e-10,3.46373e-07,3.36082e-07,1.22808e-06,0.000981528,1.61898e-05,0.000959074,0.000104205,0.000978178,0.000951881,0,0
29485000,0.712231,0.00507304,0.00848419,0.701876,-2.32838,-1.05683,0.845834,-7.85342,-3.74832,-369.267,-1.17865e-05,-6.14589e-05,4.98203e-07,-0.000258112,0.00029257,-0.00079025,0.211613,0.00200265,0.429292,-0.00379144,0.00204254,0.00283436,0,0,0.000208926,1.52221e-05,1.5082e-05,0.000215195,0.0321285,0.0326448,0.0485483,0.16575,0.166214,0.0981766,6.0326e-11,6.05355e-11,3.98503e-10,3.46375e-07,3.36025e-07,1.21974e-06,0.000973112,1.60969e-05,0.000950245,0.000103225,0.000969639,0.000942992,0,0
29585000,0.712219,0.00542937,0.00951682,0.701872,-2.30192,-1.0454,0.836751,-8.11463,-3.85018,-369.189,-1.16948e-05,-6.14708e-05,4.41548e-07,-0.000260745,0.000273526,-0.000778545,0.211629,0.00200284,0.429111,-0.00378374,0.00205718,0.00297514,0,0,0.000208766,1.52684e-05,1.5139e-05,0.000215055,0.0300524,0.0306056,0.0454122,0.163975,0.164556,0.0967366,6.02866e-11,6.04837e-11,3.98358e-10,3.39732e-07,3.30098e-07,1.19936e-06,0.000967607,1.60285e-05,0.000944488,0.000102547,0.000964072,0.000937218,0,0
29685000,0.712352,0.00568821,0.0101615,0.701726,-2.26323,-1.03626,0.829105,-8.34288,-3.95425,-369.107,-1.16955e-05,-6.1471e-05,4.41631e-07,-0.00026079,0.000273656,-0.000777083,0.211543,0.00200155,0.429106,-0.00380181,0.00197644,0.00301653,0,0,0.000208992,1.5482e-05,1.53533e-05,0.000215434,0.0317162,0.0324363,0.0452675,0.175751,0.176229,0.0982991,6.03852e-11,6.05835e-11,3.98458e-10,3.39736e-07,3.30052e-07,1.19233e-06,0.000961163,1.59379e-05,0.000937754,0.000101717,0.000957526,0.000930449,0,0
29785000,0.712428,0.00592035,0.0106234,0.70164,-2.25095,-1.0282,0.816184,-8.61313,-4.05876,-369.027,-1.15792e-05,-6.14683e-05,3.78747e-07,-0.000260397,0.000247989,-0.000767304,0.211317,0.00199907,0.429221,-0.00368325,0.00162479,0.00301553,0,0,0.00020864,1.55353e-05,1.54132e-05,0.000215193,0.0296755,0.0303961,0.0418246,0.173685,0.174311,0.0947051,6.03856e-11,6.0572e-11,3.98284e-10,3.34195e-07,3.25245e-07,1.17443e-06,0.000955449,1.58483e-05,0.000931813,0.000100942,0.000951749,0.000924496,0,0
29885000,0.712512,0.0059399,0.010752,0.701553,-2.21804,-1.0203,0.800708,-8.83664,-4.16123,-368.954,-1.15823e-05,-6.14694e-05,3.78951e-07,-0.000260611,0.000248598,-0.000760409,0.211295,0.00199845,0.429287,-0.00371878,0.00156457,0.00294818,0,0,0.000208919,1.57593e-05,1.56356e-05,0.000215572,0.0312813,0.0321732,0.0416269,0.185658,0.186163,0.0960353,6.04844e-11,6.06719e-11,3.98384e-10,3.34199e-07,3.25208e-07,1.16846e-06,0.000950347,1.57597e-05,0.000926492,0.000100232,0.000946562,0.000919158,0,0
29985000,0.712564,0.00598596,0.0108526,0.701498,-2.19356,-1.00967,0.785491,-9.07422,-4.25625,-368.877,-1.15464e-05,-6.1485e-05,3.24269e-07,-0.000264483,0.000239789,-0.000756909,0.21132,0.00199882,0.429341,-0.00369523,0.0015183,0.00288565,0,0,0.000208462,1.58153e-05,1.56969e-05,0.00021521,0.029281,0.0301456,0.0386211,0.183337,0.184017,0.0927002,6.05181e-11,6.06951e-11,3.98185e-10,3.29656e-07,3.21375e-07,1.1541e-06,0.000945656,1.56722e-05,0.000921639,9.95579e-05,0.000941823,0.000914302,0,0
30085000,0.712679,0.00592752,0.0107236,0.701384,-2.16251,-1.00248,0.772386,-9.29204,-4.35687,-368.8,-1.15469e-05,-6.14851e-05,3.24278e-07,-0.000264513,0.000239873,-0.000755956,0.211509,0.0020011,0.429328,-0.00372696,0.00168461,0.00280773,0,0,0.00020875,1.60473e-05,1.59266e-05,0.00021563,0.030832,0.0318734,0.0383882,0.195476,0.196018,0.0938298,6.0617e-11,6.07949e-11,3.98285e-10,3.29661e-07,3.21346e-07,1.14902e-06,0.000941356,1.55859e-05,0.000917164,9.89516e-05,0.000937443,0.00090982,0,0
30185000,0.712764,0.00590855,0.0105346,0.7013,-2.14724,-0.99402,0.762695,-9.53727,-4.45423,-368.718,-1.14963e-05,-6.14895e-05,2.6583e-07,-0.000265882,0.000226005,-0.00075667,0.211769,0.00200512,0.429249,-0.00363691,0.00189773,0.0027736,0,0,0.000208183,1.61046e-05,1.59881e-05,0.000215191,0.0288754,0.0298592,0.036337,0.192934,0.193679,0.0928793,6.06771e-11,6.08463e-11,3.98066e-10,3.25993e-07,3.18346e-07,1.13857e-06,0.000938269,1.55222e-05,0.00091399,9.84981e-05,0.000934335,0.000906644,0,0
30285000,0.712886,0.00576888,0.0103266,0.70118,-2.11633,-0.988766,0.753128,-9.75037,-4.55336,-368.636,-1.14943e-05,-6.14888e-05,2.65886e-07,-0.000265741,0.000225622,-0.000761051,0.211827,0.00200579,0.429279,-0.00364478,0.00193173,0.00273443,0,0,0.00020849,1.63436e-05,1.62248e-05,0.000215639,0.0303742,0.031541,0.0360904,0.205212,0.205803,0.0938819,6.07762e-11,6.09462e-11,3.98166e-10,3.25999e-07,3.18323e-07,1.13423e-06,0.000934409,1.54378e-05,0.000909983,9.79688e-05,0.000930396,0.00090263,0,0
30385000,0.712961,0.00565948,0.0100664,0.701109,-2.08905,-0.982408,0.739835,-9.96671,-4.65234,-368.56,-1.14863e-05,-6.14877e-05,2.58733e-07,-0.000265512,0.000223053,-0.000762219,0.211711,0.00200449,0.429174,-0.00362432,0.00186367,0.00288691,0,0,0.000207872,1.64003e-05,1.62854e-05,0.000215063,0.0284685,0.0295587,0.0337215,0.202482,0.203302,0.0908966,6.08551e-11,6.1019e-11,3.9793e-10,3.23081e-07,3.16001e-07,1.12476e-06,0.000930691,1.53544e-05,0.000906172,9.74346e-05,0.00092664,0.000898814,0,0
30485000,0.713033,0.00550885,0.00979218,0.701041,-2.06106,-0.976365,0.727573,-10.1741,-4.75027,-368.482,-1.14846e-05,-6.14871e-05,2.58845e-07,-0.000265395,0.000222742,-0.000765797,0.211712,0.00200468,0.429197,-0.00359913,0.00186155,0.00287641,0,0,0.000208225,1.6646e-05,1.65287e-05,0.000215506,0.0299233,0.0311905,0.0334642,0.214874,0.215524,0.0917427,6.09544e-11,6.11189e-11,3.9803e-10,3.23088e-07,3.15983e-07,1.12105e-06,0.000927215,1.52719e-05,0.00090257,9.69703e-05,0.000923084,0.000895212,0,0
30585000,0.713349,0.00531841,0.00938623,0.700726,-2.0407,-0.971117,0.691831,-10.3984,-4.85047,-368.406,-1.14721e-05,-6.14767e-05,3.07439e-07,-0.000262447,0.00021679,-0.000768395,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000197978,1.6701e-05,1.65872e-05,0.000204942,0.0280864,0.0292007,0.0313942,0.211978,0.212838,0.0889769,6.10445e-11,6.1197e-11,3.96945e-10,3.20262e-07,3.14107e-07,1.11339e-06,0,0,0,0,0,0,0,0
30685000,0.713477,0.00509688,0.00901206,0.700602,-2.01262,-0.964383,0.684686,-10.6011,-4.94717,-368.336,-1.14723e-05,-6.14753e-05,3.19278e-07,-0.000262135,0.000216873,-0.000769017,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000186934,1.69531e-05,1.68369e-05,0.00019353,0.0294865,0.0306913,0.0311278,0.224457,0.2251,0.0896908,6.11422e-11,6.12854e-11,3.96008e-10,3.19613e-07,3.13944e-07,1.11022e-06,0,0,0,0,0,0,0,0
30785000,0.713468,0.00495096,0.0086212,0.700617,-1.98731,-0.955463,0.681619,-10.8055,-5.03774,-368.258,-1.14672e-05,-6.14776e-05,2.75714e-07,-0.000264065,0.000214623,-0.00077548,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000176383,1.70044e-05,1.68915e-05,0.000182597,0.0276722,0.0287122,0.0292759,0.221426,0.222266,0.0871209,6.12387e-11,6.13728e-11,3.94834e-10,3.17407e-07,3.12548e-07,1.10403e-06,0,0,0,0,0,0,0,0
30885000,0.713478,0.00471362,0.00815792,0.700615,-1.95904,-0.948671,0.66972,-11.0028,-5.13284,-368.189,-1.14672e-05,-6.14763e-05,2.87595e-07,-0.000263753,0.000214664,-0.000776518,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000169967,1.72626e-05,1.71473e-05,0.00017589,0.0290402,0.0301791,0.0294648,0.233984,0.234631,0.0896847,6.13374e-11,6.14661e-11,3.94259e-10,3.17046e-07,3.12457e-07,1.10199e-06,0,0,0,0,0,0,0,0
30985000,0.713529,0.00455945,0.00758536,0.700569,-1.93907,-0.941688,0.664973,-11.215,-5.22541,-368.118,-1.14695e-05,-6.14742e-05,2.68327e-07,-0.000263897,0.000210324,-0.000778568,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000161362,1.73104e-05,1.71981e-05,0.000166952,0.0272817,0.0282662,0.0277795,0.230847,0.231691,0.0871856,6.14344e-11,6.15578e-11,3.93214e-10,3.15437e-07,3.11463e-07,1.09687e-06,0,0,0,0,0,0,0,0
31085000,0.713566,0.00429662,0.00702503,0.70054,-1.91172,-0.934814,0.653666,-11.4076,-5.31928,-368.054,-1.147e-05,-6.14749e-05,2.6339e-07,-0.000264045,0.000210399,-0.000777163,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.0001543,1.75745e-05,1.74599e-05,0.000159633,0.0286121,0.0296718,0.0275251,0.243463,0.244113,0.0877049,6.15329e-11,6.16507e-11,3.9251e-10,3.15063e-07,3.11365e-07,1.09455e-06,0,0,0,0,0,0,0,0
31185000,0.713651,0.00406226,0.00663094,0.700459,-1.88462,-0.929669,0.643372,-11.5979,-5.41373,-367.997,-1.14728e-05,-6.14749e-05,2.8508e-07,-0.000263543,0.000210954,-0.000772736,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000147333,1.76176e-05,1.75057e-05,0.000152378,0.0269081,0.027825,0.026024,0.240243,0.241087,0.0853764,6.1625e-11,6.17405e-11,3.91572e-10,3.13925e-07,3.10685e-07,1.09038e-06,0,0,0,0,0,0,0,0
31285000,0.713764,0.00379038,0.00604462,0.70035,-1.85589,-0.921693,0.644365,-11.785,-5.50614,-367.935,-1.1474e-05,-6.1473e-05,3.08063e-07,-0.000263109,0.000211281,-0.000771606,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000141573,1.78872e-05,1.77732e-05,0.000146406,0.0281985,0.0291856,0.0257664,0.252904,0.253564,0.0857888,6.17238e-11,6.18346e-11,3.90937e-10,3.13635e-07,3.10608e-07,1.08839e-06,0,0,0,0,0,0,0,0
31385000,0.713809,0.00351514,0.00543799,0.70031,-1.83273,-0.916721,0.642927,-11.9831,-5.6026,-367.87,-1.14881e-05,-6.1477e-05,3.0963e-07,-0.000262277,0.000209406,-0.0007701,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000135815,1.79251e-05,1.78138e-05,0.000140413,0.026546,0.0274039,0.0244238,0.249622,0.250473,0.0836156,6.1806e-11,6.19168e-11,3.90076e-10,3.12846e-07,3.10163e-07,1.08497e-06,0,0,0,0,0,0,0,0
31485000,0.713728,0.00326555,0.00475359,0.700399,-1.8034,-0.909686,0.638355,-12.1649,-5.6941,-367.807,-1.14877e-05,-6.1479e-05,2.86e-07,-0.000262735,0.000209248,-0.00076948,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000132288,1.82e-05,1.80869e-05,0.000136727,0.0278172,0.0287508,0.0245422,0.262316,0.262996,0.0857675,6.19053e-11,6.20131e-11,3.89659e-10,3.12672e-07,3.10119e-07,1.0837e-06,0,0,0,0,0,0,0,0
31585000,0.71377,0.00305191,0.00428031,0.700361,-1.77543,-0.89862,0.635439,-12.3462,-5.77742,-367.744,-1.14917e-05,-6.14679e-05,2.86729e-07,-0.000263217,0.000209134,-0.000769204,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000127361,1.82313e-05,1.81206e-05,0.000131583,0.0262188,0.0270298,0.0233109,0.258992,0.259862,0.083648,6.19728e-11,6.20823e-11,3.88847e-10,3.12137e-07,3.09845e-07,1.08085e-06,0,0,0,0,0,0,0,0
31685000,0.713821,0.00276289,0.00358542,0.700314,-1.74786,-0.89167,0.64087,-12.5224,-5.86673,-367.679,-1.14924e-05,-6.14654e-05,3.1607e-07,-0.00026269,0.000209352,-0.000769573,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000123266,1.85113e-05,1.83988e-05,0.000127304,0.0274588,0.028327,0.0230754,0.271702,0.2724,0.0839301,6.20719e-11,6.2178e-11,3.8829e-10,3.11945e-07,3.09795e-07,1.07939e-06,0,0,0,0,0,0,0,0
31785000,0.71389,0.0024206,0.00281619,0.700248,-1.72512,-0.883304,0.641293,-12.7118,-5.9527,-367.618,-1.15216e-05,-6.14589e-05,3.2127e-07,-0.000262468,0.000208526,-0.000767037,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000119083,1.85347e-05,1.84249e-05,0.000122943,0.025906,0.0266618,0.0219675,0.268353,0.269237,0.0819465,6.21207e-11,6.22299e-11,3.8752e-10,3.11596e-07,3.0964e-07,1.07705e-06,0,0,0,0,0,0,0,0
31885000,0.713951,0.00210928,0.00205784,0.70019,-1.6939,-0.874152,0.637377,-12.8828,-6.0405,-367.555,-1.15219e-05,-6.14582e-05,3.30054e-07,-0.000262326,0.000208623,-0.000766784,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000115578,1.88195e-05,1.87082e-05,0.000119312,0.0271391,0.0279519,0.0217497,0.281071,0.281788,0.0821702,6.222e-11,6.2326e-11,3.86985e-10,3.11438e-07,3.09599e-07,1.0758e-06,0,0,0,0,0,0,0,0
31985000,0.713881,0.00184769,0.00145899,0.700263,-1.66115,-0.863562,0.633563,-13.0455,-6.11947,-367.493,-1.15112e-05,-6.14427e-05,3.00329e-07,-0.000263032,0.000208686,-0.000766611,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000111993,1.88336e-05,1.87247e-05,0.00011556,0.0256377,0.0263479,0.0207539,0.277713,0.278614,0.0803111,6.22455e-11,6.23561e-11,3.86244e-10,3.11217e-07,3.09521e-07,1.07389e-06,0,0,0,0,0,0,0,0
32085000,0.71381,0.00151212,0.000687266,0.700337,-1.63138,-0.85517,0.639771,-13.2102,-6.20551,-367.434,-1.15117e-05,-6.14439e-05,2.88215e-07,-0.000263281,0.000208753,-0.000764819,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000108993,1.9123e-05,1.90128e-05,0.000112416,0.0268441,0.0276045,0.0205438,0.290429,0.291168,0.0804855,6.23449e-11,6.24526e-11,3.85723e-10,3.11084e-07,3.09488e-07,1.07282e-06,0,0,0,0,0,0,0,0
32185000,0.713716,0.00115218,-0.000241088,0.700434,-1.60526,-0.846596,0.641261,-13.382,-6.28752,-367.373,-1.15363e-05,-6.1439e-05,2.26919e-07,-0.000264001,0.000208406,-0.000763195,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000106638,1.91263e-05,1.9019e-05,0.000109964,0.0253812,0.0260504,0.0199086,0.287078,0.288003,0.0803208,6.2344e-11,6.24581e-11,3.85155e-10,3.10973e-07,3.09456e-07,1.07149e-06,0,0,0,0,0,0,0,0
32285000,0.713713,0.000850556,-0.00105434,0.700437,-1.57375,-0.838045,0.635541,-13.541,-6.37183,-367.314,-1.15371e-05,-6.14397e-05,2.23041e-07,-0.000264132,0.000208555,-0.000761186,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000103977,1.94201e-05,1.93116e-05,0.000107197,0.0265902,0.0273075,0.0197158,0.299782,0.300549,0.0804583,6.24434e-11,6.25548e-11,3.8464e-10,3.10859e-07,3.09429e-07,1.07057e-06,0,0,0,0,0,0,0,0
32385000,0.713745,0.000564701,-0.00177927,0.700403,-1.53669,-0.827774,0.637204,-13.6868,-6.45067,-367.246,-1.15093e-05,-6.14248e-05,2.58447e-07,-0.000263552,0.000208398,-0.000763616,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,0.000101223,1.94111e-05,1.93054e-05,0.000104307,0.0251706,0.0257995,0.018881,0.29645,0.297393,0.0787508,6.24117e-11,6.25298e-11,3.8393e-10,3.1075e-07,3.09393e-07,1.06926e-06,0,0,0,0,0,0,0,0
32485000,0.713692,0.000388373,-0.00209114,0.700457,-1.50473,-0.818068,0.64378,-13.8389,-6.53282,-367.182,-1.15099e-05,-6.14233e-05,2.80012e-07,-0.000263274,0.000208552,-0.000763452,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,9.89145e-05,1.97095e-05,1.96022e-05,0.000101866,0.0263618,0.0270344,0.0186968,0.309133,0.309923,0.0788512,6.25112e-11,6.26265e-11,3.83417e-10,3.10651e-07,3.0937e-07,1.06848e-06,0,0,0,0,0,0,0,0
32585000,0.713599,0.000307673,-0.00239118,0.700551,-1.47669,-0.809254,0.644656,-13.9947,-6.61491,-367.112,-1.15309e-05,-6.1426e-05,2.61676e-07,-0.000263374,0.000208641,-0.000765092,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,9.64958e-05,1.96883e-05,1.95829e-05,9.93195e-05,0.0249801,0.0255664,0.0179364,0.305832,0.306795,0.0772323,6.24459e-11,6.25689e-11,3.82714e-10,3.10545e-07,3.09312e-07,1.06741e-06,0,0,0,0,0,0,0,0
32685000,0.71355,0.000222274,-0.00250694,0.700599,-1.44573,-0.800678,0.642152,-14.1408,-6.69534,-367.044,-1.15305e-05,-6.14251e-05,2.70116e-07,-0.000263218,0.000208588,-0.000766331,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,9.44542e-05,1.99908e-05,1.98837e-05,9.7174e-05,0.0261794,0.0268045,0.0177692,0.318488,0.319301,0.0773014,6.25455e-11,6.26658e-11,3.82198e-10,3.10458e-07,3.09294e-07,1.06675e-06,0,0,0,0,0,0,0,0
32785000,0.713516,0.000182561,-0.00254833,0.700634,-1.41368,-0.790374,0.639553,-14.2782,-6.77008,-366.978,-1.1511e-05,-6.14075e-05,2.72349e-07,-0.000262782,0.000208114,-0.000767415,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,9.28612e-05,1.99555e-05,1.9849e-05,9.54985e-05,0.0248323,0.0253795,0.0173015,0.315233,0.31622,0.0772512,6.24426e-11,6.25724e-11,3.81652e-10,3.10347e-07,3.09194e-07,1.06603e-06,0,0,0,0,0,0,0,0
32885000,0.713378,0.000199802,-0.00254431,0.700775,-1.38563,-0.781871,0.641207,-14.418,-6.84889,-366.914,-1.15105e-05,-6.14094e-05,2.45057e-07,-0.00026311,0.000207976,-0.000767208,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,9.10297e-05,2.02618e-05,2.01534e-05,9.35648e-05,0.0260237,0.0266024,0.0171425,0.327852,0.328693,0.0772959,6.25423e-11,6.26693e-11,3.81131e-10,3.10269e-07,3.09179e-07,1.06546e-06,0,0,0,0,0,0,0,0
32985000,0.713332,0.000259423,-0.00257911,0.700822,-1.36054,-0.774967,0.63814,-14.5643,-6.9262,-366.85,-1.15464e-05,-6.14059e-05,2.74571e-07,-0.000262626,0.000209115,-0.000767019,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,8.91107e-05,2.02108e-05,2.01024e-05,9.15289e-05,0.0247035,0.0252055,0.0164971,0.32465,0.325654,0.0758008,6.23992e-11,6.25359e-11,3.80429e-10,3.10083e-07,3.09004e-07,1.06474e-06,0,0,0,0,0,0,0,0
33085000,0.713415,0.000182163,-0.00263535,0.700737,-1.33274,-0.768035,0.633124,-14.6991,-7.00284,-366.785,-1.15478e-05,-6.14005e-05,3.4972e-07,-0.000261757,0.000209483,-0.000767559,0.211801,0.0020058,0.429283,-0.00357704,0.00185401,0.00278088,0,0,8.74721e-05,2.05202e-05,2.041e-05,8.98126e-05,0.0259056,0.0264354,0.0163526,0.337226,0.33809,0.0758227,6.24989e-11,6.26329e-11,3.79899e-10,3.10014e-07,3.08992e-07,1.06426e-06,0,0,0,0,0,0,0,0
33185000,0.710518,0.0027164,-0.00201737,0.703671,-1.30425,-0.757692,0.584181,-14.8263,-7.07256,-366.719,-1.15107e-05,-6.13303e-05,3.7355e-07,-0.000257086,0.000207365,-0.000772823,0.212736,0.00204054,0.429649,-0.0034029,0.000968559,0.00314204,0,0,8.54001e-05,2.021e-05,2.01077e-05,8.6722e-05,0.0246348,0.0251115,0.0157769,0.334079,0.335128,0.0744066,6.20938e-11,6.1897e-11,3.79244e-10,3.05175e-07,3.0711e-07,1.05367e-06,0.00060864,1.49367e-05,0.000595381,8.73297e-05,0.000607356,0.000592997,0,0
33285000,0.662159,0.0157315,-0.000861251,0.749198,-1.29984,-0.740735,0.55226,-14.9563,-7.14746,-366.661,-1.15169e-05,-6.12967e-05,4.0363e-07,-0.000254051,0.000208034,-0.000771881,0.212415,0.0020591,0.429418,-0.00327646,0.00117507,0.00288241,0,0,9.11555e-05,2.03653e-05,2.02447e-05,7.76754e-05,0.0258725,0.0263398,0.015653,0.346605,0.347533,0.0744124,6.21399e-11,6.14614e-11,3.78919e-10,3.00825e-07,3.06703e-07,1.05106e-06,0.00053927,1.46464e-05,0.000528295,7.85182e-05,0.000538515,0.000527001,0,0
33385000,0.561476,0.0139696,-0.00160798,0.827374,-1.29732,-0.728382,0.744786,-15.0883,-7.22101,-366.594,-1.15579e-05,-6.12686e-05,4.27301e-07,-0.000251454,0.000211013,-0.000771796,0.211456,0.00206972,0.429737,-0.00302184,0.00158205,0.00310191,0,0,0.000103463,2.02247e-05,1.99951e-05,6.31865e-05,0.0243538,0.0247251,0.0150406,0.343545,0.344661,0.0730756,6.18716e-11,6.08864e-11,3.78527e-10,2.97605e-07,3.06039e-07,1.04974e-06,0.000494909,1.44466e-05,0.000504484,7.26033e-05,0.000493038,0.000503604,0,0
33485000,0.42554,0.00753177,0.00102094,0.904908,-1.28087,-0.723965,0.772925,-15.2173,-7.29356,-366.515,-1.15474e-05,-6.12883e-05,4.08746e-07,-0.000251454,0.000211013,-0.000771796,0.211918,0.00206136,0.429854,-0.00311574,0.00196912,0.003227,0,0,0.000118123,2.05724e-05,2.01632e-05,4.85261e-05,0.0256965,0.0260526,0.0150225,0.355983,0.35698,0.0744047,6.19395e-11,6.08399e-11,3.78495e-10,0,0,0,0.000451062,1.43482e-05,0.000494815,7.06886e-05,0.000442535,0.000494096,0,0
33585000,0.269154,0.00144077,-0.00138751,0.963095,-1.2402,-0.721793,0.737243,-15.3273,-7.35345,-366.443,-1.14954e-05,-6.12438e-05,3.64493e-07,-0.000251454,0.000211013,-0.000771796,0.210631,0.00203516,0.42973,-0.00286776,0.0015041,0.00314504,0,0,0.000129456,2.04108e-05,1.98433e-05,3.66109e-05,0.0247676,0.0250568,0.0146634,0.35313,0.354306,0.073066,6.15658e-11,6.03928e-11,3.78236e-10,0,0,0,0.000348899,1.42224e-05,0.000486555,6.8346e-05,0.000336603,0.000485952,0,0
33685000,0.102898,-0.00196709,-0.00455184,0.99468,-1.18759,-0.719653,0.744722,-15.4486,-7.42561,-366.367,-1.15094e-05,-6.12524e-05,3.55088e-07,-0.000251454,0.000211013,-0.000771796,0.210098,0.00202476,0.429808,-0.00283364,0.00103822,0.00324299,0,0,0.000135926,2.06419e-05,1.98882e-05,2.99634e-05,0.0263535,0.0266553,0.0148941,0.365224,0.366285,0.0729727,6.16114e-11,6.03247e-11,3.78151e-10,0,0,0,0.000256747,1.40799e-05,0.000481083,6.64495e-05,0.00024025,0.000480549,0,0
33785000,-0.0669402,-0.00362399,-0.00638425,0.99773,-1.12766,-0.703097,0.728115,-15.5703,-7.48589,-366.291,-1.15684e-05,-6.12894e-05,1.91894e-07,-0.000251454,0.000211013,-0.000771796,0.209242,0.00194993,0.42947,-0.00253473,0.000640432,0.00304236,0,0,0.000135394,2.01749e-05,1.92913e-05,2.92591e-05,0.0254602,0.0257097,0.0149875,0.36284,0.364079,0.0716963,6.10875e-11,5.96556e-11,3.77742e-10,0,0,0,0.000189673,1.38987e-05,0.00047712,6.37273e-05,0.00017061,0.000476643,0,0
33885000,-0.234586,-0.00481551,-0.00707175,0.972058,-1.061,-0.681838,0.714785,-15.6793,-7.55536,-366.219,-1.15858e-05,-6.14116e-05,5.52318e-08,-0.000251454,0.000211013,-0.000771796,0.208472,0.00186615,0.429348,-0.00223993,0.000142155,0.00304848,0,0,0.000128523,2.01535e-05,1.9179e-05,3.45802e-05,0.0272541,0.0274843,0.0156799,0.374608,0.375725,0.0715861,6.11658e-11,5.94302e-11,3.77426e-10,0,0,0,0.000145742,1.36823e-05,0.000474167,5.99393e-05,0.000125528,0.000473737,0,0
33985000,-0.382463,-0.00340854,-0.0105638,0.923904,-1.00678,-0.644403,0.687296,-15.808,-7.61325,-366.149,-1.17758e-05,-6.14164e-05,-9.98074e-08,-0.000251454,0.000211013,-0.000771796,0.208799,0.00182533,0.429252,-0.00197847,0.000395802,0.00303195,0,0,0.000116657,1.92683e-05,1.83689e-05,4.35952e-05,0.0263641,0.0265038,0.0161819,0.372652,0.373949,0.0704004,6.04808e-11,5.84693e-11,3.76709e-10,2.97609e-07,3.06043e-07,1.04974e-06,0.000117343,1.34455e-05,0.000471803,5.54644e-05,9.74032e-05,0.000471415,0,0
34085000,-0.490811,-0.00223198,-0.0122743,0.871177,-0.952057,-0.599918,0.689449,-15.9056,-7.67556,-366.077,-1.1779e-05,-6.14593e-05,-1.53756e-07,-0.000251454,0.000211013,-0.000771808,0.208691,0.00179608,0.429322,-0.00188067,0.000279749,0.0031297,0,0,0.000105703,1.89966e-05,1.82419e-05,5.28733e-05,0.0283218,0.0283865,0.0175871,0.384111,0.38528,0.071619,6.0575e-11,5.82764e-11,3.76363e-10,2.97619e-07,3.06053e-07,1.04975e-06,0.000103215,1.32692e-05,0.00047037,5.20409e-05,8.35495e-05,0.000470011,0,0
34185000,-0.562266,-0.00201989,-0.0109501,0.826882,-0.926243,-0.555452,0.692021,-16.0474,-7.74292,-366.006,-1.21872e-05,-6.15765e-05,-2.50239e-07,-0.000254041,0.000213264,-0.000772326,0.209138,0.00177649,0.429189,-0.00169085,0.000322683,0.0030385,0,0,9.58704e-05,1.79107e-05,1.73192e-05,5.92214e-05,0.0273762,0.0273213,0.0186646,0.382545,0.383888,0.0705124,5.97306e-11,5.72173e-11,3.75507e-10,2.97567e-07,3.05998e-07,1.04939e-06,8.96435e-05,1.30451e-05,0.000468704,4.77934e-05,7.09629e-05,0.000468376,0,0
34285000,-0.606777,-0.00289676,-0.0080422,0.794826,-0.876518,-0.507721,0.69107,-16.1374,-7.79613,-365.936,-1.21854e-05,-6.16366e-05,-3.35935e-07,-0.000254031,0.000213271,-0.000772338,0.209276,0.00173786,0.429165,-0.00144727,0.00034778,0.00305025,0,0,8.93155e-05,1.76281e-05,1.71354e-05,6.34095e-05,0.02953,0.0293463,0.0206625,0.393716,0.394934,0.0706023,5.98286e-11,5.70109e-11,3.7502e-10,2.97577e-07,3.06008e-07,1.04939e-06,8.08055e-05,1.28467e-05,0.000467426,4.41248e-05,6.25894e-05,0.000467119,0,0
34385000,-0.633752,-0.00355405,-0.00530465,0.77351,-0.847956,-0.467722,0.690961,-16.2695,-7.85681,-365.868,-1.26148e-05,-6.17591e-05,-4.10656e-07,-0.000259203,0.000219131,-0.00077155,0.209729,0.00173061,0.429037,-0.00129189,0.00037354,0.00292223,0,0,8.43144e-05,1.65725e-05,1.61643e-05,6.52657e-05,0.0284971,0.0282296,0.022222,0.392494,0.393872,0.0696506,5.88565e-11,5.59808e-11,3.74165e-10,2.97262e-07,3.05676e-07,1.04726e-06,7.3905e-05,1.26678e-05,0.000466247,4.10585e-05,5.66731e-05,0.000465951,0,0
34485000,-0.650127,-0.00450327,-0.00306532,0.759806,-0.793715,-0.425781,0.690391,-16.3514,-7.90153,-365.801,-1.26149e-05,-6.18043e-05,-4.83138e-07,-0.000259172,0.000219142,-0.000771429,0.209672,0.0016985,0.429047,-0.00119066,0.000233853,0.00294812,0,0,8.1402e-05,1.6366e-05,1.59923e-05,6.64908e-05,0.0307878,0.0303892,0.0248591,0.403401,0.404657,0.0699757,5.89562e-11,5.58829e-11,3.73753e-10,2.97272e-07,3.05686e-07,1.04719e-06,6.92783e-05,1.25142e-05,0.000465325,3.85143e-05,5.23526e-05,0.000465035,0,0
34585000,-0.660054,-0.00466438,-0.0018088,0.751202,-0.772388,-0.398924,0.690337,-16.4915,-7.97099,-365.731,-1.32365e-05,-6.20504e-05,-4.72174e-07,-0.000271173,0.000231243,-0.000770898,0.210088,0.00171625,0.428995,-0.00118811,0.000113838,0.0028832,0,0,7.87129e-05,1.5352e-05,1.50126e-05,6.64654e-05,0.0296033,0.0291681,0.0266545,0.402481,0.403885,0.0692015,5.7895e-11,5.4891e-11,3.7292e-10,2.96559e-07,3.04937e-07,1.04208e-06,6.50375e-05,1.23722e-05,0.000464376,3.63985e-05,4.90318e-05,0.000464087,0,0
34685000,-0.666253,-0.00504,-0.000988871,0.745708,-0.71614,-0.357857,0.687085,-16.5658,-8.00885,-365.658,-1.32369e-05,-6.20762e-05,-5.31669e-07,-0.000271132,0.000231263,-0.00077165,0.210325,0.0016981,0.429,-0.000978358,0.000224081,0.00284591,0,0,7.73587e-05,1.519e-05,1.4858e-05,6.66871e-05,0.0319989,0.0314355,0.0298061,0.413148,0.414432,0.0698475,5.79947e-11,5.48683e-11,3.72567e-10,2.96569e-07,3.04947e-07,1.04181e-06,6.22539e-05,1.22503e-05,0.000463655,3.46266e-05,4.64474e-05,0.000463367,0,0
34785000,-0.67018,-0.00459426,-0.00060649,0.742184,-0.696521,-0.335482,0.684794,-16.6981,-8.07461,-365.587,-1.38906e-05,-6.23793e-05,-5.68825e-07,-0.00028647,0.000248103,-0.000775333,0.210938,0.00170048,0.428869,-0.000808441,0.000148214,0.00266367,0,0,7.5806e-05,1.42215e-05,1.39089e-05,6.62105e-05,0.0306313,0.030079,0.0317779,0.412492,0.413911,0.0704678,5.68872e-11,5.39318e-11,3.7185e-10,2.95384e-07,3.0371e-07,1.03293e-06,5.97853e-05,1.21598e-05,0.000463006,3.34767e-05,4.48253e-05,0.000462717,0,0
34885000,-0.672706,-0.00463453,-0.000488549,0.739896,-0.642261,-0.297572,0.683623,-16.7649,-8.10628,-365.516,-1.38891e-05,-6.2401e-05,-6.17084e-07,-0.000286404,0.000248119,-0.000776114,0.210911,0.00168269,0.428861,-0.000758075,6.39403e-05,0.00266454,0,0,7.50817e-05,1.40877e-05,1.37739e-05,6.61297e-05,0.0330765,0.0323994,0.0352914,0.422941,0.424245,0.0715307,5.69861e-11,5.39521e-11,3.71525e-10,2.95394e-07,3.0372e-07,1.03237e-06,5.78468e-05,1.20569e-05,0.000462417,3.21455e-05,4.30356e-05,0.000462128,0,0
34985000,-0.675853,-0.0112604,-0.00283111,0.736945,0.322697,0.328894,-0.101465,-16.8367,-8.13297,-365.51,-1.46984e-05,-6.2786e-05,-5.86002e-07,-0.000309513,0.000273477,-0.000780454,0.211519,0.00170702,0.428801,-0.000707991,-7.89808e-05,0.00259987,0,0,7.35784e-05,1.31435e-05,1.2926e-05,6.5591e-05,0.0332822,0.0341203,0.0379574,0.422434,0.423775,0.0711367,5.58744e-11,5.30416e-11,3.70796e-10,0,0,0,5.55012e-05,1.19631e-05,0.000461671,3.12202e-05,4.15683e-05,0.000461375,0,0
35085000,-0.676011,-0.0116462,-0.00323003,0.736792,0.540888,0.349347,-0.204258,-16.7849,-8.09975,-365.521,-1.46942e-05,-6.28078e-05,-6.44539e-07,-0.000309513,0.000273477,-0.000780454,0.211491,0.00168643,0.428791,-0.000657,-0.000184325,0.00265324,0,0,7.32634e-05,1.30321e-05,1.28151e-05,6.53151e-05,0.0356394,0.0368506,0.0402655,0.432613,0.433706,0.0726946,5.5972e-11,5.3091e-11,3.70479e-10,0,0,0,5.41195e-05,1.1874e-05,0.000461122,3.01941e-05,4.03052e-05,0.000460821,0,0
35185000,-0.676064,-0.0116743,-0.00326444,0.736743,0.570353,0.387156,-0.189577,-16.7291,-8.06302,-365.523,-1.46753e-05,-6.28148e-05,-7.02569e-07,-0.000309513,0.000273477,-0.000780454,0.211647,0.00166838,0.428981,-0.000554747,-0.000196302,0.00287439,0,0,7.25557e-05,1.29249e-05,1.27061e-05,6.45468e-05,0.0378434,0.0389646,0.0394291,0.443434,0.444298,0.0722424,5.60653e-11,5.31488e-11,3.70169e-10,0,0,0,5.28196e-05,1.17908e-05,0.000460435,2.92994e-05,3.92275e-05,0.000460128,0,0
35285000,-0.67611,-0.0116906,-0.00333742,0.7367,0.601321,0.425228,-0.184891,-16.6704,-8.02247,-365.532,-1.46708e-05,-6.28338e-05,-7.79632e-07,-0.000309513,0.000273477,-0.000780454,0.211694,0.001647,0.429013,-0.000456638,-0.000252569,0.00295607,0,0,7.23675e-05,1.28258e-05,1.26033e-05,6.4342e-05,0.0401398,0.0411653,0.0412516,0.454962,0.455618,0.0740151,5.61613e-11,5.32154e-11,3.69866e-10,0,0,0,5.17882e-05,1.17126e-05,0.000459976,2.85125e-05,3.82977e-05,0.000459664,0,0
35385000,-0.6762,-0.0117338,-0.00332148,0.736617,0.631641,0.462817,-0.169735,-16.6086,-7.97827,-365.531,-1.46551e-05,-6.28505e-05,-8.70434e-07,-0.000309513,0.000273477,-0.000780454,0.211794,0.00162088,0.429079,-0.000352427,-0.000336674,0.0030895,0,0,7.18928e-05,1.27307e-05,1.25083e-05,6.37684e-05,0.0425284,0.0434479,0.0404923,0.467265,0.46773,0.0748701,5.62547e-11,5.32935e-11,3.69665e-10,0,0,0,5.09782e-05,1.1657e-05,0.000459464,2.79819e-05,3.76796e-05,0.000459148,0,0
35485000,-0.676329,-0.0117596,-0.0033271,0.736498,0.662788,0.499668,-0.165778,-16.5438,-7.93034,-365.538,-1.46505e-05,-6.28701e-05,-9.67454e-07,-0.000309513,0.000273477,-0.000780454,0.211846,0.00159679,0.429089,-0.000240005,-0.000400606,0.0031576,0,0,7.17684e-05,1.26399e-05,1.24148e-05,6.36299e-05,0.045008,0.0458146,0.0421914,0.480414,0.480702,0.0768415,5.6349e-11,5.33703e-11,3.69363e-10,0,0,0,5.01486e-05,1.15857e-05,0.000459064,2.7342e-05,3.69439e-05,0.000458744,0,0
35585000,0.686275,0.0117155,0.00351855,-0.72724,0.0368605,0.0353775,-0.000929043,-11.5844,-17.2182,-365.535,-1.46466e-05,-6.28793e-05,-9.99507e-07,-0.000309513,0.000273477,-0.000780456,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00139393,1.27121e-05,1.27991e-05,0.00124103,0.0346583,0.0346489,0.0375565,0.12528,0.12528,0.0723287,5.64472e-11,5.34651e-11,3.69362e-10,2.93716e-07,3.01976e-07,1.01968e-06,0,0,0,0,0,0,0,0
35685000,0.686261,0.0117247,0.00349247,-0.727253,0.0667464,0.0742966,-0.00067699,-11.5792,-17.2127,-365.53,-1.46455e-05,-6.28786e-05,-9.98297e-07,-0.000309513,0.000273476,-0.000780493,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00139402,1.27721e-05,1.286e-05,0.00124102,0.0350349,0.034993,0.0381125,0.12625,0.126249,0.068388,5.6547e-11,5.35649e-11,3.69462e-10,2.93726e-07,3.01986e-07,1.01969e-06,0,0,0,0,0,0,0,0
35785000,0.686246,0.0117416,0.00353142,-0.727266,0.0899857,0.103525,-0.000306539,-11.5758,-17.2087,-365.524,-1.4644e-05,-6.28773e-05,-9.9685e-07,-0.000310941,0.000274475,-0.000780851,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00139359,1.28264e-05,1.29145e-05,0.00124057,0.031084,0.0310056,0.0365336,0.0848515,0.0848505,0.0654108,5.66468e-11,5.36648e-11,3.69562e-10,0,0,1.01919e-06,0,0,0,0,0,0,0,0
35885000,0.686254,0.0117573,0.00359646,-0.727258,0.119497,0.14315,0.000993592,-11.5654,-17.1964,-365.518,-1.46429e-05,-6.28765e-05,-9.95497e-07,-0.000310941,0.000274475,-0.000781224,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00139363,1.28926e-05,1.29815e-05,0.00124066,0.0316318,0.0314824,0.0376875,0.0865344,0.0865303,0.0634357,5.67466e-11,5.37647e-11,3.69662e-10,0,0,1.01918e-06,0,0,0,0,0,0,0,0
35985000,0.686269,0.0116462,0.00360463,-0.727246,0.133464,0.163025,0.000632205,-11.5668,-17.1939,-365.515,-1.46403e-05,-6.28736e-05,-9.94909e-07,-0.000310941,0.000274475,-0.000780977,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00139178,1.29286e-05,1.30079e-05,0.00123907,0.0284421,0.0282477,0.0366889,0.0656419,0.0656364,0.0618668,5.68464e-11,5.38646e-11,3.69761e-10,0,0,1.01692e-06,0,0,0,0,0,0,0,0
36085000,0.686269,0.0116993,0.00361933,-0.727244,0.162893,0.202324,0.00154791,-11.5519,-17.1756,-365.511,-1.46395e-05,-6.2873e-05,-9.93967e-07,-0.000310941,0.000274475,-0.000781696,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00139186,1.29999e-05,1.30829e-05,0.00123915,0.0292015,0.0289022,0.0384181,0.0678085,0.0677932,0.0621939,5.69463e-11,5.39645e-11,3.69861e-10,0,0,1.01684e-06,0,0,0,0,0,0,0,0
36185000,0.686222,0.0115563,0.00363509,-0.727291,0.171961,0.216926,0.00222865,-11.5539,-17.1751,-365.506,-1.46329e-05,-6.2865e-05,-9.93512e-07,-0.000310941,0.000274475,-0.000782287,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00138827,1.30068e-05,1.30752e-05,0.00123569,0.0265486,0.0262012,0.0377893,0.0549579,0.054941,0.0614828,5.70458e-11,5.40642e-11,3.69961e-10,0,0,1.01178e-06,0,0,0,0,0,0,0,0
36285000,0.686238,0.0116343,0.00362111,-0.727275,0.201046,0.256076,0.00485648,-11.5353,-17.1514,-365.496,-1.46313e-05,-6.28639e-05,-9.91713e-07,-0.000310941,0.000274475,-0.000784986,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00138831,1.30833e-05,1.31574e-05,0.00123584,0.0274997,0.0270156,0.0398713,0.0574959,0.0574584,0.0618518,5.71457e-11,5.41641e-11,3.70061e-10,0,0,1.01146e-06,0,0,0,0,0,0,0,0
36385000,0.686181,0.0114606,0.00362972,-0.727332,0.208221,0.264907,0.00487025,-11.5361,-17.1529,-365.493,-1.46195e-05,-6.28482e-05,-9.92616e-07,-0.000310941,0.000274475,-0.000786546,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00138225,1.30515e-05,1.31052e-05,0.00123038,0.0251926,0.0246803,0.0394029,0.0485456,0.0485081,0.0616939,5.72447e-11,5.42632e-11,3.70161e-10,0,0,1.00282e-06,0,0,0,0,0,0,0,0
36485000,0.686186,0.0115272,0.00369263,-0.727325,0.23821,0.303357,0.00613785,-11.5137,-17.1245,-365.49,-1.46192e-05,-6.2848e-05,-9.92253e-07,-0.000310941,0.000274475,-0.000787493,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00138235,1.3134e-05,1.3192e-05,0.0012305,0.0263105,0.0256449,0.0417791,0.051388,0.0513152,0.0628149,5.73446e-11,5.43632e-11,3.70261e-10,0,0,1.00207e-06,0,0,0,0,0,0,0,0
36585000,0.686138,0.0112746,0.00365348,-0.727375,0.240543,0.309,0.00907068,-11.5171,-17.1289,-365.485,-1.4598e-05,-6.28195e-05,-9.94308e-07,-0.000310941,0.000274475,-0.000790345,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00137358,1.30555e-05,1.3086e-05,0.00122288,0.0242424,0.023552,0.0412946,0.0445624,0.0444937,0.0629546,5.74424e-11,5.44612e-11,3.70361e-10,0,0,9.89436e-07,0,0,0,0,0,0,0,0
36685000,0.686158,0.0112683,0.00362594,-0.727356,0.269355,0.347521,0.0110925,-11.4916,-17.0961,-365.481,-1.45976e-05,-6.28192e-05,-9.93836e-07,-0.000310941,0.000274475,-0.000792227,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00137365,1.31427e-05,1.31735e-05,0.00122307,0.0255138,0.0246417,0.044103,0.0476642,0.0475419,0.0657151,5.75423e-11,5.45612e-11,3.70461e-10,0,0,9.88464e-07,0,0,0,0,0,0,0,0
36785000,0.686124,0.0109067,0.00362896,-0.727394,0.268263,0.349485,0.0127719,-11.4978,-17.1033,-365.476,-1.45638e-05,-6.27741e-05,-9.97614e-07,-0.000310941,0.000274475,-0.000792385,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00136217,1.30128e-05,1.30077e-05,0.00121309,0.0235912,0.0227188,0.0434743,0.042072,0.0419613,0.0659638,5.7638e-11,5.46573e-11,3.7056e-10,0,0,9.71882e-07,0,0,0,0,0,0,0,0
36885000,0.686142,0.0109644,0.00364227,-0.727376,0.29635,0.385806,0.0143623,-11.4696,-17.0665,-365.472,-1.45636e-05,-6.27739e-05,-9.97336e-07,-0.000310941,0.000274475,-0.000794061,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00136225,1.31056e-05,1.31042e-05,0.00121328,0.0249794,0.0239199,0.0461653,0.0453997,0.0452144,0.068135,5.7738e-11,5.47573e-11,3.7066e-10,0,0,9.69879e-07,0,0,0,0,0,0,0,0
36985000,0.686054,0.0104695,0.00354142,-0.727467,0.292029,0.382416,0.0143019,-11.4788,-17.0775,-365.47,-1.45141e-05,-6.27067e-05,-1.00368e-06,-0.000310941,0.000274475,-0.000793047,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00134828,1.292e-05,1.28766e-05,0.00120098,0.0231344,0.0221103,0.0452753,0.0405432,0.0403808,0.0683294,5.78305e-11,5.48505e-11,3.7076e-10,0,0,9.49693e-07,0,0,0,0,0,0,0,0
37085000,0.686052,0.0105025,0.00352773,-0.727468,0.320102,0.418702,0.0176583,-11.4482,-17.0374,-365.465,-1.45139e-05,-6.27066e-05,-1.00344e-06,-0.000310941,0.000274475,-0.000794968,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00134844,1.30177e-05,1.29767e-05,0.00120111,0.0246318,0.0234107,0.0479428,0.0440692,0.0438108,0.0707868,5.79305e-11,5.49504e-11,3.7086e-10,0,0,9.46849e-07,0,0,0,0,0,0,0,0
37185000,0.685903,0.00991746,0.00346399,-0.727617,0.312316,0.40901,0.019563,-11.4605,-17.0532,-365.464,-1.44458e-05,-6.26109e-05,-1.01308e-06,-0.000310941,0.000274475,-0.000796466,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00133204,1.27762e-05,1.26925e-05,0.00118682,0.0228134,0.0216667,0.0467288,0.0396491,0.0394284,0.0708097,5.80185e-11,5.50394e-11,3.7096e-10,0,0,9.2377e-07,0,0,0,0,0,0,0,0
37285000,0.685899,0.00993799,0.00350443,-0.727621,0.339409,0.444488,0.0216032,-11.428,-17.0105,-365.461,-1.44457e-05,-6.26108e-05,-1.01295e-06,-0.000310941,0.000274475,-0.000797877,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00133222,1.28793e-05,1.27968e-05,0.00118695,0.024396,0.0230469,0.0492917,0.0433494,0.043012,0.0734311,5.81185e-11,5.51394e-11,3.7106e-10,0,0,9.20089e-07,0,0,0,0,0,0,0,0
37385000,0.685709,0.00925009,0.00338454,-0.727809,0.32698,0.429337,0.0224139,-11.4434,-17.0303,-365.46,-1.43558e-05,-6.24841e-05,-1.02562e-06,-0.000310941,0.000274475,-0.000798334,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00131396,1.25824e-05,1.24601e-05,0.00117101,0.0225717,0.0213304,0.048163,0.0391769,0.038895,0.0745704,5.82005e-11,5.52227e-11,3.7116e-10,0,0,8.95971e-07,0,0,0,0,0,0,0,0
37485000,0.685727,0.00926934,0.00337791,-0.727792,0.35289,0.465243,0.0240669,-11.4094,-16.9856,-365.458,-1.43558e-05,-6.24842e-05,-1.02565e-06,-0.000310941,0.000274475,-0.000797771,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00131409,1.26899e-05,1.2569e-05,0.00117123,0.0242276,0.0227704,0.0506143,0.0430295,0.0426113,0.0773552,5.83005e-11,5.53227e-11,3.7126e-10,0,0,8.91741e-07,0,0,0,0,0,0,0,0
37585000,0.685448,0.00847519,0.00328104,-0.728065,0.336624,0.446969,0.0290833,-11.4281,-17.0093,-365.452,-1.42426e-05,-6.23232e-05,-1.04178e-06,-0.000310941,0.000274475,-0.000804764,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00129463,1.23413e-05,1.21869e-05,0.00115391,0.0223926,0.0210625,0.0487368,0.0389829,0.0386394,0.0768232,5.8375e-11,5.53987e-11,3.7136e-10,0,0,8.65571e-07,0,0,0,0,0,0,0,0
37685000,0.685439,0.00852407,0.00333239,-0.728072,0.360932,0.481774,0.0344841,-11.3932,-16.9629,-365.443,-1.42425e-05,-6.23231e-05,-1.04153e-06,-0.000310941,0.000274475,-0.000810108,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00129486,1.24536e-05,1.23012e-05,0.00115405,0.0240925,0.022545,0.0509755,0.0429676,0.0424698,0.0795883,5.8475e-11,5.54987e-11,3.7146e-10,0,0,8.60731e-07,0,0,0,0,0,0,0,0
37785000,0.685136,0.00759148,0.00327038,-0.728368,0.341869,0.459656,0.0387038,-11.4147,-16.9904,-365.436,-1.41051e-05,-6.21251e-05,-1.06173e-06,-0.000310941,0.000274475,-0.000815213,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00127454,1.20579e-05,1.1882e-05,0.00113606,0.022227,0.0208374,0.0488209,0.038968,0.0385648,0.0787339,5.85402e-11,5.55657e-11,3.7156e-10,0,0,8.34364e-07,0,0,0,0,0,0,0,0
37885000,0.685145,0.00759944,0.00328172,-0.72836,0.365068,0.492607,0.0396757,-11.3793,-16.9428,-365.436,-1.41051e-05,-6.2125e-05,-1.06185e-06,-0.000310941,0.000274475,-0.000811777,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00127473,1.21744e-05,1.19995e-05,0.00113627,0.0239442,0.0223498,0.0508211,0.0430646,0.042492,0.0814128,5.86402e-11,5.56657e-11,3.7166e-10,0,0,8.29077e-07,0,0,0,0,0,0,0,0
37985000,0.684844,0.00662911,0.00321946,-0.728652,0.343179,0.467023,0.0419787,-11.4044,-16.9738,-365.433,-1.39393e-05,-6.18883e-05,-1.08635e-06,-0.000310941,0.000274475,-0.000809961,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00125425,1.1738e-05,1.15559e-05,0.00111801,0.0220422,0.0206357,0.0490082,0.0390614,0.0386035,0.0819361,5.86947e-11,5.5722e-11,3.71759e-10,0,0,8.04601e-07,0,0,0,0,0,0,0,0
38085000,0.684812,0.00665114,0.00324054,-0.728683,0.364449,0.498244,0.0487374,-11.369,-16.9256,-365.423,-1.39393e-05,-6.18884e-05,-1.08622e-06,-0.000310941,0.000274475,-0.000814991,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.0012546,1.18587e-05,1.16776e-05,0.0011181,0.0237634,0.0221611,0.0508236,0.04325,0.0426119,0.0845931,5.87947e-11,5.5822e-11,3.71859e-10,0,0,7.99222e-07,0,0,0,0,0,0,0,0
38185000,0.684467,0.00560551,0.00309596,-0.729015,0.338904,0.468958,0.0483148,-11.3963,-16.9599,-365.421,-1.375e-05,-6.16135e-05,-1.11499e-06,-0.000310941,0.000274475,-0.000809725,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00123441,1.13892e-05,1.1218e-05,0.00110007,0.0218263,0.0204248,0.0482959,0.0392132,0.0387083,0.0831451,5.88367e-11,5.58658e-11,3.71959e-10,0,0,7.74463e-07,0,0,0,0,0,0,0,0
38285000,0.684473,0.00562755,0.00311513,-0.72901,0.359964,0.497625,0.0501426,-11.3614,-16.9116,-365.418,-1.375e-05,-6.16135e-05,-1.115e-06,-0.000310941,0.000274475,-0.000808757,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00123465,1.15136e-05,1.13434e-05,0.00110029,0.0235325,0.021965,0.0498748,0.0434748,0.0427823,0.0856388,5.89368e-11,5.59658e-11,3.72059e-10,0,0,7.68957e-07,0,0,0,0,0,0,0,0
38385000,0.684036,0.00455432,0.00293022,-0.729428,0.33439,0.466577,0.0478172,-11.3895,-16.9488,-365.416,-1.35431e-05,-6.13029e-05,-1.14731e-06,-0.000310941,0.000274475,-0.000800487,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00121529,1.10189e-05,1.08768e-05,0.00108298,0.0215799,0.0202228,0.0472807,0.0393889,0.0388462,0.0839779,5.89649e-11,5.59955e-11,3.72158e-10,0,0,7.45751e-07,0,0,0,0,0,0,0,0
38485000,0.684042,0.00455393,0.00296154,-0.729422,0.354303,0.494879,0.0486815,-11.3551,-16.9007,-365.413,-1.35431e-05,-6.13028e-05,-1.14733e-06,-0.000310941,0.000274475,-0.000798346,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00121555,1.11468e-05,1.10061e-05,0.00108323,0.0232775,0.0217609,0.048637,0.0437062,0.0429731,0.0862942,5.90649e-11,5.60955e-11,3.72258e-10,0,0,7.40257e-07,0,0,0,0,0,0,0,0
38585000,0.683566,0.00349608,0.00273836,-0.729875,0.328905,0.461858,0.0438979,-11.3847,-16.9402,-365.417,-1.33161e-05,-6.09569e-05,-1.18388e-06,-0.000310941,0.000274475,-0.000785994,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00119734,1.0635e-05,1.05395e-05,0.00106678,0.0213083,0.0200174,0.0460313,0.0395657,0.0389958,0.0844697,5.90778e-11,5.61095e-11,3.72357e-10,0,0,7.18836e-07,0,0,0,0,0,0,0,0
38685000,0.683587,0.00356364,0.00276643,-0.729855,0.346709,0.486588,0.0442958,-11.3509,-16.8928,-365.417,-1.3316e-05,-6.09567e-05,-1.18388e-06,-0.000310941,0.000274475,-0.000781936,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00119759,1.07663e-05,1.06711e-05,0.00106711,0.022962,0.0215378,0.0477938,0.0439225,0.0431636,0.0885208,5.91778e-11,5.62095e-11,3.72457e-10,0,0,7.14832e-07,0,0,0,0,0,0,0,0
38785000,0.683119,0.00245486,0.00260209,-0.730298,0.319175,0.450364,0.0437452,-11.3826,-16.9353,-365.416,-1.30652e-05,-6.05744e-05,-1.22444e-06,-0.000310941,0.000274475,-0.000777119,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00118074,1.02447e-05,1.02109e-05,0.00105188,0.020982,0.0197857,0.0451701,0.0397275,0.0391419,0.0864932,5.9174e-11,5.62063e-11,3.72556e-10,0,0,6.9512e-07,0,0,0,0,0,0,0,0
38885000,0.683124,0.00261588,0.00267625,-0.730293,0.327185,0.461722,0.491287,-11.3501,-16.8893,-365.399,-1.30653e-05,-6.05745e-05,-1.22445e-06,-0.000310941,0.000274475,-0.000778857,0.21181,0.00158687,0.429054,-0.00022441,-0.000464628,0.0031579,0,0,0.00118106,1.03787e-05,1.03429e-05,0.00105215,0.021903,0.0206462,0.045527,0.0440985,0.0433304,0.0885263,5.9274e-11,5.63063e-11,3.72656e-10,0,0,6.9004e-07,0,0,0,0,0,0,0,0
185000,0.999749,-0.0104072,-0.0107851,-0.0166593,0.00012003,-0.0001068,-0.0115085,1.36678e-05,-4.60777e-06,-0.000265302,4.01008e-11,1.70856e-14,1.83726e-09,0,0,-7.93589e-11,0.191453,0.00184374,0.404156,0,0,0,0,0,1.59693e-06,0.00250808,0.00250843,0.00375232,0.25346,0.25346,0.562563,0.126411,0.126411,1.00079,1e-06,1e-06,9.99741e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
285000,0.999744,-0.0104987,-0.0111244,-0.0166782,0.00135698,0.000386592,-0.0252008,7.07676e-05,-1.58824e-05,-0.00161355,1.21187e-09,4.4155e-12,5.4969e-08,0,0,-1.75435e-09,0.191453,0.00184374,0.404156,0,0,0,0,0,1.2861e-06,0.00255798,0.00255845,0.00252773,0.273498,0.2735,0.562506,0.13279,0.13279,0.576885,9.99999e-07,1e-06,9.97806e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
385000,0.995986,-0.00937192,-0.011663,0.0882481,-0.00105457,0.000727164,-0.0421913,-0.000126013,4.30077e-05,-0.00388401,-7.24905e-06,-2.45061e-08,-0.000346141,0,0,-1.90333e-08,0.191453,0.00184374,0.404156,0,0,0,0,0,1.0727e-06,0.00265582,0.00265636,0.00179473,0.305224,0.305231,0.560129,0.0939616,0.0939617,0.375592,9.99993e-07,9.99998e-07,9.90503e-07,0,0,3.99998e-06,0,0,0,0,0,0,0,0
485000,0.979986,-0.0101668,-0.014249,0.198297,0.00996126,-0.0132919,-0.0813196,0.00123764,-0.00204204,-0.0088471,-8.59997e-06,1.2756e-05,-0.000975495,0,0,-1.13398e-07,0.191453,0.00184374,0.404156,0,0,0,0,0,1.6917e-06,0.00280417,0.00280445,0.00143844,0.366383,0.366396,0.554098,0.108558,0.108558,0.287379,9.9999e-07,9.99986e-07,9.75764e-07,0,0,3.99978e-06,0,0,0,0,0,0,0,0
585000,0.956922,-0.012385,-0.0191055,0.28945,0.0484905,-0.0394046,-0.147103,0.00716773,-0.00676485,-0.0198357,-3.14027e-07,4.65186e-05,-0.00176828,0,0,-5.35383e-07,0.191453,0.00184374,0.404156,0,0,0,0,0,5.48324e-06,0.0029612,0.00296079,0.00124701,0.411614,0.411657,0.543717,0.0893979,0.0893988,0.24203,9.99742e-07,9.99698e-07,9.52429e-07,0,0,3.99919e-06,0,0,0,0,0,0,0,0
685000,0.928109,-0.0144953,-0.0246496,0.371209,0.114968,-0.0683776,-0.243075,0.0233273,-0.0165798,-0.0396472,8.10302e-06,9.54591e-05,-0.00271727,0,0,-1.89024e-06,0.191453,0.00184374,0.404156,0,0,0,0,0,1.56118e-05,0.00320119,0.00319973,0.0011381,0.514176,0.514338,0.528124,0.114591,0.114597,0.217523,9.9974e-07,9.99608e-07,9.1905e-07,0,0,3.99786e-06,0,0,0,0,0,0,0,0
785000,0.894476,-0.0154738,-0.0300092,0.445839,0.184087,-0.0767286,-0.358093,0.0365285,-0.0195363,-0.0730037,1.28051e-05,0.000156564,-0.00373955,0,0,-4.62801e-06,0.191453,0.00184374,0.404156,0,0,0,0,0,3.54678e-05,0.0033053,0.00330249,0.00107209,0.535868,0.536228,0.515266,0.099003,0.0990154,0.215673,9.972e-07,9.96911e-07,8.76087e-07,0,0,3.99613e-06,0,0,0,0,0,0,0,0
885000,0.860502,-0.0163393,-0.0359576,0.507914,0.288615,-0.0795021,-0.480899,0.0735356,-0.0289842,-0.130781,1.73639e-05,0.000226046,-0.00370834,0,0,-5.20191e-06,0.191453,0.00184374,0.404156,0,0,0,0,0,6.66054e-05,0.00362336,0.00361831,0.00102584,0.675504,0.676339,0.524053,0.136491,0.136539,0.25647,9.97199e-07,9.96624e-07,8.23811e-07,0,0,3.99614e-06,0,0,0,0,0,0,0,0
985000,0.833588,-0.0147324,-0.0374469,0.550919,0.310006,-0.0511159,-0.572444,0.0734012,-0.0217008,-0.198167,8.81419e-06,0.000264187,-0.00349066,0,0,-6.44094e-06,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000110853,0.00354161,0.00353558,0.0010277,0.629197,0.630177,0.534925,0.113221,0.113269,0.30796,9.86776e-07,9.85971e-07,7.79505e-07,0,0,3.99613e-06,0,0,0,0,0,0,0,0
1085000,0.802904,-0.014513,-0.0422629,0.594431,0.410278,-0.0295526,-0.675784,0.121065,-0.0240301,-0.281338,1.00228e-05,0.000324351,-0.00349066,0,0,-6.80889e-06,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000162225,0.00391918,0.00391014,0.000986323,0.794998,0.796688,0.547532,0.161112,0.161244,0.370432,9.86776e-07,9.855e-07,7.16002e-07,0,0,3.99614e-06,0,0,0,0,0,0,0,0
1185000,0.774814,-0.0111688,-0.0406336,0.630783,0.369104,0.00968837,-0.763729,0.0985943,-0.0116675,-0.373036,-1.22529e-05,0.00034515,-0.00349066,0,0,-8.84877e-06,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000218783,0.00362096,0.00361191,0.000941244,0.669001,0.670415,0.562059,0.123851,0.12394,0.444253,9.62032e-07,9.60442e-07,6.50065e-07,0,0,3.99609e-06,0,0,0,0,0,0,0,0
1285000,0.750033,-0.0103668,-0.0437067,0.659873,0.443347,0.0404969,-0.828258,0.144961,-0.00705263,-0.467935,-1.20743e-05,0.000380202,-0.00349066,0,0,-9.05452e-06,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000277008,0.00403772,0.00402578,0.00089222,0.847308,0.849332,0.578704,0.177447,0.177645,0.529866,9.62032e-07,9.59932e-07,5.84164e-07,0,0,3.9961e-06,0,0,0,0,0,0,0,0
1385000,0.728209,-0.00643711,-0.0388839,0.684221,0.345159,0.0612047,-0.879653,0.100945,0.000924668,-0.56588,-4.50925e-05,0.000361472,-0.00354154,0,0,-1.14597e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000333044,0.00359664,0.00358681,0.00083814,0.669493,0.670787,0.597257,0.128151,0.128249,0.627746,9.20087e-07,9.17947e-07,5.20186e-07,0,0,3.99604e-06,0,0,0,0,0,0,0,0
1485000,0.709624,-0.00554697,-0.0406711,0.703384,0.394446,0.0900457,-0.913368,0.139496,0.00927935,-0.662392,-4.47418e-05,0.000374255,-0.00352254,0,0,-1.15357e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000384949,0.00403494,0.00402292,0.000783852,0.851957,0.853628,0.618173,0.183179,0.183372,0.7385,9.20086e-07,9.17591e-07,4.6094e-07,0,0,3.99605e-06,0,0,0,0,0,0,0,0
1585000,0.694313,-0.00176333,-0.034694,0.718834,0.279046,0.0880863,-0.939379,0.0891194,0.0100076,-0.759823,-8.28273e-05,0.000331516,-0.00349582,0,0,-1.37468e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000447305,0.00352664,0.00351797,0.000756669,0.655558,0.656465,0.641041,0.127726,0.127807,0.862708,8.61435e-07,8.59286e-07,4.19438e-07,0,0,3.99599e-06,0,0,0,0,0,0,0,0
1685000,0.681945,-0.000773111,-0.0357615,0.730528,0.311112,0.115069,-0.949784,0.118602,0.0201498,-0.85403,-8.28769e-05,0.000331085,-0.0034796,0,0,-1.37449e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000487811,0.00397205,0.00396186,0.000700476,0.837936,0.839027,0.666255,0.181918,0.182067,1.00113,8.61433e-07,8.59109e-07,3.69485e-07,0,0,3.996e-06,0,0,0,0,0,0,0,0
1785000,0.670318,0.000325294,-0.036766,0.741162,0.341977,0.144848,-0.961107,0.151056,0.0330039,-0.948739,-8.31082e-05,0.000329479,-0.00345425,0,0,-1.37388e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000520708,0.00445355,0.00444167,0.000647196,1.06047,1.06172,0.693799,0.258824,0.259072,1.15453,8.6143e-07,8.58933e-07,3.25235e-07,0,0,3.99601e-06,0,0,0,0,0,0,0,0
1885000,0.660367,0.00374111,-0.0315506,0.75027,0.231312,0.135002,-0.975247,0.096454,0.0289763,-1.04685,-0.000117211,0.000289851,-0.00340043,0,0,-1.56614e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000547341,0.00386723,0.00385361,0.000592087,0.820919,0.821539,0.722604,0.177469,0.177596,1.32349,7.87864e-07,7.856e-07,2.85474e-07,0,0,3.99596e-06,0,0,0,0,0,0,0,0
1985000,0.652374,0.00495541,-0.0336707,0.757133,0.26354,0.178032,-0.982076,0.126108,0.0483495,-1.14312,-0.000110872,0.000301843,-0.00330983,0,0,-1.6057e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.00056819,0.00433993,0.004317,0.000543487,1.04099,1.04159,0.754356,0.252254,0.252496,1.50928,7.87697e-07,7.85001e-07,2.51257e-07,0,0,3.99597e-06,0,0,0,0,0,0,0,0
2085000,0.646508,0.00762943,-0.0293765,0.762303,0.172592,0.160436,-0.996243,0.0799867,0.0393854,-1.24551,-0.000137325,0.000266225,-0.00319528,0,0,-1.78075e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000583149,0.00371112,0.00369337,0.000498252,0.802743,0.802818,0.78727,0.172044,0.172141,1.71229,7.02472e-07,7.0063e-07,2.21757e-07,0,0,3.99594e-06,0,0,0,0,0,0,0,0
2185000,0.640302,0.00880812,-0.0312452,0.767437,0.194151,0.203595,-1.00903,0.102635,0.0607268,-1.34815,-0.000130639,0.000274909,-0.0030942,0,0,-1.82662e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.00059393,0.00416218,0.00413899,0.000459305,1.01947,1.01929,0.823273,0.244717,0.244869,1.93417,7.02362e-07,7.00444e-07,1.96499e-07,0,0,3.99595e-06,0,0,0,0,0,0,0,0
2285000,0.63452,0.0105094,-0.0268413,0.772368,0.112831,0.172947,-1.03112,0.0620389,0.0450496,-1.45892,-0.000153119,0.000234159,-0.00299961,0,0,-1.9424e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000620659,0.00349478,0.00348,0.000436358,0.781481,0.781065,0.860201,0.166506,0.166551,2.1751,6.10028e-07,6.08999e-07,1.79789e-07,0,0,3.99594e-06,0,0,0,0,0,0,0,0
2385000,0.630455,0.01162,-0.0283334,0.775622,0.125976,0.213318,-1.05068,0.077785,0.0669676,-1.57242,-0.000146378,0.00023969,-0.00288519,0,0,-1.99163e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.00062366,0.00391239,0.00389455,0.000403811,0.991097,0.990324,0.900234,0.23693,0.236979,2.43714,6.09961e-07,6.08953e-07,1.60351e-07,0,0,3.99595e-06,0,0,0,0,0,0,0,0
2485000,0.627292,0.0124632,-0.0243847,0.778303,0.0612593,0.175059,-1.08017,0.0455716,0.0477577,-1.69748,-0.000160755,0.0001996,-0.00277107,0,0,-2.07111e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000622644,0.00322111,0.00321064,0.000373903,0.752319,0.751623,0.940884,0.160881,0.160884,2.72019,5.16132e-07,5.15778e-07,1.43522e-07,0,0,3.99595e-06,0,0,0,0,0,0,0,0
2585000,0.625754,0.0134543,-0.0255826,0.779485,0.0661897,0.211823,-1.11432,0.0552651,0.0691333,-1.83048,-0.000154117,0.000202225,-0.00264199,0,0,-2.11922e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000620694,0.00359671,0.0035846,0.000348222,0.951425,0.95034,0.984711,0.228699,0.228675,3.02677,5.16094e-07,5.15772e-07,1.28996e-07,0,0,3.99596e-06,0,0,0,0,0,0,0,0
2685000,0.623705,0.0135296,-0.0220817,0.781231,0.0165329,0.168429,-1.15624,0.0306458,0.0474848,-1.9745,-0.000161763,0.000163559,-0.00253323,0,0,-2.16191e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000615278,0.00290636,0.00289992,0.000324443,0.715073,0.714269,1.02895,0.155078,0.155054,3.35646,4.26498e-07,4.26569e-07,1.16281e-07,0,0,3.99595e-06,0,0,0,0,0,0,0,0
2785000,0.622709,0.014515,-0.0228522,0.781985,0.0143631,0.199862,-1.20108,0.0344579,0.0671395,-2.12866,-0.000156832,0.000163643,-0.0024181,0,0,-2.19578e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000610221,0.00323549,0.00322827,0.000304076,0.900118,0.898957,1.07628,0.219852,0.219783,3.71226,4.26478e-07,4.26569e-07,1.05291e-07,0,0,3.99596e-06,0,0,0,0,0,0,0,0
2885000,0.619652,0.0139369,-0.019882,0.784501,-0.020268,0.155122,-1.24469,0.0171095,0.0448462,-2.28533,-0.000158995,0.000129025,-0.00234015,0,0,-2.21013e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000620363,0.00257309,0.00256966,0.000291362,0.670246,0.669472,1.12422,0.149052,0.149013,4.09387,3.45527e-07,3.45808e-07,9.7878e-08,0,0,3.99594e-06,0,0,0,0,0,0,0,0
2985000,0.61921,0.0147898,-0.020302,0.784824,-0.0289516,0.182494,-1.30245,0.0160845,0.0625725,-2.46364,-0.00015552,0.000127732,-0.00223457,0,0,-2.23196e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000612648,0.00285513,0.00285142,0.000274264,0.839619,0.838544,1.17495,0.210347,0.210259,4.50397,3.45518e-07,3.45806e-07,8.91466e-08,0,0,3.99595e-06,0,0,0,0,0,0,0,0
3085000,0.619505,0.0137399,-0.0180409,0.784665,-0.0480134,0.140585,-1.37096,0.00621634,0.0414692,-2.66228,-0.000151261,9.75854e-05,-0.00213004,0,0,-2.2443e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000602872,0.00224302,0.00224152,0.000258143,0.621047,0.620385,1.22583,0.142859,0.142816,4.94187,2.75687e-07,2.7604e-07,8.13696e-08,0,0,3.99592e-06,0,0,0,0,0,0,0,0
3185000,0.619593,0.014445,-0.0182822,0.784577,-0.0609004,0.163007,-1.44101,0.00161263,0.0572579,-2.87047,-0.00014883,9.57457e-05,-0.00203483,0,0,-2.25672e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.00059417,0.00248055,0.00247899,0.000244347,0.773565,0.772681,1.27961,0.200387,0.200298,5.41137,2.75682e-07,2.76037e-07,7.45799e-08,0,0,3.99593e-06,0,0,0,0,0,0,0,0
3285000,0.619785,0.013104,-0.0165681,0.784487,-0.0689357,0.125551,-1.51817,-0.0026556,0.0376452,-3.09721,-0.000141206,7.04531e-05,-0.00194528,0,0,-2.26514e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000584029,0.00193255,0.0019321,0.0002311,0.570015,0.569497,1.33351,0.136612,0.136572,5.91125,2.176e-07,2.17947e-07,6.84752e-08,0,0,3.99588e-06,0,0,0,0,0,0,0,0
3385000,0.620645,0.0138138,-0.0166188,0.783794,-0.0829036,0.14434,-1.60304,-0.00987203,0.051771,-3.34382,-0.000139413,6.83693e-05,-0.00185433,0,0,-2.2718e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000574987,0.00212996,0.00212956,0.000219735,0.70561,0.70495,1.39009,0.190237,0.190159,6.44553,2.17598e-07,2.17944e-07,6.31134e-08,0,0,3.99589e-06,0,0,0,0,0,0,0,0
3485000,0.621712,0.012327,-0.0154138,0.782997,-0.0810376,0.111183,-1.69631,-0.00943771,0.0340174,-3.61227,-0.000129453,4.71736e-05,-0.00176794,0,0,-2.28153e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000564874,0.00165142,0.00165145,0.000208761,0.51944,0.519078,1.44682,0.130433,0.130399,7.01291,1.70585e-07,1.70887e-07,5.82563e-08,0,0,3.99583e-06,0,0,0,0,0,0,0,0
3585000,0.620511,0.0129166,-0.0153811,0.783941,-0.0952235,0.125881,-1.76838,-0.0182288,0.0463115,-3.86417,-0.000128535,4.57257e-05,-0.00170924,0,0,-2.28385e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000569297,0.00181406,0.00181416,0.0002024,0.639064,0.638625,1.50712,0.180171,0.180108,7.61962,1.70585e-07,1.70886e-07,5.49864e-08,0,0,3.99584e-06,0,0,0,0,0,0,0,0
3685000,0.621557,0.011366,-0.0145591,0.783151,-0.0864975,0.0964816,-1.8701,-0.0142573,0.0304663,-4.16692,-0.000117577,2.82456e-05,-0.00163202,0,0,-2.29502e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000558894,0.00140378,0.00140395,0.000192856,0.471167,0.470945,1.56661,0.124427,0.124401,8.26053,1.33256e-07,1.33502e-07,5.09654e-08,0,0,3.99578e-06,0,0,0,0,0,0,0,0
3785000,0.62307,0.011844,-0.0145222,0.781941,-0.100515,0.109998,-1.97795,-0.0238486,0.0414464,-4.49419,-0.000116555,2.62849e-05,-0.00155476,0,0,-2.29748e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000549408,0.00153701,0.00153724,0.0001846,0.576061,0.575807,1.62829,0.170409,0.170364,8.94162,1.33256e-07,1.335e-07,4.73921e-08,0,0,3.99579e-06,0,0,0,0,0,0,0,0
3885000,0.624412,0.0123667,-0.0143908,0.780864,-0.117015,0.122971,-2.08792,-0.0349294,0.0539345,-4.83757,-0.000115481,2.45574e-05,-0.0014842,0,0,-2.30029e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000540029,0.00167672,0.00167701,0.000177025,0.697887,0.697599,1.69116,0.23241,0.232339,9.66306,1.33255e-07,1.33498e-07,4.4159e-08,0,0,3.9958e-06,0,0,0,0,0,0,0,0
3985000,0.62576,0.0108157,-0.0137041,0.77982,-0.104322,0.094213,-2.20384,-0.0275675,0.0367904,-5.20412,-0.000104714,1.009e-05,-0.00141799,0,0,-2.3105e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000530163,0.00129863,0.00129881,0.000169532,0.517888,0.517775,1.75408,0.161102,0.161073,10.4246,1.03993e-07,1.0418e-07,4.11851e-08,0,0,3.99574e-06,0,0,0,0,0,0,0,0
4085000,0.627152,0.0111734,-0.0135699,0.778699,-0.11969,0.106018,-2.32125,-0.0392063,0.0475878,-5.59042,-0.000103814,8.46516e-06,-0.00135467,0,0,-2.31344e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000521148,0.00141254,0.00141276,0.000163041,0.623835,0.623723,1.81902,0.217905,0.217861,11.2309,1.03993e-07,1.04178e-07,3.85207e-08,0,0,3.99575e-06,0,0,0,0,0,0,0,0
4185000,0.626957,0.00964578,-0.0131463,0.778884,-0.102663,0.0806214,-2.41815,-0.0297797,0.0324507,-5.95721,-9.35526e-05,-3.02169e-06,-0.00130979,0,0,-2.32102e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000522672,0.00109613,0.00109615,0.000158607,0.464934,0.464921,1.88611,0.152342,0.152325,12.0855,8.12325e-08,8.13679e-08,3.66485e-08,0,0,3.9957e-06,0,0,0,0,0,0,0,0
4285000,0.628605,0.00999392,-0.013044,0.777551,-0.119195,0.0894604,-2.54439,-0.0414173,0.0417121,-6.38966,-9.27289e-05,-4.56995e-06,-0.00125081,0,0,-2.32548e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000513587,0.00118893,0.00118896,0.000152864,0.557014,0.557023,1.9531,0.204345,0.204324,12.9832,8.12321e-08,8.13665e-08,3.43771e-08,0,0,3.99571e-06,0,0,0,0,0,0,0,0
4385000,0.630485,0.0085715,-0.0127954,0.776048,-0.102211,0.0667229,-2.68177,-0.0311454,0.0285879,-6.85568,-8.28469e-05,-1.44255e-05,-0.00119292,0,0,-2.33018e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000504338,0.000925495,0.000925353,0.000147179,0.417271,0.417324,2.0202,0.144163,0.144156,13.9271,6.36011e-08,6.36938e-08,3.22739e-08,0,0,3.99566e-06,0,0,0,0,0,0,0,0
4485000,0.631809,0.0088449,-0.0126489,0.77497,-0.116018,0.0730084,-2.81097,-0.04268,0.0362341,-7.3259,-8.20894e-05,-1.57827e-05,-0.00114201,0,0,-2.33631e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000495732,0.00100116,0.001001,0.000142155,0.497443,0.497531,2.08902,0.191778,0.191773,14.9219,6.36008e-08,6.36925e-08,3.03673e-08,0,0,3.99567e-06,0,0,0,0,0,0,0,0
4585000,0.633561,0.00748653,-0.0125735,0.773554,-0.0974154,0.0548437,-2.95257,-0.0316469,0.024803,-7.83609,-7.29684e-05,-2.38096e-05,-0.0010906,0,0,-2.33518e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000487017,0.000782443,0.000782149,0.000137208,0.374826,0.374916,2.15789,0.136571,0.136572,15.9657,4.99627e-08,5.00212e-08,2.85958e-08,0,0,3.99562e-06,0,0,0,0,0,0,0,0
4685000,0.635356,0.00765972,-0.0124263,0.772082,-0.108845,0.0599464,-3.0949,-0.0426408,0.0312021,-8.36856,-7.21652e-05,-2.51359e-05,-0.00104127,0,0,-2.34398e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000478824,0.000844238,0.000843915,0.000132819,0.444512,0.444639,2.22827,0.180212,0.180219,17.0635,4.99624e-08,5.00201e-08,2.69805e-08,0,0,3.99563e-06,0,0,0,0,0,0,0,0
4785000,0.636708,0.00640215,-0.0124473,0.770978,-0.0897669,0.0433031,-3.23252,-0.0312382,0.0213009,-8.90982,-6.40213e-05,-3.15483e-05,-0.000998125,0,0,-2.33584e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000470588,0.000662815,0.000662399,0.000128496,0.337035,0.337142,2.29874,0.129548,0.129554,18.2134,3.94065e-08,3.94388e-08,2.54756e-08,0,0,3.99559e-06,0,0,0,0,0,0,0,0
4885000,0.637063,0.00653473,-0.0123613,0.770685,-0.0992787,0.0466204,-3.34594,-0.0411873,0.0262604,-9.42454,-6.34227e-05,-3.2444e-05,-0.000964813,0,0,-2.34409e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.00047123,0.000713413,0.000712954,0.00012593,0.397799,0.397941,2.37369,0.169595,0.169609,19.4315,3.94062e-08,3.94381e-08,2.44287e-08,0,0,3.9956e-06,0,0,0,0,0,0,0,0
4985000,0.63853,0.00551516,-0.0123851,0.769477,-0.0817732,0.0333494,-3.48869,-0.029984,0.0179158,-10.0133,-5.62568e-05,-3.76084e-05,-0.000924689,0,0,-2.3288e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000463119,0.000562862,0.000562362,0.000122054,0.303551,0.303657,2.44572,0.12306,0.12307,20.6944,3.12202e-08,3.12333e-08,2.31146e-08,0,0,3.99555e-06,0,0,0,0,0,0,0,0
5085000,0.640266,0.0055786,-0.0123147,0.768035,-0.0910389,0.0350512,-3.63963,-0.0392292,0.0218444,-10.639,-5.54444e-05,-3.87211e-05,-0.000883801,0,0,-2.3414e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000455422,0.00060442,0.000603872,0.000118541,0.356598,0.356735,2.51903,0.15987,0.159888,22.0176,3.12199e-08,3.12325e-08,2.19042e-08,0,0,3.99556e-06,0,0,0,0,0,0,0,0
5185000,0.642029,0.00464198,-0.0123973,0.766566,-0.0735348,0.0234955,-3.794,-0.0285248,0.0148174,-11.2947,-4.91487e-05,-4.28977e-05,-0.000844669,0,0,-2.32068e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000447762,0.00047933,0.000478779,0.000115102,0.273825,0.273921,2.59229,0.117073,0.117084,23.3987,2.4853e-08,2.48521e-08,2.07721e-08,0,0,3.99551e-06,0,0,0,0,0,0,0,0
5285000,0.643785,0.00470249,-0.0122784,0.765094,-0.0816135,0.0227215,-3.94808,-0.0367906,0.0175532,-11.9701,-4.83346e-05,-4.39163e-05,-0.000807429,0,0,-2.3345e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000440397,0.000513581,0.000512984,0.000111982,0.32022,0.320341,2.66675,0.150964,0.150983,24.8433,2.48526e-08,2.48515e-08,1.97231e-08,0,0,3.99552e-06,0,0,0,0,0,0,0,0
5385000,0.645069,0.00400367,-0.0124173,0.764013,-0.0653986,0.0114188,-4.09297,-0.0267044,0.0115862,-12.6477,-4.29725e-05,-4.70762e-05,-0.000774946,0,0,-2.30766e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.00043315,0.000409444,0.000408876,0.000108923,0.247512,0.247594,2.74122,0.111544,0.111555,26.3488,1.98831e-08,1.98727e-08,1.87419e-08,0,0,3.99546e-06,0,0,0,0,0,0,0,0
5485000,0.645449,0.00405992,-0.0123,0.763693,-0.0713501,0.0106618,-4.20757,-0.0338569,0.0129031,-13.2815,-4.23935e-05,-4.77486e-05,-0.000750614,0,0,-2.31783e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000433203,0.000437778,0.000437166,0.000107133,0.288167,0.288265,2.82081,0.142807,0.142826,27.9405,1.98829e-08,1.98723e-08,1.80515e-08,0,0,3.99547e-06,0,0,0,0,0,0,0,0
5585000,0.646903,0.00339536,-0.0124396,0.762463,-0.0573257,0.00276523,-4.35769,-0.0245851,0.00828121,-14.0097,-3.77961e-05,-5.01172e-05,-0.000719921,0,0,-2.28878e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000426057,0.000350879,0.000350315,0.00010437,0.224177,0.224238,2.89644,0.106434,0.106445,29.5777,1.59884e-08,1.59717e-08,1.718e-08,0,0,3.9954e-06,0,0,0,0,0,0,0,0
5685000,0.648181,0.00341475,-0.012299,0.761379,-0.0633741,0.000943832,-4.50495,-0.0309714,0.00869287,-14.7505,-3.706e-05,-5.09113e-05,-0.000691191,0,0,-2.30211e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000419174,0.000374409,0.000373806,0.000101802,0.260006,0.260077,2.97315,0.135331,0.135349,31.2852,1.59879e-08,1.59712e-08,1.6366e-08,0,0,3.99541e-06,0,0,0,0,0,0,0,0
5785000,0.649459,0.00291383,-0.0124583,0.760289,-0.0517937,-0.00521867,-0.00309678,-0.022568,0.00526503,-365.429,-3.31548e-05,-5.25879e-05,-0.000664059,0,0,-2.27174e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000412392,0.000301686,0.000301146,9.93217e-05,0.203508,0.203547,9.99881,0.101712,0.101722,2.00225,1.29223e-08,1.29019e-08,1.56017e-08,0,0,3.99532e-06,0,0,0,0,0,0,0,0
5885000,0.650777,0.002868,-0.0123696,0.759163,-0.0562909,-0.00673002,-0.00835999,-0.028247,0.00483468,-365.42,-3.24341e-05,-5.33113e-05,-0.000637684,0,0,-2.28805e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000405826,0.000321307,0.000320731,9.70194e-05,0.235054,0.235096,9.74009,0.128474,0.128489,0.709952,1.29219e-08,1.29014e-08,1.48855e-08,0,0,3.99533e-06,0,0,0,0,0,0,0,0
5985000,0.652086,0.0028584,-0.012309,0.758039,-0.0622958,-0.00932304,-0.00423867,-0.0345603,0.00416819,-365.404,-3.17341e-05,-5.40007e-05,-0.000612294,0,0,-2.31218e-05,0.191453,0.00184374,0.404156,0,0,0,0,0,0.000399439,0.00034157,0.000340957,9.48283e-05,0.270153,0.2702,8.84116,0.161777,0.161799,0.518931,1.29215e-08,1.2901e-08,1.42131e-08,0,0,3.99532e-06,0,0,0,0,0,0,0,0
6085000,0.704797,0.001535,-0.0126589,0.709294,-0.0503162,-0.0124098,-0.0193618,-0.025545,0.00138139,-365.406,-2.90694e-05,-5.44757e-05,-0.000612326,0,0,-2.26727e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00112913,0.00026396,0.000263216,0.000907144,0.191485,0.191497,7.28981,0.121716,0.121727,0.482369,1.04979e-08,1.04755e-08,1.42114e-08,0,0,3.99512e-06,0,0,0,0,0,0,0,0
6185000,0.703,0.00149919,-0.0125963,0.711077,-0.0551368,-0.0148313,-0.018524,-0.0308256,3.27182e-05,-365.402,-2.90693e-05,-5.44757e-05,-0.000612311,0,0,-2.28418e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000919985,0.00026463,0.000263951,0.000734749,0.195307,0.195314,5.9692,0.150006,0.150021,0.537996,1.0498e-08,1.04756e-08,1.42103e-08,0,0,3.99497e-06,0,0,0,0,0,0,0,0
6285000,0.702148,0.00146515,-0.0125912,0.711918,-0.0457712,-0.0158289,-0.0153329,-0.0232191,-0.00137622,-365.396,-2.69073e-05,-5.46053e-05,-0.000612205,0,0,-2.26911e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000743428,0.000265259,0.000264634,0.000591349,0.142012,0.142005,4.37903,0.112338,0.112345,0.517043,8.63892e-09,8.61576e-09,1.42064e-08,0,0,3.99449e-06,0,0,0,0,0,0,0,0
6385000,0.701438,0.00152121,-0.0124712,0.712619,-0.0496773,-0.0177915,-0.0475597,-0.0280043,-0.00304876,-365.408,-2.68931e-05,-5.46126e-05,-0.000611869,0,0,-2.23081e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000628702,0.000266631,0.000266043,0.00049839,0.150777,0.150768,3.1623,0.13534,0.135347,0.485949,8.63901e-09,8.61586e-09,1.42012e-08,0,0,3.99395e-06,0,0,0,0,0,0,0,0
6485000,0.700437,0.00150048,-0.0125547,0.713603,-0.0432685,-0.018617,-0.0518276,-0.0217365,-0.00352054,-365.408,-2.51288e-05,-5.4534e-05,-0.000611556,0,0,-2.22699e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000548233,0.000266205,0.000265642,0.000433406,0.119661,0.119651,2.28654,0.102937,0.102939,0.448475,7.27264e-09,7.2494e-09,1.41929e-08,0,0,3.99305e-06,0,0,0,0,0,0,0,0
6585000,0.698946,0.00149877,-0.0125373,0.715063,-0.0463346,-0.0210526,-0.0920802,-0.0261781,-0.00549509,-365.43,-2.51133e-05,-5.45418e-05,-0.00061122,0,0,-2.1141e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000488652,0.000267873,0.000267325,0.000385623,0.132536,0.132527,1.67693,0.122435,0.122438,0.410604,7.27272e-09,7.2495e-09,1.41819e-08,0,0,3.99195e-06,0,0,0,0,0,0,0,0
6685000,0.697708,0.00144885,-0.012591,0.716271,-0.0404718,-0.0210258,-0.0756646,-0.0208052,-0.00539184,-365.419,-2.36389e-05,-5.43357e-05,-0.000610769,0,0,-2.27512e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000442862,0.000264511,0.000263986,0.000349098,0.114438,0.114433,1.25876,0.0952129,0.0952134,0.376515,6.27132e-09,6.24841e-09,1.4167e-08,0,0,3.99038e-06,0,0,0,0,0,0,0,0
6785000,0.696585,0.00143156,-0.0125439,0.717363,-0.0438953,-0.023884,-0.111963,-0.0250286,-0.00760485,-365.444,-2.3605e-05,-5.43535e-05,-0.000609986,0,0,-2.11554e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000415745,0.000266153,0.000265634,0.000327005,0.130724,0.130723,1.03301,0.112819,0.112818,0.379393,6.27139e-09,6.2485e-09,1.41535e-08,0,0,3.98898e-06,0,0,0,0,0,0,0,0
6885000,0.695379,0.00134734,-0.0125886,0.718531,-0.0407724,-0.0239634,-0.12073,-0.0203098,-0.00707144,-365.45,-2.23337e-05,-5.40774e-05,-0.000609158,0,0,-2.1393e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000384882,0.000258004,0.000257515,0.000302732,0.119206,0.119213,0.80734,0.0896852,0.0896845,0.347519,5.53707e-09,5.51475e-09,1.41313e-08,0,0,3.98645e-06,0,0,0,0,0,0,0,0
6985000,0.694162,0.00138484,-0.0125463,0.719708,-0.0429111,-0.0258346,-0.128883,-0.0245242,-0.00951919,-365.457,-2.22973e-05,-5.40989e-05,-0.000608212,0,0,-2.24399e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000359521,0.000259391,0.000258909,0.000282987,0.13816,0.138171,0.645221,0.106649,0.106648,0.319783,5.53712e-09,5.51483e-09,1.41043e-08,0,0,3.98325e-06,0,0,0,0,0,0,0,0
7085000,0.692683,0.00127439,-0.0126886,0.72113,-0.0375389,-0.0260296,-0.12726,-0.0199175,-0.00856766,-365.456,-2.12057e-05,-5.37803e-05,-0.00060737,0,0,-2.4799e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000338366,0.000245043,0.000244601,0.000266651,0.128607,0.128625,0.528129,0.0863101,0.0863094,0.29624,5.00662e-09,4.98504e-09,1.40719e-08,0,0,3.97902e-06,0,0,0,0,0,0,0,0
7185000,0.691561,0.00125428,-0.0126304,0.722206,-0.040944,-0.0289542,-0.148488,-0.023849,-0.0112789,-365.474,-2.11461e-05,-5.38135e-05,-0.000605914,0,0,-2.37763e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000320465,0.000246049,0.000245611,0.000253011,0.149359,0.149385,0.441712,0.103492,0.103492,0.275727,5.00665e-09,4.98512e-09,1.40339e-08,0,0,3.97369e-06,0,0,0,0,0,0,0,0
7285000,0.690534,0.00116294,-0.0127847,0.723186,-0.0357576,-0.0275316,-0.150206,-0.0192934,-0.00988902,-365.476,-2.01952e-05,-5.3505e-05,-0.000604034,0,0,-2.72637e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000305161,0.000225096,0.00022471,0.000241467,0.138318,0.138347,0.377865,0.0847083,0.0847085,0.2582,4.63819e-09,4.61746e-09,1.39898e-08,0,0,3.96687e-06,0,0,0,0,0,0,0,0
7385000,0.689462,0.00114523,-0.012746,0.724209,-0.0369923,-0.0289639,-0.161272,-0.022982,-0.0126652,-365.488,-2.01159e-05,-5.35518e-05,-0.000602007,0,0,-2.90676e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000291955,0.000225687,0.000225306,0.000231637,0.159783,0.159819,0.329951,0.102565,0.102567,0.242862,4.6382e-09,4.61753e-09,1.39392e-08,0,0,3.95844e-06,0,0,0,0,0,0,0,0
7485000,0.688308,0.00110302,-0.0129208,0.725303,-0.0312566,-0.0266938,-0.168031,-0.0182479,-0.0106798,-365.497,-1.93474e-05,-5.32719e-05,-0.000600002,0,0,-3.19526e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000284054,0.000199178,0.000198854,0.000225729,0.144909,0.144945,0.306108,0.0842678,0.0842696,0.243676,4.39894e-09,4.37905e-09,1.38968e-08,0,0,3.95063e-06,0,0,0,0,0,0,0,0
7585000,0.687458,0.00107152,-0.0128453,0.72611,-0.03345,-0.028297,-0.172923,-0.0214907,-0.013383,-365.502,-1.92323e-05,-5.33426e-05,-0.000596988,0,0,-3.76832e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000273665,0.000199417,0.000199097,0.000218199,0.166033,0.166074,0.277293,0.102865,0.102869,0.230711,4.39892e-09,4.37912e-09,1.3834e-08,0,0,3.93842e-06,0,0,0,0,0,0,0,0
7685000,0.686434,0.00104852,-0.0130326,0.727075,-0.0275504,-0.0250843,-0.169711,-0.0168021,-0.0109302,-365.499,-1.86241e-05,-5.31417e-05,-0.00059408,0,0,-4.89678e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000264484,0.000169748,0.000169488,0.00021164,0.146483,0.14652,0.255923,0.0842905,0.0842939,0.219632,4.2576e-09,4.23853e-09,1.37641e-08,0,0,3.92362e-06,0,0,0,0,0,0,0,0
7785000,0.685283,0.00102933,-0.0130492,0.728159,-0.0286504,-0.0264857,-0.168731,-0.019655,-0.0134591,-365.499,-1.85248e-05,-5.3208e-05,-0.000591344,0,0,-6.04483e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000256336,0.00016977,0.000169512,0.000205917,0.166284,0.166326,0.240013,0.103381,0.103387,0.209986,4.25757e-09,4.23859e-09,1.36866e-08,0,0,3.90601e-06,0,0,0,0,0,0,0,0
7885000,0.684455,0.000961536,-0.0132975,0.728933,-0.0233635,-0.021851,-0.167369,-0.0150724,-0.0106631,-365.496,-1.80496e-05,-5.31013e-05,-0.000587473,0,0,-7.45948e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000249012,0.000139944,0.000139738,0.000200854,0.142627,0.14266,0.228285,0.0841718,0.0841763,0.201602,4.18378e-09,4.16542e-09,1.36011e-08,0,0,3.8849e-06,0,0,0,0,0,0,0,0
7985000,0.683643,0.000948899,-0.0132796,0.729695,-0.0242567,-0.023097,-0.174314,-0.0175109,-0.01289,-365.504,-1.78897e-05,-5.31993e-05,-0.000583275,0,0,-8.27319e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000242451,0.000139917,0.000139713,0.000196372,0.160446,0.160483,0.219947,0.103327,0.103334,0.1945,4.18373e-09,4.16547e-09,1.35081e-08,0,0,3.86066e-06,0,0,0,0,0,0,0,0
8085000,0.682591,0.000904492,-0.0132748,0.730679,-0.0254009,-0.0242903,-0.186919,-0.0200283,-0.01521,-365.52,-1.77474e-05,-5.32824e-05,-0.000579618,0,0,-8.51907e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000239045,0.0001401,0.000139895,0.000194128,0.179365,0.179405,0.220502,0.126744,0.126756,0.19784,4.1837e-09,4.16552e-09,1.34331e-08,0,0,3.84009e-06,0,0,0,0,0,0,0,0
8185000,0.681617,0.000809322,-0.0134651,0.731584,-0.0195641,-0.0198013,-0.192654,-0.015083,-0.0118819,-365.528,-1.73975e-05,-5.32488e-05,-0.000575548,0,0,-9.62055e-05,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000233512,0.000112657,0.000112493,0.000190422,0.14976,0.149789,0.216118,0.102287,0.102295,0.192184,4.15082e-09,4.13313e-09,1.3326e-08,0,0,3.80904e-06,0,0,0,0,0,0,0,0
8285000,0.680803,0.000806809,-0.0135186,0.732342,-0.0197942,-0.0213446,-0.188833,-0.0171717,-0.013843,-365.525,-1.72235e-05,-5.33668e-05,-0.000570702,0,0,-0.000119443,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000228461,0.000112953,0.000112788,0.00018706,0.166111,0.166141,0.213101,0.125014,0.125026,0.187361,4.15073e-09,4.13316e-09,1.32107e-08,0,0,3.77404e-06,0,0,0,0,0,0,0,0
8385000,0.680039,0.000787076,-0.0136856,0.733047,-0.0138757,-0.0174577,-0.186453,-0.0127131,-0.010668,-365.524,-1.69204e-05,-5.34271e-05,-0.000565147,0,0,-0.000141977,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000223822,8.97515e-05,8.96167e-05,0.000183949,0.136127,0.136146,0.211135,0.100206,0.100214,0.183394,4.13894e-09,4.12172e-09,1.30876e-08,0,0,3.73517e-06,0,0,0,0,0,0,0,0
8485000,0.679198,0.000733462,-0.0137032,0.733827,-0.0139268,-0.0182897,-0.183437,-0.0142201,-0.0123922,-365.522,-1.67252e-05,-5.35576e-05,-0.000559734,0,0,-0.00016608,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000219547,9.0295e-05,9.01579e-05,0.000181068,0.149911,0.14993,0.209722,0.121776,0.121788,0.180036,4.13883e-09,4.12175e-09,1.29565e-08,0,0,3.69242e-06,0,0,0,0,0,0,0,0
8585000,0.678398,0.00069465,-0.0138072,0.734565,-0.00931655,-0.0139987,-0.181543,-0.0103741,-0.0094711,-365.522,-1.64872e-05,-5.36539e-05,-0.000554263,0,0,-0.000189367,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000215563,7.18609e-05,7.1744e-05,0.000178381,0.121379,0.121387,0.208686,0.0972597,0.0972665,0.177316,4.13581e-09,4.11899e-09,1.28179e-08,0,0,3.64617e-06,0,0,0,0,0,0,0,0
8685000,0.677914,0.000693376,-0.013769,0.735012,-0.0101035,-0.0150613,-0.173383,-0.0114119,-0.0108477,-365.515,-1.62321e-05,-5.38257e-05,-0.000547139,0,0,-0.000222887,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000211868,7.27423e-05,7.26223e-05,0.000175847,0.132839,0.132846,0.207644,0.117383,0.117392,0.175011,4.13568e-09,4.119e-09,1.26716e-08,0,0,3.59654e-06,0,0,0,0,0,0,0,0
8785000,0.676809,0.000576003,-0.0138525,0.736028,-0.00601316,-0.0117877,-0.168816,-0.00827486,-0.00826764,-365.514,-1.60713e-05,-5.3921e-05,-0.000542777,0,0,-0.00024822,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00021057,5.88303e-05,5.87209e-05,0.000175033,0.106911,0.10691,0.212132,0.0937182,0.0937235,0.180984,4.13528e-09,4.11876e-09,1.25568e-08,0,0,3.55712e-06,0,0,0,0,0,0,0,0
8885000,0.676201,0.000561673,-0.0138577,0.736586,-0.0056107,-0.0133604,-0.167291,-0.00910794,-0.00971493,-365.514,-1.58453e-05,-5.40934e-05,-0.000536181,0,0,-0.00027183,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000207315,6.01043e-05,5.99903e-05,0.00017273,0.116407,0.116402,0.210609,0.112267,0.112273,0.179214,4.13515e-09,4.11875e-09,1.23978e-08,0,0,3.50259e-06,0,0,0,0,0,0,0,0
8985000,0.675594,0.000545089,-0.0139105,0.737142,-0.00210514,-0.0122684,-0.158078,-0.00660601,-0.00773815,-365.506,-1.56263e-05,-5.42763e-05,-0.000529386,0,0,-0.000305851,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000204279,5.00697e-05,4.99631e-05,0.000170526,0.0936313,0.0936207,0.208745,0.0898484,0.089852,0.177753,4.13497e-09,4.11867e-09,1.22321e-08,0,0,3.44626e-06,0,0,0,0,0,0,0,0
9085000,0.675014,0.000532511,-0.0139349,0.737673,-0.00153888,-0.0139359,-0.159214,-0.00692035,-0.00925418,-365.511,-1.53825e-05,-5.44606e-05,-0.000522291,0,0,-0.000323071,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000201455,5.17607e-05,5.16481e-05,0.000168403,0.101544,0.101529,0.206332,0.10682,0.106824,0.176397,4.13483e-09,4.11865e-09,1.206e-08,0,0,3.38848e-06,0,0,0,0,0,0,0,0
9185000,0.674791,0.000498866,-0.0140131,0.737876,0.00201117,-0.0127681,-0.159768,-0.00480127,-0.00752193,-365.514,-1.50891e-05,-5.46938e-05,-0.000513475,0,0,-0.000342265,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000198797,4.48554e-05,4.47458e-05,0.00016636,0.0820025,0.0819831,0.20332,0.085871,0.0858728,0.175072,4.13452e-09,4.11842e-09,1.18813e-08,0,0,3.32961e-06,0,0,0,0,0,0,0,0
9285000,0.674402,0.000424426,-0.0140571,0.73823,0.00402342,-0.0141701,-0.156947,-0.00462263,-0.00902923,-365.513,-1.48196e-05,-5.49093e-05,-0.000505394,0,0,-0.000367665,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000196344,4.69697e-05,4.68527e-05,0.000164411,0.0887345,0.0887086,0.199881,0.101348,0.101349,0.173862,4.13437e-09,4.11839e-09,1.16975e-08,0,0,3.27105e-06,0,0,0,0,0,0,0,0
9385000,0.673687,0.000345567,-0.0140506,0.738883,0.00716792,-0.0119986,-0.158696,-0.0027942,-0.00735088,-365.518,-1.46248e-05,-5.50715e-05,-0.00049939,0,0,-0.000383981,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000196082,4.24902e-05,4.23729e-05,0.000164125,0.072237,0.0722082,0.201714,0.0819508,0.0819505,0.180508,4.13418e-09,4.11826e-09,1.1556e-08,0,0,3.22731e-06,0,0,0,0,0,0,0,0
9485000,0.673498,0.000278845,-0.0140801,0.739055,0.00897836,-0.0139691,-0.156127,-0.00204442,-0.00880129,-365.52,-1.43182e-05,-5.53136e-05,-0.000490264,0,0,-0.00040422,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000193941,4.50226e-05,4.48971e-05,0.000162324,0.0781065,0.0780698,0.197145,0.0960666,0.0960648,0.179147,4.13402e-09,4.11822e-09,1.13633e-08,0,0,3.16983e-06,0,0,0,0,0,0,0,0
9585000,0.673294,0.000251963,-0.0141015,0.73924,0.0103953,-0.0130922,-0.152431,-0.000738012,-0.00732784,-365.52,-1.40268e-05,-5.5549e-05,-0.000481363,0,0,-0.000427465,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000191941,4.23728e-05,4.22466e-05,0.000160599,0.0643212,0.0642833,0.192078,0.0782007,0.0781984,0.177646,4.13376e-09,4.11808e-09,1.11657e-08,0,0,3.11345e-06,0,0,0,0,0,0,0,0
9685000,0.672934,0.000247276,-0.0141153,0.739567,0.0123672,-0.0134423,-0.145923,0.00037957,-0.00876844,-365.516,-1.37671e-05,-5.57674e-05,-0.000473372,0,0,-0.000453917,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000190104,4.53125e-05,4.51777e-05,0.000158968,0.0696541,0.0696065,0.186718,0.0911141,0.0911092,0.176128,4.13361e-09,4.11803e-09,1.09647e-08,0,0,3.05924e-06,0,0,0,0,0,0,0,0
9785000,0.672883,0.000198471,-0.0140938,0.739614,0.0157028,-0.0117566,-0.1371,0.00130873,-0.00728897,-365.509,-1.34654e-05,-5.60118e-05,-0.000463905,0,0,-0.000482529,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00018839,4.4015e-05,4.38788e-05,0.00015742,0.0582169,0.0581691,0.180982,0.0746982,0.0746937,0.174444,4.13258e-09,4.11718e-09,1.076e-08,0,0,3.00691e-06,0,0,0,0,0,0,0,0
9885000,0.672695,0.0001258,-0.0140303,0.739787,0.0180571,-0.0132236,-0.136192,0.00306498,-0.00866228,-365.512,-1.3168e-05,-5.62511e-05,-0.000454967,0,0,-0.000497406,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000186834,4.73469e-05,4.7202e-05,0.000155951,0.063261,0.0632024,0.175089,0.086582,0.0865737,0.172725,4.13242e-09,4.11712e-09,1.05529e-08,0,0,2.95732e-06,0,0,0,0,0,0,0,0
9985000,0.672503,0.000131628,-0.0140687,0.73996,0.0196729,-0.0133388,-0.131366,0.00360597,-0.00730212,-365.509,-1.29047e-05,-5.64575e-05,-0.000446325,0,0,-0.000518905,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000185381,4.70215e-05,4.68743e-05,0.00015456,0.0538154,0.0537579,0.168986,0.0714956,0.0714887,0.170842,4.12888e-09,4.11384e-09,1.0343e-08,0,0,2.91006e-06,0,0,0,0,0,0,0,0
10085000,0.672126,9.22506e-05,-0.0140648,0.740303,0.0229322,-0.015967,-0.132072,0.00580908,-0.00885258,-365.513,-1.26692e-05,-5.66496e-05,-0.000439186,0,0,-0.000530141,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000185925,5.07316e-05,5.05734e-05,0.000154741,0.0588031,0.0587336,0.167791,0.0825275,0.0825156,0.176372,4.12879e-09,4.11382e-09,1.01845e-08,0,0,2.87641e-06,0,0,0,0,0,0,0,0
10185000,0.671928,1.88368e-05,-0.014133,0.740482,0.0257896,-0.0163394,-0.132658,0.00837004,-0.0106322,-365.517,-1.23969e-05,-5.6872e-05,-0.000430929,0,0,-0.000541666,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000184658,5.46463e-05,5.44774e-05,0.000153488,0.0642761,0.0641922,0.161344,0.0951096,0.0950911,0.174126,4.12864e-09,4.11376e-09,9.9718e-09,0,0,2.83397e-06,0,0,0,0,0,0,0,0
10285000,0.671858,-4.37122e-05,-0.0141278,0.740546,0.027651,-0.0168854,-0.12193,0.00863651,-0.00934738,-365.506,-1.21673e-05,-5.70608e-05,-0.000422278,0,0,-0.000569358,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000183477,5.51286e-05,5.49581e-05,0.00015232,0.0561282,0.0560468,0.15498,0.0789873,0.0789716,0.171859,4.11977e-09,4.10524e-09,9.75816e-09,0,0,2.79435e-06,0,0,0,0,0,0,0,0
10385000,0.671888,-0.000152134,-0.0140837,0.740519,0.0137645,-0.0218878,0.00395859,0.00105685,-0.0018806,-365.493,-1.18613e-05,-5.73173e-05,-0.000412864,0,0,-0.000585675,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000182475,5.93972e-05,5.92167e-05,0.000151298,0.0347737,0.0347731,0.0376446,0.12528,0.12528,0.149189,4.11962e-09,4.10518e-09,9.5441e-09,0,0,2.76113e-06,0,0,0,0,0,0,0,0
10485000,0.67185,-0.000204837,-0.0140928,0.740553,0.0172704,-0.0233618,-0.000891165,0.00259157,-0.00414814,-365.477,-1.15785e-05,-5.75576e-05,-0.000404108,0,0,-0.000602577,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000181671,6.38713e-05,6.36804e-05,0.000150486,0.03555,0.0355474,0.0383148,0.126254,0.126254,0.13152,4.11947e-09,4.10513e-09,9.32982e-09,0,0,2.73625e-06,0,0,0,0,0,0,0,0
10585000,0.672001,-0.000241196,-0.0141546,0.740415,0.0199312,-0.0220067,-0.00469469,0.00328156,-0.0042435,-365.47,-1.13083e-05,-5.76689e-05,-0.00039466,0,0,-0.000611364,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000180967,6.83282e-05,6.81274e-05,0.000149807,0.0321918,0.0321865,0.0367459,0.0848636,0.0848635,0.118549,4.10903e-09,4.09485e-09,9.11617e-09,0,0,2.71617e-06,0,0,0,0,0,0,0,0
10685000,0.671762,-0.000277182,-0.0141548,0.740631,0.0230813,-0.0251157,-0.0104019,0.00548002,-0.00662012,-365.465,-1.10777e-05,-5.78601e-05,-0.000387601,0,0,-0.000617297,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000182088,7.31982e-05,7.29853e-05,0.000150525,0.0339484,0.0339381,0.037924,0.0865903,0.0865901,0.112461,4.10895e-09,4.09484e-09,8.95648e-09,0,0,2.70395e-06,0,0,0,0,0,0,0,0
10785000,0.671964,-0.000336326,-0.0141963,0.740448,0.0247403,-0.0250695,-0.0155428,0.00583148,-0.00629537,-365.462,-1.09206e-05,-5.77964e-05,-0.000378216,0,0,-0.000620674,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000181449,7.72938e-05,7.70741e-05,0.000149951,0.0317391,0.0317253,0.0367139,0.0657237,0.0657233,0.104526,4.06844e-09,4.05471e-09,8.74431e-09,0,0,2.68833e-06,0,0,0,0,0,0,0,0
10885000,0.672188,-0.000482351,-0.0141685,0.740245,0.0286639,-0.0277385,-0.022991,0.00850793,-0.00894548,-365.463,-1.06191e-05,-5.80414e-05,-0.000369045,0,0,-0.000620785,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000180888,8.25065e-05,8.22764e-05,0.000149451,0.0345526,0.0345306,0.0380073,0.068049,0.068048,0.0994383,4.06831e-09,4.05465e-09,8.53345e-09,0,0,2.6764e-06,0,0,0,0,0,0,0,0
10985000,0.672577,-0.000480091,-0.0142238,0.73989,0.0294518,-0.025866,-0.0294233,0.00905525,-0.0100095,-365.461,-1.04461e-05,-5.76384e-05,-0.000359174,0,0,-0.000625066,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000180236,8.55358e-05,8.5305e-05,0.000148931,0.032999,0.0329734,0.0369302,0.0552315,0.0552304,0.0944351,3.97972e-09,3.96677e-09,8.32453e-09,0,0,2.66301e-06,0,0,0,0,0,0,0,0
11085000,0.67299,-0.000569527,-0.0141719,0.739516,0.0334665,-0.0278017,-0.0340316,0.012277,-0.0127801,-365.457,-1.01297e-05,-5.79032e-05,-0.000349332,0,0,-0.000630683,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00017969,9.10061e-05,9.07656e-05,0.000148474,0.0369001,0.0368634,0.0383225,0.0581381,0.0581355,0.0919766,3.9796e-09,3.96672e-09,8.1176e-09,0,0,2.65373e-06,0,0,0,0,0,0,0,0
11185000,0.67317,-0.000507275,-0.0142383,0.73935,0.0361024,-0.0252458,-0.0408931,0.012506,-0.0126369,-365.461,-1.01784e-05,-5.72497e-05,-0.00034081,0,0,-0.000630462,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000179,9.21995e-05,9.19659e-05,0.000147946,0.0355163,0.0354784,0.0372821,0.049188,0.0491855,0.0885485,3.82988e-09,3.81809e-09,7.91316e-09,0,0,2.64113e-06,0,0,0,0,0,0,0,0
11285000,0.673341,-0.000513039,-0.0142719,0.739194,0.0405813,-0.0271276,-0.0468007,0.0164036,-0.0152984,-365.462,-9.92866e-06,-5.74589e-05,-0.000332899,0,0,-0.000632651,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000178431,9.78054e-05,9.75616e-05,0.000147503,0.040477,0.0404257,0.038725,0.0527061,0.0527011,0.0876878,3.82978e-09,3.81805e-09,7.71132e-09,0,0,2.63347e-06,0,0,0,0,0,0,0,0
11385000,0.67319,-0.000286456,-0.0142537,0.739332,0.0378648,-0.0242389,-0.0510729,0.0143304,-0.0131134,-365.463,-1.08831e-05,-5.67336e-05,-0.000326884,0,0,-0.000637921,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00017932,9.65131e-05,9.6284e-05,0.000148201,0.0387654,0.0387164,0.0380137,0.0457728,0.0457685,0.0869804,3.61506e-09,3.60475e-09,7.5616e-09,0,0,2.62268e-06,0,0,0,0,0,0,0,0
11485000,0.673361,-0.000352433,-0.0142846,0.739176,0.0405086,-0.0258081,-0.0567746,0.0183225,-0.0156783,-365.466,-1.06478e-05,-5.69315e-05,-0.000319198,0,0,-0.00063902,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000178717,0.000102106,0.000101867,0.000147735,0.0446653,0.0446011,0.0395219,0.0499358,0.0499279,0.0871252,3.61497e-09,3.60472e-09,7.36488e-09,0,0,2.61603e-06,0,0,0,0,0,0,0,0
11585000,0.673571,-0.000138887,-0.0143081,0.738984,0.0346396,-0.0215353,-0.0609783,0.0154801,-0.0132165,-365.467,-1.17032e-05,-5.6182e-05,-0.000311407,0,0,-0.000645054,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00017786,9.80028e-05,9.77887e-05,0.00014715,0.042169,0.0421115,0.038426,0.0440256,0.0440193,0.0849507,3.34281e-09,3.33421e-09,7.17138e-09,0,0,2.60329e-06,0,0,0,0,0,0,0,0
11685000,0.673882,-0.000230629,-0.014322,0.7387,0.0363652,-0.0222573,-0.0679855,0.0191016,-0.0155151,-365.474,-1.1471e-05,-5.63764e-05,-0.000303552,0,0,-0.000642786,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000177209,0.000103431,0.000103209,0.000146673,0.0488158,0.0487425,0.0399309,0.0488403,0.0488293,0.0857484,3.34275e-09,3.3342e-09,6.98135e-09,0,0,2.59742e-06,0,0,0,0,0,0,0,0
11785000,0.674237,0.000110113,-0.0143149,0.738376,0.0281243,-0.0178073,-0.071149,0.0146352,-0.0118445,-365.473,-1.28133e-05,-5.53456e-05,-0.000295644,0,0,-0.000651343,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000176257,9.66489e-05,9.64582e-05,0.000146062,0.0452043,0.0451433,0.0387691,0.0433483,0.0433402,0.0838141,3.03098e-09,3.02414e-09,6.79453e-09,0,0,2.58453e-06,0,0,0,0,0,0,0,0
11885000,0.674482,5.6855e-05,-0.0143128,0.738153,0.0316401,-0.019402,-0.0761435,0.0177365,-0.0137816,-365.477,-1.26095e-05,-5.55207e-05,-0.000288387,0,0,-0.000652863,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000175571,0.000101783,0.000101585,0.000145555,0.0523594,0.0522841,0.040256,0.0487808,0.0487673,0.0850093,3.03093e-09,3.02414e-09,6.61177e-09,0,0,2.57922e-06,0,0,0,0,0,0,0,0
11985000,0.674545,0.000437774,-0.0142497,0.738096,0.0246822,-0.0141369,-0.0800274,0.0131293,-0.0100186,-365.48,-1.38825e-05,-5.45147e-05,-0.000282346,0,0,-0.000659238,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000176172,9.28591e-05,9.26959e-05,0.000146116,0.0475066,0.0474476,0.039495,0.0433258,0.0433164,0.084979,2.70238e-09,2.69717e-09,6.477e-09,0,0,2.56748e-06,0,0,0,0,0,0,0,0
12085000,0.675073,0.000407765,-0.014267,0.737613,0.0273814,-0.0144642,-0.0890739,0.0158405,-0.011552,-365.49,-1.36613e-05,-5.47044e-05,-0.000274091,0,0,-0.000656037,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000175424,9.76057e-05,9.74362e-05,0.000145581,0.0549284,0.0548565,0.0409966,0.0493027,0.0492877,0.0864669,2.70235e-09,2.69717e-09,6.30083e-09,0,0,2.56263e-06,0,0,0,0,0,0,0,0
12185000,0.675367,0.000559694,-0.0142616,0.737343,0.024402,-0.0102327,-0.0847408,0.0138453,-0.0092867,-365.482,-1.41621e-05,-5.42701e-05,-0.000267054,0,0,-0.000673178,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00017433,8.73071e-05,8.71743e-05,0.00014489,0.0489188,0.0488646,0.039681,0.0436624,0.0436524,0.0846146,2.37871e-09,2.3749e-09,6.12827e-09,0,0,2.54961e-06,0,0,0,0,0,0,0,0
12285000,0.675772,0.000497006,-0.0142801,0.736972,0.0251159,-0.0105972,-0.0881459,0.01644,-0.0103878,-365.483,-1.3976e-05,-5.44352e-05,-0.000259761,0,0,-0.000677393,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000173544,9.16156e-05,9.14776e-05,0.000144326,0.0563671,0.0563018,0.0411371,0.0500828,0.0500674,0.0862254,2.3787e-09,2.37491e-09,5.96001e-09,0,0,2.54511e-06,0,0,0,0,0,0,0,0
12385000,0.676058,0.00061814,-0.0142857,0.736709,0.0228592,-0.00718416,-0.0849754,0.0143479,-0.00821608,-365.477,-1.43834e-05,-5.40733e-05,-0.000253347,0,0,-0.000692716,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000172389,8.07312e-05,8.06262e-05,0.000143617,0.0494488,0.0494019,0.0397579,0.0441544,0.0441446,0.0843739,2.07632e-09,2.07375e-09,5.79539e-09,0,0,2.5323e-06,0,0,0,0,0,0,0,0
12485000,0.676314,0.000557942,-0.0143141,0.736474,0.0241985,-0.00648858,-0.0908553,0.016796,-0.00896842,-365.482,-1.42366e-05,-5.42088e-05,-0.000247241,0,0,-0.000693907,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000171565,8.45903e-05,8.44812e-05,0.000143028,0.0567554,0.0566995,0.0411607,0.0509085,0.0508936,0.0860322,2.07633e-09,2.07377e-09,5.63518e-09,0,0,2.52808e-06,0,0,0,0,0,0,0,0
12585000,0.676606,0.000876591,-0.0141559,0.736209,0.0138008,-0.00314787,-0.0944872,0.00888009,-0.00708272,-365.487,-1.57257e-05,-5.39379e-05,-0.000240914,0,0,-0.00070134,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000170383,7.37679e-05,7.36892e-05,0.000142288,0.0492371,0.049198,0.0397247,0.0446731,0.0446639,0.0841632,1.80482e-09,1.80318e-09,5.47868e-09,0,0,2.51562e-06,0,0,0,0,0,0,0,0
12685000,0.676625,0.000898539,-0.0141281,0.736192,0.0156744,-0.00211962,-0.100468,0.0104804,-0.00730439,-365.496,-1.55871e-05,-5.40049e-05,-0.000236248,0,0,-0.000700759,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00017106,7.71956e-05,7.71121e-05,0.000142822,0.0562659,0.0562203,0.0416012,0.0516548,0.0516412,0.087702,1.80482e-09,1.80325e-09,5.36403e-09,0,0,2.51265e-06,0,0,0,0,0,0,0,0
12785000,0.676991,0.00117606,-0.013963,0.735858,0.0068091,-0.000997073,-0.100763,0.00376549,-0.00589124,-365.496,-1.67002e-05,-5.38996e-05,-0.000230019,0,0,-0.000712339,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000169821,6.68876e-05,6.68317e-05,0.000142063,0.0484374,0.0484061,0.0400754,0.0451454,0.045137,0.0857282,1.56776e-09,1.56685e-09,5.21454e-09,0,0,2.50053e-06,0,0,0,0,0,0,0,0
12885000,0.677371,0.00111032,-0.0140208,0.735507,0.00801578,-0.00147377,-0.103503,0.00466886,-0.0059878,-365.497,-1.65313e-05,-5.39928e-05,-0.000223967,0,0,-0.000716752,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000168918,6.99175e-05,6.98578e-05,0.000141421,0.0551261,0.0550904,0.0413742,0.052262,0.0522501,0.087425,1.56775e-09,1.56691e-09,5.06928e-09,0,0,2.49684e-06,0,0,0,0,0,0,0,0
12985000,0.677863,0.00105081,-0.0141318,0.735052,0.0125907,-0.00051633,-0.100186,0.00854356,-0.00487772,-365.495,-1.60052e-05,-5.40238e-05,-0.000217524,0,0,-0.000731114,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000167654,6.03856e-05,6.03499e-05,0.000140659,0.0472262,0.0472021,0.0398009,0.0455353,0.045528,0.0854321,1.36454e-09,1.36415e-09,4.92776e-09,0,0,2.48528e-06,0,0,0,0,0,0,0,0
13085000,0.678034,0.001044,-0.0140935,0.734895,0.0135991,-0.000388088,-0.102882,0.00998481,-0.00487781,-365.499,-1.58738e-05,-5.41033e-05,-0.000212514,0,0,-0.000733935,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000166738,6.30602e-05,6.30221e-05,0.00013998,0.053525,0.0534976,0.0410048,0.0527102,0.0527,0.0870564,1.36454e-09,1.36421e-09,4.79018e-09,0,0,2.48177e-06,0,0,0,0,0,0,0,0
13185000,0.678364,0.00100639,-0.0141191,0.73459,0.0170015,0.00159024,-0.0965613,0.0126451,-0.00391182,-365.49,-1.55855e-05,-5.41491e-05,-0.000207009,0,0,-0.000752693,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000165473,5.44246e-05,5.44071e-05,0.000139206,0.0457547,0.0457362,0.0393978,0.0458311,0.0458248,0.0850529,1.19234e-09,1.19231e-09,4.65646e-09,0,0,2.47084e-06,0,0,0,0,0,0,0,0
13285000,0.678544,0.00101139,-0.014129,0.734423,0.0180327,0.00249782,-0.0974109,0.014507,-0.00367331,-365.489,-1.54725e-05,-5.42234e-05,-0.000202505,0,0,-0.000758422,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000165976,5.679e-05,5.67702e-05,0.000139631,0.0516652,0.0516441,0.0410668,0.0530056,0.052997,0.0885515,1.19238e-09,1.19238e-09,4.55876e-09,0,0,2.46838e-06,0,0,0,0,0,0,0,0
13385000,0.678997,0.000998467,-0.0140447,0.734006,0.0150825,0.00340826,-0.0912082,0.0108236,-0.00311146,-365.477,-1.57302e-05,-5.43201e-05,-0.000196829,0,0,-0.000775595,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00016468,4.9066e-05,4.90637e-05,0.000138848,0.0441418,0.0441277,0.0393932,0.0460345,0.0460292,0.0864569,1.04724e-09,1.04743e-09,4.4316e-09,0,0,2.45804e-06,0,0,0,0,0,0,0,0
13485000,0.679449,0.00101936,-0.01405,0.733587,0.0155979,0.00364837,-0.0930575,0.0125107,-0.00272639,-365.477,-1.55987e-05,-5.44125e-05,-0.000191312,0,0,-0.000779876,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000163701,5.11629e-05,5.11593e-05,0.000138146,0.0496682,0.0496523,0.0404456,0.0531647,0.0531575,0.0880148,1.04727e-09,1.04749e-09,4.30814e-09,0,0,2.45495e-06,0,0,0,0,0,0,0,0
13585000,0.679747,0.00106372,-0.0139748,0.733313,0.0127037,0.00529421,-0.0916372,0.00923058,-0.00233618,-365.476,-1.58033e-05,-5.45239e-05,-0.000186669,0,0,-0.00078944,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000162412,4.43101e-05,4.43211e-05,0.000137363,0.0424643,0.0424536,0.0387574,0.046154,0.0461495,0.0859288,9.25127e-10,9.25472e-10,4.1883e-09,0,0,2.44533e-06,0,0,0,0,0,0,0,0
13685000,0.680207,0.00103405,-0.0139518,0.732887,0.0141645,0.00748525,-0.0979028,0.0106525,-0.00168772,-365.483,-1.56808e-05,-5.46157e-05,-0.000181264,0,0,-0.000789339,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000161432,4.61769e-05,4.61872e-05,0.000136648,0.0476287,0.0476168,0.0397138,0.053208,0.053202,0.087411,9.25167e-10,9.25539e-10,4.07202e-09,0,0,2.44241e-06,0,0,0,0,0,0,0,0
13785000,0.680504,0.00104059,-0.0138399,0.732613,0.0120452,0.00464554,-0.0963635,0.00966704,-0.00320089,-365.483,-1.57443e-05,-5.49678e-05,-0.000176669,0,0,-0.000799256,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000160164,4.01223e-05,4.01447e-05,0.00013586,0.0407909,0.040783,0.0380252,0.0462002,0.0461965,0.0853427,8.22226e-10,8.2267e-10,3.9592e-09,0,0,2.43352e-06,0,0,0,0,0,0,0,0
13885000,0.680832,0.000992951,-0.0138764,0.732307,0.0130767,0.00505366,-0.102146,0.0109958,-0.00269789,-365.49,-1.56438e-05,-5.50471e-05,-0.000172078,0,0,-0.000799423,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000159181,4.17932e-05,4.1815e-05,0.000135136,0.0456115,0.0456028,0.0388836,0.0531565,0.0531516,0.0867485,8.22274e-10,8.22738e-10,3.84978e-09,0,0,2.43077e-06,0,0,0,0,0,0,0,0
13985000,0.681045,0.00102698,-0.0138056,0.732111,0.0109061,0.00367419,-0.0993035,0.0100057,-0.00389731,-365.489,-1.56966e-05,-5.53247e-05,-0.000168308,0,0,-0.000810353,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000159245,3.64545e-05,3.64858e-05,0.000135392,0.0391531,0.0391472,0.0376886,0.046185,0.0461819,0.0865382,7.3524e-10,7.35738e-10,3.76979e-09,0,0,2.42322e-06,0,0,0,0,0,0,0,0
14085000,0.681452,0.00100475,-0.0138235,0.731732,0.0113342,0.00407737,-0.102546,0.0111683,-0.0034976,-365.495,-1.55977e-05,-5.54063e-05,-0.000163658,0,0,-0.00081112,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000158241,3.79577e-05,3.79887e-05,0.000134658,0.0436488,0.0436424,0.0384723,0.053029,0.053025,0.087926,7.35293e-10,7.35807e-10,3.66608e-09,0,0,2.42067e-06,0,0,0,0,0,0,0,0
14185000,0.681872,0.000965602,-0.013793,0.731341,0.0124487,0.00407165,-0.10157,0.0116877,-0.00305133,-365.496,-1.54576e-05,-5.55273e-05,-0.000159003,0,0,-0.000818894,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000156983,3.32493e-05,3.32886e-05,0.000133873,0.0375708,0.0375667,0.0367754,0.0461189,0.0461163,0.0858267,6.61343e-10,6.61874e-10,3.56549e-09,0,0,2.41312e-06,0,0,0,0,0,0,0,0
14285000,0.682276,0.000968232,-0.0137591,0.730965,0.0132509,0.00527654,-0.103083,0.0130361,-0.00258387,-365.498,-1.53677e-05,-5.56038e-05,-0.000154707,0,0,-0.000822057,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000155975,3.4609e-05,3.46484e-05,0.000133146,0.0417799,0.0417755,0.0374655,0.0528417,0.0528385,0.087135,6.61402e-10,6.61944e-10,3.46803e-09,0,0,2.41073e-06,0,0,0,0,0,0,0,0
14385000,0.682746,0.000930382,-0.0137117,0.730526,0.013046,0.00623738,-0.102424,0.0130798,-0.00229648,-365.499,-1.52786e-05,-5.5743e-05,-0.000150143,0,0,-0.000829643,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000154731,3.04501e-05,3.04962e-05,0.000132373,0.03607,0.0360672,0.035794,0.0460114,0.0460093,0.0850572,5.98203e-10,5.98746e-10,3.37341e-09,0,0,2.40385e-06,0,0,0,0,0,0,0,0
14485000,0.683075,0.000923947,-0.0136597,0.73022,0.0131038,0.00816828,-0.10719,0.0144405,-0.00155336,-365.508,-1.51978e-05,-5.58146e-05,-0.000146147,0,0,-0.000828977,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000153741,3.1687e-05,3.17333e-05,0.000131636,0.0400157,0.0400127,0.0363938,0.0526089,0.0526062,0.0862866,5.98266e-10,5.98816e-10,3.28188e-09,0,0,2.40161e-06,0,0,0,0,0,0,0,0
14585000,0.683115,0.000925712,-0.0134776,0.730186,0.00887481,0.00705564,-0.104889,0.0101043,-0.00289967,-365.509,-1.55253e-05,-5.6055e-05,-0.000143626,0,0,-0.000837838,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000153759,2.80047e-05,2.80563e-05,0.000131842,0.0346496,0.0346479,0.0352243,0.045871,0.0458693,0.0860865,5.43921e-10,5.44462e-10,3.21501e-09,0,0,2.39589e-06,0,0,0,0,0,0,0,0
14685000,0.683554,0.000897279,-0.0134701,0.729775,0.010688,0.00489902,-0.104977,0.0111689,-0.00226571,-365.51,-1.54405e-05,-5.61314e-05,-0.000139421,0,0,-0.000841593,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000152755,2.91364e-05,2.91881e-05,0.000131101,0.0383552,0.0383537,0.0357583,0.0523412,0.0523392,0.0872898,5.43987e-10,5.44534e-10,3.12835e-09,0,0,2.39382e-06,0,0,0,0,0,0,0,0
14785000,0.683851,0.000922529,-0.0133404,0.729499,0.00700685,0.00337591,-0.0997041,0.00757131,-0.00335938,-365.503,-1.56728e-05,-5.63357e-05,-0.000135892,0,0,-0.000853583,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000151544,2.58663e-05,2.59225e-05,0.000130335,0.0333179,0.0333172,0.0341402,0.0457046,0.0457032,0.0852201,4.96937e-10,4.97467e-10,3.04422e-09,0,0,2.38812e-06,0,0,0,0,0,0,0,0
14885000,0.684246,0.000915775,-0.0133012,0.729129,0.00804793,0.00513909,-0.104205,0.00835427,-0.00293014,-365.509,-1.5598e-05,-5.64052e-05,-0.000132088,0,0,-0.000854389,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000150551,2.69066e-05,2.69631e-05,0.000129603,0.0368141,0.0368136,0.0345962,0.0520487,0.052047,0.0863441,4.97006e-10,4.9754e-10,2.96287e-09,0,0,2.38619e-06,0,0,0,0,0,0,0,0
14985000,0.684467,0.000897923,-0.0132778,0.728923,0.00631503,0.00470731,-0.0986304,0.00666509,-0.00257035,-365.504,-1.56714e-05,-5.64934e-05,-0.000128943,0,0,-0.000865512,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000149373,2.39918e-05,2.40518e-05,0.000128844,0.032075,0.0320751,0.0330336,0.0455183,0.0455172,0.0843299,4.55994e-10,4.56506e-10,2.8839e-09,0,0,2.38106e-06,0,0,0,0,0,0,0,0
15085000,0.684798,0.00083644,-0.0132562,0.728612,0.00649478,0.00501185,-0.102302,0.00733713,-0.00208338,-365.513,-1.56095e-05,-5.65521e-05,-0.00012574,0,0,-0.000864891,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000148385,2.49531e-05,2.50135e-05,0.000128127,0.035369,0.0353692,0.0334134,0.051738,0.0517368,0.085377,4.56065e-10,4.56581e-10,2.80754e-09,0,0,2.37927e-06,0,0,0,0,0,0,0,0
15185000,0.685092,0.000827661,-0.0132175,0.728336,0.00513211,0.00568956,-0.0980059,0.00589712,-0.00181368,-365.509,-1.56534e-05,-5.6643e-05,-0.000122638,0,0,-0.000874475,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000147227,2.23457e-05,2.24089e-05,0.000127392,0.0309113,0.0309119,0.0319126,0.045317,0.0453162,0.0834202,4.20089e-10,4.2058e-10,2.73341e-09,0,0,2.37464e-06,0,0,0,0,0,0,0,0
15285000,0.685271,0.000807017,-0.0132559,0.728168,0.00545854,0.00651831,-0.0997942,0.00646373,-0.00119717,-365.512,-1.5605e-05,-5.66889e-05,-0.000120153,0,0,-0.000877174,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000147377,2.32388e-05,2.3302e-05,0.00012757,0.0340339,0.0340348,0.0326594,0.0514158,0.0514148,0.086212,4.20169e-10,4.20662e-10,2.67943e-09,0,0,2.3734e-06,0,0,0,0,0,0,0,0
15385000,0.685719,0.000796937,-0.0132032,0.727747,0.00450779,0.00671952,-0.0958849,0.00338905,-0.0011193,-365.507,-1.56795e-05,-5.68044e-05,-0.000116538,0,0,-0.00088571,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000146229,2.08964e-05,2.09618e-05,0.000126834,0.0298332,0.0298343,0.0311903,0.0451048,0.0451042,0.0842318,3.88397e-10,3.88865e-10,2.60926e-09,0,0,2.3692e-06,0,0,0,0,0,0,0,0
15485000,0.685906,0.000819444,-0.0132084,0.72757,0.00549699,0.0067817,-0.0973026,0.00390729,-0.000456841,-365.514,-1.56332e-05,-5.68494e-05,-0.000114109,0,0,-0.000886208,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000145259,2.17284e-05,2.17943e-05,0.000126119,0.0327892,0.0327908,0.0314558,0.0510863,0.0510857,0.0851713,3.88473e-10,3.88942e-10,2.54143e-09,0,0,2.36768e-06,0,0,0,0,0,0,0,0
15585000,0.686096,0.000813922,-0.0131633,0.727392,0.00328493,0.00650018,-0.0936118,0.00123005,-0.000562505,-365.513,-1.57072e-05,-5.69499e-05,-0.000111582,0,0,-0.000892957,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000144148,1.9616e-05,1.96835e-05,0.000125393,0.0288223,0.0288238,0.0300537,0.0448851,0.0448846,0.0832539,3.60246e-10,3.60688e-10,2.47556e-09,0,0,2.36391e-06,0,0,0,0,0,0,0,0
15685000,0.686378,0.000828451,-0.0131876,0.727125,0.00335619,0.00693773,-0.0959546,0.0015627,0.000119947,-365.518,-1.56558e-05,-5.70002e-05,-0.000108874,0,0,-0.000894134,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000143193,2.03947e-05,2.04627e-05,0.000124686,0.0316395,0.0316414,0.0302606,0.0507535,0.0507531,0.0841042,3.60323e-10,3.60766e-10,2.41182e-09,0,0,2.36249e-06,0,0,0,0,0,0,0,0
15785000,0.686649,0.000805671,-0.0132034,0.726869,0.00326544,0.00500629,-0.0954359,0.00128024,-0.00129945,-365.521,-1.5647e-05,-5.71851e-05,-0.000106268,0,0,-0.000898669,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000142106,1.84816e-05,1.85508e-05,0.000123979,0.0278925,0.0278944,0.0289292,0.0446604,0.0446601,0.0822504,3.35092e-10,3.35508e-10,2.34997e-09,0,0,2.3591e-06,0,0,0,0,0,0,0,0
15885000,0.686713,0.000770178,-0.0132044,0.726808,0.0040573,0.00528625,-0.0968351,0.00168818,-0.000791109,-365.526,-1.56129e-05,-5.72185e-05,-0.000104471,0,0,-0.000899935,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000142209,1.92131e-05,1.92825e-05,0.000124111,0.0305774,0.0305797,0.0294815,0.0504208,0.0504206,0.0848094,3.35176e-10,3.35593e-10,2.30496e-09,0,0,2.35813e-06,0,0,0,0,0,0,0,0
15985000,0.687069,0.00070037,-0.0131952,0.726472,0.00358842,0.00404178,-0.091931,0.00134236,-0.00195992,-365.519,-1.5598e-05,-5.73898e-05,-0.000101418,0,0,-0.000908058,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000141144,1.74725e-05,1.75429e-05,0.000123397,0.0270283,0.0270303,0.0281907,0.0444335,0.0444334,0.0829423,3.12494e-10,3.12884e-10,2.24639e-09,0,0,2.35506e-06,0,0,0,0,0,0,0,0
16085000,0.687408,0.000706993,-0.0132145,0.726151,0.00484692,0.00459487,-0.0914839,0.0017825,-0.00154465,-365.518,-1.55465e-05,-5.74402e-05,-9.87048e-05,0,0,-0.000911535,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000140211,1.81616e-05,1.82325e-05,0.000122702,0.0295975,0.0296,0.0283174,0.0500908,0.0500908,0.0836893,3.12575e-10,3.12965e-10,2.18973e-09,0,0,2.35386e-06,0,0,0,0,0,0,0,0
16185000,0.687735,0.000701833,-0.0131717,0.725842,0.00470555,0.00453347,-0.0883341,0.00137027,-0.00140275,-365.513,-1.55412e-05,-5.75185e-05,-9.59817e-05,0,0,-0.000918607,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000139171,1.6571e-05,1.66426e-05,0.000122008,0.0262303,0.0262327,0.0270974,0.0442064,0.0442064,0.0818885,2.92075e-10,2.9244e-10,2.13471e-09,0,0,2.35111e-06,0,0,0,0,0,0,0,0
16285000,0.688148,0.00072134,-0.0131884,0.725451,0.00628658,0.00459219,-0.0910586,0.00194676,-0.000924823,-365.519,-1.54883e-05,-5.75713e-05,-9.31428e-05,0,0,-0.000919072,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000138257,1.72222e-05,1.72942e-05,0.000121328,0.0286926,0.0286954,0.0271874,0.0497656,0.0497658,0.0825708,2.92157e-10,2.92521e-10,2.08149e-09,0,0,2.35e-06,0,0,0,0,0,0,0,0
16385000,0.688339,0.000679739,-0.0131892,0.725269,0.00527138,0.00348767,-0.0885703,0.0015092,-0.000857448,-365.516,-1.55029e-05,-5.76345e-05,-9.11315e-05,0,0,-0.000925345,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000137241,1.57628e-05,1.58353e-05,0.000120653,0.0254902,0.0254926,0.0260357,0.0439806,0.0439807,0.0808352,2.73539e-10,2.73878e-10,2.02979e-09,0,0,2.34754e-06,0,0,0,0,0,0,0,0
16485000,0.688575,0.00068719,-0.0131403,0.725046,0.00412251,0.00450164,-0.0924558,0.00196435,-0.00045331,-365.524,-1.54636e-05,-5.76739e-05,-8.90133e-05,0,0,-0.000925298,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000136349,1.63795e-05,1.64525e-05,0.000119985,0.0278566,0.0278594,0.0260946,0.0494465,0.0494469,0.0814567,2.73622e-10,2.7396e-10,1.97977e-09,0,0,2.34652e-06,0,0,0,0,0,0,0,0
16585000,0.68878,0.000813405,-0.0130837,0.724852,0.00141268,0.00547648,-0.0925765,-0.000731396,0.00184818,-365.523,-1.55899e-05,-5.75958e-05,-8.71112e-05,0,0,-0.000929993,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000136294,1.5035e-05,1.51079e-05,0.000120087,0.0248073,0.0248098,0.025331,0.0437574,0.0437577,0.081409,2.56641e-10,2.56956e-10,1.94314e-09,0,0,2.34455e-06,0,0,0,0,0,0,0,0
16685000,0.688962,0.000817767,-0.0130726,0.72468,0.00148326,0.00631391,-0.0919029,-0.000564023,0.00244366,-365.52,-1.55563e-05,-5.76287e-05,-8.5348e-05,0,0,-0.000933932,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000135405,1.56209e-05,1.56941e-05,0.000119425,0.0270855,0.0270885,0.0253687,0.0491352,0.0491357,0.0819967,2.56725e-10,2.57039e-10,1.89574e-09,0,0,2.34361e-06,0,0,0,0,0,0,0,0
16785000,0.689199,0.000840854,-0.0130378,0.724454,-0.00122122,0.00718573,-0.0900876,-0.00278732,0.00418605,-365.517,-1.56481e-05,-5.75826e-05,-8.3365e-05,0,0,-0.000939123,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000134428,1.43767e-05,1.44501e-05,0.000118769,0.0241711,0.0241737,0.0243247,0.043538,0.0435384,0.080321,2.41164e-10,2.41456e-10,1.84967e-09,0,0,2.34162e-06,0,0,0,0,0,0,0,0
16885000,0.689374,0.000858334,-0.0129852,0.724289,-0.00175083,0.00847404,-0.090133,-0.00291266,0.00493291,-365.516,-1.56133e-05,-5.7617e-05,-8.15202e-05,0,0,-0.000942196,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000133569,1.4934e-05,1.50078e-05,0.000118112,0.0263681,0.026371,0.0243389,0.0488319,0.0488326,0.0808528,2.41249e-10,2.4154e-10,1.80509e-09,0,0,2.34076e-06,0,0,0,0,0,0,0,0
16985000,0.689524,0.000805397,-0.0129118,0.724147,-0.00157257,0.00649695,-0.0884211,-0.00349588,0.00291587,-365.515,-1.56281e-05,-5.77741e-05,-7.99146e-05,0,0,-0.000945865,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00013262,1.37786e-05,1.38524e-05,0.000117467,0.0235779,0.0235806,0.0233527,0.043323,0.0433234,0.0792273,2.26942e-10,2.27213e-10,1.76172e-09,0,0,2.33896e-06,0,0,0,0,0,0,0,0
17085000,0.689778,0.000777586,-0.013001,0.723904,-0.00106785,0.00769023,-0.0895319,-0.00362687,0.00360545,-365.52,-1.55926e-05,-5.78099e-05,-7.80014e-05,0,0,-0.000946715,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000131775,1.43106e-05,1.43847e-05,0.00011683,0.0256973,0.0257005,0.0233464,0.0485372,0.0485379,0.0797066,2.27028e-10,2.27298e-10,1.71978e-09,0,0,2.33818e-06,0,0,0,0,0,0,0,0
17185000,0.689937,0.000778457,-0.0129452,0.723753,-0.000698941,0.00794456,-0.0897836,-0.00406644,0.00190565,-365.524,-1.5608e-05,-5.79553e-05,-7.64793e-05,0,0,-0.000948393,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000131715,1.32343e-05,1.3308e-05,0.000116908,0.0230233,0.0230261,0.0227086,0.0431126,0.0431131,0.079715,2.13837e-10,2.14087e-10,1.68905e-09,0,0,2.33675e-06,0,0,0,0,0,0,0,0
17285000,0.690129,0.000755007,-0.0129159,0.723571,0.00118159,0.00938278,-0.0875363,-0.00403356,0.00276342,-365.519,-1.55753e-05,-5.79875e-05,-7.47557e-05,0,0,-0.000952497,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000130883,1.37417e-05,1.38158e-05,0.000116271,0.0250759,0.0250793,0.0226903,0.0482512,0.048252,0.0801631,2.13923e-10,2.14173e-10,1.64926e-09,0,0,2.33602e-06,0,0,0,0,0,0,0,0
17385000,0.690386,0.000727116,-0.012862,0.723327,0.00170033,0.0087462,-0.0844514,-0.00334601,0.00119051,-365.514,-1.554e-05,-5.81402e-05,-7.29845e-05,0,0,-0.000957912,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000129968,1.27347e-05,1.28086e-05,0.000115648,0.0225107,0.0225137,0.0218032,0.0429077,0.0429083,0.0786005,2.01717e-10,2.01948e-10,1.61052e-09,0,0,2.33455e-06,0,0,0,0,0,0,0,0
17485000,0.690615,0.000731853,-0.0128658,0.723108,0.00201772,0.0087232,-0.0842212,-0.00317622,0.00206206,-365.515,-1.55083e-05,-5.81719e-05,-7.12875e-05,0,0,-0.000959927,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000129153,1.32202e-05,1.32944e-05,0.000115029,0.0244994,0.0245029,0.0217711,0.0479749,0.0479759,0.0790015,2.01805e-10,2.02035e-10,1.57305e-09,0,0,2.33389e-06,0,0,0,0,0,0,0,0
17585000,0.690802,0.000659323,-0.0128433,0.72293,0.00306182,0.00738575,-0.0782611,-0.00264033,0.000585012,-365.505,-1.54809e-05,-5.83107e-05,-6.96376e-05,0,0,-0.000966574,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000128273,1.22753e-05,1.23492e-05,0.000114411,0.02203,0.0220331,0.0209387,0.0427084,0.0427091,0.0775006,1.90483e-10,1.90695e-10,1.53655e-09,0,0,2.33256e-06,0,0,0,0,0,0,0,0
17685000,0.691029,0.000628565,-0.0128289,0.722713,0.00389992,0.0084842,-0.080204,-0.00228045,0.00137874,-365.508,-1.54495e-05,-5.83423e-05,-6.79427e-05,0,0,-0.000967574,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000127482,1.274e-05,1.28143e-05,0.000113803,0.0239623,0.023966,0.0208964,0.0477081,0.0477091,0.0778583,1.90571e-10,1.90783e-10,1.50125e-09,0,0,2.33195e-06,0,0,0,0,0,0,0,0
17785000,0.691365,0.000545321,-0.0128245,0.722392,0.00574675,0.00794956,-0.0796019,-0.00155372,0.0010768,-365.51,-1.53597e-05,-5.84344e-05,-6.5882e-05,0,0,-0.000970271,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000126628,1.18505e-05,1.19244e-05,0.000113199,0.0215835,0.0215867,0.0201165,0.0425152,0.0425159,0.0764168,1.80046e-10,1.80241e-10,1.46686e-09,0,0,2.33075e-06,0,0,0,0,0,0,0,0
17885000,0.691475,0.00056022,-0.0128134,0.722287,0.00700852,0.00772534,-0.0807611,-0.000921338,0.0018911,-365.514,-1.5338e-05,-5.84562e-05,-6.47109e-05,0,0,-0.000971238,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000126636,1.22963e-05,1.23703e-05,0.000113256,0.0234604,0.0234641,0.0203183,0.0474509,0.047452,0.078236,1.80138e-10,1.80332e-10,1.44182e-09,0,0,2.33034e-06,0,0,0,0,0,0,0,0
17985000,0.69174,0.000499173,-0.012797,0.722033,0.0084988,0.00542093,-0.0779221,-0.000433179,0.00146122,-365.511,-1.52794e-05,-5.85308e-05,-6.31622e-05,0,0,-0.000975287,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000125783,1.14565e-05,1.153e-05,0.000112667,0.0211638,0.021167,0.019572,0.0423281,0.0423289,0.0767973,1.70335e-10,1.70513e-10,1.40913e-09,0,0,2.32924e-06,0,0,0,0,0,0,0,0
18085000,0.691832,0.000506023,-0.0128102,0.721945,0.00880945,0.0055874,-0.0774805,0.000440384,0.00196798,-365.508,-1.52592e-05,-5.85507e-05,-6.20921e-05,0,0,-0.000978039,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000125016,1.18842e-05,1.1958e-05,0.000112081,0.0229919,0.0229955,0.0195164,0.0472032,0.0472044,0.0770895,1.70424e-10,1.70602e-10,1.37751e-09,0,0,2.32872e-06,0,0,0,0,0,0,0,0
18185000,0.692096,0.000453591,-0.0127765,0.721692,0.00948439,0.00579549,-0.0750915,0.00135802,0.00166981,-365.505,-1.52273e-05,-5.86125e-05,-6.05212e-05,0,0,-0.000981876,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000124191,1.10891e-05,1.11623e-05,0.000111502,0.0207721,0.0207753,0.0188173,0.0421472,0.0421481,0.0757084,1.61278e-10,1.61441e-10,1.34668e-09,0,0,2.32773e-06,0,0,0,0,0,0,0,0
18285000,0.692298,0.000395181,-0.0127339,0.721499,0.0093139,0.00568464,-0.0753712,0.00229483,0.00224602,-365.506,-1.5205e-05,-5.86347e-05,-5.93211e-05,0,0,-0.000983497,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000123435,1.14996e-05,1.15732e-05,0.000110937,0.0225521,0.0225556,0.0187534,0.046965,0.0469663,0.0759543,1.61368e-10,1.6153e-10,1.31681e-09,0,0,2.32726e-06,0,0,0,0,0,0,0,0
18385000,0.692597,0.000383578,-0.0127497,0.721212,0.0106979,0.00679477,-0.073132,0.00298555,0.00196127,-365.501,-1.5181e-05,-5.86972e-05,-5.77415e-05,0,0,-0.000987508,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000122632,1.07454e-05,1.08183e-05,0.000110373,0.0204036,0.0204068,0.0180987,0.0419726,0.0419736,0.0746288,1.52822e-10,1.5297e-10,1.28771e-09,0,0,2.32636e-06,0,0,0,0,0,0,0,0
18485000,0.692739,0.000416214,-0.0127378,0.721076,0.011416,0.00741507,-0.0751395,0.00414013,0.00267173,-365.502,-1.51602e-05,-5.8718e-05,-5.66189e-05,0,0,-0.000988712,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000122628,1.11404e-05,1.12134e-05,0.000110417,0.0221416,0.0221453,0.018257,0.0467361,0.0467375,0.0762825,1.52915e-10,1.53063e-10,1.26652e-09,0,0,2.32603e-06,0,0,0,0,0,0,0,0
18585000,0.693013,0.000377826,-0.0126689,0.720814,0.0110198,0.0069782,-0.074923,0.00349058,0.00221009,-365.503,-1.51975e-05,-5.87844e-05,-5.51419e-05,0,0,-0.000991245,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000121837,1.04226e-05,1.04949e-05,0.000109856,0.0200578,0.020061,0.0176307,0.0418042,0.0418052,0.0749611,1.4492e-10,1.45054e-10,1.23883e-09,0,0,2.3252e-06,0,0,0,0,0,0,0,0
18685000,0.693176,0.00033636,-0.0126918,0.720657,0.0110955,0.00688728,-0.077857,0.00459882,0.0029397,-365.511,-1.51758e-05,-5.88063e-05,-5.39571e-05,0,0,-0.000990848,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000121119,1.08025e-05,1.08751e-05,0.000109299,0.0217523,0.0217559,0.0175622,0.0465162,0.0465176,0.0751543,1.45011e-10,1.45145e-10,1.212e-09,0,0,2.3248e-06,0,0,0,0,0,0,0,0
18785000,0.693309,0.000336677,-0.0126692,0.720529,0.0102832,0.0063889,-0.0762025,0.00386244,0.00249327,-365.51,-1.522e-05,-5.88601e-05,-5.29356e-05,0,0,-0.000993644,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000120353,1.01186e-05,1.01905e-05,0.000108748,0.0197273,0.0197304,0.016975,0.0416417,0.0416428,0.0738863,1.37524e-10,1.37646e-10,1.18583e-09,0,0,2.32405e-06,0,0,0,0,0,0,0,0
18885000,0.69359,0.000343381,-0.0126466,0.720259,0.0106774,0.00739872,-0.0771371,0.00490864,0.00321553,-365.511,-1.5192e-05,-5.88878e-05,-5.14267e-05,0,0,-0.000995055,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000119653,1.04842e-05,1.05564e-05,0.000108205,0.0213837,0.0213872,0.0169056,0.0463045,0.046306,0.0740525,1.37616e-10,1.37737e-10,1.16048e-09,0,0,2.32367e-06,0,0,0,0,0,0,0,0
18985000,0.693779,0.000339542,-0.0126411,0.720077,0.0117486,0.00765857,-0.0776833,0.00612847,0.00272488,-365.511,-1.51456e-05,-5.89525e-05,-5.01614e-05,0,0,-0.000997052,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000118914,9.83112e-06,9.90259e-06,0.000107662,0.0194169,0.01942,0.0163558,0.0414849,0.041486,0.0728355,1.30599e-10,1.3071e-10,1.13574e-09,0,0,2.32299e-06,0,0,0,0,0,0,0,0
19085000,0.693969,0.00032069,-0.0125884,0.719894,0.0122225,0.00869816,-0.0756579,0.00730858,0.00356787,-365.508,-1.51229e-05,-5.89747e-05,-4.89507e-05,0,0,-0.000999671,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000118234,1.01832e-05,1.02549e-05,0.000107131,0.0210345,0.0210381,0.0162857,0.0461009,0.0461024,0.0729775,1.30691e-10,1.30801e-10,1.11176e-09,0,0,2.32265e-06,0,0,0,0,0,0,0,0
19185000,0.694049,0.000312578,-0.0124823,0.719819,0.0120823,0.00825509,-0.0763696,0.00813614,0.00302454,-365.509,-1.50979e-05,-5.90356e-05,-4.81216e-05,0,0,-0.00100143,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000118172,9.55845e-06,9.62917e-06,0.000107158,0.0191199,0.0191229,0.0159553,0.0413335,0.0413347,0.0731222,1.24113e-10,1.24213e-10,1.09415e-09,0,0,2.3221e-06,0,0,0,0,0,0,0,0
19285000,0.694142,0.000349197,-0.0124302,0.719731,0.0121181,0.00800865,-0.0752782,0.00931578,0.00383891,-365.505,-1.50818e-05,-5.90512e-05,-4.72687e-05,0,0,-0.001004,0.2098,0.00202043,0.432662,0,0,0,0,0,0.0001175,9.89791e-06,9.96877e-06,0.000106633,0.0207037,0.0207071,0.0158861,0.0459047,0.0459063,0.0732468,1.24206e-10,1.24305e-10,1.0713e-09,0,0,2.32178e-06,0,0,0,0,0,0,0,0
19385000,0.694338,0.000311523,-0.0123761,0.719543,0.0105623,0.00658758,-0.0707297,0.00786582,0.00322509,-365.497,-1.51353e-05,-5.91099e-05,-4.61307e-05,0,0,-0.0010079,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000116787,9.29964e-06,9.3698e-06,0.000106111,0.0188349,0.0188378,0.015392,0.0411872,0.0411884,0.0720832,1.18033e-10,1.18123e-10,1.049e-09,0,0,2.3212e-06,0,0,0,0,0,0,0,0
19485000,0.694609,0.000329248,-0.012391,0.71928,0.00954847,0.00589193,-0.0746593,0.00885193,0.00383371,-365.504,-1.51116e-05,-5.91335e-05,-4.48433e-05,0,0,-0.00100773,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00011613,9.62733e-06,9.69765e-06,0.000105601,0.0203863,0.0203895,0.0153241,0.0457155,0.0457171,0.0721873,1.18125e-10,1.18215e-10,1.02737e-09,0,0,2.32091e-06,0,0,0,0,0,0,0,0
19585000,0.694844,0.000358534,-0.0123044,0.719055,0.00816233,0.00445804,-0.0743937,0.00750825,0.00320172,-365.504,-1.51486e-05,-5.91877e-05,-4.35493e-05,0,0,-0.00100963,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000115441,9.05359e-06,9.12314e-06,0.000105085,0.0185653,0.018568,0.014859,0.0410457,0.0410469,0.0710607,1.12331e-10,1.12413e-10,1.00623e-09,0,0,2.32038e-06,0,0,0,0,0,0,0,0
19685000,0.694955,0.000353036,-0.0123461,0.718947,0.00866493,0.00241317,-0.0737302,0.00834331,0.00354429,-365.506,-1.51343e-05,-5.92018e-05,-4.27758e-05,0,0,-0.00101078,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000114801,9.36993e-06,9.43966e-06,0.000104588,0.020081,0.0200839,0.0147919,0.0455327,0.0455343,0.0711464,1.12425e-10,1.12506e-10,9.85751e-10,0,0,2.32011e-06,0,0,0,0,0,0,0,0
19785000,0.695056,0.000391761,-0.0123384,0.71885,0.00654909,0.000900354,-0.0730292,0.00705724,0.00294692,-365.505,-1.51736e-05,-5.92317e-05,-4.20457e-05,0,0,-0.00101285,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000114735,8.81978e-06,8.88862e-06,0.000104609,0.0183035,0.0183059,0.0145212,0.0409087,0.0409099,0.0713236,1.06988e-10,1.07061e-10,9.70694e-10,0,0,2.31969e-06,0,0,0,0,0,0,0,0
19885000,0.695343,0.000348836,-0.0122802,0.718573,0.00530756,0.000823758,-0.0728283,0.00766969,0.00302463,-365.507,-1.51495e-05,-5.92556e-05,-4.07383e-05,0,0,-0.00101388,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000114106,9.12485e-06,9.19382e-06,0.000104114,0.0197888,0.0197915,0.014456,0.0453559,0.0453574,0.0713954,1.07081e-10,1.07154e-10,9.51148e-10,0,0,2.31943e-06,0,0,0,0,0,0,0,0
19985000,0.695604,0.000295529,-0.0122691,0.71832,0.00318577,-0.000584073,-0.0702021,0.00645535,0.00248058,-365.502,-1.51655e-05,-5.92874e-05,-3.95348e-05,0,0,-0.0010166,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000113441,8.59612e-06,8.66443e-06,0.000103619,0.0180513,0.0180536,0.0140376,0.0407756,0.0407768,0.0703186,1.01975e-10,1.0204e-10,9.32035e-10,0,0,2.31898e-06,0,0,0,0,0,0,0,0
20085000,0.695921,0.000274689,-0.0122394,0.718014,0.00270829,-0.00206098,-0.0707023,0.00676173,0.00237136,-365.502,-1.51396e-05,-5.93128e-05,-3.81364e-05,0,0,-0.00101792,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00011283,8.89101e-06,8.95944e-06,0.000103135,0.0195088,0.0195112,0.0139752,0.0451843,0.0451859,0.0703752,1.02068e-10,1.02134e-10,9.13504e-10,0,0,2.31875e-06,0,0,0,0,0,0,0,0
20185000,0.696104,0.000349672,-0.0122226,0.717836,0.00111808,-0.00339473,-0.067452,0.00477272,0.00193254,-365.496,-1.5182e-05,-5.93269e-05,-3.71359e-05,0,0,-0.00102103,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000112185,8.38269e-06,8.45042e-06,0.000102649,0.01781,0.017812,0.0135821,0.0406463,0.0406475,0.0693408,9.72728e-11,9.73318e-11,8.95378e-10,0,0,2.31833e-06,0,0,0,0,0,0,0,0
20285000,0.696309,0.000320454,-0.0122039,0.717638,3.3465e-05,-0.00480368,-0.07004,0.00482576,0.00152071,-365.501,-1.51641e-05,-5.93445e-05,-3.61695e-05,0,0,-0.00102137,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000111587,8.66782e-06,8.73566e-06,0.000102179,0.0192397,0.0192418,0.0135223,0.045018,0.0450196,0.0693841,9.73669e-11,9.7426e-11,8.77798e-10,0,0,2.31811e-06,0,0,0,0,0,0,0,0
20385000,0.696445,0.000313669,-0.0122459,0.717505,-0.00220572,-0.00618774,-0.0667968,0.00310358,0.00120236,-365.494,-1.51939e-05,-5.93424e-05,-3.54482e-05,0,0,-0.00102469,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000110954,8.1789e-06,8.24612e-06,0.00010171,0.0175782,0.0175799,0.0131528,0.0405205,0.0405217,0.0683902,9.28627e-11,9.29156e-11,8.60599e-10,0,0,2.31773e-06,0,0,0,0,0,0,0,0
20485000,0.696555,0.000354428,-0.0122559,0.717399,-0.00269471,-0.00690951,-0.0680802,0.00284804,0.000551954,-365.499,-1.51827e-05,-5.93534e-05,-3.48429e-05,0,0,-0.00102495,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000110927,8.45501e-06,8.52217e-06,0.000101732,0.0189786,0.0189806,0.0132411,0.0448564,0.0448579,0.0696131,9.29584e-11,9.30114e-11,8.48062e-10,0,0,2.31758e-06,0,0,0,0,0,0,0,0
20585000,0.69664,0.000364711,-0.0123139,0.717316,-0.00243378,-0.007472,-0.0699772,0.00239319,0.000367795,-365.502,-1.5169e-05,-5.93441e-05,-3.42365e-05,0,0,-0.00102598,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000110306,7.98433e-06,8.05091e-06,0.000101263,0.0173543,0.0173559,0.0128869,0.0403981,0.0403992,0.0686242,8.87278e-11,8.87752e-11,8.31621e-10,0,0,2.31722e-06,0,0,0,0,0,0,0,0
20685000,0.696827,0.000386796,-0.0123332,0.717133,-0.00245079,-0.00867475,-0.0697437,0.00214157,-0.000421789,-365.5,-1.51538e-05,-5.93588e-05,-3.34282e-05,0,0,-0.00102762,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000109729,8.25145e-06,8.31815e-06,0.000100812,0.0187296,0.0187313,0.0128319,0.0446993,0.0447007,0.068646,8.88223e-11,8.88698e-11,8.1567e-10,0,0,2.31703e-06,0,0,0,0,0,0,0,0
20785000,0.696995,0.000398567,-0.0123187,0.71697,-0.00362549,-0.008276,-0.0688686,0.00175056,-0.00041374,-365.499,-1.51349e-05,-5.93458e-05,-3.26425e-05,0,0,-0.00102933,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000109124,7.79773e-06,7.86382e-06,0.000100356,0.0171365,0.017138,0.012498,0.0402786,0.0402797,0.0676953,8.48479e-11,8.48902e-11,8.00054e-10,0,0,2.3167e-06,0,0,0,0,0,0,0,0
20885000,0.697244,0.000384887,-0.0123087,0.716728,-0.00415686,-0.0106218,-0.0702143,0.00136723,-0.00135668,-365.503,-1.51169e-05,-5.93634e-05,-3.16739e-05,0,0,-0.00102985,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000108562,8.05632e-06,8.12251e-06,9.99133e-05,0.018486,0.0184875,0.0124443,0.0445459,0.0445472,0.0676998,8.49427e-11,8.49851e-11,7.84889e-10,0,0,2.31653e-06,0,0,0,0,0,0,0,0
20985000,0.697378,0.000380881,-0.012329,0.716598,-0.00444744,-0.011866,-0.0686823,0.0027783,-0.00130375,-365.501,-1.50678e-05,-5.93425e-05,-3.09619e-05,0,0,-0.00103182,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000107975,7.61917e-06,7.68481e-06,9.94654e-05,0.0169249,0.0169261,0.0121298,0.0401617,0.0401628,0.0667857,8.12092e-11,8.12468e-11,7.70048e-10,0,0,2.31622e-06,0,0,0,0,0,0,0,0
21085000,0.697558,0.000368725,-0.0123236,0.716423,-0.00449367,-0.014259,-0.0691717,0.0023153,-0.00261468,-365.504,-1.50552e-05,-5.93547e-05,-3.02885e-05,0,0,-0.00103252,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000107944,7.86994e-06,7.93552e-06,9.94859e-05,0.0182492,0.0182504,0.0122109,0.044396,0.0443973,0.0679247,8.13055e-11,8.13432e-11,7.59231e-10,0,0,2.3161e-06,0,0,0,0,0,0,0,0
21185000,0.697672,0.000388759,-0.0123281,0.716311,-0.00394655,-0.0138939,-0.0687918,0.00362565,-0.00236919,-365.506,-1.50092e-05,-5.93192e-05,-2.97103e-05,0,0,-0.00103379,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000107363,7.44846e-06,7.51351e-06,9.90446e-05,0.016719,0.01672,0.0119086,0.0400472,0.0400482,0.0670152,7.77983e-11,7.78316e-11,7.45027e-10,0,0,2.31582e-06,0,0,0,0,0,0,0,0
21285000,0.697947,0.000422581,-0.012288,0.716044,-0.00479393,-0.0157927,-0.0682225,0.00318262,-0.0038452,-365.505,-1.49924e-05,-5.93355e-05,-2.88134e-05,0,0,-0.00103516,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000106819,7.6914e-06,7.75649e-06,9.86213e-05,0.0180198,0.0180208,0.0118606,0.0442492,0.0442504,0.0670046,7.78935e-11,7.7927e-11,7.31228e-10,0,0,2.31566e-06,0,0,0,0,0,0,0,0
21385000,0.698012,0.000450431,-0.0122869,0.715981,-0.00548746,-0.0160172,-0.0670685,0.00261644,-0.00257711,-365.505,-1.49727e-05,-5.9264e-05,-2.82886e-05,0,0,-0.00103667,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000106258,7.2849e-06,7.3495e-06,9.81857e-05,0.016519,0.0165198,0.0115753,0.0399349,0.0399358,0.0661296,7.45986e-11,7.4628e-11,7.17716e-10,0,0,2.3154e-06,0,0,0,0,0,0,0,0
21485000,0.698198,0.00046159,-0.012264,0.7158,-0.00605546,-0.0172029,-0.0678355,0.00200152,-0.00422657,-365.507,-1.49586e-05,-5.92778e-05,-2.75352e-05,0,0,-0.00103739,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000105733,7.52071e-06,7.58536e-06,9.77666e-05,0.0177971,0.017798,0.0115302,0.0441053,0.0441064,0.0661129,7.4694e-11,7.47236e-11,7.04586e-10,0,0,2.31525e-06,0,0,0,0,0,0,0,0
21585000,0.698302,0.000449885,-0.0122381,0.715698,-0.00677293,-0.0150493,-0.0670811,0.00156904,-0.00286146,-365.509,-1.49327e-05,-5.92066e-05,-2.69954e-05,0,0,-0.0010387,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000105184,7.12843e-06,7.19261e-06,9.73437e-05,0.0163251,0.0163259,0.0112609,0.0398245,0.0398253,0.0652708,7.15982e-11,7.1624e-11,6.91726e-10,0,0,2.31501e-06,0,0,0,0,0,0,0,0
21685000,0.698424,0.000448945,-0.0122744,0.715579,-0.00679483,-0.0163082,-0.066006,0.000882067,-0.004446,-365.51,-1.49211e-05,-5.92178e-05,-2.63811e-05,0,0,-0.00103956,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000104675,7.35763e-06,7.42191e-06,9.69321e-05,0.0175793,0.0175801,0.0112185,0.043964,0.043965,0.0652489,7.16937e-11,7.17198e-11,6.79226e-10,0,0,2.31487e-06,0,0,0,0,0,0,0,0
21785000,0.698452,0.000435589,-0.0122776,0.715551,-0.00732696,-0.012401,-0.0665522,-0.000236719,-0.00126261,-365.514,-1.4921e-05,-5.90942e-05,-2.60592e-05,0,0,-0.00104048,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000104618,6.97928e-06,7.04302e-06,9.69338e-05,0.0161359,0.0161366,0.0110767,0.0397159,0.0397166,0.0654939,6.87859e-11,6.88085e-11,6.70021e-10,0,0,2.31467e-06,0,0,0,0,0,0,0,0
21885000,0.698594,0.000438268,-0.0122281,0.715414,-0.0071682,-0.0126227,-0.0662538,-0.000967461,-0.00250963,-365.517,-1.49109e-05,-5.9104e-05,-2.55246e-05,0,0,-0.00104103,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000104111,7.2017e-06,7.26546e-06,9.65316e-05,0.0173691,0.01737,0.011037,0.0438251,0.043826,0.0654669,6.88817e-11,6.89045e-11,6.5804e-10,0,0,2.31455e-06,0,0,0,0,0,0,0,0
21985000,0.698741,0.000438489,-0.0122746,0.715269,-0.00772131,-0.0108312,-0.0648683,-0.00178652,0.00031392,-365.518,-1.49002e-05,-5.90026e-05,-2.49241e-05,-1.90541e-11,1.81222e-11,-0.0010425,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000103584,6.83647e-06,6.8999e-06,9.61225e-05,0.0159877,0.0159883,0.0107917,0.0396088,0.0396095,0.06466,6.61478e-11,6.61675e-11,6.463e-10,4e-06,4e-06,2.31433e-06,0,0,0,0,0,0,0,0
22085000,0.698864,0.000448397,-0.0122611,0.71515,-0.00814833,-0.00997192,-0.0668188,-0.00256234,-0.000714823,-365.521,-1.48903e-05,-5.90122e-05,-2.44016e-05,-1.4181e-09,1.34865e-09,-0.00104297,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000103092,7.0529e-06,7.11637e-06,9.5727e-05,0.0178425,0.0178433,0.0107555,0.0436908,0.0436917,0.0646293,6.62437e-11,6.62637e-11,6.34884e-10,4.00001e-06,4.00001e-06,2.31421e-06,0,0,0,0,0,0,0,0
22185000,0.699002,0.000422512,-0.012239,0.715015,-0.0077524,-0.00915171,-0.0649445,-0.00228188,-0.000696539,-365.522,-1.48546e-05,-5.89975e-05,-2.38405e-05,-2.19424e-06,1.8249e-06,-0.00104438,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000102577,6.70088e-06,6.76401e-06,9.53264e-05,0.0177193,0.0177198,0.010523,0.0395106,0.0395112,0.0638455,6.3678e-11,6.36953e-11,6.23688e-10,3.98832e-06,3.98832e-06,2.314e-06,0,0,0,0,0,0,0,0
22285000,0.699072,0.000459725,-0.0122726,0.714946,-0.00923831,-0.00994351,-0.0652974,-0.00313184,-0.00165638,-365.525,-1.48465e-05,-5.90054e-05,-2.34106e-05,-2.20881e-06,1.84004e-06,-0.0010449,0.2098,0.00202043,0.432662,0,0,0,0,0,0.0001021,6.91169e-06,6.97489e-06,9.49373e-05,0.0210651,0.0210656,0.0104903,0.0436178,0.0436186,0.0638118,6.37741e-11,6.37917e-11,6.12803e-10,3.98833e-06,3.98833e-06,2.31389e-06,0,0,0,0,0,0,0,0
22385000,0.699129,0.000439082,-0.0122688,0.71489,-0.00969301,-0.0092817,-0.0632331,-0.00280171,-0.00152907,-365.523,-1.48101e-05,-5.89881e-05,-2.29908e-05,-7.28363e-06,6.90639e-06,-0.00104676,0.2098,0.00202043,0.432662,0,0,0,0,0,0.00010205,6.58074e-06,6.64351e-06,9.4934e-05,0.021795,0.0217952,0.0103743,0.0394803,0.0394809,0.0640738,6.14052e-11,6.14203e-11,6.04789e-10,3.9242e-06,3.9242e-06,2.31372e-06,0,0,0,0,0,0,0,0
22485000,0.699258,0.000448134,-0.0122341,0.714765,-0.010328,-0.00909499,-0.0623154,-0.00380106,-0.00247264,-365.521,-1.48e-05,-5.89978e-05,-2.24623e-05,-7.36244e-06,6.986e-06,-0.00104813,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000101577,6.78601e-06,6.8488e-06,9.45512e-05,0.0264394,0.0264395,0.010345,0.0437365,0.0437372,0.0640368,6.15014e-11,6.15168e-11,5.94344e-10,3.92421e-06,3.92421e-06,2.31361e-06,0,0,0,0,0,0,0,0
22585000,0.69939,0.000413562,-0.0122113,0.714636,-0.00942537,-0.00793334,-0.0622894,-0.00406933,-0.00125941,-365.521,-1.47585e-05,-5.89633e-05,-2.19324e-05,-2.14701e-05,2.19648e-05,-0.00104939,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000101085,6.49251e-06,6.55501e-06,9.41625e-05,0.0272231,0.027223,0.0101338,0.0396167,0.0396172,0.0632851,5.9393e-11,5.94066e-11,5.84097e-10,3.78036e-06,3.78036e-06,2.31343e-06,0,0,0,0,0,0,0,0
22685000,0.699523,0.00045316,-0.0122372,0.714505,-0.0105946,-0.00773124,-0.0614444,-0.00505521,-0.00204649,-365.522,-1.47484e-05,-5.89731e-05,-2.14002e-05,-2.15769e-05,2.20764e-05,-0.00105032,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000100624,6.69356e-06,6.75613e-06,9.37877e-05,0.0328688,0.0328684,0.0101076,0.0441672,0.0441678,0.0632465,5.94894e-11,5.95032e-11,5.7413e-10,3.78037e-06,3.78037e-06,2.31333e-06,0,0,0,0,0,0,0,0
22785000,0.6995,0.000431532,-0.0122193,0.714528,-0.0102308,-0.00583424,-0.0595012,-0.00599992,-0.00169031,-365.517,-1.47374e-05,-5.89575e-05,-2.13044e-05,-2.92215e-05,3.14098e-05,-0.00105253,0.2098,0.00202043,0.432662,0,0,0,0,0,0.000100142,6.45819e-06,6.52052e-06,9.34096e-05,0.0328594,0.0328588,0.00990735,0.0399889,0.0399893,0.0625218,5.77154e-11,5.77277e-11,5.6435e-10,3.55196e-06,3.55195e-06,2.31315e-06,0,0,0,0,0,0,0,0
22885000,0.699619,0.00044503,-0.0121956,0.714412,-0.011401,-0.00545792,-0.0582586,-0.00707148,-0.00224943,-365.516,-1.47295e-05,-5.89652e-05,-2.08874e-05,-2.94002e-05,3.15909e-05,-0.00105358,0.2098,0.00202043,0.432662,0,0,0,0,0,9.96906e-05,6.6559e-06,6.71825e-06,9.3046e-05,0.0391344,0.0391336,0.0098841,0.0449471,0.0449476,0.0624822,5.7812e-11,5.78245e-11,5.54834e-10,3.55196e-06,3.55196e-06,2.31306e-06,0,0,0,0,0,0,0,0
22985000,0.699724,0.000428521,-0.012183,0.714309,-0.0104551,-0.00509388,-0.0562932,-0.00757673,-0.0018673,-365.512,-1.47098e-05,-5.89619e-05,-2.04574e-05,-3.56968e-05,4.33477e-05,-0.0010555,0.2098,0.00202043,0.432662,0,0,0,0,0,9.92223e-05,6.49413e-06,6.55626e-06,9.26749e-05,0.0376946,0.0376937,0.00969341,0.0405946,0.0405949,0.0617832,5.64145e-11,5.64262e-11,5.45497e-10,3.25645e-06,3.25643e-06,2.31289e-06,0,0,0,0,0,0,0,0
23085000,0.699759,0.000391739,-0.012135,0.714276,-0.0108276,-0.00486821,-0.0569539,-0.00863951,-0.00234347,-365.511,-1.47048e-05,-5.8967e-05,-2.01885e-05,-3.59477e-05,4.3594e-05,-0.00105661,0.2098,0.00202043,0.432662,0,0,0,0,0,9.91985e-05,6.69024e-06,6.75224e-06,9.26805e-05,0.0442146,0.0442135,0.00976647,0.0460071,0.0460075,0.062712,5.6512e-11,5.65239e-11,5.38682e-10,3.25645e-06,3.25644e-06,2.31283e-06,0,0,0,0,0,0,0,0
23185000,0.699855,0.000438046,-0.0121017,0.714182,-0.0136595,-0.00492399,-0.0546868,-0.0123096,-0.00190716,-365.506,-1.47257e-05,-5.89642e-05,-1.98182e-05,-4.29741e-05,2.40628e-05,-0.00105872,0.2098,0.00202043,0.432662,0,0,0,0,0,9.87354e-05,6.6069e-06,6.66867e-06,9.23144e-05,0.0411087,0.0411076,0.00958106,0.0413639,0.0413641,0.0620161,5.54835e-11,5.54948e-11,5.29709e-10,2.9246e-06,2.92458e-06,2.31267e-06,0,0,0,0,0,0,0,0
23285000,0.699941,0.000373336,-0.0121152,0.714098,-0.0141544,-0.00611042,-0.0544955,-0.0136928,-0.00246213,-365.507,-1.47179e-05,-5.89719e-05,-1.94024e-05,-4.31416e-05,2.42399e-05,-0.00105935,0.2098,0.00202043,0.432662,0,0,0,0,0,9.83055e-05,6.80306e-06,6.8649e-06,9.1958e-05,0.0475384,0.047537,0.00956267,0.0472051,0.0472053,0.0619746,5.55803e-11,5.55918e-11,5.20973e-10,2.9246e-06,2.92458e-06,2.31259e-06,0,0,0,0,0,0,0,0
23385000,0.700059,0.000434666,-0.0120727,0.713983,-0.0161932,-0.00542907,-0.0549594,-0.0165914,-0.0019189,-365.51,-1.47218e-05,-5.89706e-05,-1.9011e-05,-5.10498e-05,9.58379e-06,-0.00106019,0.2098,0.00202043,0.432662,0,0,0,0,0,9.78544e-05,6.7924e-06,6.854e-06,9.16001e-05,0.0429294,0.0429281,0.0093855,0.0421955,0.0421956,0.0613028,5.48708e-11,5.4882e-11,5.12398e-10,2.58802e-06,2.588e-06,2.31244e-06,0,0,0,0,0,0,0,0
23485000,0.700206,0.00255251,-0.00989051,0.713867,-0.0229812,-0.00618616,-0.0872772,-0.0184849,-0.0024922,-365.512,-1.47123e-05,-5.89803e-05,-1.84977e-05,-5.1305e-05,9.84323e-06,-0.00106093,0.2098,0.00202043,0.432662,0,0,0,0,0,9.74381e-05,6.98444e-06,7.04296e-06,9.12616e-05,0.0490425,0.0490408,0.00937175,0.0483875,0.0483875,0.061256,5.49677e-11,5.49791e-11,5.04042e-10,2.58802e-06,2.588e-06,2.31236e-06,0,0,0,0,0,0,0,0
23585000,0.69987,0.00782847,-0.00221733,0.714224,-0.0305039,-0.00306107,-0.118017,-0.0164002,-0.000496471,-365.512,-1.46766e-05,-5.89748e-05,-1.82227e-05,-6.87331e-05,3.05554e-05,-0.00106278,0.2098,0.00202043,0.432662,0,0,0,0,0,9.70448e-05,7.02524e-06,7.06984e-06,9.08972e-05,0.0433367,0.0433349,0.00920448,0.0429954,0.0429954,0.0606078,5.45055e-11,5.45165e-11,4.95843e-10,2.27079e-06,2.27077e-06,2.31224e-06,0,0,0,0,0,0,0,0
23685000,0.699272,0.00763165,0.00402623,0.714804,-0.0608144,-0.01131,-0.167502,-0.0208552,-0.00112659,-365.523,-1.46715e-05,-5.89806e-05,-1.79322e-05,-6.89338e-05,3.07454e-05,-0.00106324,0.2098,0.00202043,0.432662,0,0,0,0,0,9.70937e-05,7.2244e-06,7.25076e-06,9.08498e-05,0.0489786,0.0489781,0.00927925,0.0494382,0.0494381,0.0615005,5.46034e-11,5.46142e-11,4.89859e-10,2.27079e-06,2.27077e-06,2.31218e-06,0,0,0,0,0,0,0,0
23785000,0.699028,0.00481654,0.0010485,0.715077,-0.0788057,-0.0205319,-0.220348,-0.0176057,0.000435372,-365.532,-1.46225e-05,-5.89817e-05,-1.75591e-05,-9.06779e-05,8.93739e-05,-0.00106479,0.2098,0.00202043,0.432662,0,0,0,0,0,9.66937e-05,7.31699e-06,7.35126e-06,9.0465e-05,0.0426298,0.042631,0.0091201,0.0436981,0.043698,0.0608555,5.43189e-11,5.43296e-11,4.81971e-10,1.98673e-06,1.98672e-06,2.3121e-06,0,0,0,0,0,0,0,0
23885000,0.698959,0.00218729,-0.00504586,0.71514,-0.0953607,-0.0296747,-0.27395,-0.0264198,-0.00211029,-365.554,-1.46146e-05,-5.89903e-05,-1.71253e-05,-9.08692e-05,8.95533e-05,-0.00106517,0.2098,0.00202043,0.432662,0,0,0,0,0,9.62984e-05,7.52474e-06,7.57316e-06,9.00956e-05,0.0477358,0.0477378,0.00911361,0.0502861,0.0502859,0.0608114,5.44161e-11,5.44267e-11,4.74281e-10,1.98673e-06,1.98672e-06,2.31203e-06,0,0,0,0,0,0,0,0
23985000,0.698942,0.000782645,-0.0097795,0.715111,-0.0938745,-0.0324078,-0.325983,-0.0294321,-0.00526498,-365.576,-1.45828e-05,-5.90056e-05,-1.6799e-05,-9.74821e-05,0.000113009,-0.00106574,0.2098,0.00202043,0.432662,0,0,0,0,0,9.58621e-05,7.66548e-06,7.72128e-06,8.97363e-05,0.0411526,0.0411537,0.00896598,0.0442661,0.0442659,0.060189,5.4253e-11,5.42639e-11,4.66729e-10,1.74083e-06,1.74084e-06,2.31198e-06,0,0,0,0,0,0,0,0
24085000,0.699051,0.00197491,-0.00874025,0.715016,-0.0951832,-0.0321878,-0.374326,-0.0388358,-0.00846605,-365.601,-1.45748e-05,-5.90156e-05,-1.63249e-05,-9.79767e-05,0.000113516,-0.00106691,0.2098,0.00202043,0.432662,0,0,0,0,0,9.54681e-05,7.87092e-06,7.92485e-06,8.94107e-05,0.0457175,0.0457181,0.00896387,0.0509036,0.0509033,0.0601476,5.43503e-11,5.43613e-11,4.59369e-10,1.74083e-06,1.74084e-06,2.31193e-06,0,0,0,0,0,0,0,0
24185000,0.699098,0.00308515,-0.00633641,0.714991,-0.0947257,-0.031809,-0.421157,-0.039714,-0.0102584,-365.626,-1.45414e-05,-5.90295e-05,-1.59768e-05,-0.000108405,0.000140241,-0.00106691,0.2098,0.00202043,0.432662,0,0,0,0,0,9.50511e-05,8.02179e-06,8.07134e-06,8.90889e-05,0.0392089,0.039209,0.00882385,0.044686,0.0446857,0.0595469,5.4268e-11,5.42791e-11,4.52141e-10,1.53234e-06,1.53235e-06,2.31188e-06,0,0,0,0,0,0,0,0
24285000,0.699074,0.00359782,-0.00541728,0.71502,-0.104606,-0.0356583,-0.476364,-0.0496577,-0.013623,-365.667,-1.45376e-05,-5.90343e-05,-1.57524e-05,-0.000108575,0.000140422,-0.00106724,0.2098,0.00202043,0.432662,0,0,0,0,0,9.46682e-05,8.23262e-06,8.28022e-06,8.8766e-05,0.0432633,0.0432633,0.00882597,0.0512959,0.0512954,0.0595084,5.43654e-11,5.43764e-11,4.45093e-10,1.53233e-06,1.53235e-06,2.31185e-06,0,0,0,0,0,0,0,0
24385000,0.699045,0.00372571,-0.00567662,0.715046,-0.112379,-0.046625,-0.527811,-0.0563597,-0.0275081,-365.709,-1.45184e-05,-5.90675e-05,-1.55427e-05,-7.9782e-05,0.000146556,-0.00106652,0.2098,0.00202043,0.432662,0,0,0,0,0,9.46151e-05,8.40761e-06,8.45513e-06,8.87606e-05,0.0370281,0.0370279,0.00877193,0.044961,0.0449606,0.0598104,5.43366e-11,5.43476e-11,4.39903e-10,1.35768e-06,1.3577e-06,2.3118e-06,0,0,0,0,0,0,0,0
24485000,0.699139,0.00453004,-0.00169905,0.714969,-0.124954,-0.0515638,-0.578957,-0.0681457,-0.0323492,-365.757,-1.45143e-05,-5.90738e-05,-1.52745e-05,-8.01401e-05,0.000146902,-0.00106708,0.2098,0.00202043,0.432662,0,0,0,0,0,9.42335e-05,8.6194e-06,8.65867e-06,8.8458e-05,0.0406184,0.0406183,0.00877624,0.0514852,0.0514846,0.059774,5.4434e-11,5.4445e-11,4.33114e-10,1.35768e-06,1.3577e-06,2.31179e-06,0,0,0,0,0,0,0,0
24585000,0.699291,0.00505932,0.00214061,0.714816,-0.136587,-0.0642307,-0.62804,-0.0712117,-0.0425966,-365.807,-1.44883e-05,-5.90992e-05,-1.48394e-05,-6.96195e-05,0.00017291,-0.00106441,0.2098,0.00202043,0.432662,0,0,0,0,0,9.38164e-05,8.80603e-06,8.83546e-06,8.81544e-05,0.0347694,0.0347699,0.00864816,0.0451034,0.0451029,0.059197,5.44395e-11,5.44502e-11,4.26445e-10,1.21224e-06,1.21226e-06,2.31169e-06,0,0,0,0,0,0,0,0
24685000,0.699396,0.00510275,0.0032117,0.714709,-0.160627,-0.0779268,-0.708157,-0.0860241,-0.0496789,-365.87,-1.44809e-05,-5.91084e-05,-1.44051e-05,-6.97751e-05,0.000173168,-0.0010646,0.2098,0.00202043,0.432662,0,0,0,0,0,9.34419e-05,9.02767e-06,9.05402e-06,8.78436e-05,0.037943,0.0379447,0.00866525,0.0514999,0.0514994,0.0591642,5.45371e-11,5.45477e-11,4.19938e-10,1.21224e-06,1.21226e-06,2.31169e-06,0,0,0,0,0,0,0,0
24785000,0.699376,0.00486928,0.00200132,0.714734,-0.175522,-0.0890703,-0.7953,-0.0927619,-0.059715,-365.938,-1.44677e-05,-5.91464e-05,-1.42287e-05,-8.42488e-05,0.000200296,-0.00106248,0.2098,0.00202043,0.432662,0,0,0,0,0,9.30272e-05,9.22768e-06,9.25687e-06,8.75297e-05,0.0325256,0.0325279,0.00855828,0.0451293,0.0451288,0.058603,5.45666e-11,5.45769e-11,4.13541e-10,1.09156e-06,1.09157e-06,2.31152e-06,0,0,0,0,0,0,0,0
24885000,0.699394,0.00650584,0.00354459,0.714698,-0.196469,-0.100263,-0.818538,-0.111303,-0.0691374,-366.015,-1.44639e-05,-5.91518e-05,-1.39893e-05,-8.43961e-05,0.000200504,-0.00106253,0.2098,0.00202043,0.432662,0,0,0,0,0,9.26565e-05,9.45576e-06,9.48061e-06,8.72277e-05,0.0353481,0.0353514,0.00855703,0.0513706,0.05137,0.0585753,5.46643e-11,5.46744e-11,4.07303e-10,1.09156e-06,1.09158e-06,2.31153e-06,0,0,0,0,0,0,0,0
24985000,0.699337,0.00842529,0.0055207,0.714721,-0.209721,-0.10528,-0.87353,-0.112852,-0.0751988,-366.091,-1.44584e-05,-5.91849e-05,-1.39293e-05,-0.000113611,0.000252042,-0.00105787,0.2098,0.00202043,0.432662,0,0,0,0,0,9.25841e-05,9.66796e-06,9.68721e-06,8.72312e-05,0.0303854,0.0303898,0.0085182,0.0450553,0.0450549,0.058893,5.47108e-11,5.47206e-11,4.02709e-10,9.91252e-07,9.91265e-07,2.31128e-06,0,0,0,0,0,0,0,0
25085000,0.699367,0.00882681,0.00502793,0.714691,-0.23926,-0.116177,-0.924199,-0.135303,-0.0862311,-366.175,-1.44552e-05,-5.91905e-05,-1.36995e-05,-0.000113854,0.000252329,-0.00105775,0.2098,0.00202043,0.432662,0,0,0,0,0,9.22164e-05,9.9001e-06,9.92053e-06,8.69289e-05,0.0328903,0.0328972,0.00853081,0.0511218,0.0511215,0.0588685,5.48086e-11,5.48182e-11,3.96694e-10,9.91252e-07,9.9127e-07,2.31129e-06,0,0,0,0,0,0,0,0
25185000,0.699429,0.008368,0.00349814,0.714645,-0.263933,-0.131857,-0.97365,-0.156399,-0.11409,-366.259,-1.44399e-05,-5.92311e-05,-1.33937e-05,-9.14905e-05,0.000254499,-0.00105367,0.2098,0.00202043,0.432662,0,0,0,0,0,9.18036e-05,1.01181e-05,1.01419e-05,8.66255e-05,0.0283663,0.0283737,0.00841889,0.0448968,0.0448964,0.0583286,5.48671e-11,5.48763e-11,3.90774e-10,9.0776e-07,9.07772e-07,2.31093e-06,0,0,0,0,0,0,0,0
25285000,0.69954,0.0101306,0.00996991,0.714452,-0.291838,-0.141314,-1.02852,-0.18409,-0.127661,-366.353,-1.44355e-05,-5.92387e-05,-1.30803e-05,-9.17445e-05,0.000254851,-0.00105325,0.2098,0.00202043,0.432662,0,0,0,0,0,9.14363e-05,1.03604e-05,1.03659e-05,8.63463e-05,0.0306012,0.0306111,0.00843574,0.0507785,0.0507784,0.0583085,5.4965e-11,5.4974e-11,3.85004e-10,9.07759e-07,9.07777e-07,2.31093e-06,0,0,0,0,0,0,0,0
25385000,0.699644,0.0115712,0.0167642,0.714201,-0.319554,-0.161801,-1.07696,-0.196129,-0.148305,-366.448,-1.44259e-05,-5.92708e-05,-1.27873e-05,-9.10425e-05,0.000292879,-0.00104613,0.2098,0.00202043,0.432662,0,0,0,0,0,9.10086e-05,1.06011e-05,1.05829e-05,8.60641e-05,0.0264894,0.0265013,0.00832863,0.0446686,0.0446684,0.0577868,5.50332e-11,5.5042e-11,3.79321e-10,8.38099e-07,8.38108e-07,2.31046e-06,0,0,0,0,0,0,0,0
25485000,0.699745,0.0118623,0.0182757,0.71406,-0.367289,-0.185717,-1.13068,-0.230464,-0.165636,-366.557,-1.44193e-05,-5.9278e-05,-1.24306e-05,-9.09493e-05,0.000293003,-0.00104596,0.2098,0.00202043,0.432662,0,0,0,0,0,9.06501e-05,1.08465e-05,1.0823e-05,8.57766e-05,0.0284938,0.0285122,0.00834658,0.0503609,0.0503615,0.0577713,5.51309e-11,5.51398e-11,3.73783e-10,8.38098e-07,8.38114e-07,2.31044e-06,0,0,0,0,0,0,0,0
25585000,0.699894,0.0114096,0.0162977,0.713969,-0.407274,-0.217806,-1.18544,-0.259143,-0.205022,-366.668,-1.44049e-05,-5.93218e-05,-1.21287e-05,-7.24207e-05,0.000306482,-0.00104185,0.2098,0.00202043,0.432662,0,0,0,0,0,9.02405e-05,1.10747e-05,1.10591e-05,8.54896e-05,0.0247626,0.0247826,0.00824652,0.0443836,0.0443839,0.057267,5.52074e-11,5.52159e-11,3.6832e-10,7.79829e-07,7.79837e-07,2.30982e-06,0,0,0,0,0,0,0,0
25685000,0.699874,0.0147628,0.0226218,0.713755,-0.454489,-0.238563,-1.2386,-0.302127,-0.227787,-366.789,-1.44009e-05,-5.93258e-05,-1.1918e-05,-7.23043e-05,0.00030654,-0.0010418,0.2098,0.00202043,0.432662,0,0,0,0,0,9.01916e-05,1.13446e-05,1.13059e-05,8.549e-05,0.0265699,0.0265973,0.00833599,0.0498864,0.049888,0.0580885,5.53057e-11,5.53143e-11,3.64347e-10,7.7983e-07,7.79845e-07,2.30978e-06,0,0,0,0,0,0,0,0
25785000,0.699843,0.0175878,0.0294854,0.713471,-0.496777,-0.264407,-1.2855,-0.317987,-0.256044,-366.908,-1.43999e-05,-5.9366e-05,-1.15881e-05,-8.54993e-05,0.000367592,-0.00103462,0.2098,0.00202043,0.432662,0,0,0,0,0,8.97509e-05,1.16186e-05,1.15513e-05,8.51905e-05,0.0231861,0.0232184,0.00823551,0.0440531,0.0440543,0.0575864,5.53891e-11,5.53974e-11,3.59064e-10,7.30989e-07,7.30995e-07,2.30901e-06,0,0,0,0,0,0,0,0
25885000,0.711372,0.0184771,0.029872,0.701938,-0.567156,-0.292964,-1.33567,-0.371179,-0.283941,-367.037,-1.44004e-05,-5.93665e-05,-1.15913e-05,-8.56003e-05,0.000367643,-0.00103428,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000909679,1.32027e-05,1.22049e-05,0.000933193,0.025042,0.0250987,0.00813145,0.0493679,0.0493712,0.057565,5.54889e-11,5.54972e-11,3.59155e-10,7.3099e-07,7.31003e-07,2.30892e-06,0,0,0,0,0,0,0,0
25985000,0.710277,0.017479,0.0266134,0.703201,-0.62108,-0.330616,-1.39095,-0.412094,-0.341345,-367.169,-1.44016e-05,-5.94123e-05,-1.15982e-05,-6.47036e-05,0.000397017,-0.00103469,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000698319,1.26361e-05,1.20718e-05,0.000715072,0.0223281,0.0224171,0.00882953,0.0436852,0.0436877,0.0570356,5.55612e-11,5.55687e-11,3.59198e-10,6.8724e-07,6.87244e-07,2.30876e-06,0,0,0,0,0,0,0,0
26085000,0.704954,0.0220478,0.0360173,0.707995,-0.686491,-0.356786,-1.41782,-0.47737,-0.375697,-367.309,-1.44021e-05,-5.94129e-05,-1.16071e-05,-6.49063e-05,0.000397021,-0.00103446,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000573289,1.31552e-05,1.22529e-05,0.000576512,0.0243872,0.0245298,0.0105801,0.0488248,0.0488309,0.0569572,5.5661e-11,5.56685e-11,3.59286e-10,6.8724e-07,6.87252e-07,2.30873e-06,0,0,0,0,0,0,0,0
26185000,0.702729,0.0246929,0.0460582,0.709535,-0.734832,-0.38889,-1.38633,-0.500328,-0.417595,-367.441,-1.44726e-05,-5.94993e-05,-1.16258e-05,-8.53923e-05,0.000487555,-0.00104957,0.217062,0.00209036,0.427576,0,0,0,0,0,0.00048611,1.37204e-05,1.2336e-05,0.000484898,0.0220692,0.0222533,0.0129263,0.043298,0.0433028,0.0564588,5.56813e-11,5.56877e-11,3.5934e-10,6.44967e-07,6.44964e-07,2.30435e-06,0,0,0,0,0,0,0,0
26285000,0.702337,0.0257011,0.0487366,0.709709,-0.82724,-0.429743,-1.37504,-0.57837,-0.458528,-367.578,-1.4473e-05,-5.94998e-05,-1.16317e-05,-8.55705e-05,0.000487536,-0.00104964,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000436231,1.37884e-05,1.23897e-05,0.00043557,0.0242789,0.0245686,0.016447,0.0482978,0.0483099,0.0573112,5.57812e-11,5.57875e-11,3.59429e-10,6.44969e-07,6.44973e-07,2.30435e-06,0,0,0,0,0,0,0,0
26385000,0.703193,0.0248158,0.0451583,0.709129,-0.907601,-0.487734,-1.37908,-0.645986,-0.546272,-367.712,-1.44513e-05,-5.9575e-05,-1.16501e-05,-5.14446e-05,0.000505075,-0.00104768,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000383455,1.333e-05,1.23117e-05,0.000384288,0.0222244,0.0225471,0.0202167,0.0429209,0.0429302,0.056983,5.57336e-11,5.57386e-11,3.5949e-10,6.04154e-07,6.04117e-07,2.28865e-06,0,0,0,0,0,0,0,0
26485000,0.703276,0.0323191,0.0600168,0.707641,-1.00101,-0.525768,-1.38323,-0.741178,-0.596966,-367.847,-1.44517e-05,-5.95759e-05,-1.16594e-05,-5.1751e-05,0.000505021,-0.00104851,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000342197,1.42279e-05,1.26332e-05,0.000344825,0.024551,0.0249707,0.0252979,0.0478209,0.0478429,0.0573993,5.58335e-11,5.58383e-11,3.59571e-10,6.04144e-07,6.04125e-07,2.28827e-06,0,0,0,0,0,0,0,0
26585000,0.702756,0.0390253,0.0768788,0.706188,-1.08982,-0.577346,-1.37088,-0.782884,-0.662087,-367.98,-1.46027e-05,-5.97408e-05,-1.16905e-05,-7.63399e-05,0.000610944,-0.00106048,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000307775,1.52722e-05,1.28937e-05,0.000311962,0.0226271,0.0231107,0.0297649,0.0425795,0.0425964,0.0574082,5.5713e-11,5.57168e-11,3.59638e-10,5.65049e-07,5.64934e-07,2.25553e-06,0,0,0,0,0,0,0,0
26685000,0.703662,0.0404874,0.0803254,0.704818,-1.23537,-0.638045,-1.36045,-0.899122,-0.722806,-368.115,-1.4603e-05,-5.97408e-05,-1.16904e-05,-7.62908e-05,0.00061097,-0.00106135,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000281393,1.53379e-05,1.29677e-05,0.00028661,0.0250697,0.0257433,0.0360489,0.0474182,0.0474568,0.058462,5.58129e-11,5.58166e-11,3.59715e-10,5.65024e-07,5.64939e-07,2.25388e-06,0,0,0,0,0,0,0,0
26785000,0.704523,0.0385924,0.0745221,0.704702,-1.35521,-0.722795,-1.363,-0.994658,-0.85421,-368.253,-1.46432e-05,-5.98e-05,-1.17366e-05,-2.01145e-05,0.00065395,-0.00105909,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000258377,1.45797e-05,1.27746e-05,0.00026396,0.0231763,0.0238833,0.0404184,0.0422924,0.0423219,0.0588681,5.56242e-11,5.56276e-11,3.59783e-10,5.28102e-07,5.27832e-07,2.20114e-06,0,0,0,0,0,0,0,0
26885000,0.704034,0.0470774,0.0950807,0.702197,-1.49888,-0.77977,-1.37548,-1.13706,-0.92918,-368.39,-1.46433e-05,-5.97997e-05,-1.17342e-05,-2.00219e-05,0.000653988,-0.00105879,0.217062,0.00209036,0.427576,0,0,0,0,0,0.00023914,1.59582e-05,1.32093e-05,0.000245366,0.0256792,0.0265632,0.0475916,0.0471043,0.0471669,0.0607514,5.57242e-11,5.57271e-11,3.59854e-10,5.28052e-07,5.27831e-07,2.19712e-06,0,0,0,0,0,0,0,0
26985000,0.703264,0.0542658,0.117679,0.699019,-1.62042,-0.855321,-1.34898,-1.1953,-1.02723,-368.523,-1.50422e-05,-6.00287e-05,-1.17638e-05,-4.36352e-05,0.000821175,-0.0010946,0.217062,0.00209036,0.427576,0,0,0,0,0,0.000223761,1.75183e-05,1.35215e-05,0.000230813,0.0237527,0.0247176,0.0509774,0.0420705,0.0421188,0.0624203,5.54789e-11,5.54834e-11,3.59928e-10,4.93797e-07,4.93234e-07,2.12702e-06,0,0,0,0,0,0,0,0
27085000,0.703857,0.0554671,0.122609,0.697478,-1.82488,-0.945037,-1.32048,-1.36751,-1.11723,-368.654,-1.5042e-05,-6.0029e-05,-1.17677e-05,-4.36756e-05,0.000821028,-0.00109867,0.213575,0.00204508,0.429749,-0.00177554,0.00386709,0.00110396,0,0,0.000222923,1.80823e-05,1.3705e-05,0.000231036,0.0263494,0.0277353,0.0582424,0.0468838,0.0469911,0.0652645,5.55789e-11,5.55833e-11,3.60022e-10,4.93806e-07,4.93235e-07,2.12043e-06,0.00139134,1.86354e-05,0.00139453,0.000554546,0.00138999,0.0013885,0,0
27185000,0.70594,0.052278,0.112613,0.697305,-2.02469,-1.00574,-1.3015,-1.56378,-1.19359,-368.78,-1.50082e-05,-6.02729e-05,-1.17785e-05,-0.0001023,0.000812759,-0.00110103,0.213923,0.00204595,0.429798,-0.00211267,0.00354791,0.00122585,0,0,0.000220323,1.69337e-05,1.33963e-05,0.000228889,0.0263141,0.0278809,0.0595845,0.0494345,0.0495439,0.0660518,5.53151e-11,5.5326e-11,3.60115e-10,4.73097e-07,4.71882e-07,2.03562e-06,0.00132623,1.84998e-05,0.00132965,0.000344557,0.00132457,0.00132284,0,0
27285000,0.707411,0.0466593,0.0975493,0.698482,-2.18758,-1.07362,-1.29113,-1.77471,-1.2977,-368.909,-1.50081e-05,-6.02729e-05,-1.17792e-05,-0.000102302,0.000812718,-0.00110192,0.213521,0.00204405,0.430238,-0.00179055,0.00381684,0.00174776,0,0,0.000220954,1.58318e-05,1.32043e-05,0.000229652,0.0289715,0.0309338,0.0666299,0.0550702,0.0552858,0.0696888,5.5415e-11,5.5426e-11,3.60211e-10,4.73107e-07,4.71871e-07,2.02581e-06,0.00130123,1.83763e-05,0.00130463,0.000264814,0.00129954,0.00129813,0,0
27385000,0.708914,0.0404755,0.0814613,0.699405,-2.27944,-1.08882,-1.28051,-1.96249,-1.36726,-369.037,-1.53973e-05,-6.06645e-05,-1.17727e-05,-0.000193214,0.000903495,-0.00113306,0.213153,0.00203864,0.430079,-0.00210179,0.00424315,0.00191405,0,0,0.000218191,1.45462e-05,1.28364e-05,0.000226441,0.0283868,0.0302366,0.065871,0.0575348,0.0577299,0.0702054,5.51256e-11,5.51509e-11,3.60303e-10,4.53125e-07,4.508e-07,1.93484e-06,0.00128371,1.82562e-05,0.00128621,0.000221668,0.00128213,0.00128023,0,0
27485000,0.709447,0.0347199,0.0663567,0.700769,-2.36604,-1.12561,-1.26611,-2.19504,-1.47811,-369.167,-1.5398e-05,-6.06646e-05,-1.1771e-05,-0.000193242,0.000903699,-0.0011294,0.21291,0.00203558,0.429934,-0.00217321,0.0043946,0.00213515,0,0,0.000218839,1.38557e-05,1.27505e-05,0.000226649,0.0309498,0.0329685,0.0721505,0.0639866,0.0643249,0.0744049,5.52253e-11,5.52509e-11,3.604e-10,4.53134e-07,4.50772e-07,1.92234e-06,0.00126635,1.81374e-05,0.0012673,0.000195287,0.00126486,0.00126181,0,0
27585000,0.710175,0.0300155,0.0537493,0.701329,-2.45021,-1.13519,-1.2825,-2.46534,-1.57814,-369.305,-1.51426e-05,-6.07808e-05,-1.1807e-05,-0.000218836,0.000846318,-0.0010758,0.212895,0.00203175,0.430165,-0.00246961,0.00396395,0.0019784,0,0,0.000215937,1.31625e-05,1.25301e-05,0.000223108,0.0298638,0.0315381,0.0701064,0.066237,0.0665232,0.0758405,5.49283e-11,5.49761e-11,3.6049e-10,4.34389e-07,4.30591e-07,1.83605e-06,0.00125202,1.80493e-05,0.00125106,0.000180179,0.00125059,0.00124585,0,0
27685000,0.709963,0.0291106,0.0515324,0.701747,-2.48916,-1.14856,-1.28317,-2.71238,-1.69233,-369.433,-1.51425e-05,-6.07808e-05,-1.18074e-05,-0.000218831,0.000846281,-0.0010764,0.212818,0.00202981,0.430093,-0.0025965,0.00395217,0.00210481,0,0,0.000216076,1.32116e-05,1.26312e-05,0.00022292,0.0323382,0.0340239,0.0755933,0.0734673,0.0739099,0.0805037,5.50276e-11,5.5076e-11,3.60588e-10,4.34398e-07,4.30547e-07,1.82255e-06,0.00123354,1.79328e-05,0.00123022,0.000166021,0.00123214,0.00122522,0,0
27785000,0.710139,0.0295914,0.0534421,0.701406,-2.54017,-1.15004,-1.28709,-2.97928,-1.7898,-369.565,-1.50275e-05,-6.09177e-05,-1.18484e-05,-0.00024857,0.000820964,-0.00105303,0.212718,0.00202526,0.429785,-0.00309156,0.00403064,0.00230145,0,0,0.000213187,1.31348e-05,1.25571e-05,0.000219722,0.0308947,0.0322165,0.0712863,0.075399,0.0757645,0.0798428,5.47392e-11,5.48146e-11,3.6067e-10,4.1713e-07,4.1169e-07,1.73975e-06,0.0012205,1.78189e-05,0.0012154,0.000154625,0.00121914,0.00121056,0,0
27885000,0.710136,0.028977,0.0517101,0.701565,-2.57817,-1.16452,-1.28944,-3.23533,-1.90559,-369.699,-1.50295e-05,-6.09182e-05,-1.18461e-05,-0.000248693,0.000821502,-0.00104542,0.212846,0.0020274,0.429733,-0.00306395,0.00413302,0.00217148,0,0,0.000213213,1.32134e-05,1.26737e-05,0.00021965,0.0333169,0.0346293,0.0756666,0.0833547,0.083873,0.0845311,5.48382e-11,5.49145e-11,3.60769e-10,4.17137e-07,4.11628e-07,1.72558e-06,0.00121067,1.77073e-05,0.00120443,0.000146562,0.00120936,0.00119964,0,0
27985000,0.710481,0.0279783,0.0477643,0.701536,-2.64478,-1.17198,-1.2984,-3.54265,-2.01964,-369.832,-1.4695e-05,-6.09316e-05,-1.18936e-05,-0.000251215,0.000749142,-0.00101561,0.212795,0.00202621,0.429479,-0.00316395,0.00416903,0.0023108,0,0,0.000211066,1.29737e-05,1.25738e-05,0.000217218,0.0315983,0.0325997,0.0703972,0.0848916,0.0853169,0.0831971,5.45717e-11,5.46766e-11,3.6084e-10,4.01509e-07,3.94428e-07,1.65273e-06,0.00120142,1.75973e-05,0.00119379,0.000139287,0.00120012,0.00118907,0,0
28085000,0.709955,0.0334352,0.0602149,0.700872,-2.68142,-1.18293,-1.3109,-3.80873,-2.13731,-369.962,-1.4695e-05,-6.09316e-05,-1.18938e-05,-0.000251214,0.000749131,-0.00101575,0.212808,0.00202479,0.429454,-0.00337065,0.0041334,0.00236148,0,0,0.000210753,1.35135e-05,1.28271e-05,0.000216975,0.0339562,0.0349349,0.0737873,0.0935116,0.0940772,0.0876971,5.46705e-11,5.47765e-11,3.60939e-10,4.01514e-07,3.94356e-07,1.63881e-06,0.00119573,1.74894e-05,0.00118732,0.000134089,0.00119447,0.00118264,0,0
28185000,0.709762,0.0388961,0.0744487,0.699416,-2.7487,-1.19709,-1.07487,-4.11296,-2.25038,-370.093,-1.4488e-05,-6.09637e-05,-1.19334e-05,-0.000257899,0.000704848,-0.000999919,0.212851,0.00202469,0.429426,-0.00344982,0.00409478,0.00231253,0,0,0.000208493,1.3968e-05,1.29008e-05,0.00021502,0.0318389,0.0325866,0.067312,0.0946045,0.0950711,0.0857721,5.44362e-11,5.45699e-11,3.60998e-10,3.876e-07,3.78992e-07,1.57686e-06,0.00119424,1.73839e-05,0.00118564,0.000129224,0.00119302,0.00118105,0,0
28285000,0.711643,0.0318633,0.0588888,0.699343,-2.74783,-1.2086,-0.217017,-4.3879,-2.37069,-370.159,-1.44881e-05,-6.09638e-05,-1.19334e-05,-0.00025791,0.000704884,-0.000999471,0.212905,0.00202417,0.429484,-0.00355257,0.00400171,0.00234258,0,0,0.000208496,1.35003e-05,1.28709e-05,0.000215958,0.0333559,0.0339923,0.0682594,0.103792,0.104382,0.0918554,5.45352e-11,5.46698e-11,3.61098e-10,3.87605e-07,3.78938e-07,1.56712e-06,0.00119314,1.7306e-05,0.0011845,0.000126538,0.00119195,0.00117994,0,0
28385000,0.714029,0.0158761,0.0277004,0.699388,-2.77605,-1.21431,0.642293,-4.72096,-2.49176,-370.145,-1.41408e-05,-6.09586e-05,-1.19874e-05,-0.00025654,0.000633479,-0.000963378,0.212607,0.00201881,0.429598,-0.00361456,0.00350471,0.00243818,0,0,0.000207691,1.27985e-05,1.26523e-05,0.000216028,0.0307968,0.0311944,0.0680569,0.104457,0.104948,0.0957344,5.42995e-11,5.44549e-11,3.61164e-10,3.74383e-07,3.64695e-07,1.55046e-06,0.00118343,1.7201e-05,0.00117407,0.000122716,0.00118226,0.00116935,0,0
28485000,0.714338,0.00630458,0.00841466,0.699722,-2.73406,-1.2058,0.972496,-4.99689,-2.61299,-370.062,-1.41428e-05,-6.09593e-05,-1.19875e-05,-0.000256692,0.000633971,-0.000957604,0.211756,0.00200747,0.429579,-0.00357255,0.00276547,0.00281286,0,0,0.000207771,1.29183e-05,1.27957e-05,0.000216057,0.0325746,0.0328421,0.0688983,0.114098,0.114681,0.0993331,5.43975e-11,5.45546e-11,3.61264e-10,3.74382e-07,3.64591e-07,1.53474e-06,0.00115484,1.70932e-05,0.00114346,0.000119657,0.00115354,0.00113819,0,0
28585000,0.713652,0.00454918,0.00477765,0.70047,-2.70307,-1.18411,0.864695,-5.33205,-2.73357,-369.979,-1.37734e-05,-6.09476e-05,-1.20465e-05,-0.000254125,0.00056028,-0.000921216,0.212066,0.00201091,0.430012,-0.00354091,0.00271913,0.0022207,0,0,0.000207779,1.29923e-05,1.28469e-05,0.000215139,0.0307111,0.030794,0.070263,0.114373,0.114876,0.102686,5.41616e-11,5.43343e-11,3.61321e-10,3.61662e-07,3.51157e-07,1.51561e-06,0.0011221,1.69856e-05,0.0011084,0.000116581,0.00112059,0.00110254,0,0
28685000,0.712618,0.00381197,0.0037785,0.701532,-2.63352,-1.16464,0.860756,-5.59895,-2.85103,-369.901,-1.37771e-05,-6.0949e-05,-1.20478e-05,-0.000254401,0.000561123,-0.000911544,0.211949,0.00200992,0.429673,-0.00351394,0.00277288,0.00254392,0,0,0.000208344,1.31618e-05,1.30097e-05,0.000214648,0.0326466,0.032642,0.0709277,0.124485,0.125034,0.105786,5.4259e-11,5.4434e-11,3.61421e-10,3.61657e-07,3.51028e-07,1.49737e-06,0.00109311,1.68801e-05,0.00107741,0.000114212,0.00109133,0.00107109,0,0
28785000,0.711955,0.00363362,0.00358744,0.702207,-2.60702,-1.14453,0.865208,-5.92908,-2.96403,-369.819,-1.34262e-05,-6.09569e-05,-1.21252e-05,-0.000255922,0.000490057,-0.000886106,0.211827,0.00200707,0.429903,-0.00357712,0.00235871,0.00235191,0,0,0.000208502,1.32077e-05,1.30507e-05,0.000213928,0.0306475,0.030607,0.0636455,0.124304,0.124821,0.10054,5.4071e-11,5.42577e-11,3.61431e-10,3.50266e-07,3.39163e-07,1.43619e-06,0.00106832,1.67765e-05,0.0010509,0.000111951,0.00106627,0.00104428,0,0
28885000,0.711403,0.00358968,0.00376489,0.702765,-2.5416,-1.12675,0.851096,-6.18654,-3.07762,-369.739,-1.34287e-05,-6.09578e-05,-1.21263e-05,-0.000256116,0.000490639,-0.000879528,0.211719,0.0020061,0.4296,-0.00353949,0.00240631,0.00264901,0,0,0.00020893,1.33735e-05,1.32175e-05,0.000213794,0.0325363,0.0324921,0.0652049,0.13483,0.13535,0.10597,5.41693e-11,5.43575e-11,3.61531e-10,3.50267e-07,3.39087e-07,1.42513e-06,0.00105215,1.67001e-05,0.0010337,0.000110558,0.00104991,0.00102687,0,0
28985000,0.711115,0.00390625,0.00433127,0.703051,-2.53195,-1.11297,0.843813,-6.52913,-3.19488,-369.658,-1.30262e-05,-6.09304e-05,-1.22144e-05,-0.000250442,0.000407713,-0.000852365,0.211341,0.00200008,0.429585,-0.00356024,0.00179886,0.00280879,0,0,0.000209098,1.3411e-05,1.32577e-05,0.000213531,0.0305188,0.0305158,0.0588885,0.134226,0.134755,0.100976,5.40318e-11,5.42228e-11,3.61507e-10,3.40152e-07,3.2896e-07,1.37757e-06,0.00103348,1.65995e-05,0.00101383,0.000108795,0.00103102,0.00100682,0,0
29085000,0.710914,0.00402389,0.00469127,0.703252,-2.473,-1.09629,0.833062,-6.7794,-3.30535,-369.579,-1.30284e-05,-6.09312e-05,-1.22156e-05,-0.000250604,0.000408195,-0.000846946,0.211227,0.00199866,0.429306,-0.00355808,0.00181785,0.00309209,0,0,0.000209366,1.35826e-05,1.34309e-05,0.000213584,0.0323457,0.032406,0.0590769,0.145115,0.145614,0.103378,5.41299e-11,5.43225e-11,3.61607e-10,3.40151e-07,3.28874e-07,1.36539e-06,0.00101754,1.65002e-05,0.000996939,0.000107293,0.00101489,0.000989754,0,0
29185000,0.710828,0.00424926,0.00508668,0.703335,-2.4416,-1.08297,0.82112,-7.07122,-3.41975,-369.505,-1.28521e-05,-6.09108e-05,-1.2262e-05,-0.000246268,0.000370929,-0.000824079,0.211632,0.00200462,0.429549,-0.00346927,0.00198918,0.00266365,0,0,0.00020945,1.36201e-05,1.34732e-05,0.000213509,0.0303146,0.0304468,0.0537047,0.144114,0.144661,0.0988445,5.40397e-11,5.42287e-11,3.61549e-10,3.31282e-07,3.20333e-07,1.32862e-06,0.00100377,1.64027e-05,0.000982353,0.000105916,0.00100095,0.000975054,0,0
29285000,0.710713,0.00454545,0.00585675,0.703443,-2.38823,-1.06906,0.843332,-7.31275,-3.52737,-369.428,-1.28547e-05,-6.09118e-05,-1.22638e-05,-0.000246469,0.000371518,-0.000817424,0.21159,0.00200402,0.42945,-0.00347795,0.00199455,0.00274986,0,0,0.000209718,1.37957e-05,1.36528e-05,0.000213654,0.0320524,0.0322965,0.0536785,0.15532,0.155807,0.100898,5.41381e-11,5.43285e-11,3.61648e-10,3.31283e-07,3.20264e-07,1.31847e-06,0.000991892,1.63068e-05,0.000969817,0.000104712,0.000988921,0.000962392,0,0
29385000,0.710696,0.00508169,0.00731735,0.703443,-2.37497,-1.06139,0.850063,-7.61612,-3.64528,-369.352,-1.26398e-05,-6.08749e-05,-1.232e-05,-0.000238303,0.000324504,-0.000789352,0.211791,0.00200584,0.429438,-0.00354788,0.00197229,0.0026607,0,0,0.000209701,1.38278e-05,1.36974e-05,0.000213576,0.0300114,0.0303212,0.0490672,0.153955,0.154527,0.0967628,5.40888e-11,5.42719e-11,3.61557e-10,3.23567e-07,3.13102e-07,1.28959e-06,0.000981901,1.62124e-05,0.000959289,0.000103616,0.000978813,0.000951789,0,0
29485000,0.710679,0.00554714,0.00842542,0.703444,-2.32934,-1.05054,0.846188,-7.85132,-3.75087,-369.269,-1.26403e-05,-6.08751e-05,-1.23205e-05,-0.000238347,0.000324633,-0.00078789,0.211882,0.0020076,0.4294,-0.00348437,0.00209493,0.00264227,0,0,0.000209953,1.40101e-05,1.38839e-05,0.00021381,0.0317065,0.0321586,0.0489707,0.165433,0.165922,0.0985115,5.41875e-11,5.43717e-11,3.61656e-10,3.23569e-07,3.13046e-07,1.28107e-06,0.000973485,1.61195e-05,0.000950456,0.000102631,0.000970288,0.000942879,0,0
29585000,0.71063,0.00590021,0.00945959,0.703478,-2.30289,-1.03911,0.837021,-8.11228,-3.85352,-369.19,-1.25587e-05,-6.08826e-05,-1.23721e-05,-0.000240105,0.000305745,-0.000775645,0.211899,0.00200781,0.429229,-0.00346915,0.00211292,0.00277482,0,0,0.000209833,1.40498e-05,1.39328e-05,0.000213643,0.0296949,0.0301897,0.0457726,0.16374,0.164346,0.0970269,5.41753e-11,5.43501e-11,3.61537e-10,3.1696e-07,3.07123e-07,1.25995e-06,0.000967983,1.6051e-05,0.000944697,0.000101949,0.00096473,0.000937092,0,0
29685000,0.710718,0.00616337,0.0101056,0.703377,-2.26452,-1.0292,0.829387,-8.34065,-3.95692,-369.108,-1.25592e-05,-6.08828e-05,-1.23726e-05,-0.000240146,0.000305865,-0.00077427,0.21182,0.00200666,0.429234,-0.00347746,0.00203637,0.00280383,0,0,0.00021006,1.42435e-05,1.41272e-05,0.000213959,0.0313314,0.0319831,0.0456216,0.175455,0.175957,0.0985922,5.42742e-11,5.445e-11,3.61636e-10,3.16963e-07,3.07079e-07,1.25278e-06,0.000961539,1.59604e-05,0.000937963,0.000101112,0.000958198,0.000930306,0,0
29785000,0.710759,0.00639211,0.0105672,0.703327,-2.25216,-1.02122,0.816406,-8.61053,-4.06233,-369.028,-1.24552e-05,-6.08778e-05,-1.24269e-05,-0.000238892,0.000280219,-0.00076385,0.21159,0.00200421,0.429363,-0.00335044,0.00168417,0.00279274,0,0,0.000209753,1.42897e-05,1.41789e-05,0.000213695,0.029349,0.030009,0.0421238,0.173466,0.174115,0.09495,5.42936e-11,5.44603e-11,3.61492e-10,3.11389e-07,3.0222e-07,1.23426e-06,0.00095583,1.58708e-05,0.000932021,0.000100332,0.000952435,0.000924337,0,0
29885000,0.710798,0.00641725,0.0106965,0.703285,-2.21957,-1.01258,0.800909,-8.83418,-4.16406,-368.955,-1.24579e-05,-6.08788e-05,-1.24299e-05,-0.000239102,0.000280811,-0.000756965,0.211576,0.0020038,0.429439,-0.00337653,0.00162992,0.00271331,0,0,0.000210031,1.44927e-05,1.43805e-05,0.00021401,0.0309303,0.0317526,0.0419209,0.185383,0.185911,0.0962827,5.43927e-11,5.45601e-11,3.61591e-10,3.11393e-07,3.02185e-07,1.22817e-06,0.000950729,1.57821e-05,0.000926699,9.9616e-05,0.000947263,0.000918984,0,0
29985000,0.710819,0.00646176,0.0108001,0.703262,-2.19515,-1.00214,0.78565,-9.07151,-4.26009,-368.877,-1.24264e-05,-6.08897e-05,-1.24737e-05,-0.000242061,0.00027214,-0.000753231,0.211604,0.0020043,0.429504,-0.00334462,0.00158692,0.00263983,0,0,0.000209618,1.45413e-05,1.44337e-05,0.000213628,0.0289824,0.0297863,0.0388725,0.183134,0.183837,0.092909,5.44387e-11,5.4598e-11,3.61426e-10,3.06766e-07,2.9826e-07,1.21334e-06,0.000946045,1.56946e-05,0.000921847,9.89349e-05,0.00094254,0.000914115,0,0
30085000,0.71089,0.00640958,0.0106715,0.703193,-2.16443,-0.994208,0.77253,-9.28951,-4.35992,-368.801,-1.24268e-05,-6.08899e-05,-1.24741e-05,-0.000242089,0.000272216,-0.00075233,0.2118,0.00200677,0.429501,-0.00336613,0.00175787,0.00254966,0,0,0.000209905,1.47515e-05,1.46418e-05,0.000213981,0.0305111,0.0314835,0.0386356,0.195223,0.195788,0.0940409,5.45379e-11,5.46979e-11,3.61525e-10,3.06771e-07,2.98232e-07,1.20816e-06,0.000941749,1.56082e-05,0.000917374,9.83221e-05,0.000938177,0.000909621,0,0
30185000,0.710946,0.0063884,0.0104839,0.70314,-2.14912,-0.985994,0.762807,-9.53439,-4.45837,-368.718,-1.23817e-05,-6.08915e-05,-1.25165e-05,-0.000242599,0.000258338,-0.000752729,0.212053,0.00201077,0.429433,-0.00326926,0.00196694,0.00250774,0,0,0.000209382,1.48013e-05,1.46953e-05,0.000213523,0.0286015,0.0295259,0.0365554,0.192747,0.193513,0.0930681,5.46051e-11,5.47583e-11,3.61344e-10,3.02981e-07,2.95112e-07,1.19736e-06,0.000938669,1.55445e-05,0.000914202,9.7863e-05,0.000935082,0.000906436,0,0
30285000,0.711024,0.00625521,0.0102763,0.703065,-2.11855,-0.980004,0.753231,-9.74769,-4.55666,-368.636,-1.23799e-05,-6.08908e-05,-1.25139e-05,-0.00024246,0.000257958,-0.000757207,0.212117,0.0020116,0.429472,-0.00326725,0.00200429,0.00245637,0,0,0.000209686,1.50178e-05,1.49097e-05,0.000213903,0.0300796,0.0311794,0.0363056,0.20498,0.205593,0.0940732,5.47044e-11,5.48582e-11,3.61443e-10,3.02987e-07,2.9509e-07,1.19293e-06,0.000934815,1.54601e-05,0.000910197,9.73275e-05,0.000931161,0.000902411,0,0
30385000,0.71107,0.00614574,0.0100195,0.703023,-2.09133,-0.97391,0.739919,-9.96372,-4.65679,-368.561,-1.23732e-05,-6.08875e-05,-1.25081e-05,-0.000241319,0.000255596,-0.000758342,0.212002,0.0020103,0.429379,-0.00323952,0.00193775,0.00259782,0,0,0.000209108,1.50673e-05,1.49627e-05,0.000213306,0.0282161,0.0292489,0.0339093,0.20231,0.203149,0.0910612,5.4787e-11,5.49358e-11,3.61247e-10,2.99924e-07,2.92632e-07,1.18315e-06,0.000931109,1.53767e-05,0.000906388,9.67853e-05,0.000927426,0.000898586,0,0
30485000,0.711098,0.00600178,0.00974558,0.703,-2.06368,-0.967144,0.727642,-10.1714,-4.75384,-368.482,-1.23718e-05,-6.0887e-05,-1.25058e-05,-0.000241204,0.000255288,-0.000761998,0.212005,0.00201059,0.429412,-0.00320417,0.00193566,0.00257485,0,0,0.000209458,1.52897e-05,1.5183e-05,0.00021368,0.0296513,0.0308544,0.0336493,0.214663,0.215333,0.0919096,5.48864e-11,5.50357e-11,3.61345e-10,2.9993e-07,2.92615e-07,1.17937e-06,0.000927641,1.52941e-05,0.00090279,9.63146e-05,0.000923891,0.000894974,0,0
30585000,0.711422,0.00581004,0.00934111,0.702679,-2.0433,-0.962253,0.691899,-10.3953,-4.85517,-368.406,-1.23608e-05,-6.08753e-05,-1.24368e-05,-0.000237156,0.000249442,-0.000764553,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000199267,1.5338e-05,1.52344e-05,0.000203277,0.0278511,0.0289136,0.0315571,0.21182,0.212697,0.089122,5.49781e-11,5.51177e-11,3.60449e-10,2.96952e-07,2.90602e-07,1.17147e-06,0,0,0,0,0,0,0,0
30685000,0.711549,0.00559536,0.00896698,0.702557,-2.01554,-0.95492,0.684731,-10.5983,-4.95086,-368.337,-1.23614e-05,-6.08728e-05,-1.24135e-05,-0.000236516,0.000249672,-0.000765235,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000188241,1.55661e-05,1.54605e-05,0.000192017,0.0292325,0.0303833,0.0312886,0.224265,0.224925,0.089838,5.50763e-11,5.52082e-11,3.59691e-10,2.96314e-07,2.9045e-07,1.16825e-06,0,0,0,0,0,0,0,0
30785000,0.711555,0.00544794,0.00858037,0.702557,-1.9902,-0.946486,0.681647,-10.8023,-5.04263,-368.259,-1.23576e-05,-6.08731e-05,-1.24261e-05,-0.000237487,0.000247794,-0.000771711,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000177725,1.56115e-05,1.55088e-05,0.000181243,0.0274522,0.0284494,0.0294187,0.22128,0.222134,0.0872499,5.51735e-11,5.52978e-11,3.5872e-10,2.93951e-07,2.88917e-07,1.16187e-06,0,0,0,0,0,0,0,0
30885000,0.711548,0.00521769,0.00811703,0.702571,-1.96228,-0.93907,0.669711,-11,-5.13673,-368.19,-1.23578e-05,-6.08711e-05,-1.24063e-05,-0.000236969,0.00024793,-0.000772796,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000171308,1.58451e-05,1.57404e-05,0.000174603,0.0288018,0.0298953,0.0296086,0.233809,0.23447,0.0898217,5.52724e-11,5.53923e-11,3.58261e-10,2.93595e-07,2.88833e-07,1.1598e-06,0,0,0,0,0,0,0,0
30985000,0.711609,0.00506104,0.00754656,0.702517,-1.94222,-0.932557,0.664944,-11.2118,-5.23052,-368.118,-1.23598e-05,-6.08687e-05,-1.2399e-05,-0.000236269,0.000243651,-0.000774745,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000162722,1.58878e-05,1.57857e-05,0.000165785,0.0270737,0.0280223,0.0279081,0.230711,0.231566,0.0873067,5.53702e-11,5.54856e-11,3.57397e-10,2.91833e-07,2.87706e-07,1.15453e-06,0,0,0,0,0,0,0,0
31085000,0.711636,0.00480552,0.00698611,0.702498,-1.91521,-0.925097,0.653596,-11.4047,-5.32336,-368.055,-1.23606e-05,-6.08684e-05,-1.23941e-05,-0.000236164,0.00024384,-0.000773341,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000155655,1.61267e-05,1.60228e-05,0.000158546,0.0283858,0.0294081,0.0276521,0.243304,0.243965,0.0878281,5.54691e-11,5.55798e-11,3.56829e-10,2.91467e-07,2.87615e-07,1.15216e-06,0,0,0,0,0,0,0,0
31185000,0.711725,0.00457015,0.00659536,0.702413,-1.88807,-0.920407,0.643259,-11.5945,-5.41906,-367.997,-1.2363e-05,-6.08683e-05,-1.23586e-05,-0.000234813,0.000244711,-0.000768891,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000148696,1.61655e-05,1.60642e-05,0.000151379,0.0267092,0.0275965,0.0261384,0.240116,0.240969,0.085486,5.55631e-11,5.56718e-11,3.56053e-10,2.90185e-07,2.86812e-07,1.14787e-06,0,0,0,0,0,0,0,0
31285000,0.711826,0.00430559,0.00600889,0.702317,-1.85969,-0.911849,0.64421,-11.782,-5.51043,-367.935,-1.23644e-05,-6.08657e-05,-1.23284e-05,-0.000234158,0.000245133,-0.000767799,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000142926,1.64095e-05,1.63064e-05,0.000145468,0.0279818,0.0289381,0.0258795,0.252758,0.253426,0.0859003,5.56622e-11,5.5767e-11,3.55543e-10,2.89901e-07,2.86742e-07,1.14585e-06,0,0,0,0,0,0,0,0
31385000,0.711873,0.00402824,0.00540336,0.702276,-1.83643,-0.907326,0.642736,-11.9796,-5.60817,-367.87,-1.23762e-05,-6.08704e-05,-1.2308e-05,-0.000232549,0.000243249,-0.000766169,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000137169,1.64443e-05,1.63436e-05,0.00013954,0.0263542,0.0271877,0.0245263,0.249501,0.250359,0.0837156,5.57484e-11,5.5853e-11,3.5483e-10,2.88984e-07,2.86188e-07,1.14234e-06,0,0,0,0,0,0,0,0
31485000,0.711771,0.00378621,0.0047189,0.702386,-1.80746,-0.89969,0.638111,-12.1618,-5.69864,-367.807,-1.23761e-05,-6.08716e-05,-1.23226e-05,-0.000232848,0.000243169,-0.000765521,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000133632,1.66931e-05,1.6591e-05,0.000135877,0.027607,0.0285149,0.0246454,0.26218,0.262868,0.0858738,5.58478e-11,5.595e-11,3.54501e-10,2.88815e-07,2.86148e-07,1.14104e-06,0,0,0,0,0,0,0,0
31585000,0.711811,0.00356924,0.00424993,0.702349,-1.77942,-0.889111,0.63516,-12.3426,-5.78327,-367.744,-1.23788e-05,-6.08636e-05,-1.23039e-05,-0.000232909,0.000243278,-0.00076529,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000128702,1.67225e-05,1.66227e-05,0.000130786,0.0260314,0.026822,0.0234048,0.258875,0.259752,0.0837438,5.59224e-11,5.60257e-11,3.5383e-10,2.8817e-07,2.85785e-07,1.13812e-06,0,0,0,0,0,0,0,0
31685000,0.711847,0.00328772,0.00355488,0.702318,-1.7522,-0.881602,0.640548,-12.5192,-5.87152,-367.679,-1.23797e-05,-6.08605e-05,-1.22666e-05,-0.000232198,0.000243581,-0.000765713,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000124595,1.6976e-05,1.68748e-05,0.000126543,0.0272526,0.0280999,0.0231683,0.271575,0.27228,0.0840278,5.60217e-11,5.61222e-11,3.53383e-10,2.87984e-07,2.85739e-07,1.13663e-06,0,0,0,0,0,0,0,0
31785000,0.711912,0.00294115,0.00278689,0.702257,-1.72933,-0.873712,0.640938,-12.708,-5.95883,-367.618,-1.24043e-05,-6.08578e-05,-1.22451e-05,-0.000231579,0.000242578,-0.000763115,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000120405,1.69989e-05,1.69003e-05,0.000122222,0.025721,0.0264603,0.0220525,0.268239,0.269128,0.0820351,5.60814e-11,5.61841e-11,3.52747e-10,2.87546e-07,2.85515e-07,1.13424e-06,0,0,0,0,0,0,0,0
31885000,0.711956,0.00263744,0.00202838,0.702216,-1.69848,-0.863979,0.636979,-12.8795,-6.04555,-367.555,-1.24049e-05,-6.08564e-05,-1.22272e-05,-0.000231259,0.000242757,-0.000762886,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000116889,1.72569e-05,1.71571e-05,0.000118621,0.0269341,0.02773,0.0218338,0.280951,0.281674,0.0822605,5.61808e-11,5.62809e-11,3.52319e-10,2.87394e-07,2.85478e-07,1.13297e-06,0,0,0,0,0,0,0,0
31985000,0.711884,0.00237259,0.0014351,0.702292,-1.66565,-0.85388,0.633132,-13.0416,-6.12587,-367.493,-1.23936e-05,-6.0846e-05,-1.22358e-05,-0.000231751,0.00024318,-0.000762769,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000113295,1.72722e-05,1.71747e-05,0.000114899,0.0254521,0.0261492,0.0208311,0.2776,0.278505,0.0803936,5.62217e-11,5.63252e-11,3.51707e-10,2.87109e-07,2.85354e-07,1.13101e-06,0,0,0,0,0,0,0,0
32085000,0.711796,0.00204465,0.000663058,0.702384,-1.63624,-0.844935,0.639294,-13.2068,-6.21083,-367.434,-1.23943e-05,-6.08463e-05,-1.22382e-05,-0.000231819,0.000243328,-0.000760965,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000110283,1.75344e-05,1.74359e-05,0.000111778,0.0266383,0.0273852,0.0206202,0.290313,0.291057,0.0805697,5.63212e-11,5.64224e-11,3.5129e-10,2.86982e-07,2.85324e-07,1.12993e-06,0,0,0,0,0,0,0,0
32185000,0.71169,0.00168032,-0.000263189,0.702492,-1.60998,-0.836831,0.640752,-13.3779,-6.29422,-367.373,-1.24139e-05,-6.08467e-05,-1.22785e-05,-0.000232347,0.000242855,-0.000759248,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000107919,1.75408e-05,1.74452e-05,0.000109333,0.0251939,0.0258527,0.0199802,0.286963,0.287892,0.0804012,5.63409e-11,5.64468e-11,3.50822e-10,2.86831e-07,2.85271e-07,1.12856e-06,0,0,0,0,0,0,0,0
32285000,0.711669,0.00138631,-0.00107662,0.702513,-1.57886,-0.827713,0.634983,-13.5375,-6.37744,-367.315,-1.24149e-05,-6.08465e-05,-1.22736e-05,-0.000232306,0.000243077,-0.000757236,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000105247,1.78071e-05,1.77106e-05,0.000106585,0.026381,0.0270876,0.0197867,0.29967,0.30044,0.0805402,5.64404e-11,5.65441e-11,3.5041e-10,2.86722e-07,2.85247e-07,1.12763e-06,0,0,0,0,0,0,0,0
32385000,0.711695,0.00109761,-0.00179546,0.702485,-1.54171,-0.81792,0.636631,-13.6826,-6.45763,-367.246,-1.23871e-05,-6.08383e-05,-1.22189e-05,-0.000231602,0.00024335,-0.000759806,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000102482,1.78034e-05,1.77096e-05,0.000103714,0.0249789,0.0255998,0.0189467,0.296331,0.297278,0.0788263,5.64351e-11,5.65438e-11,3.49824e-10,2.86603e-07,2.85217e-07,1.1263e-06,0,0,0,0,0,0,0,0
32485000,0.711623,0.000927309,-0.0021071,0.702558,-1.51013,-0.807664,0.643171,-13.8352,-6.53869,-367.183,-1.23879e-05,-6.08362e-05,-1.21881e-05,-0.00023117,0.000243574,-0.000759687,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,0.000100161,1.80739e-05,1.79788e-05,0.000101287,0.0261476,0.026812,0.0187617,0.309021,0.309814,0.0789283,5.65347e-11,5.66412e-11,3.49414e-10,2.86509e-07,2.85198e-07,1.12551e-06,0,0,0,0,0,0,0,0
32585000,0.711523,0.000840228,-0.00240439,0.702658,-1.48193,-0.799335,0.644037,-13.9903,-6.62215,-367.112,-1.24031e-05,-6.08448e-05,-1.21815e-05,-0.000231085,0.000243547,-0.000761301,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,9.77319e-05,1.80601e-05,1.7967e-05,9.87557e-05,0.0247828,0.0253633,0.0179967,0.305708,0.306675,0.0773036,5.65021e-11,5.66145e-11,3.48834e-10,2.8642e-07,2.85173e-07,1.12442e-06,0,0,0,0,0,0,0,0
32685000,0.711456,0.000760288,-0.00251957,0.702726,-1.45136,-0.790215,0.641499,-14.137,-6.70147,-367.044,-1.2403e-05,-6.08432e-05,-1.21604e-05,-0.000230782,0.000243571,-0.000762577,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,9.56786e-05,1.83344e-05,1.82399e-05,9.66214e-05,0.0259575,0.0265767,0.0178288,0.318374,0.319191,0.0773741,5.66018e-11,5.6712e-11,3.4842e-10,2.86339e-07,2.85158e-07,1.12375e-06,0,0,0,0,0,0,0,0
32785000,0.711408,0.000713866,-0.00255477,0.702774,-1.41918,-0.780405,0.638884,-14.2736,-6.77759,-366.978,-1.23813e-05,-6.08344e-05,-1.21388e-05,-0.000230437,0.000243321,-0.000763718,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,9.40751e-05,1.83089e-05,1.82151e-05,9.49438e-05,0.024627,0.0251703,0.0173579,0.315101,0.316092,0.0773214,5.65386e-11,5.6656e-11,3.47972e-10,2.86274e-07,2.85121e-07,1.12302e-06,0,0,0,0,0,0,0,0
32885000,0.711251,0.000736344,-0.00254999,0.702933,-1.39153,-0.771389,0.640504,-14.414,-6.8553,-366.915,-1.23811e-05,-6.08353e-05,-1.21517e-05,-0.000230599,0.000243263,-0.000763502,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,9.22317e-05,1.85869e-05,1.84915e-05,9.30191e-05,0.0257927,0.0263676,0.0171983,0.327735,0.32858,0.0773675,5.66383e-11,5.67535e-11,3.47554e-10,2.86202e-07,2.85109e-07,1.12244e-06,0,0,0,0,0,0,0,0
32985000,0.711195,0.000786918,-0.00258226,0.702989,-1.36623,-0.764988,0.637427,-14.5595,-6.93398,-366.851,-1.24086e-05,-6.08399e-05,-1.21026e-05,-0.000230123,0.00024409,-0.000763324,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,9.03012e-05,1.85484e-05,1.84531e-05,9.09916e-05,0.0244892,0.0249891,0.0165492,0.324509,0.325517,0.0758675,5.65423e-11,5.66649e-11,3.46976e-10,2.86094e-07,2.85027e-07,1.12171e-06,0,0,0,0,0,0,0,0
33085000,0.711259,0.000714758,-0.00263789,0.702925,-1.33882,-0.757546,0.632375,-14.6949,-7.0095,-366.785,-1.24101e-05,-6.08342e-05,-1.20203e-05,-0.000229136,0.000244512,-0.00076397,0.212092,0.00201174,0.429502,-0.00318353,0.00192901,0.00247787,0,0,8.86512e-05,1.88293e-05,1.87326e-05,8.92818e-05,0.0256635,0.0261915,0.0164041,0.337104,0.337972,0.0758907,5.6642e-11,5.67624e-11,3.4655e-10,2.8603e-07,2.85018e-07,1.12123e-06,0,0,0,0,0,0,0,0
33185000,0.708352,0.00324443,-0.00201279,0.705849,-1.31018,-0.747607,0.583422,-14.8213,-7.08058,-366.719,-1.2371e-05,-6.07674e-05,-1.19734e-05,-0.000223933,0.000242635,-0.00076957,0.213051,0.00205611,0.429845,-0.00295159,0.00101891,0.00281275,0,0,8.65325e-05,1.85732e-05,1.84818e-05,8.62203e-05,0.02441,0.0248869,0.0158252,0.333928,0.334978,0.0744702,5.63376e-11,5.61946e-11,3.46015e-10,2.8203e-07,2.8354e-07,1.10949e-06,0.000608854,1.49583e-05,0.000595554,8.67775e-05,0.000607694,0.000593018,0,0
33285000,0.65983,0.0162645,-0.000857578,0.751238,-1.30622,-0.730111,0.551485,-14.9519,-7.15439,-366.661,-1.23771e-05,-6.0725e-05,-1.19332e-05,-0.000219987,0.00024335,-0.000768616,0.212726,0.0020837,0.429611,-0.00276926,0.00118195,0.0025399,0,0,9.20941e-05,1.87291e-05,1.86218e-05,7.73441e-05,0.0256176,0.0260894,0.015701,0.346478,0.347406,0.0744771,5.63949e-11,5.58679e-11,3.45763e-10,2.78361e-07,2.83203e-07,1.10663e-06,0.000539282,1.46668e-05,0.000528481,7.80376e-05,0.000538585,0.000527103,0,0
33385000,0.558889,0.0144886,-0.00167722,0.829114,-1.30328,-0.718349,0.744014,-15.0831,-7.22938,-366.595,-1.24084e-05,-6.07006e-05,-1.1891e-05,-0.000216975,0.000246008,-0.00076844,0.21172,0.0021007,0.429935,-0.00247926,0.00147872,0.00275289,0,0,0.000104046,1.8614e-05,1.84167e-05,6.32028e-05,0.0241309,0.0245097,0.0150844,0.343381,0.344498,0.0731364,5.61965e-11,5.54242e-11,3.45447e-10,2.75732e-07,2.82743e-07,1.10523e-06,0.000494268,1.44665e-05,0.000504672,7.21863e-05,0.000492414,0.000503735,0,0
33485000,0.422672,0.00802672,0.000849355,0.906247,-1.28708,-0.713152,0.772114,-15.2127,-7.30088,-366.516,-1.23996e-05,-6.07131e-05,-1.19021e-05,-0.000216975,0.000246008,-0.00076844,0.212157,0.00209564,0.43005,-0.00256599,0.00176699,0.00287734,0,0,0.000118239,1.89256e-05,1.858e-05,4.8983e-05,0.0254064,0.0257755,0.0150711,0.355846,0.356844,0.0744687,5.62711e-11,5.54082e-11,3.45438e-10,0,0,0,0.000449978,1.43681e-05,0.000495006,7.03101e-05,0.000441375,0.000494241,0,0
33585000,0.266081,0.00190197,-0.00164767,0.963947,-1.24612,-0.710955,0.736403,-15.3219,-7.36218,-366.444,-1.23462e-05,-6.06767e-05,-1.19308e-05,-0.000216975,0.000246008,-0.00076844,0.210825,0.00207425,0.429929,-0.00232732,0.00116275,0.00279552,0,0,0.000129098,1.87897e-05,1.83149e-05,3.75317e-05,0.0244463,0.0247536,0.0147258,0.352951,0.354128,0.0731262,5.59876e-11,5.50654e-11,3.45235e-10,0,0,0,0.000347295,1.42422e-05,0.000486749,6.80301e-05,0.000335041,0.000486109,0,0
33685000,0.0996947,-0.00154355,-0.00490065,0.995005,-1.19376,-0.707437,0.743833,-15.4439,-7.43318,-366.368,-1.23583e-05,-6.06756e-05,-1.19293e-05,-0.000216975,0.000246008,-0.00076844,0.210301,0.00207007,0.430013,-0.00232543,0.000615571,0.00288759,0,0,0.000135127,1.90001e-05,1.83725e-05,3.12896e-05,0.0259397,0.0262673,0.0149833,0.365083,0.366143,0.0730344,5.60445e-11,5.50313e-11,3.4518e-10,0,0,0,0.000255171,1.40988e-05,0.000481278,6.61697e-05,0.000238854,0.000480706,0,0
33785000,-0.0701547,-0.00326829,-0.00679412,0.997508,-1.13361,-0.690426,0.727214,-15.5648,-7.49502,-366.291,-1.24021e-05,-6.07109e-05,-1.2053e-05,-0.000216975,0.000246008,-0.00076844,0.209483,0.00200491,0.429686,-0.00207367,0.000187295,0.00268099,0,0,0.000134273,1.85985e-05,1.78616e-05,3.08666e-05,0.0250264,0.0253074,0.0151101,0.362646,0.363885,0.0717553,5.56397e-11,5.45056e-11,3.44848e-10,0,0,0,0.00018836,1.39159e-05,0.000477316,6.34759e-05,0.000169576,0.000476799,0,0
33885000,-0.23772,-0.00453364,-0.00755229,0.971294,-1.06753,-0.667221,0.713865,-15.6745,-7.56316,-366.22,-1.24167e-05,-6.08032e-05,-1.21579e-05,-0.000216975,0.000246008,-0.00076844,0.208765,0.00193341,0.429574,-0.00184151,-0.000306571,0.0026781,0,0,0.000127233,1.85873e-05,1.77756e-05,3.63137e-05,0.0267127,0.0269886,0.0158514,0.37446,0.375575,0.0716488,5.57223e-11,5.43426e-11,3.44599e-10,0,0,0,0.000144643,1.36971e-05,0.00047436,5.97152e-05,0.000124809,0.000473888,0,0
33985000,-0.385413,-0.0032094,-0.0110588,0.922673,-1.01325,-0.629328,0.686395,-15.8026,-7.62281,-366.149,-1.25772e-05,-6.08066e-05,-1.22583e-05,-0.000216975,0.000246008,-0.00076844,0.209111,0.00190895,0.429492,-0.00164648,-4.10564e-05,0.00265416,0,0,0.000115388,1.78199e-05,1.70705e-05,4.5262e-05,0.0258174,0.0260118,0.0164033,0.37244,0.37374,0.0704624,5.51867e-11,5.35767e-11,3.44008e-10,2.75736e-07,2.82747e-07,1.10523e-06,0.000116439,1.34574e-05,0.000471993,5.52702e-05,9.69209e-05,0.000471562,0,0
34085000,-0.493595,-0.00209451,-0.012791,0.869595,-0.95951,-0.58299,0.688554,-15.901,-7.68351,-366.078,-1.25797e-05,-6.08286e-05,-1.22854e-05,-0.000216975,0.000246008,-0.000768452,0.209022,0.00189159,0.429569,-0.00160204,-0.000134496,0.00274436,0,0,0.000104534,1.75874e-05,1.69638e-05,5.43911e-05,0.0276568,0.0277951,0.0178857,0.383956,0.385122,0.0716922,5.5282e-11,5.34385e-11,3.43734e-10,2.75746e-07,2.82757e-07,1.10524e-06,0.000102381,1.32786e-05,0.000470558,5.18667e-05,8.31872e-05,0.000470155,0,0
34185000,-0.56488,-0.00196039,-0.0114489,0.825092,-0.933464,-0.538315,0.691229,-16.0423,-7.75291,-366.006,-1.29355e-05,-6.09394e-05,-1.23242e-05,-0.000219489,0.000247872,-0.000769038,0.209453,0.00188856,0.429452,-0.00147785,-6.26847e-05,0.00265235,0,0,9.48358e-05,1.66387e-05,1.61522e-05,6.05543e-05,0.0267242,0.0267505,0.0190383,0.382317,0.383665,0.0705881,5.46159e-11,5.25874e-11,3.4303e-10,2.75703e-07,2.82711e-07,1.10484e-06,8.89249e-05,1.30517e-05,0.000468889,4.76417e-05,7.0718e-05,0.000468516,0,0
34285000,-0.609284,-0.0028846,-0.00855504,0.792901,-0.884816,-0.488711,0.690312,-16.1331,-7.80431,-365.937,-1.29339e-05,-6.09746e-05,-1.23752e-05,-0.000219483,0.000247876,-0.000769054,0.209595,0.00186372,0.429433,-0.00129532,-2.85577e-06,0.00265943,0,0,8.83751e-05,1.63937e-05,1.59925e-05,6.46023e-05,0.0287483,0.0286707,0.0211491,0.393552,0.394769,0.0706951,5.47143e-11,5.24364e-11,3.42638e-10,2.75713e-07,2.82721e-07,1.10484e-06,8.01209e-05,1.28502e-05,0.000467609,4.39897e-05,6.24155e-05,0.000467257,0,0
34385000,-0.636172,-0.00359253,-0.00578582,0.771517,-0.855823,-0.448801,0.690297,-16.2647,-7.86718,-365.869,-1.33081e-05,-6.11003e-05,-1.23952e-05,-0.00022469,0.000252811,-0.00076832,0.210017,0.00187022,0.429317,-0.00119208,4.94095e-05,0.00253549,0,0,8.34375e-05,1.5467e-05,1.51347e-05,6.63363e-05,0.0277489,0.0275885,0.022799,0.392252,0.393637,0.0697502,5.3942e-11,5.16034e-11,3.41937e-10,2.75443e-07,2.82438e-07,1.10249e-06,7.33029e-05,1.26694e-05,0.000466425,4.09353e-05,5.65512e-05,0.000466084,0,0
34485000,-0.652509,-0.00456697,-0.00355405,0.757759,-0.802591,-0.405067,0.68975,-16.3475,-7.90992,-365.801,-1.33083e-05,-6.11276e-05,-1.24393e-05,-0.000224672,0.000252816,-0.000768197,0.209956,0.00184838,0.429328,-0.00113721,-6.12799e-05,0.00256066,0,0,8.05528e-05,1.52882e-05,1.49854e-05,6.74837e-05,0.0299043,0.0296377,0.025578,0.40323,0.404485,0.0701046,5.40418e-11,5.15404e-11,3.41608e-10,2.75453e-07,2.82448e-07,1.10241e-06,6.86892e-05,1.25135e-05,0.000465502,3.83993e-05,5.2262e-05,0.000465166,0,0
34585000,-0.662401,-0.00476809,-0.00225781,0.749131,-0.780331,-0.378408,0.689832,-16.4872,-7.98177,-365.731,-1.38567e-05,-6.13748e-05,-1.2381e-05,-0.000236581,0.000263368,-0.000767761,0.21033,0.00187661,0.429288,-0.00117446,-0.000159947,0.00250488,0,0,7.78727e-05,1.43934e-05,1.41163e-05,6.73796e-05,0.0287773,0.0284673,0.0274601,0.402229,0.403641,0.0693413,5.31929e-11,5.07338e-11,3.40926e-10,2.74838e-07,2.81805e-07,1.09676e-06,6.45197e-05,1.23703e-05,0.000464545,3.62893e-05,4.8967e-05,0.00046421,0,0
34685000,-0.668595,-0.0051553,-0.00144096,0.743607,-0.725003,-0.33562,0.686615,-16.5624,-8.01748,-365.659,-1.38573e-05,-6.13883e-05,-1.24146e-05,-0.000236559,0.000263381,-0.000768557,0.210561,0.00186655,0.429294,-0.00100105,-2.79185e-05,0.00246776,0,0,7.65105e-05,1.42531e-05,1.39825e-05,6.75551e-05,0.0310361,0.0306214,0.030773,0.41297,0.414255,0.0700313,5.32926e-11,5.07322e-11,3.40647e-10,2.74847e-07,2.81815e-07,1.09647e-06,6.17418e-05,1.22469e-05,0.000463823,3.45212e-05,4.63978e-05,0.000463487,0,0
34785000,-0.672514,-0.00473808,-0.00101469,0.740069,-0.704236,-0.313667,0.68455,-16.6943,-8.08576,-365.587,-1.44368e-05,-6.16963e-05,-1.24057e-05,-0.000251969,0.000278233,-0.000772532,0.211134,0.0018759,0.429175,-0.000855537,-9.24999e-05,0.00229678,0,0,7.49359e-05,1.33934e-05,1.31357e-05,6.70188e-05,0.0297501,0.0293318,0.0328129,0.412232,0.413663,0.0706712,5.24007e-11,4.99668e-11,3.40063e-10,2.7382e-07,2.80747e-07,1.08667e-06,5.93363e-05,1.21562e-05,0.000463163,3.33737e-05,4.47876e-05,0.000462827,0,0
34885000,-0.67505,-0.00478378,-0.000897592,0.737756,-0.650774,-0.274118,0.683418,-16.762,-8.11515,-365.517,-1.44356e-05,-6.17088e-05,-1.24318e-05,-0.000251931,0.000278241,-0.000773355,0.211101,0.00186448,0.429167,-0.000834862,-0.000159071,0.00229903,0,0,7.4188e-05,1.32776e-05,1.3019e-05,6.69043e-05,0.0320617,0.0315403,0.0364959,0.422758,0.424065,0.0717958,5.24998e-11,5.00004e-11,3.39808e-10,2.7383e-07,2.80757e-07,1.08606e-06,5.7401e-05,1.2052e-05,0.000462572,3.20442e-05,4.30065e-05,0.000462235,0,0
34985000,-0.678192,-0.0114315,-0.00321707,0.734788,0.311685,0.358451,-0.101127,-16.8339,-8.14399,-365.51,-1.516e-05,-6.20959e-05,-1.23606e-05,-0.000274947,0.000301041,-0.000777969,0.211667,0.00189484,0.429124,-0.000804968,-0.000291883,0.00224284,0,0,7.26584e-05,1.24331e-05,1.22606e-05,6.63008e-05,0.032333,0.0332428,0.0392105,0.422173,0.423529,0.0714144,5.15987e-11,4.92522e-11,3.39213e-10,0,0,0,5.5114e-05,1.19583e-05,0.000461811,3.11208e-05,4.1548e-05,0.000461468,0,0
35085000,-0.678371,-0.0118188,-0.00361701,0.734615,0.529302,0.381555,-0.203858,-16.7832,-8.10762,-365.522,-1.51564e-05,-6.21106e-05,-1.23965e-05,-0.000274947,0.000301041,-0.000777969,0.211634,0.00187956,0.42912,-0.00077942,-0.00038288,0.00229121,0,0,7.23096e-05,1.23369e-05,1.21657e-05,6.59988e-05,0.0345809,0.0358652,0.0416141,0.432433,0.433533,0.0730493,5.16966e-11,4.93099e-11,3.38964e-10,0,0,0,5.37333e-05,1.18683e-05,0.000461256,3.00953e-05,4.02897e-05,0.000460905,0,0
35185000,-0.678448,-0.011848,-0.00365064,0.734544,0.558047,0.420682,-0.188723,-16.7287,-8.06759,-365.523,-1.51394e-05,-6.2113e-05,-1.24405e-05,-0.000274947,0.000301041,-0.000777969,0.211788,0.00186693,0.429319,-0.000701387,-0.000382857,0.00251051,0,0,7.15382e-05,1.2245e-05,1.2072e-05,6.51482e-05,0.0366776,0.037889,0.0406734,0.443317,0.444183,0.0725957,5.17909e-11,4.93749e-11,3.38722e-10,0,0,0,5.24206e-05,1.17844e-05,0.000460547,2.92008e-05,3.92158e-05,0.000460189,0,0
35285000,-0.678519,-0.011866,-0.00372272,0.734478,0.588349,0.46013,-0.183918,-16.6712,-8.02359,-365.532,-1.51354e-05,-6.21265e-05,-1.24945e-05,-0.000274947,0.000301041,-0.000777969,0.21183,0.00184997,0.429355,-0.000625161,-0.000427854,0.00258792,0,0,7.13115e-05,1.21601e-05,1.1984e-05,6.49169e-05,0.0388628,0.0399964,0.0425642,0.454889,0.455541,0.0744471,5.18875e-11,4.9447e-11,3.38485e-10,0,0,0,5.13891e-05,1.17055e-05,0.000460082,2.84137e-05,3.82888e-05,0.000459718,0,0
35385000,-0.678639,-0.0119096,-0.00370504,0.734366,0.617934,0.499048,-0.168389,-16.6108,-7.97584,-365.53,-1.51214e-05,-6.21398e-05,-1.25741e-05,-0.000274947,0.000301041,-0.000777969,0.21193,0.00182732,0.429427,-0.000536904,-0.00050472,0.00272147,0,0,7.07696e-05,1.20793e-05,1.19031e-05,6.4264e-05,0.0411354,0.0421816,0.0417015,0.467212,0.46767,0.0753035,5.19819e-11,4.95289e-11,3.38333e-10,0,0,0,5.05658e-05,1.16494e-05,0.000459551,2.78828e-05,3.76724e-05,0.000459184,0,0
35485000,-0.678793,-0.011937,-0.00370936,0.734223,0.648419,0.537281,-0.164333,-16.5474,-7.92419,-365.537,-1.51173e-05,-6.21547e-05,-1.26472e-05,-0.000274947,0.000301041,-0.000777969,0.211978,0.00180704,0.429442,-0.000444008,-0.000559252,0.00278584,0,0,7.06044e-05,1.20021e-05,1.18237e-05,6.40981e-05,0.0434951,0.0444481,0.0434567,0.480354,0.480634,0.0773534,5.2077e-11,4.96095e-11,3.38097e-10,0,0,0,4.97358e-05,1.15776e-05,0.000459145,2.72423e-05,3.69385e-05,0.000458772,0,0
35585000,0.692836,0.0118653,0.00396658,-0.720986,0.0357919,0.0368406,-0.000926509,-11.5844,-17.2181,-365.534,-1.51137e-05,-6.21626e-05,-1.26731e-05,-0.000274947,0.000301041,-0.000777971,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00137012,1.2084e-05,1.22183e-05,0.00126413,0.0346564,0.0346459,0.0375612,0.12528,0.12528,0.0727829,5.21754e-11,4.97052e-11,3.38113e-10,2.72368e-07,2.79243e-07,1.07212e-06,0,0,0,0,0,0,0,0
35685000,0.692865,0.0118738,0.00393577,-0.720959,0.0644995,0.0773805,-0.000674672,-11.5794,-17.2124,-365.529,-1.51128e-05,-6.21619e-05,-1.2672e-05,-0.000274946,0.000301041,-0.000778009,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00137006,1.21434e-05,1.22789e-05,0.00126427,0.0350241,0.0349773,0.0381386,0.12625,0.126249,0.0687823,5.22752e-11,4.98051e-11,3.38213e-10,2.72378e-07,2.79253e-07,1.07213e-06,0,0,0,0,0,0,0,0
35785000,0.692892,0.0118904,0.00396973,-0.720932,0.0868615,0.107841,-0.000305553,-11.5762,-17.2083,-365.523,-1.51114e-05,-6.21609e-05,-1.26708e-05,-0.000276306,0.000301947,-0.000778389,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00136947,1.21981e-05,1.23338e-05,0.00126395,0.0310664,0.030978,0.0365932,0.0848512,0.0848501,0.0657557,5.2375e-11,4.9905e-11,3.38313e-10,0,0,1.07158e-06,0,0,0,0,0,0,0,0
35885000,0.692942,0.0119046,0.00403009,-0.720884,0.115188,0.14907,0.000991605,-11.5661,-17.1954,-365.518,-1.51104e-05,-6.21603e-05,-1.26696e-05,-0.000276306,0.000301947,-0.000778778,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00136935,1.22636e-05,1.24001e-05,0.00126418,0.0316057,0.0314371,0.0378011,0.0865335,0.0865289,0.0637398,5.24749e-11,5.0005e-11,3.38412e-10,0,0,1.07157e-06,0,0,0,0,0,0,0,0
35985000,0.693002,0.0117958,0.00403126,-0.720828,0.12854,0.169863,0.000628499,-11.5675,-17.1928,-365.514,-1.5108e-05,-6.21576e-05,-1.26691e-05,-0.000276306,0.000301947,-0.000778534,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00136735,1.23017e-05,1.24287e-05,0.00126269,0.0284115,0.0281916,0.036855,0.0656409,0.0656346,0.062137,5.25747e-11,5.01048e-11,3.38512e-10,0,0,1.06906e-06,0,0,0,0,0,0,0,0
36085000,0.693044,0.011848,0.00404163,-0.720786,0.156799,0.210758,0.00154293,-11.5533,-17.1737,-365.51,-1.51072e-05,-6.21571e-05,-1.26683e-05,-0.000276306,0.000301947,-0.000779285,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00136727,1.23718e-05,1.25027e-05,0.00126291,0.029158,0.0288196,0.0386676,0.0678059,0.0677886,0.0624462,5.26746e-11,5.02048e-11,3.38612e-10,0,0,1.06898e-06,0,0,0,0,0,0,0,0
36185000,0.693043,0.01171,0.0040489,-0.72079,0.165463,0.22604,0.00223467,-11.5553,-17.1732,-365.505,-1.51013e-05,-6.21497e-05,-1.26679e-05,-0.000276306,0.000301947,-0.000779942,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00136351,1.23836e-05,1.25e-05,0.00125947,0.0265004,0.0261077,0.0380995,0.0549552,0.054936,0.0617128,5.27743e-11,5.03045e-11,3.38712e-10,0,0,1.06339e-06,0,0,0,0,0,0,0,0
36285000,0.6931,0.0117874,0.00403082,-0.720734,0.193397,0.266772,0.00486835,-11.5374,-17.1485,-365.496,-1.50999e-05,-6.21487e-05,-1.26664e-05,-0.000276306,0.000301947,-0.000782765,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00136339,1.24585e-05,1.25807e-05,0.00125976,0.0274348,0.0268879,0.0402885,0.0574902,0.0574478,0.0620712,5.28742e-11,5.04045e-11,3.38812e-10,0,0,1.06304e-06,0,0,0,0,0,0,0,0
36385000,0.693088,0.0116216,0.00402901,-0.720748,0.200413,0.27611,0.00491309,-11.538,-17.15,-365.492,-1.50891e-05,-6.21338e-05,-1.26672e-05,-0.000276306,0.000301947,-0.00078446,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00135716,1.24351e-05,1.25372e-05,0.00125424,0.0251235,0.0245438,0.0398772,0.0485401,0.0484976,0.0619014,5.29733e-11,5.05037e-11,3.38912e-10,0,0,1.0535e-06,0,0,0,0,0,0,0,0
36485000,0.693135,0.0116869,0.00408775,-0.720702,0.229285,0.316155,0.00617921,-11.5165,-17.1204,-365.489,-1.50888e-05,-6.21336e-05,-1.26669e-05,-0.000276306,0.000301947,-0.000785437,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.0013571,1.25159e-05,1.26222e-05,0.0012545,0.0262213,0.0254677,0.0423766,0.0513777,0.0512952,0.0630281,5.30732e-11,5.06037e-11,3.39012e-10,0,0,1.05268e-06,0,0,0,0,0,0,0,0
36585000,0.693132,0.0114463,0.00403569,-0.720709,0.231648,0.322137,0.00917558,-11.5197,-17.125,-365.484,-1.50695e-05,-6.21065e-05,-1.26688e-05,-0.000276306,0.000301947,-0.000788507,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00134815,1.245e-05,1.25289e-05,0.00124673,0.0241515,0.0233702,0.0419335,0.0445527,0.044475,0.0631628,5.31713e-11,5.0702e-11,3.39112e-10,0,0,1.03877e-06,0,0,0,0,0,0,0,0
36685000,0.693193,0.0114394,0.00400328,-0.72065,0.259371,0.362228,0.0112088,-11.4952,-17.0908,-365.48,-1.50692e-05,-6.21063e-05,-1.26684e-05,-0.000276306,0.000301947,-0.000790462,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00134805,1.25347e-05,1.26141e-05,0.00124705,0.0253999,0.0244139,0.0448777,0.0476474,0.0475089,0.0659531,5.32713e-11,5.0802e-11,3.39212e-10,0,0,1.0377e-06,0,0,0,0,0,0,0,0
36785000,0.693203,0.0110929,0.0039903,-0.720646,0.25853,0.364407,0.0129557,-11.501,-17.0982,-365.475,-1.50383e-05,-6.20632e-05,-1.26718e-05,-0.000276306,0.000301947,-0.000790714,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00133637,1.24221e-05,1.24653e-05,0.00123681,0.0234786,0.0224921,0.044266,0.042057,0.0419315,0.0661993,5.33676e-11,5.08986e-11,3.39312e-10,0,0,1.01949e-06,0,0,0,0,0,0,0,0
36885000,0.693264,0.0111498,0.00399938,-0.720587,0.285609,0.402286,0.0145538,-11.4738,-17.0599,-365.472,-1.50381e-05,-6.2063e-05,-1.26716e-05,-0.000276306,0.000301947,-0.000792443,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00133628,1.25122e-05,1.25592e-05,0.00123713,0.024841,0.0236433,0.0470891,0.0453749,0.045165,0.0684082,5.34676e-11,5.09986e-11,3.39412e-10,0,0,1.0173e-06,0,0,0,0,0,0,0,0
36985000,0.693221,0.0106741,0.00387954,-0.720635,0.281777,0.399008,0.0145776,-11.4826,-17.0712,-365.469,-1.49929e-05,-6.19987e-05,-1.26773e-05,-0.000276306,0.000301947,-0.000791476,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00132209,1.23481e-05,1.23526e-05,0.00122444,0.0230008,0.0218417,0.0461852,0.0405216,0.0403373,0.0685978,5.35611e-11,5.10927e-11,3.39512e-10,0,0,9.95208e-07,0,0,0,0,0,0,0,0
37085000,0.693262,0.0107066,0.0038614,-0.720596,0.308886,0.436853,0.0179449,-11.4531,-17.0294,-365.465,-1.49928e-05,-6.19986e-05,-1.26771e-05,-0.000276306,0.000301947,-0.000793452,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00132208,1.24428e-05,1.24497e-05,0.00122471,0.0244708,0.0230891,0.0489769,0.0440352,0.043742,0.0711044,5.36611e-11,5.11927e-11,3.39612e-10,0,0,9.92103e-07,0,0,0,0,0,0,0,0
37185000,0.693162,0.0101431,0.0037765,-0.7207,0.301822,0.427179,0.0199841,-11.4647,-17.0456,-365.464,-1.49304e-05,-6.19068e-05,-1.26858e-05,-0.000276306,0.000301947,-0.0007951,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00130542,1.22274e-05,1.21902e-05,0.00120992,0.0226611,0.0213613,0.0477169,0.0396201,0.0393694,0.071116,5.37508e-11,5.12831e-11,3.39712e-10,0,0,9.66953e-07,0,0,0,0,0,0,0,0
37285000,0.6932,0.0101626,0.00381242,-0.720663,0.328017,0.464202,0.0220272,-11.4333,-17.0011,-365.46,-1.49303e-05,-6.19068e-05,-1.26857e-05,-0.000276306,0.000301947,-0.000796528,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00130544,1.23272e-05,1.22912e-05,0.00121018,0.024215,0.0226868,0.0503904,0.0433051,0.0429218,0.0737938,5.38508e-11,5.13831e-11,3.39812e-10,0,0,9.62953e-07,0,0,0,0,0,0,0,0
37385000,0.693063,0.00949846,0.00366881,-0.720805,0.316531,0.448941,0.0229838,-11.448,-17.0215,-365.459,-1.48477e-05,-6.1785e-05,-1.26972e-05,-0.000276306,0.000301947,-0.000797058,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00128688,1.20602e-05,1.19821e-05,0.00119362,0.0224028,0.0209952,0.0491986,0.03914,0.038819,0.0749255,5.39353e-11,5.14685e-11,3.39911e-10,0,0,9.36789e-07,0,0,0,0,0,0,0,0
37485000,0.693122,0.00951713,0.00365767,-0.720748,0.341588,0.486373,0.0246126,-11.4151,-16.9747,-365.457,-1.48477e-05,-6.1785e-05,-1.26972e-05,-0.000276306,0.000301947,-0.000796412,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00128684,1.21641e-05,1.20875e-05,0.00119396,0.0240297,0.0223802,0.0517461,0.0429745,0.0424988,0.0777724,5.40353e-11,5.15685e-11,3.40011e-10,0,0,9.32214e-07,0,0,0,0,0,0,0,0
37585000,0.692897,0.00874692,0.0035347,-0.720975,0.326413,0.467857,0.0298347,-11.4327,-16.9992,-365.451,-1.47433e-05,-6.163e-05,-1.27118e-05,-0.000276306,0.000301947,-0.000803655,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00126704,1.18487e-05,1.17351e-05,0.00117593,0.0222112,0.0207051,0.0497708,0.0389378,0.0385462,0.0772086,5.41133e-11,5.16475e-11,3.40111e-10,0,0,9.03966e-07,0,0,0,0,0,0,0,0
37685000,0.692931,0.0087946,0.00358185,-0.720941,0.349946,0.504155,0.0352632,-11.3989,-16.9506,-365.442,-1.47432e-05,-6.163e-05,-1.27116e-05,-0.000276306,0.000301947,-0.00080913,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00126709,1.19572e-05,1.18455e-05,0.00117619,0.0238816,0.0221333,0.0520876,0.042902,0.0423351,0.0800351,5.42133e-11,5.17475e-11,3.40211e-10,0,0,8.98756e-07,0,0,0,0,0,0,0,0
37785000,0.692684,0.00788486,0.00349134,-0.72119,0.332105,0.481678,0.0396668,-11.4194,-16.979,-365.435,-1.46161e-05,-6.14388e-05,-1.27299e-05,-0.000276306,0.000301947,-0.000814307,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00124637,1.15972e-05,1.14573e-05,0.00115738,0.0220363,0.0204659,0.0498204,0.038915,0.0384547,0.0791392,5.42833e-11,5.18186e-11,3.40311e-10,0,0,8.7044e-07,0,0,0,0,0,0,0,0
37885000,0.692734,0.00789217,0.00349817,-0.721142,0.354624,0.516108,0.0405769,-11.3851,-16.9291,-365.435,-1.46161e-05,-6.14387e-05,-1.273e-05,-0.000276306,0.000301947,-0.000810667,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.0012464,1.17096e-05,1.15706e-05,0.00115771,0.0237239,0.0219259,0.0518812,0.0429889,0.0423366,0.0818757,5.43833e-11,5.19186e-11,3.40411e-10,0,0,8.6478e-07,0,0,0,0,0,0,0,0
37985000,0.692494,0.00694334,0.00340623,-0.721382,0.334055,0.490047,0.0430176,-11.409,-16.9612,-365.432,-1.44621e-05,-6.12097e-05,-1.27523e-05,-0.000276306,0.000301947,-0.000808635,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00122546,1.13104e-05,1.11585e-05,0.00113855,0.0218453,0.0202581,0.0499639,0.039001,0.038478,0.0823679,5.44439e-11,5.19803e-11,3.40511e-10,0,0,8.38628e-07,0,0,0,0,0,0,0,0
38085000,0.692504,0.00696461,0.00342293,-0.721373,0.354735,0.522699,0.0497859,-11.3746,-16.9106,-365.421,-1.44621e-05,-6.12098e-05,-1.27522e-05,-0.000276306,0.000301947,-0.000813744,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00122563,1.14267e-05,1.12758e-05,0.00113876,0.023537,0.0217335,0.0518264,0.0431652,0.0424377,0.0850797,5.45439e-11,5.20803e-11,3.40611e-10,0,0,8.32896e-07,0,0,0,0,0,0,0,0
38185000,0.692431,0.00669142,0.00336384,-0.721445,0.359136,0.532414,0.0480654,-11.3708,-16.9041,-365.421,-1.44263e-05,-6.1155e-05,-1.27572e-05,-0.000276306,0.000301947,-0.000804962,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.0012192,1.13918e-05,1.12406e-05,0.00113295,0.0235285,0.0216795,0.0491786,0.0407977,0.0400625,0.0835765,5.46361e-11,5.21723e-11,3.40711e-10,0,0,8.06579e-07,0,0,0,0,0,0,0,0
38285000,0.692478,0.00671408,0.0033789,-0.7214,0.380605,0.563703,0.0499201,-11.3339,-16.8493,-365.418,-1.44263e-05,-6.1155e-05,-1.27572e-05,-0.000276306,0.000301947,-0.000803958,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00121927,1.1513e-05,1.13628e-05,0.00113329,0.025343,0.023283,0.0507912,0.0454131,0.044419,0.0861184,5.47361e-11,5.22723e-11,3.40811e-10,0,0,8.0074e-07,0,0,0,0,0,0,0,0
38385000,0.692363,0.00632848,0.00328223,-0.721514,0.380591,0.567115,0.0467284,-11.3353,-16.8503,-365.417,-1.43696e-05,-6.10679e-05,-1.27652e-05,-0.000276306,0.000301947,-0.000793306,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00121084,1.14218e-05,1.12735e-05,0.00112562,0.0250781,0.0230233,0.0480815,0.0428061,0.0418432,0.0843999,5.48219e-11,5.23581e-11,3.40911e-10,0,0,7.76188e-07,0,0,0,0,0,0,0,0
38485000,0.692411,0.00632991,0.00330944,-0.721468,0.40174,0.599102,0.0476756,-11.2962,-16.792,-365.414,-1.43696e-05,-6.10678e-05,-1.27653e-05,-0.000276306,0.000301947,-0.00079116,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00121093,1.15478e-05,1.14004e-05,0.00112598,0.0270118,0.0247296,0.0494605,0.0478638,0.0465911,0.0867574,5.49219e-11,5.24581e-11,3.41011e-10,0,0,7.70389e-07,0,0,0,0,0,0,0,0
38585000,0.692228,0.0058631,0.00316513,-0.721648,0.397822,0.595131,0.0424034,-11.3035,-16.8012,-365.418,-1.42877e-05,-6.09411e-05,-1.27773e-05,-0.000276306,0.000301947,-0.000777343,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00120063,1.13941e-05,1.12529e-05,0.00111643,0.0264362,0.0242311,0.0467473,0.0449136,0.0437247,0.0848753,5.4999e-11,5.25353e-11,3.4111e-10,0,0,7.47826e-07,0,0,0,0,0,0,0,0
38685000,0.69229,0.00593383,0.00319015,-0.721588,0.417641,0.624438,0.0428928,-11.2627,-16.7402,-365.419,-1.42876e-05,-6.09409e-05,-1.27773e-05,-0.000276306,0.000301947,-0.000773253,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00120071,1.15246e-05,1.13845e-05,0.00111687,0.0284295,0.0260115,0.0485381,0.0503876,0.048845,0.0889807,5.5099e-11,5.26353e-11,3.4121e-10,0,0,7.43618e-07,0,0,0,0,0,0,0,0
38785000,0.692069,0.0053188,0.00308721,-0.721805,0.407979,0.611648,0.0422422,-11.2762,-16.7587,-365.417,-1.41774e-05,-6.07694e-05,-1.27941e-05,-0.000276306,0.000301947,-0.000767937,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00118869,1.13059e-05,1.11787e-05,0.00110573,0.0275055,0.0252379,0.0458143,0.0470057,0.0456142,0.0868944,5.51651e-11,5.27014e-11,3.4131e-10,0,0,7.22936e-07,0,0,0,0,0,0,0,0
38885000,0.692114,0.00548355,0.00315973,-0.72176,0.417344,0.626048,0.48988,-11.2347,-16.6964,-365.401,-1.41774e-05,-6.07695e-05,-1.27941e-05,-0.000276306,0.000301947,-0.000769835,0.211941,0.00179793,0.429407,-0.000432996,-0.000621003,0.00278558,0,0,0.00118884,1.14405e-05,1.13138e-05,0.00110611,0.0286556,0.0262794,0.0461724,0.0528387,0.051063,0.0889576,5.52651e-11,5.28014e-11,3.4141e-10,0,0,7.17618e-07,0,0,0,0,0,0,0,0
1 Timestamp state[0] state[1] state[2] state[3] state[4] state[5] state[6] state[7] state[8] state[9] state[10] state[11] state[12] state[13] state[14] state[15] state[16] state[17] state[18] state[19] state[20] state[21] state[22] state[23] variance[0] variance[1] variance[2] variance[3] variance[4] variance[5] variance[6] variance[7] variance[8] variance[9] variance[10] variance[11] variance[12] variance[13] variance[14] variance[15] variance[16] variance[17] variance[18] variance[19] variance[20] variance[21] variance[22] variance[23]
2 15000 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
3 85000 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
4 185000 1 0.999749 0 -0.0104072 0 -0.0107851 0 -0.0166593 0 0.00012003 0 -0.0001068 0 -0.0115085 0 1.36678e-05 0 -4.60777e-06 0 -0.000265302 0 4.01008e-11 0 1.70856e-14 0 1.83726e-09 0 0 0 -7.93589e-11 0 0.191453 0 0.00184374 0 0.404156 0 0 0 0 0 0 1.59693e-06 0 0.00250808 0 0.00250843 0 0.00375232 0 0.25346 0 0.25346 0 0.562563 0 0.126411 0 0.126411 0 1.00079 0 1e-06 0 1e-06 0 9.99741e-07 0 0 0 4.00001e-06 0 0 0 0 0 0 0 0
5 285000 1 0.999744 0 -0.0104987 0 -0.0111244 0 -0.0166782 0 0.00135698 0 0.000386592 0 -0.0252008 0 7.07676e-05 0 -1.58824e-05 0 -0.00161355 0 1.21187e-09 0 4.4155e-12 0 5.4969e-08 0 0 0 -1.75435e-09 0 0.191453 0 0.00184374 0 0.404156 0 0 0 0 0 0 1.2861e-06 0 0.00255798 0 0.00255845 0 0.00252773 0 0.273498 0 0.2735 0 0.562506 0 0.13279 0 0.13279 0 0.576885 0 9.99999e-07 0 1e-06 0 9.97806e-07 0 0 0 4.00001e-06 0 0 0 0 0 0 0 0
6 385000 0.989603 0.995986 -0.00857216 -0.00937192 -0.0119078 -0.011663 0.143073 0.0882481 0.000133666 -0.00105457 -0.000277178 0.000727164 -0.00414673 -0.0421913 9.49438e-07 -0.000126013 -2.44198e-06 4.30077e-05 -6.03039e-05 -0.00388401 0 -7.24905e-06 0 -2.45061e-08 0 -0.000346141 0 0 0 -1.90333e-08 0.152965 0.191453 0.00147309 0.00184374 0.410088 0.404156 0 0 0 0 0 0.000102935 1.0727e-06 0.00248519 0.00265582 0.0024849 0.00265636 0.00489915 0.00179473 25.0004 0.305224 25.0004 0.305231 0.562573 0.560129 0.259374 0.0939616 0.259374 0.0939617 4.00051 0.375592 1e-06 9.99993e-07 1e-06 9.99998e-07 1e-06 9.90503e-07 0 0 4e-06 3.99998e-06 0 0 0 0 0 0 0 0
7 485000 0.873043 0.979986 -0.00536963 -0.0101668 -0.0150435 -0.014249 0.487382 0.198297 0.0032852 0.00996126 -0.00268215 -0.0132919 -0.0560697 -0.0813196 0.000172131 0.00123764 -0.000145157 -0.00204204 -0.0022496 -0.0088471 2.10632e-08 -8.59997e-06 2.20741e-06 1.2756e-05 -9.68587e-05 -0.000975495 0 0 -1.10347e-09 -1.13398e-07 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000100385 1.6917e-06 0.00250732 0.00280417 0.00250648 0.00280445 0.00321251 0.00143844 25.009 0.366383 25.009 0.366396 0.563297 0.554098 0.609397 0.108558 0.609397 0.108558 0.802449 0.287379 1e-06 9.9999e-07 1e-06 9.99986e-07 9.99306e-07 9.75764e-07 0 0 4.00001e-06 3.99978e-06 0 0 0 0 0 0 0 0
8 585000 0.824127 0.956922 -0.00455437 -0.012385 -0.0165729 -0.0191055 0.566144 0.28945 0.00699165 0.0484905 -0.00309858 -0.0394046 -0.143324 -0.147103 0.000215882 0.00716773 -0.000108838 -0.00676485 -0.0115127 -0.0198357 1.22864e-07 -3.14027e-07 7.37986e-06 4.65186e-05 -0.000290141 -0.00176828 0 0 -3.82915e-08 -5.35383e-07 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 8.31666e-05 5.48324e-06 0.00257636 0.0029612 0.00257509 0.00296079 0.00215765 0.00124701 7.81318 0.411614 7.81318 0.411657 0.564696 0.543717 0.228164 0.0893979 0.228164 0.0893988 0.451649 0.24203 1e-06 9.99742e-07 9.99996e-07 9.99698e-07 9.94631e-07 9.52429e-07 0 0 4e-06 3.99919e-06 0 0 0 0 0 0 0 0
9 685000 0.795498 0.928109 -0.00413653 -0.0144953 -0.0176833 -0.0246496 0.605685 0.371209 0.0171541 0.114968 -0.00419003 -0.0683776 -0.237402 -0.243075 0.00162021 0.0233273 -0.000502731 -0.0165798 -0.0283793 -0.0396472 3.22707e-07 8.10302e-06 1.41331e-05 9.54591e-05 -0.000523548 -0.00271727 0 0 -3.07404e-07 -1.89024e-06 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 9.50057e-05 1.56118e-05 0.0026951 0.00320119 0.00269348 0.00319973 0.00166608 0.0011381 7.85164 0.514176 7.85165 0.514338 0.564631 0.528124 0.486038 0.114591 0.486038 0.114597 0.322081 0.217523 1e-06 9.9974e-07 9.99986e-07 9.99608e-07 9.82817e-07 9.1905e-07 0 0 3.99989e-06 3.99786e-06 0 0 0 0 0 0 0 0
10 785000 0.776637 0.894476 -0.0037867 -0.0154738 -0.0186074 -0.0300092 0.629662 0.445839 0.0184876 0.184087 -0.00234201 -0.0767286 -0.31876 -0.358093 0.000927229 0.0365285 -0.000187065 -0.0195363 -0.0544486 -0.0730037 5.98717e-07 1.28051e-05 2.11077e-05 0.000156564 -0.000752349 -0.00373955 0 0 -9.39324e-07 -4.62801e-06 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000126298 3.54678e-05 0.00285709 0.0033053 0.00285512 0.00330249 0.00138078 0.00107209 2.59846 0.535868 2.59847 0.536228 0.565093 0.515266 0.195718 0.099003 0.195718 0.0990154 0.277167 0.215673 9.99947e-07 9.972e-07 9.99914e-07 9.96911e-07 9.61995e-07 8.76087e-07 0 0 3.99965e-06 3.99613e-06 0 0 0 0 0 0 0 0
11 885000 0.761537 0.860502 -0.00356561 -0.0163393 -0.0193954 -0.0359576 0.647821 0.507914 0.0309543 0.288615 0.000136874 -0.0795021 -0.394552 -0.480899 0.00363055 0.0735356 -0.000258594 -0.0289842 -0.0989389 -0.130781 9.84626e-07 1.73639e-05 2.83689e-05 0.000226046 -0.000980539 -0.00370834 0 0 -1.02684e-06 -5.20191e-06 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000172615 6.66054e-05 0.00307433 0.00362336 0.00307199 0.00361831 0.00119368 0.00102584 2.66011 0.675504 2.66014 0.676339 0.575936 0.524053 0.329464 0.136491 0.329464 0.136539 0.30756 0.25647 9.99947e-07 9.97199e-07 9.99882e-07 9.96624e-07 9.30419e-07 8.23811e-07 0 0 3.99966e-06 3.99614e-06 0 0 0 0 0 0 0 0
12 985000 0.750605 0.833588 -0.00332776 -0.0147324 -0.0200672 -0.0374469 0.660438 0.550919 0.0442467 0.310006 0.00297509 -0.0511159 -0.448454 -0.572444 0.0076697 0.0734012 -2.24434e-06 -0.0217008 -0.148863 -0.198167 1.32346e-06 8.81419e-06 3.37909e-05 0.000264187 -0.00114481 -0.00349066 0 0 -1.07041e-06 -6.44094e-06 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000237131 0.000110853 0.00334084 0.00354161 0.00333813 0.00353558 0.00110676 0.0010277 2.74789 0.629197 2.74795 0.630177 0.589654 0.534925 0.517242 0.113221 0.517244 0.113269 0.349642 0.30796 9.99947e-07 9.86776e-07 9.99848e-07 9.85971e-07 8.99523e-07 7.79505e-07 0 0 3.99967e-06 3.99613e-06 0 0 0 0 0 0 0 0
13 1085000 0.738766 0.802904 -0.00312073 -0.014513 -0.0207373 -0.0422629 0.673636 0.594431 0.0469934 0.410278 0.00631671 -0.0295526 -0.502946 -0.675784 0.00644321 0.121065 0.000519088 -0.0240301 -0.206395 -0.281338 1.55343e-06 1.00228e-05 4.00967e-05 0.000324351 -0.00133222 -0.00349066 0 0 -1.11788e-06 -6.80889e-06 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000303816 0.000162225 0.00362807 0.00391918 0.00362491 0.00391014 0.000998511 0.000986323 1.28895 0.794998 1.28902 0.796688 0.605335 0.547532 0.244167 0.161112 0.244168 0.161244 0.403746 0.370432 9.99313e-07 9.86776e-07 9.99157e-07 9.855e-07 8.49714e-07 7.16002e-07 0 0 3.99968e-06 3.99614e-06 0 0 0 0 0 0 0 0
14 1185000 0.728138 0.774814 -0.00293566 -0.0111688 -0.0213864 -0.0406336 0.68509 0.630783 0.0619802 0.369104 0.0103432 0.00968837 -0.544385 -0.763729 0.012204 0.0985943 0.0015029 -0.0116675 -0.266853 -0.373036 1.94941e-06 -1.22529e-05 4.54893e-05 0.00034515 -0.00148444 -0.00349066 0 0 -1.13815e-06 -8.84877e-06 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000373673 0.000218783 0.00399142 0.00362096 0.00398771 0.00361191 0.000912053 0.000941244 1.41199 0.669001 1.41211 0.670415 0.623813 0.562059 0.351605 0.123851 0.351609 0.12394 0.470375 0.444253 9.99313e-07 9.62032e-07 9.99085e-07 9.60442e-07 7.92293e-07 6.50065e-07 0 0 3.99969e-06 3.99609e-06 0 0 0 0 0 0 0 0
15 1285000 0.718913 0.750033 -0.00263894 -0.0103668 -0.0218149 -0.0437067 0.694753 0.659873 0.0623883 0.443347 0.0132016 0.0404969 -0.573057 -0.828258 0.0100819 0.144961 0.00168317 -0.00705263 -0.327915 -0.467935 1.31663e-06 -1.20743e-05 4.88296e-05 0.000380202 -0.00158775 -0.00349066 0 0 -1.18406e-06 -9.05452e-06 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000442006 0.000277008 0.00430784 0.00403772 0.00430363 0.00402578 0.000839067 0.00089222 0.88672 0.847308 0.886854 0.849332 0.64532 0.578704 0.196911 0.177447 0.196914 0.177645 0.550125 0.529866 9.95822e-07 9.62032e-07 9.95513e-07 9.59932e-07 7.29291e-07 5.84164e-07 0 0 3.99969e-06 3.9961e-06 0 0 0 0 0 0 0 0
16 1385000 0.710664 0.728209 -0.00248824 -0.00643711 -0.0223633 -0.0388839 0.703171 0.684221 0.077594 0.345159 0.0194662 0.0612047 -0.593152 -0.879653 0.0172375 0.100945 0.0034496 0.000924668 -0.389065 -0.56588 1.52808e-06 -4.50925e-05 5.13907e-05 0.000361472 -0.00165592 -0.00354154 0 0 -1.18834e-06 -1.14597e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000504887 0.000333044 0.00476305 0.00359664 0.00475815 0.00358681 0.000775431 0.00083814 1.05403 0.669493 1.05423 0.670787 0.669981 0.597257 0.273433 0.128151 0.273443 0.128249 0.643692 0.627746 9.95821e-07 9.20087e-07 9.9542e-07 9.17947e-07 6.63746e-07 5.20186e-07 0 0 3.9997e-06 3.99604e-06 0 0 0 0 0 0 0 0
17 1485000 0.703484 0.709624 -0.00215002 -0.00554697 -0.0224526 -0.0406711 0.710353 0.703384 0.0746768 0.394446 0.0216206 0.0900457 -0.610058 -0.913368 0.0138393 0.139496 0.00326718 0.00927935 -0.450268 -0.662392 -1.08398e-06 -4.47418e-05 5.13457e-05 0.000374255 -0.00168925 -0.00352254 0 0 -1.27411e-06 -1.15357e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000560261 0.000384949 0.0050028 0.00403494 0.00499758 0.00402292 0.000718738 0.000783852 0.81848 0.851957 0.818678 0.853628 0.697829 0.618173 0.171176 0.183179 0.171183 0.183372 0.75185 0.7385 9.83423e-07 9.20086e-07 9.82944e-07 9.17591e-07 5.98938e-07 4.6094e-07 0 0 3.9997e-06 3.99605e-06 0 0 0 0 0 0 0 0
18 1585000 0.697385 0.694313 -0.00197633 -0.00176333 -0.0228396 -0.034694 0.71633 0.718834 0.0883755 0.279046 0.0280848 0.0880863 -0.623672 -0.939379 0.0219981 0.0891194 0.00573443 0.0100076 -0.511978 -0.759823 -1.07812e-06 -8.28273e-05 5.14128e-05 0.000331516 -0.00169099 -0.00349582 0 0 -1.27415e-06 -1.37468e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000629453 0.000447305 0.00553687 0.00352664 0.00553094 0.00351797 0.000692817 0.000756669 1.03667 0.655558 1.03695 0.656465 0.728778 0.641041 0.237839 0.127726 0.237856 0.127807 0.875451 0.862708 9.83423e-07 8.61435e-07 9.82875e-07 8.59286e-07 5.5197e-07 4.19438e-07 0 0 3.99971e-06 3.99599e-06 0 0 0 0 0 0 0 0
19 1685000 0.693162 0.681945 -0.00146275 -0.000773111 -0.0223927 -0.0357615 0.720433 0.730528 0.0810576 0.311112 0.0296606 0.115069 -0.635863 -0.949784 0.0168264 0.118602 0.00492085 0.0201498 -0.575307 -0.85403 -7.04487e-06 -8.28769e-05 4.68718e-05 0.000331085 -0.00164827 -0.0034796 0 0 -1.42489e-06 -1.37449e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000667764 0.000487811 0.00552227 0.00397205 0.00551657 0.00396186 0.000643773 0.000700476 0.882656 0.837936 0.882892 0.839027 0.762581 0.666255 0.159426 0.181918 0.159437 0.182067 1.01538 1.00113 9.51599e-07 8.61433e-07 9.51006e-07 8.59109e-07 4.92619e-07 3.69485e-07 0 0 3.9997e-06 3.996e-06 0 0 0 0 0 0 0 0
20 1785000 0.688801 0.670318 -0.0012436 0.000325294 -0.0227101 -0.036766 0.724593 0.741162 0.0949689 0.341977 0.0378508 0.144848 -0.651971 -0.961107 0.0254986 0.151056 0.00819823 0.0330039 -0.640843 -0.948739 -7.14823e-06 -8.31082e-05 4.55646e-05 0.000329479 -0.0016127 -0.00345425 0 0 -1.42454e-06 -1.37388e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000696221 0.000520708 0.00610853 0.00445355 0.00610208 0.00444167 0.000599744 0.000647196 1.14829 1.06047 1.14861 1.06172 0.799277 0.693799 0.226764 0.258824 0.226788 0.259072 1.17259 1.15453 9.51598e-07 8.6143e-07 9.50932e-07 8.58933e-07 4.38039e-07 3.25235e-07 0 0 3.99971e-06 3.99601e-06 0 0 0 0 0 0 0 0
21 1885000 0.684729 0.660367 -0.000443559 0.00374111 -0.0216395 -0.0315506 0.728476 0.75027 0.0788938 0.231312 0.0367569 0.135002 -0.669842 -0.975247 0.0183086 0.096454 0.00659167 0.0289763 -0.709709 -1.04685 -1.68846e-05 -0.000117211 3.90306e-05 0.000289851 -0.00157486 -0.00340043 0 0 -1.63824e-06 -1.56614e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000716372 0.000547341 0.00566002 0.00386723 0.00565468 0.00385361 0.000558894 0.000592087 0.971056 0.820919 0.971275 0.821539 0.838384 0.722604 0.156213 0.177469 0.156226 0.177596 1.34801 1.32349 8.9045e-07 7.87864e-07 8.89804e-07 7.856e-07 3.88834e-07 2.85474e-07 0 0 3.9997e-06 3.99596e-06 0 0 0 0 0 0 0 0
22 1985000 0.681947 0.652374 -0.000266737 0.00495541 -0.0218138 -0.0336707 0.731076 0.757133 0.0893574 0.26354 0.0446547 0.178032 -0.692518 -0.982076 0.0265368 0.126108 0.0106216 0.0483495 -0.78457 -1.14312 -1.70013e-05 -0.000110872 3.70254e-05 0.000301843 -0.00151333 -0.00330983 0 0 -1.63922e-06 -1.6057e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000728971 0.00056819 0.00625746 0.00433993 0.00625151 0.004317 0.000522792 0.000543487 1.26603 1.04099 1.26632 1.04159 0.879927 0.754356 0.228245 0.252254 0.228272 0.252496 1.54267 1.50928 8.9045e-07 7.87697e-07 8.89758e-07 7.85001e-07 3.44909e-07 2.51257e-07 0 0 3.99971e-06 3.99597e-06 0 0 0 0 0 0 0 0
23 2085000 0.680376 0.646508 0.000644228 0.00762943 -0.0202761 -0.0293765 0.732582 0.762303 0.0666931 0.172592 0.0377439 0.160436 -0.72217 -0.996243 0.017395 0.0799867 0.00772231 0.0393854 -0.867867 -1.24551 -2.91839e-05 -0.000137325 2.7456e-05 0.000266225 -0.00143551 -0.00319528 0 0 -1.87274e-06 -1.78075e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000735499 0.000583149 0.00535096 0.00371112 0.00534671 0.00369337 0.000488751 0.000498252 1.01071 0.802743 1.01088 0.802818 0.923402 0.78727 0.156001 0.172044 0.156013 0.172141 1.75747 1.71229 8.00793e-07 7.02472e-07 8.00185e-07 7.0063e-07 3.061e-07 2.21757e-07 0 0 3.99969e-06 3.99594e-06 0 0 0 0 0 0 0 0
24 2185000 0.678162 0.640302 0.00086873 0.00880812 -0.0207403 -0.0312452 0.734619 0.767437 0.0760968 0.194151 0.0486686 0.203595 -0.751552 -1.00903 0.0249739 0.102635 0.0127309 0.0607268 -0.953968 -1.34815 -2.77314e-05 -0.000130639 2.79212e-05 0.000274909 -0.0013773 -0.0030942 0 0 -1.90259e-06 -1.82662e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000736905 0.00059393 0.00591738 0.00416218 0.00591035 0.00413899 0.000459 0.000459305 1.30832 1.01947 1.30845 1.01929 0.969067 0.823273 0.231498 0.244717 0.231514 0.244869 1.99361 1.93417 8.00704e-07 7.02362e-07 8.00061e-07 7.00444e-07 2.71967e-07 1.96499e-07 0 0 3.9997e-06 3.99595e-06 0 0 0 0 0 0 0 0
25 2285000 0.67637 0.63452 0.0016509 0.0105094 -0.0198491 -0.0268413 0.736292 0.772368 0.0578561 0.112831 0.0471775 0.172947 -0.785207 -1.03112 0.0169127 0.0620389 0.0104879 0.0450496 -1.04757 -1.45892 -3.49864e-05 -0.000153119 2.40597e-05 0.000234159 -0.00131793 -0.00299961 0 0 -2.23399e-06 -1.9424e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00076091 0.000620659 0.00474262 0.00349478 0.00473467 0.00348 0.000442516 0.000436358 0.980676 0.781481 0.980576 0.781065 1.0171 0.860201 0.154526 0.166506 0.154524 0.166551 2.25259 2.1751 6.96344e-07 6.10028e-07 6.95866e-07 6.08999e-07 2.48965e-07 1.79789e-07 0 0 3.9997e-06 3.99594e-06 0 0 0 0 0 0 0 0
26 2385000 0.674997 0.630455 0.00190538 0.01162 -0.0208074 -0.0283334 0.737524 0.775622 0.0715387 0.125976 0.0643129 0.213318 -0.820814 -1.05068 0.0253434 0.077785 0.0183526 0.0669676 -1.14865 -1.57242 -2.99038e-05 -0.000146378 2.87089e-05 0.00023969 -0.00125678 -0.00288519 0 0 -2.36882e-06 -1.99163e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000754766 0.00062366 0.00525084 0.00391239 0.00523782 0.00389455 0.00041633 0.000403811 1.25711 0.991097 1.25677 0.990324 1.06644 0.900234 0.229664 0.23693 0.229641 0.236979 2.53466 2.43714 6.96157e-07 6.09961e-07 6.9571e-07 6.08953e-07 2.21911e-07 1.60351e-07 0 0 3.99971e-06 3.99595e-06 0 0 0 0 0 0 0 0
27 2485000 0.673831 0.627292 0.00247058 0.0124632 -0.0193836 -0.0243847 0.738627 0.778303 0.0489537 0.0612593 0.0531012 0.175059 -0.859331 -1.08017 0.0159946 0.0455716 0.0129955 0.0477577 -1.2581 -1.69748 -3.82934e-05 -0.000160755 2.01397e-05 0.0001996 -0.00119881 -0.00277107 0 0 -2.66523e-06 -2.07111e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00074613 0.000622644 0.00405847 0.00322111 0.00404952 0.00321064 0.00039186 0.000373903 0.90194 0.752319 0.90167 0.751623 1.11688 0.940884 0.150391 0.160881 0.150377 0.160884 2.841 2.72019 5.93715e-07 5.16132e-07 5.93485e-07 5.15778e-07 1.98329e-07 1.43522e-07 0 0 3.99971e-06 3.99595e-06 0 0 0 0 0 0 0 0
28 2585000 0.67405 0.625754 0.00270029 0.0134543 -0.0202287 -0.0255826 0.738403 0.779485 0.0591248 0.0661897 0.0693035 0.211823 -0.912298 -1.11432 0.0231822 0.0552651 0.0211813 0.0691333 -1.3864 -1.83048 -3.34327e-05 -0.000154117 2.34881e-05 0.000202225 -0.00112301 -0.00264199 0 0 -2.83052e-06 -2.11922e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000735856 0.000620694 0.00450115 0.00359671 0.00448976 0.0035846 0.000370633 0.000348222 1.147 0.951425 1.14655 0.95034 1.16912 0.984711 0.221802 0.228699 0.221765 0.228675 3.17313 3.02677 5.9363e-07 5.16094e-07 5.93445e-07 5.15772e-07 1.77739e-07 1.28996e-07 0 0 3.99972e-06 3.99596e-06 0 0 0 0 0 0 0 0
29 2685000 0.673166 0.623705 0.00303506 0.0135296 -0.0186818 -0.0220817 0.739249 0.781231 0.0365361 0.0165329 0.0527507 0.168429 -0.956886 -1.15624 0.0138935 0.0306458 0.013784 0.0474848 -1.5129 -1.9745 -4.14168e-05 -0.000161763 1.27258e-05 0.000163559 -0.00107217 -0.00253323 0 0 -3.03108e-06 -2.16191e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000723504 0.000615278 0.00344478 0.00290636 0.00343813 0.00289992 0.000350862 0.000324443 0.807576 0.715073 0.807311 0.714269 1.22223 1.02895 0.144248 0.155078 0.144233 0.155054 3.53164 3.35646 5.0222e-07 4.26498e-07 5.02173e-07 4.26569e-07 1.59679e-07 1.16281e-07 0 0 3.99972e-06 3.99595e-06 0 0 0 0 0 0 0 0
30 2785000 0.673236 0.622709 0.0033343 0.014515 -0.0192003 -0.0228522 0.739171 0.781985 0.0426704 0.0143631 0.0650539 0.199862 -1.01101 -1.20108 0.0188759 0.0344579 0.020817 0.0671395 -1.65732 -2.12866 -3.83548e-05 -0.000156832 1.40911e-05 0.000163643 -0.00101102 -0.0024181 0 0 -3.14948e-06 -2.19578e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000711001 0.000610221 0.00382697 0.00323549 0.00381912 0.00322827 0.00033346 0.000304076 1.02014 0.900118 1.01976 0.898957 1.27693 1.07628 0.210221 0.219852 0.210187 0.219783 3.91832 3.71226 5.02181e-07 4.26478e-07 5.02165e-07 4.26569e-07 1.43921e-07 1.05291e-07 0 0 3.99973e-06 3.99596e-06 0 0 0 0 0 0 0 0
31 2885000 0.672047 0.619652 0.00342885 0.0139369 -0.0178013 -0.019882 0.740287 0.784501 0.0239806 -0.020268 0.0477436 0.155122 -1.05215 -1.24469 0.0109054 0.0171095 0.0130033 0.0448462 -1.79343 -2.28533 -4.48691e-05 -0.000158995 3.58368e-06 0.000129025 -0.000974493 -0.00234015 0 0 -3.24004e-06 -2.21013e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00071867 0.000620363 0.00294694 0.00257309 0.00294259 0.00256966 0.000324621 0.000291362 0.717308 0.670246 0.717097 0.669472 1.33456 1.12422 0.137218 0.149052 0.137205 0.149013 4.33665 4.09387 4.2379e-07 3.45527e-07 4.23828e-07 3.45808e-07 1.3334e-07 9.7878e-08 0 0 3.99974e-06 3.99594e-06 0 0 0 0 0 0 0 0
32 2985000 0.672029 0.61921 0.00366362 0.0147898 -0.0180856 -0.020302 0.740295 0.784824 0.0262658 -0.0289516 0.0581709 0.182494 -1.10972 -1.30245 0.0139879 0.0160845 0.0189646 0.0625725 -1.95383 -2.46364 -4.28147e-05 -0.00015552 4.03277e-06 0.000127732 -0.000923281 -0.00223457 0 0 -3.32156e-06 -2.23196e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000704067 0.000612648 0.00327739 0.00285513 0.00327241 0.00285142 0.000309483 0.000274264 0.902317 0.839619 0.902016 0.838544 1.39173 1.17495 0.197428 0.210347 0.197399 0.210259 4.78303 4.50397 4.2377e-07 3.45518e-07 4.23827e-07 3.45806e-07 1.20747e-07 8.91466e-08 0 0 3.99975e-06 3.99595e-06 0 0 0 0 0 0 0 0
33 3085000 0.672519 0.619505 0.00386688 0.0137399 -0.0184229 -0.0180409 0.739841 0.784665 0.0293609 -0.0480134 0.0681637 0.140585 -1.17314 -1.37096 0.0175458 0.00621634 0.0261732 0.0414692 -2.13121 -2.66228 -4.05722e-05 -0.000151261 4.56187e-06 9.75854e-05 -0.000869679 -0.00213004 0 0 -3.40309e-06 -2.2443e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000689255 0.000602872 0.0036289 0.00224302 0.00362324 0.00224152 0.000295657 0.000258143 1.12185 0.621047 1.12144 0.620385 1.44986 1.22583 0.282398 0.142859 0.282345 0.142816 5.26086 4.94187 4.23751e-07 2.75687e-07 4.23826e-07 2.7604e-07 1.0963e-07 8.13696e-08 0 0 3.99976e-06 3.99592e-06 0 0 0 0 0 0 0 0
34 3185000 0.672636 0.619593 0.00377716 0.014445 -0.0172142 -0.0182822 0.739763 0.784577 0.0123418 -0.0609004 0.0505563 0.163007 -1.23388 -1.44101 0.00968653 0.00161263 0.016983 0.0572579 -2.3112 -2.87047 -4.48912e-05 -0.00014883 -5.05414e-06 9.57457e-05 -0.000826235 -0.00203483 0 0 -3.4305e-06 -2.25672e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00067372 0.00059417 0.00284128 0.00248055 0.0028381 0.00247899 0.000282826 0.000244347 0.802527 0.773565 0.802299 0.772681 1.50871 1.27961 0.185026 0.200387 0.185003 0.200298 5.771 5.41137 3.56999e-07 2.75682e-07 3.57083e-07 2.76037e-07 9.97812e-08 7.45799e-08 0 0 3.99977e-06 3.99593e-06 0 0 0 0 0 0 0 0
35 3285000 0.672686 0.619785 0.00396283 0.013104 -0.0174048 -0.0165681 0.739713 0.784487 0.0127302 -0.0689357 0.0593761 0.125551 -1.29365 -1.51817 0.0113083 -0.0026556 0.022939 0.0376452 -2.50031 -3.09721 -4.34474e-05 -0.000141206 -4.95429e-06 7.04531e-05 -0.000785643 -0.00194528 0 0 -3.47666e-06 -2.26514e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000659075 0.000584029 0.00314584 0.00193255 0.00314228 0.0019321 0.000271159 0.0002311 0.995069 0.570015 0.994764 0.569497 1.56875 1.33351 0.261925 0.136612 0.261883 0.136572 6.31539 5.91125 3.56988e-07 2.176e-07 3.57083e-07 2.17947e-07 9.10672e-08 6.84752e-08 0 0 3.99978e-06 3.99588e-06 0 0 0 0 0 0 0 0
36 3385000 0.673281 0.620645 0.00385424 0.0138138 -0.0164498 -0.0166188 0.739194 0.783794 0.0019349 -0.0829036 0.0440225 0.14434 -1.36316 -1.60304 0.00581985 -0.00987203 0.0150133 0.051771 -2.70991 -3.34382 -4.56688e-05 -0.000139413 -1.31079e-05 6.83693e-05 -0.000742195 -0.00185433 0 0 -3.46299e-06 -2.2718e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00064399 0.000574987 0.00248962 0.00212996 0.00248755 0.00212956 0.000260301 0.000219735 0.720692 0.70561 0.720523 0.70495 1.62944 1.39009 0.173713 0.190237 0.173695 0.190159 6.89463 6.44553 2.99793e-07 2.17598e-07 2.99876e-07 2.17944e-07 8.32982e-08 6.31134e-08 0 0 3.99979e-06 3.99589e-06 0 0 0 0 0 0 0 0
37 3485000 0.674003 0.621712 0.00404082 0.012327 -0.0166142 -0.0154138 0.738531 0.782997 0.00178498 -0.0810376 0.0517378 0.111183 -1.43517 -1.69631 0.00625674 -0.00943771 0.0201685 0.0340174 -2.93352 -3.61227 -4.43192e-05 -0.000129453 -1.31993e-05 4.71736e-05 -0.000699927 -0.00176794 0 0 -3.4945e-06 -2.28153e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000629805 0.000564874 0.0027539 0.00165142 0.00275158 0.00165145 0.000250398 0.000208761 0.89154 0.51944 0.89132 0.519078 1.69127 1.44682 0.243704 0.130433 0.243672 0.130399 7.51063 7.01291 2.99786e-07 1.70585e-07 2.99876e-07 1.70887e-07 7.63928e-08 5.82563e-08 0 0 3.9998e-06 3.99583e-06 0 0 0 0 0 0 0 0
38 3585000 0.673473 0.620511 0.00381202 0.0129166 -0.0158731 -0.0153811 0.739032 0.783941 -0.0043401 -0.0952235 0.0377591 0.125881 -1.48621 -1.76838 0.00282433 -0.0182288 0.0131368 0.0463115 -3.13438 -3.86417 -4.54648e-05 -0.000128535 -2.00601e-05 4.57257e-05 -0.000675457 -0.00170924 0 0 -3.44807e-06 -2.28385e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000631129 0.000569297 0.00219541 0.00181406 0.00219401 0.00181416 0.000245431 0.0002024 0.653596 0.639064 0.653479 0.638625 1.75731 1.50712 0.163654 0.180171 0.163641 0.180108 8.1721 7.61962 2.5043e-07 1.70585e-07 2.50502e-07 1.70886e-07 7.16654e-08 5.49864e-08 0 0 3.9998e-06 3.99584e-06 0 0 0 0 0 0 0 0
39 3685000 0.674036 0.621557 0.00397304 0.011366 -0.0159874 -0.0145591 0.738515 0.783151 -0.00509734 -0.0864975 0.0440246 0.0964816 -1.55893 -1.8701 0.00248277 -0.0142573 0.0175182 0.0304663 -3.37604 -4.16692 -4.43947e-05 -0.000117577 -2.02243e-05 2.82456e-05 -0.000639127 -0.00163202 0 0 -3.46319e-06 -2.29502e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000616849 0.000558894 0.0024243 0.00140378 0.00242273 0.00140395 0.000236562 0.000192856 0.806662 0.471167 0.806512 0.470945 1.82096 1.56661 0.22781 0.124427 0.227786 0.124401 8.86575 8.26053 2.50425e-07 1.33256e-07 2.50501e-07 1.33502e-07 6.59746e-08 5.09654e-08 0 0 3.99981e-06 3.99578e-06 0 0 0 0 0 0 0 0
40 3785000 0.674842 0.62307 0.00367256 0.011844 -0.0155035 -0.0145222 0.73779 0.781941 -0.00757749 -0.100515 0.0331376 0.109998 -1.63529 -1.97795 0.00073607 -0.0238486 0.0115664 0.0414464 -3.63464 -4.49419 -4.40305e-05 -0.000116555 -2.60436e-05 2.62849e-05 -0.000603184 -0.00155476 0 0 -3.41564e-06 -2.29748e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000602528 0.000549408 0.00193924 0.00153701 0.00193822 0.00153724 0.000228266 0.0001846 0.597218 0.576061 0.59714 0.575807 1.8852 1.62829 0.154758 0.170409 0.154747 0.170364 9.59968 8.94162 2.07729e-07 1.33256e-07 2.07786e-07 1.335e-07 6.08491e-08 4.73921e-08 0 0 3.9998e-06 3.99579e-06 0 0 0 0 0 0 0 0
41 3885000 0.675562 0.624412 0.00385368 0.0123667 -0.0154905 -0.0143908 0.73713 0.780864 -0.0103391 -0.117015 0.0370677 0.122971 -1.71012 -2.08792 -8.54303e-05 -0.0349294 0.0153019 0.0539345 -3.8997 -4.83757 -4.31137e-05 -0.000115481 -2.62207e-05 2.45574e-05 -0.000570974 -0.0014842 0 0 -3.41947e-06 -2.30029e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000589028 0.000540029 0.00213653 0.00167672 0.0021354 0.00167701 0.000220645 0.000177025 0.734947 0.697887 0.734846 0.697599 1.95043 1.69116 0.213938 0.23241 0.213921 0.232339 10.3756 9.66306 2.07725e-07 1.33255e-07 2.07786e-07 1.33498e-07 5.62515e-08 4.4159e-08 0 0 3.99981e-06 3.9958e-06 0 0 0 0 0 0 0 0
42 3985000 0.676076 0.62576 0.00361358 0.0108157 -0.0150409 -0.0137041 0.73667 0.77982 -0.0124243 -0.104322 0.0286208 0.094213 -1.78135 -2.20384 -0.000858018 -0.0275675 0.010098 0.0367904 -4.169 -5.20412 -4.21982e-05 -0.000104714 -3.11085e-05 1.009e-05 -0.000542874 -0.00141799 0 0 -3.36729e-06 -2.3105e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000575491 0.000530163 0.00170941 0.00129863 0.00170864 0.00129881 0.000213436 0.000169532 0.548215 0.517888 0.54816 0.517775 2.0162 1.75408 0.146832 0.161102 0.146824 0.161073 11.1944 10.4246 1.7093e-07 1.03993e-07 1.70974e-07 1.0418e-07 5.20768e-08 4.11851e-08 0 0 3.9998e-06 3.99574e-06 0 0 0 0 0 0 0 0
43 4085000 0.676733 0.627152 0.00369168 0.0111734 -0.0150365 -0.0135699 0.736066 0.778699 -0.0146068 -0.11969 0.0332205 0.106018 -1.85517 -2.32125 -0.00219148 -0.0392063 0.0133897 0.0475878 -4.45371 -5.59042 -4.14169e-05 -0.000103814 -3.12986e-05 8.46516e-06 -0.000515045 -0.00135467 0 0 -3.36189e-06 -2.31344e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000562839 0.000521148 0.0018783 0.00141254 0.00187744 0.00141276 0.000206779 0.000163041 0.672175 0.623835 0.672105 0.623723 2.08284 1.81902 0.201677 0.217905 0.201665 0.217861 12.058 11.2309 1.70927e-07 1.03993e-07 1.70974e-07 1.04178e-07 4.83236e-08 3.85207e-08 0 0 3.99981e-06 3.99575e-06 0 0 0 0 0 0 0 0
44 4185000 0.676679 0.626957 0.00338446 0.00964578 -0.0147014 -0.0131463 0.736124 0.778884 -0.0141219 -0.102663 0.025778 0.0806214 -1.91293 -2.41815 -0.00211361 -0.0297797 0.00893692 0.0324507 -4.7177 -5.95721 -4.01867e-05 -9.35526e-05 -3.53782e-05 -3.02169e-06 -0.000496504 -0.00130979 0 0 -3.31429e-06 -2.32102e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000562545 0.000522672 0.0015 0.00109613 0.00149939 0.00109615 0.000203546 0.000158607 0.50398 0.464934 0.503943 0.464921 2.15478 1.88611 0.139678 0.152342 0.139673 0.152325 12.982 12.0855 1.39502e-07 8.12325e-08 1.39533e-07 8.13679e-08 4.57232e-08 3.66485e-08 0 0 3.9998e-06 3.9957e-06 0 0 0 0 0 0 0 0
45 4285000 0.677471 0.628605 0.00350782 0.00999392 -0.0147428 -0.013044 0.735393 0.777551 -0.0185235 -0.119195 0.0294048 0.0894604 -1.98963 -2.54439 -0.00369886 -0.0414173 0.0118777 0.0417121 -5.02731 -6.38966 -3.94678e-05 -9.27289e-05 -3.55753e-05 -4.56995e-06 -0.000470546 -0.00125081 0 0 -3.30301e-06 -2.32548e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000550124 0.000513587 0.00164347 0.00118893 0.00164278 0.00118896 0.000197523 0.000152864 0.615433 0.557014 0.615384 0.557023 2.22293 1.9531 0.190644 0.204345 0.190635 0.204324 13.9401 12.9832 1.395e-07 8.12321e-08 1.39533e-07 8.13665e-08 4.25535e-08 3.43771e-08 0 0 3.99981e-06 3.99571e-06 0 0 0 0 0 0 0 0
46 4385000 0.67843 0.630485 0.00320133 0.0085715 -0.0145229 -0.0127954 0.734515 0.776048 -0.0180995 -0.102211 0.0221424 0.0667229 -2.07311 -2.68177 -0.0031214 -0.0311454 0.00800394 0.0285879 -5.35801 -6.85568 -3.76293e-05 -8.28469e-05 -3.91136e-05 -1.44255e-05 -0.000444182 -0.00119292 0 0 -3.25554e-06 -2.33018e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000537829 0.000504338 0.00130879 0.000925495 0.00130828 0.000925353 0.000191787 0.000147179 0.46302 0.417271 0.462993 0.417324 2.29167 2.0202 0.133124 0.144163 0.13312 0.144156 14.9466 13.9271 1.12991e-07 6.36011e-08 1.13011e-07 6.36938e-08 3.96521e-08 3.22739e-08 0 0 3.9998e-06 3.99566e-06 0 0 0 0 0 0 0 0
47 4485000 0.678847 0.631809 0.0033097 0.0088449 -0.0145121 -0.0126489 0.734129 0.77497 -0.0210447 -0.116018 0.0245552 0.0730084 -2.14364 -2.81097 -0.00509011 -0.04268 0.0104889 0.0362341 -5.6742 -7.3259 -3.70707e-05 -8.20894e-05 -3.92788e-05 -1.57827e-05 -0.000424061 -0.00114201 0 0 -3.24206e-06 -2.33631e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000526291 0.000495732 0.00142972 0.00100116 0.00142915 0.001001 0.000186435 0.000142155 0.563061 0.497443 0.563028 0.497531 2.3613 2.08902 0.180532 0.191778 0.180525 0.191773 16.0039 14.9219 1.12989e-07 6.36008e-08 1.13011e-07 6.36925e-08 3.70229e-08 3.03673e-08 0 0 3.99981e-06 3.99567e-06 0 0 0 0 0 0 0 0
48 4585000 0.679696 0.633561 0.00295496 0.00748653 -0.014398 -0.0125735 0.733347 0.773554 -0.0186622 -0.0974154 0.0196752 0.0548437 -2.22542 -2.95257 -0.00393227 -0.0316469 0.00709342 0.024803 -6.02296 -7.83609 -3.50454e-05 -7.29684e-05 -4.22469e-05 -2.38096e-05 -0.000401298 -0.0010906 0 0 -3.20017e-06 -2.33518e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000514875 0.000487017 0.00113538 0.000782443 0.00113493 0.000782149 0.000181344 0.000137208 0.42475 0.374826 0.424732 0.374916 2.4314 2.15789 0.127043 0.136571 0.12704 0.136572 17.1125 15.9657 9.09303e-08 4.99627e-08 9.09433e-08 5.00212e-08 3.46059e-08 2.85958e-08 0 0 3.9998e-06 3.99562e-06 0 0 0 0 0 0 0 0
49 4685000 0.680583 0.635356 0.00301114 0.00765972 -0.0143872 -0.0124263 0.732523 0.772082 -0.0202887 -0.108845 0.0221621 0.0599464 -2.30705 -3.0949 -0.00588814 -0.0426408 0.00937948 0.0312021 -6.38377 -8.36856 -3.44384e-05 -7.21652e-05 -4.24383e-05 -2.51359e-05 -0.000379542 -0.00104127 0 0 -3.18098e-06 -2.34398e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000504097 0.000478824 0.00123661 0.000844238 0.00123611 0.000843915 0.000176603 0.000132819 0.513937 0.444512 0.513916 0.444639 2.50231 2.22827 0.171148 0.180212 0.171143 0.180219 18.2748 17.0635 9.09287e-08 4.99624e-08 9.09432e-08 5.00201e-08 3.24066e-08 2.69805e-08 0 0 3.99981e-06 3.99563e-06 0 0 0 0 0 0 0 0
50 4785000 0.680992 0.636708 0.00264364 0.00640215 -0.0143127 -0.0124473 0.732146 0.770978 -0.0171015 -0.0897669 0.0167532 0.0433031 -2.37557 -3.23252 -0.00429667 -0.0312382 0.00633029 0.0213009 -6.72678 -8.90982 -3.25319e-05 -6.40213e-05 -4.48974e-05 -3.15483e-05 -0.000363356 -0.000998125 0 0 -3.14504e-06 -2.33584e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000493473 0.000470588 0.000979857 0.000662815 0.000979469 0.000662399 0.000172072 0.000128496 0.388659 0.337035 0.388649 0.337142 2.57373 2.29874 0.12135 0.129548 0.121348 0.129554 19.4914 18.2134 7.28172e-08 3.94065e-08 7.28244e-08 3.94388e-08 3.03777e-08 2.54756e-08 0 0 3.9998e-06 3.99559e-06 0 0 0 0 0 0 0 0
51 4885000 0.681257 0.637063 0.00269074 0.00653473 -0.0143351 -0.0123613 0.731899 0.770685 -0.0184823 -0.0992787 0.0187656 0.0466204 -2.43901 -3.34594 -0.0060845 -0.0411873 0.0082642 0.0262604 -7.06867 -9.42454 -3.21386e-05 -6.34227e-05 -4.50273e-05 -3.2444e-05 -0.000349277 -0.000964813 0 0 -3.13032e-06 -2.34409e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00049268 0.00047123 0.00106412 0.000713413 0.00106368 0.000712954 0.000170022 0.00012593 0.467971 0.397799 0.467959 0.397941 2.6515 2.37369 0.162353 0.169595 0.16235 0.169609 20.7894 19.4315 7.28162e-08 3.94062e-08 7.28244e-08 3.94381e-08 2.89698e-08 2.44287e-08 0 0 3.99981e-06 3.9956e-06 0 0 0 0 0 0 0 0
52 4985000 0.681765 0.63853 0.00245219 0.00551516 -0.0142384 -0.0123851 0.731429 0.769477 -0.0158401 -0.0817732 0.0149598 0.0333494 -2.50951 -3.48869 -0.00430745 -0.029984 0.00562811 0.0179158 -7.43485 -10.0133 -3.03498e-05 -5.62568e-05 -4.70806e-05 -3.76084e-05 -0.000333984 -0.000924689 0 0 -3.09296e-06 -2.3288e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000482393 0.000463119 0.000842151 0.000562862 0.000841811 0.000562362 0.000165857 0.000122054 0.354845 0.303551 0.354838 0.303657 2.72425 2.44572 0.11599 0.12306 0.115988 0.12307 22.1215 20.6944 5.81213e-08 3.12202e-08 5.81241e-08 3.12333e-08 2.72172e-08 2.31146e-08 0 0 3.9998e-06 3.99555e-06 0 0 0 0 0 0 0 0
53 5085000 0.682549 0.640266 0.00247674 0.0055786 -0.0142814 -0.0123147 0.730696 0.768035 -0.0178727 -0.0910389 0.0163651 0.0350512 -2.59012 -3.63963 -0.00598819 -0.0392292 0.00736801 0.0218444 -7.83341 -10.639 -2.98653e-05 -5.54444e-05 -4.72601e-05 -3.87211e-05 -0.000316654 -0.000883801 0 0 -3.07141e-06 -2.3414e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000472642 0.000455422 0.000912001 0.00060442 0.000911617 0.000603872 0.00016193 0.000118541 0.425065 0.356598 0.425056 0.356735 2.79779 2.51903 0.154082 0.15987 0.15408 0.159888 23.5135 22.0176 5.81201e-08 3.12199e-08 5.8124e-08 3.12325e-08 2.56104e-08 2.19042e-08 0 0 3.99981e-06 3.99556e-06 0 0 0 0 0 0 0 0
54 5185000 0.683383 0.642029 0.00251131 0.00464198 -0.014262 -0.0123973 0.729916 0.766566 -0.019224 -0.0735348 0.0185348 0.0234955 -2.67124 -3.794 -0.00779792 -0.0285248 0.00931152 0.0148174 -8.24667 -11.2947 -2.93849e-05 -4.91487e-05 -4.74249e-05 -4.28977e-05 -0.000299795 -0.000844669 0 0 -3.04927e-06 -2.32068e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000463195 0.000447762 0.000984755 0.00047933 0.000984327 0.000478779 0.000158199 0.000115102 0.505162 0.273825 0.50515 0.273921 2.87186 2.59229 0.203981 0.117073 0.203978 0.117084 24.9665 23.3987 5.8119e-08 2.4853e-08 5.8124e-08 2.48521e-08 2.41257e-08 2.07721e-08 0 0 3.99982e-06 3.99551e-06 0 0 0 0 0 0 0 0
55 5285000 0.684196 0.643785 0.00227379 0.00470249 -0.0142075 -0.0122784 0.729156 0.765094 -0.0163739 -0.0816135 0.0124089 0.0227215 -2.75125 -3.94808 -0.00569043 -0.0367906 0.00644643 0.0175532 -8.66705 -11.9701 -2.77315e-05 -4.83346e-05 -4.91776e-05 -4.39163e-05 -0.000284213 -0.000807429 0 0 -3.00532e-06 -2.3345e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00045391 0.000440397 0.000779433 0.000513581 0.0007791 0.000512984 0.000154631 0.000111982 0.385225 0.32022 0.385219 0.320341 2.94645 2.66675 0.146294 0.150964 0.146292 0.150983 26.4813 24.8433 4.63126e-08 2.48526e-08 4.63134e-08 2.48515e-08 2.27471e-08 1.97231e-08 0 0 3.99981e-06 3.99552e-06 0 0 0 0 0 0 0 0
56 5385000 0.684549 0.645069 0.00240329 0.00400367 -0.0142048 -0.0124173 0.728824 0.764013 -0.0178114 -0.0653986 0.0122244 0.0114188 -2.81623 -4.09297 -0.00739156 -0.0267044 0.00779035 0.0115862 -9.06342 -12.6477 -2.74018e-05 -4.29725e-05 -4.93081e-05 -4.70762e-05 -0.000272628 -0.000774946 0 0 -2.98733e-06 -2.30766e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000445101 0.00043315 0.000839494 0.000409444 0.000839124 0.000408876 0.000151252 0.000108923 0.455695 0.247512 0.455689 0.247594 3.02182 2.74122 0.192334 0.111544 0.192331 0.111555 28.0611 26.3488 4.63116e-08 1.98831e-08 4.63133e-08 1.98727e-08 2.14771e-08 1.87419e-08 0 0 3.99982e-06 3.99546e-06 0 0 0 0 0 0 0 0
57 5485000 0.684711 0.645449 0.00222181 0.00405992 -0.014148 -0.0123 0.728674 0.763693 -0.0145457 -0.0713501 0.00794831 0.0106618 -2.87212 -4.20757 -0.00537066 -0.0338569 0.0051244 0.0129031 -9.4489 -13.2815 -2.60773e-05 -4.23935e-05 -5.06334e-05 -4.77486e-05 -0.000263399 -0.000750614 0 0 -2.95134e-06 -2.31783e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000444003 0.000433203 0.000665095 0.000437778 0.000664809 0.000437166 0.000149755 0.000107133 0.348643 0.288167 0.348639 0.288265 3.10384 2.82081 0.138971 0.142807 0.13897 0.142826 29.7421 27.9405 3.68972e-08 1.98829e-08 3.68957e-08 1.98723e-08 2.05812e-08 1.80515e-08 0 0 3.99981e-06 3.99547e-06 0 0 0 0 0 0 0 0
58 5585000 0.685244 0.646903 0.00225001 0.00339536 -0.014113 -0.0124396 0.728174 0.762463 -0.0163413 -0.0573257 0.00865131 0.00276523 -2.94143 -4.35769 -0.00691855 -0.0245851 0.00607097 0.00828121 -9.87277 -14.0097 -2.57504e-05 -3.77961e-05 -5.07776e-05 -5.01172e-05 -0.000251889 -0.000719921 0 0 -2.93089e-06 -2.28878e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000435446 0.000426057 0.000714624 0.000350879 0.000714307 0.000350315 0.000146625 0.00010437 0.410516 0.224177 0.410511 0.224238 3.18045 2.89644 0.181429 0.106434 0.181427 0.106445 31.4568 29.5777 3.68964e-08 1.59884e-08 3.68956e-08 1.59717e-08 1.94659e-08 1.718e-08 0 0 3.99982e-06 3.9954e-06 0 0 0 0 0 0 0 0
59 5685000 0.685589 0.648181 0.0021151 0.00341475 -0.0140507 -0.012299 0.72785 0.761379 -0.0144422 -0.0633741 0.00520435 0.000943832 -3.00682 -4.50495 -0.00508099 -0.0309714 0.0040031 0.00869287 -10.2944 -14.7505 -2.45466e-05 -3.706e-05 -5.17811e-05 -5.09113e-05 -0.000241854 -0.000691191 0 0 -2.89389e-06 -2.30211e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000427094 0.000419174 0.000567284 0.000374409 0.000567041 0.000373806 0.000143587 0.000101802 0.315452 0.260006 0.315448 0.260077 3.25753 2.97315 0.132105 0.135331 0.132104 0.135349 33.2397 31.2852 2.94278e-08 1.59879e-08 2.9425e-08 1.59712e-08 1.84254e-08 1.6366e-08 0 0 3.99982e-06 3.99541e-06 0 0 0 0 0 0 0 0
60 5785000 0.685971 0.649459 0.0021878 0.00291383 -0.0140129 -0.0124583 0.727491 0.760289 -0.017225 -0.0517937 0.00546744 -0.00521867 -0.00307082 -0.00309678 -0.00663488 -0.022568 0.00461389 0.00526503 -365.429 -2.42774e-05 -3.31548e-05 -5.19113e-05 -5.25879e-05 -0.00023238 -0.000664059 0 0 -2.8746e-06 -2.27174e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000419096 0.000412392 0.000608134 0.000301686 0.000607866 0.000301146 0.000140723 9.93217e-05 0.369673 0.203508 0.369667 0.203547 9.99881 0.171265 0.101712 0.171263 0.101722 2.00225 2.94271e-08 1.29223e-08 2.94249e-08 1.29019e-08 1.74605e-08 1.56017e-08 0 0 3.99983e-06 3.99532e-06 0 0 0 0 0 0 0 0
61 5885000 0.686391 0.650777 0.0020374 0.002868 -0.0140071 -0.0123696 0.727095 0.759163 -0.0148974 -0.0562909 0.00371742 -0.00673002 -0.00663697 -0.00835999 -0.00499634 -0.028247 0.00304435 0.00483468 -365.42 -2.31925e-05 -3.24341e-05 -5.26527e-05 -5.33113e-05 -0.000223035 -0.000637684 0 0 -2.86764e-06 -2.28805e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.00041127 0.000405826 0.000484106 0.000321307 0.0004839 0.000320731 0.000137961 9.70194e-05 0.285283 0.235054 0.285277 0.235096 9.74018 9.74009 0.125684 0.128474 0.125683 0.128489 0.709952 2.35201e-08 1.29219e-08 2.35165e-08 1.29014e-08 1.65582e-08 1.48855e-08 0 0 3.99983e-06 3.99533e-06 0 0 0 0 0 0 0 0
62 5985000 0.686838 0.652086 0.00208672 0.0028584 -0.0140049 -0.012309 0.726673 0.758039 -0.0180418 -0.0622958 0.00383239 -0.00932304 0.001181 -0.00423867 -0.00665473 -0.0345603 0.00350939 0.00416819 -365.403 -365.404 -2.29297e-05 -3.17341e-05 -5.27882e-05 -5.40007e-05 -0.000213766 -0.000612294 0 0 -2.95092e-06 -2.31218e-05 0.145057 0.191453 0.00139693 0.00184374 0.412416 0.404156 0 0 0 0 0 0.000403782 0.000399439 0.000517838 0.00034157 0.000517612 0.000340957 0.000135331 9.48283e-05 0.332928 0.270153 0.33292 0.2702 8.84143 8.84116 0.16181 0.161777 0.161809 0.161799 0.518932 0.518931 2.35196e-08 1.29215e-08 2.35165e-08 1.2901e-08 1.57192e-08 1.42131e-08 0 0 3.99982e-06 3.99532e-06 0 0 0 0 0 0 0 0
63 6085000 0.6875 0.704797 0.00195993 0.001535 -0.0140139 -0.0126589 0.726046 0.709294 -0.0162914 -0.0503162 0.00296948 -0.0124098 -0.0178643 -0.0193618 -0.00515058 -0.025545 0.00235926 0.00138139 -365.405 -365.406 -2.18709e-05 -2.90694e-05 -5.33722e-05 -5.44757e-05 -0.000203461 -0.000612326 0 0 -2.89253e-06 -2.26727e-05 0.145057 0.2098 0.00139693 0.00202043 0.412416 0.432662 0 0 0 0 0 0.000396449 0.00112913 0.000413668 0.00026396 0.000413494 0.000263216 0.000132797 0.000907144 0.258195 0.191485 0.258188 0.191497 7.29172 7.28981 0.11969 0.121716 0.119689 0.121727 0.482378 0.482369 1.8854e-08 1.04979e-08 1.885e-08 1.04755e-08 1.4933e-08 1.42114e-08 0 0 3.99973e-06 3.99512e-06 0 0 0 0 0 0 0 0
64 6185000 0.687679 0.703 0.00191575 0.00149919 -0.013985 -0.0125963 0.725877 0.711077 -0.0192131 -0.0551368 0.00269257 -0.0148313 -0.0197431 -0.018524 -0.00691727 -0.0308256 0.00271576 3.27182e-05 -365.402 -2.16994e-05 -2.90693e-05 -5.34641e-05 -5.44757e-05 -0.000197396 -0.000612311 0 0 -3.04775e-06 -2.28418e-05 0.145057 0.2098 0.00139693 0.00202043 0.412416 0.432662 0 0 0 0 0 0.000395352 0.000919985 0.000441583 0.00026463 0.000441391 0.000263951 0.000131782 0.000734749 0.3 0.195307 0.299991 0.195314 5.97241 5.9692 0.153046 0.150006 0.153045 0.150021 0.538038 0.537996 1.88536e-08 1.0498e-08 1.885e-08 1.04756e-08 1.43778e-08 1.42103e-08 0 0 3.99958e-06 3.99497e-06 0 0 0 0 0 0 0 0
65 6285000 0.688282 0.702148 0.00177952 0.00146515 -0.0140432 -0.0125912 0.725305 0.711918 -0.0161119 -0.0457712 0.00242873 -0.0158289 -0.0199419 -0.0153329 -0.00534824 -0.0232191 0.00186943 -0.00137622 -365.397 -365.396 -2.07085e-05 -2.69073e-05 -5.39168e-05 -5.46053e-05 -0.000188315 -0.000612205 0 0 -3.27844e-06 -2.26911e-05 0.145057 0.2098 0.00139693 0.00202043 0.412416 0.432662 0 0 0 0 0 0.000388239 0.000743428 0.000354168 0.000265259 0.00035402 0.000264634 0.000129406 0.000591349 0.233927 0.142012 0.233919 0.142005 4.38238 4.37903 0.114107 0.112338 0.114106 0.112345 0.517119 0.517043 1.51678e-08 8.63892e-09 1.51636e-08 8.61576e-09 1.36775e-08 1.42064e-08 0 0 3.99922e-06 3.99449e-06 0 0 0 0 0 0 0 0
66 6385000 0.68893 0.701438 0.00183978 0.00152121 -0.0139509 -0.0124712 0.724691 0.712619 -0.0179162 -0.0496773 0.00275739 -0.0177915 -0.0551852 -0.0475597 -0.00703114 -0.0280043 0.00221778 -0.00304876 -365.409 -365.408 -2.04489e-05 -2.68931e-05 -5.40631e-05 -5.46126e-05 -0.000179138 -0.000611869 0 0 -2.91488e-06 -2.23081e-05 0.145057 0.2098 0.00139693 0.00202043 0.412416 0.432662 0 0 0 0 0 0.0003814 0.000628702 0.000377325 0.000266631 0.000377165 0.000266043 0.000127133 0.00049839 0.270687 0.150777 0.270677 0.150768 3.16523 3.1623 0.144941 0.13534 0.14494 0.135347 0.486049 0.485949 1.51674e-08 8.63901e-09 1.51635e-08 8.61586e-09 1.30228e-08 1.42012e-08 0 0 3.99868e-06 3.99395e-06 0 0 0 0 0 0 0 0
67 6485000 0.689452 0.700437 0.00175066 0.00150048 -0.0140663 -0.0125547 0.724192 0.713603 -0.015116 -0.0432685 0.00191415 -0.018617 -0.0617157 -0.0518276 -0.00537219 -0.0217365 0.00155968 -0.00352054 -365.41 -365.408 -1.95459e-05 -2.51288e-05 -5.4432e-05 -5.4534e-05 -0.000171206 -0.000611556 0 0 -3.29939e-06 -2.22699e-05 0.145057 0.2098 0.00139693 0.00202043 0.412416 0.432662 0 0 0 0 0 0.000374704 0.000548233 0.000303954 0.000266205 0.00030383 0.000265642 0.000124939 0.000433406 0.212189 0.119661 0.21218 0.119651 2.28878 2.28654 0.108913 0.102937 0.108912 0.102939 0.448584 0.448475 1.22515e-08 7.27264e-09 1.22473e-08 7.2494e-09 1.24071e-08 1.41929e-08 0 0 3.99788e-06 3.99305e-06 0 0 0 0 0 0 0 0
68 6585000 0.689751 0.698946 0.00175025 0.00149877 -0.0140708 -0.0125373 0.723908 0.715063 -0.0160327 -0.0463346 0.00181654 -0.0210526 -0.103523 -0.0920802 -0.00686866 -0.0261781 0.00180366 -0.00549509 -365.433 -365.43 -1.93814e-05 -2.51133e-05 -5.45276e-05 -5.45418e-05 -0.000165411 -0.00061122 0 0 -2.27038e-06 -2.1141e-05 0.145057 0.2098 0.00139693 0.00202043 0.412416 0.432662 0 0 0 0 0 0.000368189 0.000488652 0.00032323 0.000267873 0.000323094 0.000267325 0.000122852 0.000385623 0.24457 0.132536 0.24456 0.132527 1.6784 1.67693 0.137451 0.122435 0.13745 0.122438 0.410712 0.410604 1.22511e-08 7.27272e-09 1.22473e-08 7.2495e-09 1.18286e-08 1.41819e-08 0 0 3.99679e-06 3.99195e-06 0 0 0 0 0 0 0 0
69 6685000 0.704438 0.697708 0.0013807 0.00144885 -0.0141441 -0.012591 0.709623 0.716271 -0.0126404 -0.0404718 0.00144579 -0.0210258 -0.0877564 -0.0756646 -0.00516254 -0.0208052 0.00124274 -0.00539184 -365.422 -365.419 -1.8654e-05 -2.36389e-05 -5.47813e-05 -5.43357e-05 -0.000160794 -0.000610769 0 0 -4.38969e-06 -2.27512e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00144739 0.000442862 0.000260445 0.000264511 0.000259909 0.000263986 0.00121714 0.000349098 0.190139 0.114438 0.19013 0.114433 1.25898 1.25876 0.104083 0.0952129 0.104082 0.0952134 0.376614 0.376515 9.93918e-09 6.27132e-09 9.93512e-09 6.24841e-09 1.14158e-08 1.4167e-08 0 0 3.99532e-06 3.99038e-06 0 0 0 0 0 0 0 0
70 6785000 0.704885 0.696585 0.00137156 0.00143156 -0.014111 -0.0125439 0.70918 0.717363 -0.0140215 -0.0438953 0.000900028 -0.023884 -0.122135 -0.111963 -0.00649166 -0.0250286 0.00137702 -0.00760485 -365.447 -365.444 -1.8649e-05 -2.3605e-05 -5.4784e-05 -5.43535e-05 -0.000160689 -0.000609986 0 0 -2.86484e-06 -2.11554e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00109915 0.000415745 0.000260667 0.000266153 0.000260259 0.000265634 0.0009244 0.000327005 0.191922 0.130724 0.191912 0.130723 1.02818 1.03301 0.129598 0.112819 0.129596 0.112818 0.379444 0.379393 9.93927e-09 6.27139e-09 9.93521e-09 6.2485e-09 1.14121e-08 1.41535e-08 0 0 3.99392e-06 3.98898e-06 0 0 0 0 0 0 0 0
71 6885000 0.704136 0.695379 0.00138548 0.00134734 -0.0140415 -0.0125886 0.709924 0.718531 -0.0136586 -0.0407724 0.000177781 -0.0239634 -0.128743 -0.12073 -0.00499294 -0.0203098 0.000899876 -0.00707144 -365.453 -365.45 -1.81348e-05 -2.23337e-05 -5.49054e-05 -5.40774e-05 -0.000160729 -0.000609158 0 0 -3.60625e-06 -2.1393e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00083927 0.000384882 0.000261063 0.000258004 0.000260751 0.000257515 0.000706747 0.000302732 0.137222 0.119206 0.137215 0.119213 0.79864 0.80734 0.0979423 0.0896852 0.0979413 0.0896845 0.347412 0.347519 8.16361e-09 5.53707e-09 8.15934e-09 5.51475e-09 1.14051e-08 1.41313e-08 0 0 3.9915e-06 3.98645e-06 0 0 0 0 0 0 0 0
72 6985000 0.703424 0.694162 0.00145336 0.00138484 -0.0140073 -0.0125463 0.710631 0.719708 -0.0140832 -0.0429111 0.000640705 -0.0258346 -0.135016 -0.128883 -0.00639625 -0.0245242 0.000963651 -0.00951919 -365.46 -365.457 -1.81382e-05 -2.22973e-05 -5.49037e-05 -5.40989e-05 -0.000160808 -0.000608212 0 0 -4.75233e-06 -2.24399e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000684073 0.000359521 0.000262057 0.000259391 0.000261801 0.000258909 0.000576955 0.000282987 0.144019 0.13816 0.144012 0.138171 0.633741 0.645221 0.118779 0.106649 0.118778 0.106648 0.319461 0.319783 8.16369e-09 5.53712e-09 8.15944e-09 5.51483e-09 1.13973e-08 1.41043e-08 0 0 3.98828e-06 3.98325e-06 0 0 0 0 0 0 0 0
73 7085000 0.702308 0.692683 0.0014451 0.00127439 -0.0139916 -0.0126886 0.711734 0.72113 -0.0123993 -0.0375389 -0.000647408 -0.0260296 -0.131771 -0.12726 -0.00500258 -0.0199175 0.000608756 -0.00856766 -365.458 -365.456 -1.76978e-05 -2.12057e-05 -5.49773e-05 -5.37803e-05 -0.000161031 -0.00060737 0 0 -7.6544e-06 -2.4799e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000581021 0.000338366 0.00026167 0.000245043 0.000261451 0.000244601 0.000490833 0.000266651 0.111855 0.128607 0.11185 0.128625 0.514682 0.528129 0.0908423 0.0863101 0.0908413 0.0863094 0.295665 0.29624 6.85774e-09 5.00662e-09 6.85341e-09 4.98504e-09 1.13875e-08 1.40719e-08 0 0 3.98415e-06 3.97902e-06 0 0 0 0 0 0 0 0
74 7185000 0.701912 0.691561 0.0014537 0.00125428 -0.0139377 -0.0126304 0.712126 0.722206 -0.0145538 -0.040944 -0.00119025 -0.0289542 -0.151432 -0.148488 -0.00634285 -0.023849 0.000532112 -0.0112789 -365.476 -365.474 -1.76951e-05 -2.11461e-05 -5.49786e-05 -5.38135e-05 -0.000160966 -0.000605914 0 0 -6.6746e-06 -2.37763e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000507619 0.000320465 0.000262991 0.000246049 0.000262799 0.000245611 0.000429679 0.000253011 0.12282 0.149359 0.122816 0.149385 0.426916 0.441712 0.108384 0.103492 0.108382 0.103492 0.274884 0.275727 6.85782e-09 5.00665e-09 6.85351e-09 4.98512e-09 1.13764e-08 1.40339e-08 0 0 3.97879e-06 3.97369e-06 0 0 0 0 0 0 0 0
75 7285000 0.7017 0.690534 0.00147235 0.00116294 -0.0138803 -0.0127847 0.712336 0.723186 -0.0162872 -0.0357576 -0.00137467 -0.0275316 -0.151912 -0.150206 -0.00788352 -0.0192934 0.0003876 -0.00988902 -365.477 -365.476 -1.76971e-05 -2.01952e-05 -5.49774e-05 -5.3505e-05 -0.000160945 -0.000604034 0 0 -1.07183e-05 -2.72637e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00045279 0.000305161 0.000264661 0.000225096 0.000264489 0.00022471 0.000384053 0.000241467 0.136303 0.138318 0.136299 0.138347 0.362166 0.377865 0.128725 0.0847083 0.128723 0.0847085 0.257075 0.2582 6.8579e-09 4.63819e-09 6.8536e-09 4.61746e-09 1.13636e-08 1.39898e-08 0 0 3.97204e-06 3.96687e-06 0 0 0 0 0 0 0 0
76 7385000 0.70137 0.689462 0.00146212 0.00114523 -0.0138616 -0.012746 0.712661 0.724209 -0.014355 -0.0369923 -0.000682973 -0.0289639 -0.161798 -0.161272 -0.00658226 -0.022982 0.000170294 -0.0126652 -365.489 -365.488 -1.72942e-05 -2.01159e-05 -5.50174e-05 -5.35518e-05 -0.000160884 -0.000602007 0 0 -1.24342e-05 -2.90676e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000410296 0.000291955 0.000261246 0.000225687 0.000261089 0.000225306 0.000348797 0.000231637 0.118413 0.159783 0.118413 0.159819 0.313697 0.329951 0.100086 0.102565 0.100085 0.102567 0.241455 0.242862 5.90074e-09 4.6382e-09 5.89645e-09 4.61753e-09 1.13483e-08 1.39392e-08 0 0 3.9635e-06 3.95844e-06 0 0 0 0 0 0 0 0
77 7485000 0.701247 0.688308 0.00152335 0.00110302 -0.0137933 -0.0129208 0.712784 0.725303 -0.0162934 -0.0312566 -0.000839486 -0.0266938 -0.167818 -0.168031 -0.00812962 -0.0182479 0.000108627 -0.0106798 -365.497 -1.72908e-05 -1.93474e-05 -5.50194e-05 -5.32719e-05 -0.000160714 -0.000600002 0 0 -1.58442e-05 -3.19526e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000384636 0.000284054 0.000262866 0.000199178 0.000262719 0.000198854 0.00032753 0.000225729 0.135199 0.144909 0.135201 0.144945 0.288934 0.306108 0.118551 0.0842678 0.118549 0.0842696 0.241776 0.243676 5.90082e-09 4.39894e-09 5.89655e-09 4.37905e-09 1.13354e-08 1.38968e-08 0 0 3.95572e-06 3.95063e-06 0 0 0 0 0 0 0 0
78 7585000 0.701215 0.687458 0.00149016 0.00107152 -0.0137452 -0.0128453 0.712816 0.72611 -0.0158046 -0.03345 -0.000321018 -0.028297 -0.171899 -0.172923 -0.00684865 -0.0214907 2.35484e-05 -0.013383 -365.503 -365.502 -1.69185e-05 -1.92323e-05 -5.50461e-05 -5.33426e-05 -0.00016043 -0.000596988 0 0 -2.1388e-05 -3.76832e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000355681 0.000273665 0.00025474 0.000199417 0.000254606 0.000199097 0.000303665 0.000218199 0.123715 0.166033 0.12372 0.166074 0.260044 0.277293 0.0943152 0.102865 0.0943142 0.102869 0.228517 0.230711 5.1993e-09 4.39892e-09 5.19509e-09 4.37912e-09 1.13159e-08 1.3834e-08 0 0 3.94325e-06 3.93842e-06 0 0 0 0 0 0 0 0
79 7685000 0.700892 0.686434 0.00156641 0.00104852 -0.0136774 -0.0130326 0.713135 0.727075 -0.017965 -0.0275504 -0.000244637 -0.0250843 -0.1681 -0.169711 -0.00855498 -0.0168021 9.25826e-07 -0.0109302 -365.499 -1.6922e-05 -1.86241e-05 -5.50455e-05 -5.31417e-05 -0.000160383 -0.00059408 0 0 -3.31519e-05 -4.89678e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000331759 0.000264484 0.000256094 0.000169748 0.000255968 0.000169488 0.000284051 0.00021164 0.143102 0.146483 0.143109 0.14652 0.23878 0.255923 0.112202 0.0842905 0.112201 0.0842939 0.217154 0.219632 5.19937e-09 4.2576e-09 5.19518e-09 4.23853e-09 1.12939e-08 1.37641e-08 0 0 3.92824e-06 3.92362e-06 0 0 0 0 0 0 0 0
80 7785000 0.700359 0.685283 0.00153733 0.00102933 -0.0137302 -0.0130492 0.713657 0.728159 -0.016668 -0.0286504 0.000294973 -0.0264857 -0.166576 -0.168731 -0.00731456 -0.019655 3.32299e-06 -0.0134591 -365.498 -365.499 -1.65928e-05 -1.85248e-05 -5.50596e-05 -5.3208e-05 -0.000160516 -0.000591344 0 0 -4.43513e-05 -6.04483e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000311647 0.000256336 0.000241902 0.00016977 0.000241785 0.000169512 0.000267691 0.000205917 0.133409 0.166284 0.133419 0.166326 0.223131 0.240013 0.0909311 0.103381 0.0909308 0.103387 0.207244 0.209986 4.69304e-09 4.25757e-09 4.68895e-09 4.23859e-09 1.12685e-08 1.36866e-08 0 0 3.91006e-06 3.90601e-06 0 0 0 0 0 0 0 0
81 7885000 0.700227 0.684455 0.00155643 0.000961536 -0.0137322 -0.0132975 0.713787 0.728933 -0.0194186 -0.0233635 0.00147926 -0.021851 -0.164808 -0.167369 -0.00912385 -0.0150724 9.89445e-05 -0.0106631 -365.495 -365.496 -1.65878e-05 -1.80496e-05 -5.50641e-05 -5.31013e-05 -0.000160186 -0.000587473 0 0 -5.88925e-05 -7.45948e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000294502 0.000249012 0.000242871 0.000139944 0.000242759 0.000139738 0.000253874 0.000200854 0.154511 0.142627 0.154524 0.14266 0.211835 0.228285 0.109114 0.0841718 0.109114 0.0841763 0.198625 0.201602 4.69311e-09 4.18378e-09 4.68904e-09 4.16542e-09 1.12399e-08 1.36011e-08 0 0 3.88837e-06 3.8849e-06 0 0 0 0 0 0 0 0
82 7985000 0.700087 0.683643 0.00152408 0.000948899 -0.0137601 -0.0132796 0.713924 0.729695 -0.018015 -0.0242567 0.0020018 -0.023097 -0.171152 -0.174314 -0.00782371 -0.0175109 0.00020131 -0.01289 -365.502 -365.504 -1.62692e-05 -1.78897e-05 -5.50923e-05 -5.31993e-05 -0.000159693 -0.000583275 0 0 -6.65339e-05 -8.27319e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000279728 0.000242451 0.000222226 0.000139917 0.000222123 0.000139713 0.000242059 0.000196372 0.143191 0.160446 0.143205 0.160483 0.204034 0.219947 0.0894533 0.103327 0.0894539 0.103334 0.191306 0.1945 4.34195e-09 4.18373e-09 4.338e-09 4.16547e-09 1.12077e-08 1.35081e-08 0 0 3.86303e-06 3.86066e-06 0 0 0 0 0 0 0 0
83 8085000 0.699924 0.682591 0.00151132 0.000904492 -0.0137498 -0.0132748 0.714083 0.730679 -0.019857 -0.0254009 0.00273893 -0.0242903 -0.183199 -0.186919 -0.00973548 -0.0200283 0.000459462 -0.01521 -365.518 -365.52 -1.62517e-05 -1.77474e-05 -5.51025e-05 -5.32824e-05 -0.000159074 -0.000579618 0 0 -6.85521e-05 -8.51907e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000270514 0.000239045 0.000222782 0.0001401 0.000222682 0.000139895 0.000234794 0.000194128 0.164947 0.179365 0.164964 0.179405 0.204647 0.220502 0.108381 0.126744 0.108382 0.126756 0.194116 0.19784 4.34202e-09 4.1837e-09 4.33809e-09 4.16552e-09 1.11812e-08 1.34331e-08 0 0 3.84145e-06 3.84009e-06 0 0 0 0 0 0 0 0
84 8185000 0.699519 0.681617 0.0014276 0.000809322 -0.0137787 -0.0134651 0.714479 0.731584 -0.018676 -0.0195641 0.00345243 -0.0198013 -0.188425 -0.192654 -0.00816942 -0.015083 0.000576049 -0.0118819 -365.526 -365.528 -1.5983e-05 -1.73975e-05 -5.51334e-05 -5.32488e-05 -0.000158905 -0.000575548 0 0 -7.94094e-05 -9.62055e-05 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000258846 0.000233512 0.000196701 0.000112657 0.000196609 0.000112493 0.000225641 0.000190422 0.149701 0.14976 0.149718 0.149789 0.201091 0.216118 0.0891759 0.102287 0.0891776 0.102295 0.188308 0.192184 4.11447e-09 4.15082e-09 4.11066e-09 4.13313e-09 1.11422e-08 1.3326e-08 0 0 3.80879e-06 3.80904e-06 0 0 0 0 0 0 0 0
85 8285000 0.699264 0.680803 0.00146217 0.000806809 -0.0138254 -0.0135186 0.714728 0.732342 -0.019942 -0.0197942 0.00358094 -0.0213446 -0.184673 -0.188833 -0.0101674 -0.0171717 0.000944614 -0.013843 -365.523 -365.525 -1.59746e-05 -1.72235e-05 -5.514e-05 -5.33668e-05 -0.000158497 -0.000570702 0 0 -0.000102378 -0.000119443 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000248507 0.000228461 0.000196903 0.000112953 0.000196814 0.000112788 0.000217626 0.00018706 0.171067 0.166111 0.171087 0.166141 0.199012 0.213101 0.108889 0.125014 0.108892 0.125026 0.18338 0.187361 4.11453e-09 4.15073e-09 4.11075e-09 4.13316e-09 1.10989e-08 1.32107e-08 0 0 3.77159e-06 3.77404e-06 0 0 0 0 0 0 0 0
86 8385000 0.699055 0.680039 0.0014328 0.000787076 -0.0138719 -0.0136856 0.714932 0.733047 -0.0175171 -0.0138757 0.00383804 -0.0174577 -0.182319 -0.186453 -0.00834807 -0.0127131 0.000957637 -0.010668 -365.521 -365.524 -1.57414e-05 -1.69204e-05 -5.51848e-05 -5.34271e-05 -0.000157769 -0.000565147 0 0 -0.00012503 -0.000141977 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000239291 0.000223822 0.000167709 8.97515e-05 0.000167631 8.96167e-05 0.000210528 0.000183949 0.150993 0.136127 0.151011 0.136146 0.198094 0.211135 0.0893233 0.100206 0.0893259 0.100214 0.179353 0.183394 3.98068e-09 4.13894e-09 3.977e-09 4.12172e-09 1.10513e-08 1.30876e-08 0 0 3.73007e-06 3.73517e-06 0 0 0 0 0 0 0 0
87 8485000 0.698712 0.679198 0.00142104 0.000733462 -0.0138806 -0.0137032 0.715267 0.733827 -0.0188761 -0.0139268 0.00459043 -0.0182897 -0.179339 -0.183437 -0.0102555 -0.0142201 0.00137268 -0.0123922 -365.52 -365.522 -1.57284e-05 -1.67252e-05 -5.51937e-05 -5.35576e-05 -0.000157252 -0.000559734 0 0 -0.000148862 -0.00016608 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000231001 0.000219547 0.00016769 9.0295e-05 0.000167613 9.01579e-05 0.00020421 0.000181068 0.170993 0.149911 0.171015 0.14993 0.197814 0.209722 0.109536 0.121776 0.109541 0.121788 0.175989 0.180036 3.98073e-09 4.13883e-09 3.97709e-09 4.12175e-09 1.09989e-08 1.29565e-08 0 0 3.68398e-06 3.69242e-06 0 0 0 0 0 0 0 0
88 8585000 0.698377 0.678398 0.00136009 0.00069465 -0.013899 -0.0138072 0.715594 0.734565 -0.016556 -0.00931655 0.00563078 -0.0139987 -0.177416 -0.181543 -0.0082619 -0.0103741 0.00131149 -0.0094711 -365.52 -365.522 -1.55597e-05 -1.64872e-05 -5.52315e-05 -5.36539e-05 -0.000156812 -0.000554263 0 0 -0.000172116 -0.000189367 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000223473 0.000215563 0.000138308 7.18609e-05 0.000138244 7.1744e-05 0.000198567 0.000178381 0.146723 0.121379 0.146741 0.121387 0.197984 0.208686 0.089237 0.0972597 0.0892402 0.0972665 0.173312 0.177316 3.91141e-09 4.13581e-09 3.90787e-09 4.11899e-09 1.09419e-08 1.28179e-08 0 0 3.63382e-06 3.64617e-06 0 0 0 0 0 0 0 0
89 8685000 0.698347 0.677914 0.00140618 0.000693376 -0.0138521 -0.013769 0.715624 0.735012 -0.0189073 -0.0101035 0.00613671 -0.0150613 -0.169542 -0.173383 -0.0100868 -0.0114119 0.00190363 -0.0108477 -365.513 -365.515 -1.55221e-05 -1.62321e-05 -5.52548e-05 -5.38257e-05 -0.00015547 -0.000547139 0 0 -0.00020609 -0.000222887 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000216623 0.000211868 0.000138231 7.27423e-05 0.000138169 7.26223e-05 0.000193471 0.000175847 0.164683 0.132839 0.164704 0.132846 0.198194 0.207644 0.109481 0.117383 0.109487 0.117392 0.171103 0.175011 3.91146e-09 4.13568e-09 3.90796e-09 4.119e-09 1.08799e-08 1.26716e-08 0 0 3.57955e-06 3.59654e-06 0 0 0 0 0 0 0 0
90 8785000 0.697901 0.676809 0.00125287 0.000576003 -0.0138762 -0.0138525 0.716058 0.736028 -0.0161308 -0.00601316 0.00653713 -0.0117877 -0.165173 -0.168816 -0.00805508 -0.00827486 0.00173621 -0.00826764 -365.511 -365.514 -1.54101e-05 -1.60713e-05 -5.52856e-05 -5.3921e-05 -0.000155183 -0.000542777 0 0 -0.000231824 -0.00024822 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000212642 0.00021057 0.000111244 5.88303e-05 0.000111193 5.87209e-05 0.000190721 0.000175033 0.137861 0.106911 0.137876 0.10691 0.203511 0.212132 0.0885189 0.0937182 0.0885225 0.0937235 0.176877 0.180984 3.88115e-09 4.13528e-09 3.87772e-09 4.11876e-09 1.08299e-08 1.25568e-08 0 0 3.53626e-06 3.55712e-06 0 0 0 0 0 0 0 0
91 8885000 0.697667 0.676201 0.00128774 0.000561673 -0.0138838 -0.0138577 0.716287 0.736586 -0.0172077 -0.0056107 0.00680158 -0.0133604 -0.163548 -0.167291 -0.00977927 -0.00910794 0.00243726 -0.00971493 -365.512 -365.514 -1.53855e-05 -1.58453e-05 -5.53006e-05 -5.40934e-05 -0.000154331 -0.000536181 0 0 -0.00025533 -0.00027183 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000206779 0.000207315 0.00011127 6.01043e-05 0.00011122 5.99903e-05 0.00018643 0.00017273 0.153449 0.116407 0.153467 0.116402 0.203304 0.210609 0.1083 0.112267 0.108305 0.112273 0.175319 0.179214 3.88119e-09 4.13515e-09 3.8778e-09 4.11875e-09 1.07588e-08 1.23978e-08 0 0 3.47595e-06 3.50259e-06 0 0 0 0 0 0 0 0
92 8985000 0.697398 0.675594 0.00124372 0.000545089 -0.0139036 -0.0139105 0.716548 0.737142 -0.0142891 -0.00210514 0.00561456 -0.0122684 -0.15447 -0.158078 -0.00768514 -0.00660601 0.00205229 -0.00773815 -365.504 -365.506 -1.53011e-05 -1.56263e-05 -5.53324e-05 -5.42763e-05 -0.000153494 -0.000529386 0 0 -0.000290075 -0.000305851 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000201389 0.000204279 8.82923e-05 5.00697e-05 8.82548e-05 4.99631e-05 0.000182501 0.000170526 0.126073 0.0936313 0.126086 0.0936207 0.202731 0.208745 0.0870468 0.0898484 0.0870505 0.089852 0.174111 0.177753 3.87081e-09 4.13497e-09 3.86749e-09 4.11867e-09 1.06825e-08 1.22321e-08 0 0 3.41335e-06 3.44626e-06 0 0 0 0 0 0 0 0
93 9085000 0.697124 0.675014 0.00128353 0.000532511 -0.0139276 -0.0139349 0.716814 0.737673 -0.0154167 -0.00153888 0.00575223 -0.0139359 -0.155345 -0.159214 -0.00918227 -0.00692035 0.00261095 -0.00925418 -365.508 -365.511 -1.52722e-05 -1.53825e-05 -5.53496e-05 -5.44606e-05 -0.000152502 -0.000522291 0 0 -0.000306964 -0.000323071 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00019643 0.000201455 8.85515e-05 5.17607e-05 8.85142e-05 5.16481e-05 0.000178876 0.000168403 0.139245 0.101544 0.139261 0.101529 0.201555 0.206332 0.105955 0.10682 0.105961 0.106824 0.173043 0.176397 3.87084e-09 4.13483e-09 3.86757e-09 4.11865e-09 1.06007e-08 1.206e-08 0 0 3.34873e-06 3.38848e-06 0 0 0 0 0 0 0 0
94 9185000 0.697166 0.674791 0.00122948 0.000498866 -0.0139795 -0.0140131 0.716772 0.737876 -0.0121536 0.00201117 0.00492832 -0.0127681 -0.155689 -0.159768 -0.00712334 -0.00480127 0.00213737 -0.00752193 -365.512 -365.514 -1.51851e-05 -1.50891e-05 -5.53915e-05 -5.46938e-05 -0.000150421 -0.000513475 0 0 -0.000326688 -0.000342265 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000191833 0.000198797 7.0159e-05 4.48554e-05 7.01325e-05 4.47458e-05 0.000175532 0.00016636 0.112997 0.0820025 0.113007 0.0819831 0.199713 0.20332 0.0848989 0.085871 0.0849025 0.0858728 0.172037 0.175072 3.86856e-09 4.13452e-09 3.86536e-09 4.11842e-09 1.05134e-08 1.18813e-08 0 0 3.28267e-06 3.32961e-06 0 0 0 0 0 0 0 0
95 9285000 0.69701 0.674402 0.00121145 0.000424426 -0.0140198 -0.0140571 0.716924 0.73823 -0.0120057 0.00402342 0.00525283 -0.0141701 -0.152745 -0.156947 -0.00837461 -0.00462263 0.00265907 -0.00902923 -365.511 -365.513 -1.51416e-05 -1.48196e-05 -5.54171e-05 -5.49093e-05 -0.000148941 -0.000505394 0 0 -0.000352593 -0.000367665 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000187616 0.000196344 7.07395e-05 4.69697e-05 7.07126e-05 4.68527e-05 0.000172443 0.000164411 0.123985 0.0887345 0.123997 0.0887086 0.197342 0.199881 0.102663 0.101348 0.102668 0.101349 0.171158 0.173862 3.86859e-09 4.13437e-09 3.86543e-09 4.11839e-09 1.04209e-08 1.16975e-08 0 0 3.21663e-06 3.27105e-06 0 0 0 0 0 0 0 0
96 9385000 0.696772 0.673687 0.00117061 0.000345567 -0.0139628 -0.0140506 0.717156 0.738883 -0.0119052 0.00716792 0.00658904 -0.0119986 -0.154398 -0.158696 -0.00959896 -0.0027942 0.00325291 -0.00735088 -365.516 -365.518 -1.51117e-05 -1.46248e-05 -5.54347e-05 -5.50715e-05 -0.000147926 -0.00049939 0 0 -0.000369312 -0.000383981 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000185604 0.000196082 7.15131e-05 4.24902e-05 7.14855e-05 4.23729e-05 0.000171224 0.000164125 0.135487 0.072237 0.135501 0.0722082 0.199946 0.201714 0.123705 0.0819508 0.123712 0.0819505 0.177924 0.180508 3.86863e-09 4.13418e-09 3.86551e-09 4.11826e-09 1.03481e-08 1.1556e-08 0 0 3.16731e-06 3.22731e-06 0 0 0 0 0 0 0 0
97 9485000 0.69674 0.673498 0.00110707 0.000278845 -0.0140144 -0.0140801 0.717186 0.739055 -0.00920687 0.00897836 0.00537996 -0.0139691 -0.15161 -0.156127 -0.00731195 -0.00204442 0.0027177 -0.00880129 -365.518 -365.52 -1.50439e-05 -1.43182e-05 -5.54699e-05 -5.53136e-05 -0.000145813 -0.000490264 0 0 -0.000390219 -0.00040422 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000181969 0.000193941 5.76944e-05 4.50226e-05 5.76757e-05 4.48971e-05 0.00016854 0.000162324 0.109044 0.0781065 0.109053 0.0780698 0.196268 0.197145 0.0987328 0.0960666 0.0987373 0.0960648 0.176929 0.179147 3.8685e-09 4.13402e-09 3.86544e-09 4.11822e-09 1.02461e-08 1.13633e-08 0 0 3.10215e-06 3.16983e-06 0 0 0 0 0 0 0 0
98 9585000 0.696658 0.673294 0.00112287 0.000251963 -0.0139982 -0.0141015 0.717266 0.73924 -0.0103143 0.0103953 0.00578248 -0.0130922 -0.147691 -0.152431 -0.00834798 -0.000738012 0.00327615 -0.00732784 -365.517 -365.52 -1.49889e-05 -1.40268e-05 -5.55019e-05 -5.5549e-05 -0.000143939 -0.000481363 0 0 -0.000414492 -0.000427465 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000178628 0.000191941 5.88408e-05 4.23728e-05 5.88214e-05 4.22466e-05 0.000166054 0.000160599 0.118547 0.0643212 0.118557 0.0642833 0.19198 0.192078 0.118088 0.0782007 0.118094 0.0781984 0.17579 0.177646 3.86851e-09 4.13376e-09 3.86551e-09 4.11808e-09 1.01388e-08 1.11657e-08 0 0 3.03832e-06 3.11345e-06 0 0 0 0 0 0 0 0
99 9685000 0.696398 0.672934 0.00113429 0.000247276 -0.0140275 -0.0141153 0.717518 0.739567 -0.00803226 0.0123672 0.00622521 -0.0134423 -0.141029 -0.145923 -0.00641589 0.00037957 0.00273605 -0.00876844 -365.513 -365.516 -1.49573e-05 -1.37671e-05 -5.55178e-05 -5.57674e-05 -0.000142773 -0.000473372 0 0 -0.000441707 -0.000453917 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000175572 0.000190104 4.88473e-05 4.53125e-05 4.88352e-05 4.51777e-05 0.00016376 0.000158968 0.0953444 0.0696541 0.0953504 0.0696065 0.18727 0.186718 0.0944612 0.0911141 0.0944651 0.0911092 0.174611 0.176128 3.86837e-09 4.13361e-09 3.86543e-09 4.11803e-09 1.00266e-08 1.09647e-08 0 0 2.97675e-06 3.05924e-06 0 0 0 0 0 0 0 0
100 9785000 0.696397 0.672883 0.00112702 0.000198471 -0.0139765 -0.0140938 0.71752 0.739614 -0.00666722 0.0157028 0.00748069 -0.0117566 -0.131935 -0.1371 -0.00720051 0.00130873 0.00341987 -0.00728897 -365.506 -365.509 -1.48918e-05 -1.34654e-05 -5.5556e-05 -5.60118e-05 -0.000140548 -0.000463905 0 0 -0.000472068 -0.000482529 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000172772 0.00018839 5.03913e-05 4.4015e-05 5.03783e-05 4.38788e-05 0.000161643 0.00015742 0.103246 0.0582169 0.103253 0.0581691 0.182073 0.180982 0.112134 0.0746982 0.112139 0.0746937 0.173248 0.174444 3.86837e-09 4.13258e-09 3.8655e-09 4.11718e-09 9.90938e-09 1.076e-08 0 0 2.9175e-06 3.00691e-06 0 0 0 0 0 0 0 0
101 9885000 0.696237 0.672695 0.00108647 0.0001258 -0.0139178 -0.0140303 0.717676 0.739787 -0.00477259 0.0180571 0.00688529 -0.0132236 -0.130748 -0.136192 -0.0053618 0.00306498 0.00295168 -0.00866228 -365.509 -365.512 -1.48452e-05 -1.3168e-05 -5.55796e-05 -5.62511e-05 -0.000138745 -0.000454967 0 0 -0.000487589 -0.000497406 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00017024 0.000186834 4.34888e-05 4.73469e-05 4.34817e-05 4.7202e-05 0.000159684 0.000155951 0.0833416 0.063261 0.083345 0.0632024 0.176606 0.175089 0.090091 0.086582 0.0900941 0.0865737 0.171821 0.172725 3.86795e-09 4.13242e-09 3.86514e-09 4.11712e-09 9.78757e-09 1.05529e-08 0 0 2.86127e-06 2.95732e-06 0 0 0 0 0 0 0 0
102 9985000 0.696046 0.672503 0.00112585 0.000131628 -0.0139358 -0.0140687 0.717861 0.73996 -0.0047242 0.0196729 0.00657869 -0.0133388 -0.125677 -0.131366 -0.00587554 0.00360597 0.00363089 -0.00730212 -365.506 -365.509 -1.47993e-05 -1.29047e-05 -5.56064e-05 -5.64575e-05 -0.000137192 -0.000446325 0 0 -0.000510134 -0.000518905 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000167932 0.000185381 4.54375e-05 4.70215e-05 4.54286e-05 4.68743e-05 0.000157881 0.00015456 0.0900321 0.0538154 0.0900356 0.0537579 0.170834 0.168986 0.106173 0.0714956 0.106177 0.0714887 0.170204 0.170842 3.86795e-09 4.12888e-09 3.86521e-09 4.11384e-09 9.66111e-09 1.0343e-08 0 0 2.80795e-06 2.91006e-06 0 0 0 0 0 0 0 0
103 10085000 0.695925 0.672126 0.00111825 9.22506e-05 -0.0139319 -0.0140648 0.717979 0.740303 -0.00258346 0.0229322 0.00480048 -0.015967 -0.126139 -0.132072 -0.00434069 0.00580908 0.00298773 -0.00885258 -365.51 -365.513 -1.47543e-05 -1.26692e-05 -5.56282e-05 -5.66496e-05 -0.000135522 -0.000439186 0 0 -0.000522234 -0.000530141 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000167419 0.000185925 4.0937e-05 5.07316e-05 4.09318e-05 5.05734e-05 0.000157696 0.000154741 0.0732397 0.0588031 0.0732412 0.0587336 0.169909 0.167791 0.0857993 0.0825275 0.0858017 0.0825156 0.175933 0.176372 3.86764e-09 4.12879e-09 3.86495e-09 4.11382e-09 9.56338e-09 1.01845e-08 0 0 2.76995e-06 2.87641e-06 0 0 0 0 0 0 0 0
104 10185000 0.695676 0.671928 0.00111391 1.88368e-05 -0.0139917 -0.014133 0.718219 0.740482 -0.00237022 0.0257896 0.00640248 -0.0163394 -0.126497 -0.132658 -0.00459062 0.00837004 0.00351096 -0.0106322 -365.514 -365.517 -1.47186e-05 -1.23969e-05 -5.56488e-05 -5.6872e-05 -0.000134301 -0.000430929 0 0 -0.00053416 -0.000541666 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000165492 0.000184658 4.32857e-05 5.46463e-05 4.32783e-05 5.44774e-05 0.000156151 0.000153488 0.0790574 0.0642761 0.0790585 0.0641922 0.163643 0.161344 0.100435 0.0951096 0.100438 0.0950911 0.173912 0.174126 3.86763e-09 4.12864e-09 3.86501e-09 4.11376e-09 9.42952e-09 9.9718e-09 0 0 2.7222e-06 2.83397e-06 0 0 0 0 0 0 0 0
105 10285000 0.695527 0.671858 0.00105745 -4.37122e-05 -0.0139725 -0.0141278 0.718363 0.740546 -0.000546491 0.027651 0.00478271 -0.0168854 -0.115454 -0.12193 -0.00335293 0.00863651 0.00288296 -0.00934738 -365.502 -365.506 -1.46704e-05 -1.21673e-05 -5.56737e-05 -5.70608e-05 -0.000132714 -0.000422278 0 0 -0.000563502 -0.000569358 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000163748 0.000183477 4.06011e-05 5.51286e-05 4.05969e-05 5.49581e-05 0.00015475 0.00015232 0.0650473 0.0561282 0.0650471 0.0560468 0.157393 0.15498 0.0817081 0.0789873 0.0817099 0.0789716 0.171841 0.171859 3.86752e-09 4.11977e-09 3.86498e-09 4.10524e-09 9.29208e-09 9.75816e-09 0 0 2.67789e-06 2.79435e-06 0 0 0 0 0 0 0 0
106 10385000 0.695439 0.671888 0.00102611 -0.000152134 -0.0139197 -0.0140837 0.718449 0.740519 0.0113944 0.0137645 -0.0203235 -0.0218878 0.00395206 0.00395859 0.000951113 0.00105685 -0.00180988 -0.0018806 -365.489 -365.493 -1.46067e-05 -1.18613e-05 -5.57103e-05 -5.73173e-05 -0.000130525 -0.000412864 0 0 -0.000581462 -0.000585675 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000162274 0.000182475 4.33385e-05 5.93972e-05 4.33323e-05 5.92167e-05 0.000153548 0.000151298 0.0347254 0.0347737 0.0347253 0.0347731 0.0376514 0.0376446 0.12528 0.12528 0.149194 0.149189 3.86751e-09 4.11962e-09 3.86505e-09 4.10518e-09 9.15109e-09 9.5441e-09 0 0 2.64074e-06 2.76113e-06 0 0 0 0 0 0 0 0
107 10485000 0.695267 0.67185 0.00104904 -0.000204837 -0.0139219 -0.0140928 0.718616 0.740553 0.0121846 0.0172704 -0.0199027 -0.0233618 -0.000794477 -0.000891165 0.00211183 0.00259157 -0.00382334 -0.00414814 -365.474 -365.477 -1.45576e-05 -1.15785e-05 -5.57386e-05 -5.75576e-05 -0.000128851 -0.000404108 0 0 -0.000600041 -0.000602577 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000161082 0.000181671 4.62695e-05 6.38713e-05 4.62608e-05 6.36804e-05 0.000152612 0.000150486 0.0353241 0.03555 0.035324 0.0355474 0.0383423 0.0383148 0.126252 0.126254 0.126252 0.126254 0.131539 0.13152 3.86749e-09 4.11947e-09 3.86511e-09 4.10513e-09 9.00693e-09 9.32982e-09 0 0 2.61293e-06 2.73625e-06 0 0 0 0 0 0 0 0
108 10585000 0.695247 0.672001 0.0010811 -0.000241196 -0.0139732 -0.0141546 0.718634 0.740415 0.0126651 0.0199312 -0.017033 -0.0220067 -0.00437551 -0.00469469 0.00251857 0.00328156 -0.00372231 -0.0042435 -365.466 -365.47 -1.45014e-05 -1.13083e-05 -5.56983e-05 -5.76689e-05 -0.000126581 -0.00039466 0 0 -0.000610657 -0.000611364 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000160074 0.000180967 4.92771e-05 6.83282e-05 4.92658e-05 6.81274e-05 0.000151853 0.000149807 0.0317308 0.0321918 0.0317305 0.0321865 0.0368 0.0367459 0.0848584 0.0848636 0.0848584 0.0848635 0.118582 0.118549 3.8632e-09 4.10903e-09 3.86091e-09 4.09485e-09 8.86018e-09 9.11617e-09 0 0 2.59057e-06 2.71617e-06 0 0 0 0 0 0 0 0
109 10685000 0.695111 0.671762 0.00111479 -0.000277182 -0.013967 -0.0141548 0.718766 0.740631 0.0127454 0.0230813 -0.0180157 -0.0251157 -0.00982359 -0.0104019 0.00382799 0.00548002 -0.00548902 -0.00662012 -365.462 -365.465 -1.44521e-05 -1.10777e-05 -5.57263e-05 -5.78601e-05 -0.000124868 -0.000387601 0 0 -0.000618188 -0.000617297 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000160605 0.000182088 5.25877e-05 7.31982e-05 5.25731e-05 7.29853e-05 0.00015251 0.000150525 0.0330327 0.0339484 0.0330321 0.0339381 0.0380193 0.037924 0.0865672 0.0865903 0.0865671 0.0865901 0.11252 0.112461 3.86321e-09 4.10895e-09 3.86099e-09 4.09484e-09 8.74854e-09 8.95648e-09 0 0 2.57694e-06 2.70395e-06 0 0 0 0 0 0 0 0
110 10785000 0.695098 0.671964 0.00110558 -0.000336326 -0.013995 -0.0141963 0.718778 0.740448 0.0125456 0.0247403 -0.0167377 -0.0250695 -0.0145644 -0.0155428 0.00394682 0.00583148 -0.00500968 -0.00629537 -365.46 -365.462 -1.44111e-05 -1.09206e-05 -5.56186e-05 -5.77964e-05 -0.00012255 -0.000378216 0 0 -0.000623328 -0.000620674 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000159817 0.000181449 5.55841e-05 7.72938e-05 5.55673e-05 7.70741e-05 0.000151925 0.000149951 0.0304781 0.0317391 0.0304773 0.0317253 0.0368422 0.0367139 0.0656909 0.0657237 0.0656909 0.0657233 0.104598 0.104526 3.84565e-09 4.06844e-09 3.84352e-09 4.05471e-09 8.59746e-09 8.74431e-09 0 0 2.55977e-06 2.68833e-06 0 0 0 0 0 0 0 0
111 10885000 0.695085 0.672188 0.00104238 -0.000482351 -0.0139554 -0.0141685 0.718792 0.740245 0.0131617 0.0286639 -0.0171198 -0.0277385 -0.021463 -0.022991 0.00521381 0.00850793 -0.00668624 -0.00894548 -365.461 -365.463 -1.43491e-05 -1.06191e-05 -5.56534e-05 -5.80414e-05 -0.000120372 -0.000369045 0 0 -0.000625516 -0.000620785 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000159156 0.000180888 5.92492e-05 8.25065e-05 5.92298e-05 8.22764e-05 0.000151471 0.000149451 0.0325365 0.0345526 0.0325353 0.0345306 0.0381869 0.0380073 0.067955 0.068049 0.0679549 0.068048 0.0995395 0.0994383 3.84563e-09 4.06831e-09 3.84358e-09 4.05465e-09 8.44442e-09 8.53345e-09 0 0 2.54653e-06 2.6764e-06 0 0 0 0 0 0 0 0
112 10985000 0.695213 0.672577 0.00106388 -0.000480091 -0.0139893 -0.0142238 0.718667 0.73989 0.012601 0.0294518 -0.0144151 -0.025866 -0.0272705 -0.0294233 0.00569318 0.00905525 -0.00774586 -0.0100095 -365.459 -365.461 -1.41944e-05 -1.04461e-05 -5.53843e-05 -5.76384e-05 -0.000117467 -0.000359174 0 0 -0.000632205 -0.000625066 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000158499 0.000180236 6.18681e-05 8.55358e-05 6.18474e-05 8.5305e-05 0.00015099 0.000148931 0.0306309 0.032999 0.0306294 0.0329734 0.0371409 0.0369302 0.0551273 0.0552315 0.0551273 0.0552304 0.0945432 0.0944351 3.80515e-09 3.97972e-09 3.80323e-09 3.96677e-09 8.28969e-09 8.32453e-09 0 0 2.53217e-06 2.66301e-06 0 0 0 0 0 0 0 0
113 11085000 0.695343 0.67299 0.00105966 -0.000569527 -0.0139281 -0.0141719 0.718542 0.739516 0.0131492 0.0334665 -0.0139242 -0.0278017 -0.03101 -0.0340316 0.00701136 0.012277 -0.00920767 -0.0127801 -365.454 -365.457 -1.411e-05 -1.01297e-05 -5.5432e-05 -5.79032e-05 -0.000114515 -0.000349332 0 0 -0.000640992 -0.000630683 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000157969 0.00017969 6.58455e-05 9.10061e-05 6.58221e-05 9.07656e-05 0.000150638 0.000148474 0.0334824 0.0369001 0.0334802 0.0368634 0.0385905 0.0383225 0.0578973 0.0581381 0.0578972 0.0581355 0.0921173 0.0919766 3.80512e-09 3.9796e-09 3.80329e-09 3.96672e-09 8.13375e-09 8.1176e-09 0 0 2.52195e-06 2.65373e-06 0 0 0 0 0 0 0 0
114 11185000 0.695259 0.67317 0.00109167 -0.000507275 -0.0139753 -0.0142383 0.718622 0.73935 0.0151749 0.0361024 -0.0113406 -0.0252458 -0.0372693 -0.0408931 0.00748475 0.012506 -0.00931783 -0.0126369 -365.458 -365.461 -1.39685e-05 -1.01784e-05 -5.50922e-05 -5.72497e-05 -0.000112565 -0.00034081 0 0 -0.000642102 -0.000630462 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000157398 0.000179 6.76532e-05 9.21995e-05 6.76297e-05 9.19659e-05 0.00015018 0.000147946 0.0318909 0.0355163 0.0318886 0.0354784 0.0375738 0.0372821 0.0489544 0.049188 0.0489543 0.0491855 0.0886902 0.0885485 3.73262e-09 3.82988e-09 3.73094e-09 3.81809e-09 7.97661e-09 7.91316e-09 0 0 2.50883e-06 2.64113e-06 0 0 0 0 0 0 0 0
115 11285000 0.695154 0.673341 0.00116236 -0.000513039 -0.0140009 -0.0142719 0.718724 0.739194 0.016082 0.0405813 -0.0108071 -0.0271276 -0.0423446 -0.0468007 0.00905915 0.0164036 -0.0104186 -0.0152984 -365.459 -365.462 -1.39264e-05 -9.92866e-06 -5.51161e-05 -5.74589e-05 -0.000111089 -0.000332899 0 0 -0.000646477 -0.000632651 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000156943 0.000178431 7.18788e-05 9.78054e-05 7.18519e-05 9.75616e-05 0.000149886 0.000147503 0.0355487 0.040477 0.0355456 0.0404257 0.0390759 0.038725 0.0522326 0.0527061 0.0522323 0.0527011 0.0878644 0.0876878 3.7326e-09 3.82978e-09 3.731e-09 3.81805e-09 7.81901e-09 7.71132e-09 0 0 2.50048e-06 2.63347e-06 0 0 0 0 0 0 0 0
116 11385000 0.695004 0.67319 0.00127594 -0.000286456 -0.0139978 -0.0142537 0.718868 0.739332 0.0142027 0.0378648 -0.00846435 -0.0242389 -0.0461921 -0.0510729 0.00783319 0.0143304 -0.00878408 -0.0131134 -365.46 -365.463 -1.42345e-05 -1.08831e-05 -5.48795e-05 -5.67336e-05 -0.000109752 -0.000326884 0 0 -0.000651677 -0.000637921 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000157708 0.00017932 7.24349e-05 9.65131e-05 7.24088e-05 9.6284e-05 0.000150654 0.000148201 0.0339454 0.0387654 0.0339423 0.0387164 0.0383837 0.0380137 0.0453555 0.0457728 0.0453552 0.0457685 0.0871594 0.0869804 3.62147e-09 3.61506e-09 3.62003e-09 3.60475e-09 7.69999e-09 7.5616e-09 0 0 2.48966e-06 2.62268e-06 0 0 0 0 0 0 0 0
117 11485000 0.694879 0.673361 0.00128156 -0.000352433 -0.0140192 -0.0142846 0.718989 0.739176 0.0133456 0.0405086 -0.00755507 -0.0258081 -0.0509602 -0.0567746 0.00921872 0.0183225 -0.00958582 -0.0156783 -365.462 -365.466 -1.41928e-05 -1.06478e-05 -5.49035e-05 -5.69315e-05 -0.000108271 -0.000319198 0 0 -0.000654988 -0.00063902 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000157301 0.000178717 7.68234e-05 0.000102106 7.6794e-05 0.000101867 0.000150372 0.000147735 0.0383719 0.0446653 0.0383677 0.0446011 0.0399509 0.0395219 0.0491613 0.0499358 0.0491608 0.0499279 0.087342 0.0871252 3.62144e-09 3.61497e-09 3.62009e-09 3.60472e-09 7.54178e-09 7.36488e-09 0 0 2.4825e-06 2.61603e-06 0 0 0 0 0 0 0 0
118 11585000 0.694801 0.673571 0.00134032 -0.000138887 -0.0140634 -0.0143081 0.719063 0.738984 0.00939458 0.0346396 -0.0043671 -0.0215353 -0.054537 -0.0609783 0.00776025 0.0154801 -0.00801147 -0.0132165 -365.463 -365.467 -1.44824e-05 -1.17032e-05 -5.47141e-05 -5.6182e-05 -0.00010647 -0.000311407 0 0 -0.000661158 -0.000645054 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000156766 0.00017786 7.57727e-05 9.80028e-05 7.57465e-05 9.77887e-05 0.000149885 0.00014715 0.036438 0.042169 0.0364338 0.0421115 0.0388561 0.038426 0.0433946 0.0440256 0.0433941 0.0440193 0.0851559 0.0849507 3.46948e-09 3.34281e-09 3.46833e-09 3.33421e-09 7.38327e-09 7.17138e-09 0 0 2.46989e-06 2.60329e-06 0 0 0 0 0 0 0 0
119 11685000 0.694796 0.673882 0.00131503 -0.000230629 -0.0140675 -0.014322 0.719068 0.7387 0.00779862 0.0363652 -0.00267606 -0.0222573 -0.0604784 -0.0679855 0.00861013 0.0191016 -0.00839893 -0.0155151 -365.469 -365.474 -1.44306e-05 -1.1471e-05 -5.47441e-05 -5.63764e-05 -0.000104587 -0.000303552 0 0 -0.000661284 -0.000642786 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000156374 0.000177209 8.02268e-05 0.000103431 8.01976e-05 0.000103209 0.000149612 0.000146673 0.0415502 0.0488158 0.0415446 0.0487425 0.0404159 0.0399309 0.0477418 0.0488403 0.0477411 0.0488293 0.0859919 0.0857484 3.46946e-09 3.34275e-09 3.46839e-09 3.3342e-09 7.22555e-09 6.98135e-09 0 0 2.46365e-06 2.59742e-06 0 0 0 0 0 0 0 0
120 11785000 0.694851 0.674237 0.00144819 0.000110113 -0.0140846 -0.0143149 0.719014 0.738376 0.00251796 0.0281243 -0.000169466 -0.0178073 -0.0630016 -0.071149 0.0061438 0.0146352 -0.00605815 -0.0118445 -365.468 -365.473 -1.48655e-05 -1.28133e-05 -5.44111e-05 -5.53456e-05 -0.000102393 -0.000295644 0 0 -0.000669822 -0.000651343 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000155818 0.000176257 7.73969e-05 9.66489e-05 7.73729e-05 9.64582e-05 0.000149097 0.000146062 0.0390017 0.0452043 0.0389966 0.0451433 0.0392425 0.0387691 0.0425116 0.0433483 0.042511 0.0433402 0.0840403 0.0838141 3.2802e-09 3.03098e-09 3.27935e-09 3.02414e-09 7.0677e-09 6.79453e-09 0 0 2.45114e-06 2.58453e-06 0 0 0 0 0 0 0 0
121 11885000 0.694785 0.674482 0.00145295 5.6855e-05 -0.014075 -0.0143128 0.719079 0.738153 0.00291652 0.0316401 0.000328636 -0.019402 -0.0669277 -0.0761435 0.00645022 0.0177365 -0.00605449 -0.0137816 -365.471 -365.477 -1.48205e-05 -1.26095e-05 -5.44379e-05 -5.55207e-05 -0.00010075 -0.000288387 0 0 -0.000673619 -0.000652863 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000155436 0.000175571 8.18173e-05 0.000101783 8.17905e-05 0.000101585 0.000148804 0.000145555 0.0446749 0.0523594 0.0446687 0.0522841 0.0407783 0.040256 0.0473941 0.0487808 0.0473931 0.0487673 0.0852733 0.0850093 3.28019e-09 3.03093e-09 3.27941e-09 3.02414e-09 6.91148e-09 6.61177e-09 0 0 2.44558e-06 2.57922e-06 0 0 0 0 0 0 0 0
122 11985000 0.694793 0.674545 0.00160308 0.000437774 -0.01404 -0.0142497 0.719071 0.738096 -0.00034581 0.0246822 0.00304317 -0.0141369 -0.0704423 -0.0800274 0.00427983 0.0131293 -0.00394518 -0.0100186 -365.474 -365.48 -1.51465e-05 -1.38825e-05 -5.41632e-05 -5.45147e-05 -9.87766e-05 -0.000282346 0 0 -0.00067925 -0.000659238 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000156173 0.000176172 7.72655e-05 9.28591e-05 7.72454e-05 9.26959e-05 0.000149464 0.000146116 0.0413134 0.0475066 0.0413083 0.0474476 0.0400017 0.039495 0.0423279 0.0433258 0.0423272 0.0433164 0.0852316 0.084979 3.06226e-09 2.70238e-09 3.06166e-09 2.69717e-09 6.79441e-09 6.477e-09 0 0 2.43447e-06 2.56748e-06 0 0 0 0 0 0 0 0
123 12085000 0.694981 0.675073 0.00162396 0.000407765 -0.014051 -0.014267 0.718889 0.737613 -0.000422612 0.0273814 0.00463728 -0.0144642 -0.0781835 -0.0890739 0.00425926 0.0158405 -0.00357882 -0.011552 -365.483 -365.49 -1.50721e-05 -1.36613e-05 -5.42091e-05 -5.47044e-05 -9.59632e-05 -0.000274091 0 0 -0.000678863 -0.000656037 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000155771 0.000175424 8.15623e-05 9.76057e-05 8.15395e-05 9.74362e-05 0.00014915 0.000145581 0.0473991 0.0549284 0.0473929 0.0548565 0.041546 0.0409966 0.0477126 0.0493027 0.0477115 0.0492877 0.0867578 0.0864669 3.06225e-09 2.70235e-09 3.06172e-09 2.69717e-09 6.64015e-09 6.30083e-09 0 0 2.42945e-06 2.56263e-06 0 0 0 0 0 0 0 0
124 12185000 0.69499 0.675367 0.00157592 0.000559694 -0.0140734 -0.0142616 0.71888 0.737343 0.000259155 0.024402 0.00639042 -0.0102327 -0.0733913 -0.0847408 0.00475009 0.0138453 -0.0030108 -0.0092867 -365.475 -365.482 -1.47742e-05 -1.41621e-05 -5.43477e-05 -5.42701e-05 -9.39522e-05 -0.000267054 0 0 -0.000695791 -0.000673178 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000155178 0.00017433 7.556e-05 8.73071e-05 7.55456e-05 8.71743e-05 0.000148543 0.00014489 0.043147 0.0489188 0.0431419 0.0488646 0.0401956 0.039681 0.0425697 0.0436624 0.0425689 0.0436524 0.0848784 0.0846146 2.82734e-09 2.37871e-09 2.827e-09 2.3749e-09 6.48658e-09 6.12827e-09 0 0 2.41714e-06 2.54961e-06 0 0 0 0 0 0 0 0
125 12285000 0.695078 0.675772 0.00155557 0.000497006 -0.0140862 -0.0142801 0.718795 0.736972 -0.00150354 0.0251159 0.00782645 -0.0105972 -0.0755756 -0.0881459 0.00473153 0.01644 -0.00228166 -0.0103878 -365.475 -365.483 -1.47146e-05 -1.3976e-05 -5.43853e-05 -5.44352e-05 -9.16924e-05 -0.000259761 0 0 -0.000702404 -0.000677393 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00015476 0.000173544 7.96615e-05 9.16156e-05 7.96447e-05 9.14776e-05 0.000148197 0.000144326 0.0494694 0.0563671 0.0494631 0.0563018 0.0416861 0.0411371 0.0483979 0.0500828 0.0483966 0.0500674 0.0865253 0.0862254 2.82734e-09 2.3787e-09 2.82706e-09 2.37491e-09 6.33543e-09 5.96001e-09 0 0 2.41256e-06 2.54511e-06 0 0 0 0 0 0 0 0
126 12385000 0.695086 0.676058 0.00147604 0.00061814 -0.0141064 -0.0142857 0.718787 0.736709 -7.32354e-05 0.0228592 0.00832706 -0.00718416 -0.0721657 -0.0849754 0.00524763 0.0143479 -0.00205086 -0.00821608 -365.469 -365.477 -1.44084e-05 -1.43834e-05 -5.46108e-05 -5.40733e-05 -8.99891e-05 -0.000253347 0 0 -0.000716977 -0.000692716 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000154133 0.000172389 7.26178e-05 8.07312e-05 7.26101e-05 8.06262e-05 0.000147563 0.000143617 0.0443824 0.0494488 0.0443777 0.0494019 0.0402641 0.0397579 0.0430368 0.0441544 0.0430359 0.0441446 0.0846437 0.0843739 2.58771e-09 2.07632e-09 2.58759e-09 2.07375e-09 6.18535e-09 5.79539e-09 0 0 2.40055e-06 2.5323e-06 0 0 0 0 0 0 0 0
127 12485000 0.695039 0.676314 0.00144974 0.000557942 -0.01413 -0.0143141 0.718832 0.736474 -0.000869334 0.0241985 0.010527 -0.00648858 -0.0770605 -0.0908553 0.0052312 0.016796 -0.00110993 -0.00896842 -365.473 -365.482 -1.43724e-05 -1.42366e-05 -5.46342e-05 -5.42088e-05 -8.85825e-05 -0.000247241 0 0 -0.000719901 -0.000693907 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00015369 0.000171565 7.6476e-05 8.45903e-05 7.64662e-05 8.44812e-05 0.000147183 0.000143028 0.050798 0.0567554 0.0507922 0.0566995 0.0416933 0.0411607 0.0492332 0.0509085 0.0492319 0.0508936 0.0863352 0.0860322 2.58771e-09 2.07633e-09 2.58765e-09 2.07377e-09 6.03796e-09 5.63518e-09 0 0 2.39632e-06 2.52808e-06 0 0 0 0 0 0 0 0
128 12585000 0.695049 0.676606 0.00155194 0.000876591 -0.0140034 -0.0141559 0.718824 0.736209 -0.00676615 0.0138008 0.0110151 -0.00314787 -0.0806043 -0.0944872 0.000428274 0.00888009 -0.00116162 -0.00708272 -365.478 -365.487 -1.51431e-05 -1.57257e-05 -5.49232e-05 -5.39379e-05 -8.67214e-05 -0.000240914 0 0 -0.00072572 -0.00070134 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000153048 0.000170383 6.88342e-05 7.37679e-05 6.88337e-05 7.36892e-05 0.000146505 0.000142288 0.0450204 0.0492371 0.0450161 0.049198 0.0402092 0.0397247 0.0435895 0.0446731 0.0435886 0.0446639 0.0844344 0.0841632 2.35374e-09 1.80482e-09 2.3538e-09 1.80318e-09 5.89201e-09 5.47868e-09 0 0 2.3847e-06 2.51562e-06 0 0 0 0 0 0 0 0
129 12685000 0.694982 0.676625 0.00159697 0.000898539 -0.0139636 -0.0141281 0.71889 0.736192 -0.006825 0.0156744 0.0130499 -0.00211962 -0.0857697 -0.100468 -0.000248249 0.0104804 4.15681e-05 -0.00730439 -365.486 -365.496 -1.51104e-05 -1.55871e-05 -5.49456e-05 -5.40049e-05 -8.53929e-05 -0.000236248 0 0 -0.000726432 -0.000700759 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000153857 0.00017106 7.24239e-05 7.71956e-05 7.24213e-05 7.71121e-05 0.000147279 0.000142822 0.0513921 0.0562659 0.0513871 0.0562203 0.0421128 0.0416012 0.0500718 0.0516548 0.0500705 0.0516412 0.0880163 0.087702 2.35378e-09 1.80482e-09 2.35387e-09 1.80325e-09 5.78437e-09 5.36403e-09 0 0 2.38176e-06 2.51265e-06 0 0 0 0 0 0 0 0
130 12785000 0.695072 0.676991 0.00169012 0.00117606 -0.0138246 -0.013963 0.718806 0.735858 -0.0117324 0.0068091 0.0115606 -0.000997073 -0.0860284 -0.100763 -0.00408074 0.00376549 -0.000374765 -0.00589124 -365.486 -365.496 -1.56499e-05 -1.67002e-05 -5.52999e-05 -5.38996e-05 -8.33572e-05 -0.000230019 0 0 -0.000736543 -0.000712339 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000153172 0.000169821 6.45855e-05 6.68876e-05 6.4592e-05 6.68317e-05 0.000146571 0.000142063 0.0451058 0.0484374 0.0451022 0.0484061 0.0405347 0.0400754 0.0441377 0.0451454 0.0441368 0.045137 0.086008 0.0857282 2.13293e-09 1.56776e-09 2.13311e-09 1.56685e-09 5.64235e-09 5.21454e-09 0 0 2.37051e-06 2.50053e-06 0 0 0 0 0 0 0 0
131 12885000 0.69516 0.677371 0.00164543 0.00111032 -0.0138672 -0.0140208 0.71872 0.735507 -0.0123095 0.00801578 0.0118938 -0.00147377 -0.0877696 -0.103503 -0.0052697 0.00466886 0.000778518 -0.0059878 -365.486 -365.497 -1.5603e-05 -1.65313e-05 -5.53326e-05 -5.39928e-05 -8.14422e-05 -0.000223967 0 0 -0.00074253 -0.000716752 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000152661 0.000168918 6.79002e-05 6.99175e-05 6.79052e-05 6.98578e-05 0.000146118 0.000141421 0.0513495 0.0551261 0.0513454 0.0550904 0.0418456 0.0413742 0.0508255 0.052262 0.0508243 0.0522501 0.0877324 0.087425 2.13295e-09 1.56775e-09 2.13317e-09 1.56691e-09 5.50336e-09 5.06928e-09 0 0 2.36689e-06 2.49684e-06 0 0 0 0 0 0 0 0
132 12985000 0.695384 0.677863 0.00144833 0.00105081 -0.0139932 -0.0141318 0.718501 0.735052 -0.00482726 0.0125907 0.0104322 -0.00051633 -0.0843951 -0.100186 0.000826252 0.00854356 0.000162521 -0.00487772 -365.484 -365.495 -1.46026e-05 -1.60052e-05 -5.56911e-05 -5.40238e-05 -7.88997e-05 -0.000217524 0 0 -0.000756367 -0.000731114 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000151944 0.000167654 6.01773e-05 6.03856e-05 6.01907e-05 6.03499e-05 0.000145395 0.000140659 0.0447413 0.0472262 0.0447385 0.0472021 0.0402187 0.0398009 0.0446285 0.0455353 0.0446277 0.045528 0.0857048 0.0854321 1.92956e-09 1.36454e-09 1.92984e-09 1.36415e-09 5.3663e-09 4.92776e-09 0 0 2.3562e-06 2.48528e-06 0 0 0 0 0 0 0 0
133 13085000 0.695279 0.678034 0.00145983 0.001044 -0.0139447 -0.0140935 0.718603 0.734895 -0.00531773 0.0135991 0.0112329 -0.000388088 -0.0863389 -0.102882 0.000332588 0.00998481 0.0012534 -0.00487781 -365.487 -365.499 -1.45754e-05 -1.58738e-05 -5.57105e-05 -5.41033e-05 -7.77641e-05 -0.000212514 0 0 -0.00076026 -0.000733935 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000151412 0.000166738 6.32236e-05 6.30602e-05 6.32361e-05 6.30221e-05 0.000144889 0.00013998 0.0507789 0.053525 0.0507757 0.0534976 0.041428 0.0410048 0.0514487 0.0527102 0.0514476 0.0527 0.0873524 0.0870564 1.92959e-09 1.36454e-09 1.9299e-09 1.36421e-09 5.23214e-09 4.79018e-09 0 0 2.3528e-06 2.48177e-06 0 0 0 0 0 0 0 0
134 13185000 0.695364 0.678364 0.0012955 0.00100639 -0.0139918 -0.0141191 0.718521 0.73459 0.00110737 0.0170015 0.0110431 0.00159024 -0.0801976 -0.0965613 0.00527027 0.0126451 0.000656174 -0.00391182 -365.478 -365.49 -1.38534e-05 -1.55855e-05 -5.60248e-05 -5.41491e-05 -7.58674e-05 -0.000207009 0 0 -0.000777816 -0.000752693 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000150681 0.000165473 5.58351e-05 5.44246e-05 5.58553e-05 5.44071e-05 0.000144143 0.000139206 0.0440386 0.0457547 0.0440365 0.0457362 0.0397687 0.0393978 0.0450364 0.0458311 0.0450357 0.0458248 0.0853151 0.0850529 1.74555e-09 1.19234e-09 1.74589e-09 1.19231e-09 5.10034e-09 4.65646e-09 0 0 2.34273e-06 2.47084e-06 0 0 0 0 0 0 0 0
135 13285000 0.695456 0.678544 0.00131002 0.00101139 -0.0139949 -0.014129 0.718431 0.734423 0.000922163 0.0180327 0.0124984 0.00249782 -0.0802287 -0.0974109 0.00539059 0.014507 0.00184023 -0.00367331 -365.475 -365.489 -1.38112e-05 -1.54725e-05 -5.60556e-05 -5.42234e-05 -7.40769e-05 -0.000202505 0 0 -0.000784541 -0.000758422 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000151354 0.000165976 5.86305e-05 5.679e-05 5.86493e-05 5.67702e-05 0.000144787 0.000139631 0.0498409 0.0516652 0.0498386 0.0516441 0.0414446 0.0410668 0.0519281 0.0530056 0.0519272 0.052997 0.0888456 0.0885515 1.7456e-09 1.19238e-09 1.74596e-09 1.19238e-09 5.00354e-09 4.55876e-09 0 0 2.34036e-06 2.46838e-06 0 0 0 0 0 0 0 0
136 13385000 0.695658 0.678997 0.00117982 0.000998467 -0.0139309 -0.0140447 0.718237 0.734006 0.000948407 0.0150825 0.0115298 0.00340826 -0.0742492 -0.0912082 0.00399744 0.0108236 0.00101567 -0.00311146 -365.464 -365.477 -1.37126e-05 -1.57302e-05 -5.6387e-05 -5.43201e-05 -7.18267e-05 -0.000196829 0 0 -0.000800279 -0.000775595 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000150584 0.00016468 5.17027e-05 4.9066e-05 5.17285e-05 4.90637e-05 0.000144024 0.000138848 0.0431031 0.0441418 0.0431016 0.0441277 0.03972 0.0393932 0.0453539 0.0460345 0.0453533 0.0460292 0.0867167 0.0864569 1.58088e-09 1.04724e-09 1.58126e-09 1.04743e-09 4.87641e-09 4.4316e-09 0 0 2.33084e-06 2.45804e-06 0 0 0 0 0 0 0 0
137 13485000 0.695839 0.679449 0.001211 0.00101936 -0.0139296 -0.01405 0.718062 0.733587 0.000385368 0.0155979 0.0121965 0.00364837 -0.0752476 -0.0930575 0.00411184 0.0125107 0.00220182 -0.00272639 -365.462 -365.477 -1.36645e-05 -1.55987e-05 -5.64234e-05 -5.44125e-05 -6.9725e-05 -0.000191312 0 0 -0.00080567 -0.000779876 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000149968 0.000163701 5.42662e-05 5.11629e-05 5.42912e-05 5.11593e-05 0.000143466 0.000138146 0.0486471 0.0496682 0.0486454 0.0496523 0.0407681 0.0404456 0.0522679 0.0531647 0.0522671 0.0531575 0.0882909 0.0880148 1.58092e-09 1.04727e-09 1.58132e-09 1.04749e-09 4.75226e-09 4.30814e-09 0 0 2.32789e-06 2.45495e-06 0 0 0 0 0 0 0 0
138 13585000 0.695892 0.679747 0.00115452 0.00106372 -0.013875 -0.0139748 0.718012 0.733313 0.000215043 0.0127037 0.0122138 0.00529421 -0.0743712 -0.0916372 0.00292308 0.00923058 0.00136763 -0.00233618 -365.462 -365.476 -1.35757e-05 -1.58033e-05 -5.6721e-05 -5.45239e-05 -6.83313e-05 -0.000186669 0 0 -0.000813628 -0.00078944 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000149182 0.000162412 4.78607e-05 4.43101e-05 4.78917e-05 4.43211e-05 0.000142695 0.000137363 0.0420126 0.0424643 0.0420114 0.0424536 0.0390326 0.0387574 0.0455837 0.046154 0.0455832 0.0461495 0.0861724 0.0859288 1.43444e-09 9.25127e-10 1.43484e-09 9.25472e-10 4.63068e-09 4.1883e-09 0 0 2.31905e-06 2.44533e-06 0 0 0 0 0 0 0 0
139 13685000 0.696083 0.680207 0.00113269 0.00103405 -0.0138455 -0.0139518 0.717827 0.732887 0.000868977 0.0141645 0.0146683 0.00748525 -0.07985 -0.0979028 0.00295961 0.0106525 0.00269387 -0.00168772 -365.468 -365.483 -1.35273e-05 -1.56808e-05 -5.67593e-05 -5.46157e-05 -6.61403e-05 -0.000181264 0 0 -0.000814624 -0.000789339 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000148547 0.000161432 5.02146e-05 4.61769e-05 5.02451e-05 4.61872e-05 0.000142106 0.000136648 0.0472965 0.0476287 0.0472953 0.0476168 0.0399811 0.0397138 0.0524816 0.053208 0.052481 0.053202 0.0876669 0.087411 1.43448e-09 9.25167e-10 1.4349e-09 9.25539e-10 4.51204e-09 4.07202e-09 0 0 2.31629e-06 2.44241e-06 0 0 0 0 0 0 0 0
140 13785000 0.696148 0.680504 0.00105255 0.00104059 -0.0137529 -0.0138399 0.717765 0.732613 0.00103775 0.0120452 0.0104693 0.00464554 -0.0788725 -0.0963635 0.00382173 0.00966704 0.000146131 -0.00320089 -365.468 -365.483 -1.33447e-05 -1.57443e-05 -5.72858e-05 -5.49678e-05 -6.45676e-05 -0.000176669 0 0 -0.000823055 -0.000799256 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000147756 0.000160164 4.43441e-05 4.01223e-05 4.43799e-05 4.01447e-05 0.000141323 0.00013586 0.0408444 0.0407909 0.0408436 0.040783 0.0382498 0.0380252 0.0457338 0.0462002 0.0457333 0.0461965 0.0855684 0.0853427 1.30457e-09 8.22226e-10 1.30498e-09 8.2267e-10 4.39604e-09 3.9592e-09 0 0 2.30813e-06 2.43352e-06 0 0 0 0 0 0 0 0
141 13885000 0.696223 0.680832 0.00100861 0.000992951 -0.0137842 -0.0138764 0.717692 0.732307 0.00137256 0.0130767 0.0110656 0.00505366 -0.0840698 -0.102146 0.00393883 0.0109958 0.00121888 -0.00269789 -365.475 -365.49 -1.33102e-05 -1.56438e-05 -5.73136e-05 -5.50471e-05 -6.29837e-05 -0.000172078 0 0 -0.000823993 -0.000799423 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000147099 0.000159181 4.65105e-05 4.17932e-05 4.65457e-05 4.1815e-05 0.000140709 0.000135136 0.0458665 0.0456115 0.0458658 0.0456028 0.0390975 0.0388836 0.0525876 0.0531565 0.052587 0.0531516 0.086983 0.0867485 1.30462e-09 8.22274e-10 1.30504e-09 8.22738e-10 4.28293e-09 3.84978e-09 0 0 2.30554e-06 2.43077e-06 0 0 0 0 0 0 0 0
142 13985000 0.69637 0.681045 0.000964608 0.00102698 -0.0137313 -0.0138056 0.717551 0.732111 0.0013041 0.0109061 0.00849048 0.00367419 -0.0817903 -0.0993035 0.00462503 0.0100057 -0.000898567 -0.00389731 -365.473 -365.489 -1.31478e-05 -1.56966e-05 -5.77428e-05 -5.53247e-05 -6.13037e-05 -0.000168308 0 0 -0.000833359 -0.000810353 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000147471 0.000159245 4.11608e-05 3.64545e-05 4.11999e-05 3.64858e-05 0.000141043 0.000135392 0.0396405 0.0391531 0.03964 0.0391472 0.0378683 0.0376886 0.0458148 0.046185 0.0458145 0.0461819 0.0867538 0.0865382 1.18946e-09 7.3524e-10 1.18986e-09 7.35738e-10 4.19972e-09 3.76979e-09 0 0 2.29862e-06 2.42322e-06 0 0 0 0 0 0 0 0
143 14085000 0.696529 0.681452 0.000944464 0.00100475 -0.0137454 -0.0138235 0.717397 0.731732 0.00118775 0.0113342 0.00901719 0.00407737 -0.0844303 -0.102546 0.00473111 0.0111683 -2.9911e-05 -0.0034976 -365.479 -365.495 -1.31086e-05 -1.55977e-05 -5.77749e-05 -5.54063e-05 -5.94798e-05 -0.000163658 0 0 -0.000834851 -0.00081112 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000146778 0.000158241 4.31593e-05 3.79577e-05 4.31982e-05 3.79887e-05 0.000140405 0.000134658 0.0444031 0.0436488 0.0444027 0.0436424 0.0386392 0.0384723 0.052604 0.053029 0.0526035 0.053025 0.0881475 0.087926 1.18951e-09 7.35293e-10 1.18993e-09 7.35807e-10 4.09137e-09 3.66608e-09 0 0 2.29623e-06 2.42067e-06 0 0 0 0 0 0 0 0
144 14185000 0.696723 0.681872 0.000843552 0.000965602 -0.0137321 -0.013793 0.717209 0.731341 0.00414946 0.0124487 0.00791787 0.00407165 -0.0839947 -0.10157 0.00672631 0.0116877 -0.000406482 -0.00305133 -365.48 -365.496 -1.27826e-05 -1.54576e-05 -5.79722e-05 -5.55273e-05 -5.74936e-05 -0.000159003 0 0 -0.000841391 -0.000818894 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000145952 0.000156983 3.82972e-05 3.32493e-05 3.83399e-05 3.32886e-05 0.000139614 0.000133873 0.0384319 0.0375708 0.0384317 0.0375667 0.0369089 0.0367754 0.0458378 0.0461189 0.0458375 0.0461163 0.0860217 0.0858267 1.08727e-09 6.61343e-10 1.08767e-09 6.61874e-10 3.98567e-09 3.56549e-09 0 0 2.2893e-06 2.41312e-06 0 0 0 0 0 0 0 0
145 14285000 0.696892 0.682276 0.000847509 0.000968232 -0.0136961 -0.0137591 0.717045 0.730965 0.00457853 0.0132509 0.00916658 0.00527654 -0.0849875 -0.103083 0.00716751 0.0130361 0.000432142 -0.00258387 -365.481 -365.498 -1.27468e-05 -1.53677e-05 -5.80016e-05 -5.56038e-05 -5.58276e-05 -0.000154707 0 0 -0.000845063 -0.000822057 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000145235 0.000155975 4.01461e-05 3.4609e-05 4.01886e-05 3.46484e-05 0.000138968 0.000133146 0.0429609 0.0417799 0.0429608 0.0417755 0.0375849 0.0374655 0.0525481 0.0528417 0.0525477 0.0528385 0.0873329 0.087135 1.08732e-09 6.61402e-10 1.08773e-09 6.61944e-10 3.88273e-09 3.46803e-09 0 0 2.28707e-06 2.41073e-06 0 0 0 0 0 0 0 0
146 14385000 0.697145 0.682746 0.000757359 0.000930382 -0.0136636 -0.0137117 0.7168 0.730526 0.00605447 0.013046 0.00922616 0.00623738 -0.0848675 -0.102424 0.00852979 0.0130798 2.56151e-05 -0.00229648 -365.482 -365.499 -1.25131e-05 -1.52786e-05 -5.81989e-05 -5.5743e-05 -5.37522e-05 -0.000150143 0 0 -0.000851423 -0.000829643 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000144395 0.000154731 3.57294e-05 3.04501e-05 3.57751e-05 3.04962e-05 0.000138184 0.000132373 0.0372546 0.03607 0.0372547 0.0360672 0.0358852 0.035794 0.0458126 0.0460114 0.0458124 0.0460093 0.0852314 0.0850572 9.96284e-10 5.98203e-10 9.96667e-10 5.98746e-10 3.78228e-09 3.37341e-09 0 0 2.28074e-06 2.40385e-06 0 0 0 0 0 0 0 0
147 14485000 0.697244 0.683075 0.000750959 0.000923947 -0.0136102 -0.0136597 0.716704 0.73022 0.00588737 0.0131038 0.0111666 0.00816828 -0.0892035 -0.10719 0.0091306 0.0144405 0.00105341 -0.00155336 -365.491 -365.508 -1.24816e-05 -1.51978e-05 -5.82258e-05 -5.58146e-05 -5.22416e-05 -0.000146147 0 0 -0.000851276 -0.000828977 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000143676 0.000153741 3.7445e-05 3.1687e-05 3.74907e-05 3.17333e-05 0.000137513 0.000131636 0.0415626 0.0400157 0.0415627 0.0400127 0.0364699 0.0363938 0.0524354 0.0526089 0.0524351 0.0526062 0.086461 0.0862866 9.96341e-10 5.98266e-10 9.96736e-10 5.98816e-10 3.68463e-09 3.28188e-09 0 0 2.27866e-06 2.40161e-06 0 0 0 0 0 0 0 0
148 14585000 0.697226 0.683115 0.000708053 0.000925712 -0.0134304 -0.0134776 0.716725 0.730186 0.00299286 0.00887481 0.00920759 0.00705564 -0.0877076 -0.104889 0.00595267 0.0101043 -0.000870504 -0.00289967 -365.493 -365.509 -1.27737e-05 -1.55253e-05 -5.85642e-05 -5.6055e-05 -5.14641e-05 -0.000143626 0 0 -0.000858449 -0.000837838 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000143965 0.000153759 3.34298e-05 2.80047e-05 3.34779e-05 2.80563e-05 0.000137792 0.000131842 0.0361154 0.0346496 0.0361157 0.0346479 0.0352785 0.0352243 0.0457489 0.045871 0.0457487 0.0458693 0.0862465 0.0860865 9.14998e-10 5.43921e-10 9.15363e-10 5.44462e-10 3.61304e-09 3.21501e-09 0 0 2.2734e-06 2.39589e-06 0 0 0 0 0 0 0 0
149 14685000 0.697447 0.683554 0.000677681 0.000897279 -0.0134211 -0.0134701 0.716511 0.729775 0.00450698 0.010688 0.00692931 0.00489902 -0.0872931 -0.104977 0.00636859 0.0111689 -4.03669e-05 -0.00226571 -365.493 -365.51 -1.27336e-05 -1.54405e-05 -5.85979e-05 -5.61314e-05 -4.95623e-05 -0.000139421 0 0 -0.000862582 -0.000841593 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000143217 0.000152755 3.50267e-05 2.91364e-05 3.50747e-05 2.91881e-05 0.000137107 0.000131101 0.0402173 0.0383552 0.0402178 0.0383537 0.035797 0.0357583 0.0522786 0.0523412 0.0522784 0.0523392 0.0874478 0.0872898 9.15058e-10 5.43987e-10 9.15433e-10 5.44534e-10 3.51985e-09 3.12835e-09 0 0 2.27147e-06 2.39382e-06 0 0 0 0 0 0 0 0
150 14785000 0.697555 0.683851 0.000668695 0.000922529 -0.0132939 -0.0133404 0.716408 0.729499 0.00193559 0.00700685 0.00470482 0.00337591 -0.0827129 -0.0997041 0.00376793 0.00757131 -0.00161534 -0.00335938 -365.486 -365.503 -1.29569e-05 -1.56728e-05 -5.88589e-05 -5.63357e-05 -4.82145e-05 -0.000135892 0 0 -0.000873025 -0.000853583 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000142363 0.000151544 3.13699e-05 2.58663e-05 3.14202e-05 2.59225e-05 0.000136321 0.000130335 0.0350298 0.0333179 0.0350304 0.0333172 0.0341596 0.0341402 0.0456545 0.0457046 0.0456544 0.0457032 0.0853589 0.0852201 8.42089e-10 4.96937e-10 8.42433e-10 4.97467e-10 3.42907e-09 3.04422e-09 0 0 2.26622e-06 2.38812e-06 0 0 0 0 0 0 0 0
151 14885000 0.697737 0.684246 0.000659611 0.000915775 -0.0132537 -0.0133012 0.716231 0.729129 0.00291116 0.00804793 0.00631458 0.00513909 -0.0868092 -0.104205 0.00400155 0.00835427 -0.00107078 -0.00293014 -365.492 -365.509 -1.29234e-05 -1.5598e-05 -5.88879e-05 -5.64052e-05 -4.65904e-05 -0.000132088 0 0 -0.000874195 -0.000854389 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000141605 0.000150551 3.28599e-05 2.69066e-05 3.29102e-05 2.69631e-05 0.00013563 0.000129603 0.0389501 0.0368141 0.038951 0.0368136 0.0346002 0.0345962 0.0520892 0.0520487 0.052089 0.052047 0.086479 0.0863441 8.42152e-10 4.97006e-10 8.42505e-10 4.9754e-10 3.34087e-09 2.96287e-09 0 0 2.26443e-06 2.38619e-06 0 0 0 0 0 0 0 0
152 14985000 0.697777 0.684467 0.000613935 0.000897923 -0.0132373 -0.0132778 0.716193 0.728923 0.00218905 0.00631503 0.00536299 0.00470731 -0.0819647 -0.0986304 0.00319978 0.00666509 -0.00108794 -0.00257035 -365.487 -365.504 -1.2971e-05 -1.56714e-05 -5.89832e-05 -5.64934e-05 -4.54979e-05 -0.000128943 0 0 -0.000883876 -0.000865512 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000140758 0.000149373 2.95203e-05 2.39918e-05 2.95723e-05 2.40518e-05 0.000134847 0.000128844 0.0340029 0.032075 0.0340036 0.0320751 0.0330225 0.0330336 0.0455365 0.0455183 0.0455364 0.0455172 0.0844482 0.0843299 7.76418e-10 4.55994e-10 7.76739e-10 4.56506e-10 3.255e-09 2.8839e-09 0 0 2.25968e-06 2.38106e-06 0 0 0 0 0 0 0 0
153 15085000 0.697902 0.684798 0.000549099 0.00083644 -0.0132143 -0.0132562 0.716071 0.728612 0.00232611 0.00649478 0.00550745 0.00501185 -0.0853677 -0.102302 0.00342624 0.00733713 -0.000552215 -0.00208338 -365.496 -365.513 -1.29479e-05 -1.56095e-05 -5.90035e-05 -5.65521e-05 -4.43646e-05 -0.00012574 0 0 -0.000883535 -0.000864891 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000139988 0.000148385 3.09142e-05 2.49531e-05 3.09663e-05 2.50135e-05 0.000134161 0.000128127 0.0377413 0.035369 0.0377422 0.0353692 0.0333873 0.0334134 0.0518753 0.051738 0.0518752 0.0517368 0.0854898 0.085377 7.76483e-10 4.56065e-10 7.76812e-10 4.56581e-10 3.1716e-09 2.80754e-09 0 0 2.25802e-06 2.37927e-06 0 0 0 0 0 0 0 0
154 15185000 0.69802 0.685092 0.000517842 0.000827661 -0.0131825 -0.0132175 0.715957 0.728336 0.00188655 0.00513211 0.0057531 0.00568956 -0.081753 -0.0980059 0.0027584 0.00589712 -0.000581622 -0.00181368 -365.493 -365.509 -1.29763e-05 -1.56534e-05 -5.90913e-05 -5.6643e-05 -4.31881e-05 -0.000122638 0 0 -0.000891835 -0.000874475 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000139135 0.000147227 2.7856e-05 2.23457e-05 2.79095e-05 2.24089e-05 0.000133399 0.000127392 0.033028 0.0309113 0.0330289 0.0309119 0.0318751 0.0319126 0.0454006 0.045317 0.0454006 0.0453162 0.0835189 0.0834202 7.17056e-10 4.20089e-10 7.17354e-10 4.2058e-10 3.09045e-09 2.73341e-09 0 0 2.25374e-06 2.37464e-06 0 0 0 0 0 0 0 0
155 15285000 0.698126 0.685271 0.000490116 0.000807017 -0.0132207 -0.0132559 0.715852 0.728168 0.00225734 0.00545854 0.00638615 0.00651831 -0.0832667 -0.0997942 0.00298163 0.00646373 2.5996e-05 -0.00119717 -365.494 -365.512 -1.29545e-05 -1.5605e-05 -5.91099e-05 -5.66889e-05 -4.21403e-05 -0.000120153 0 0 -0.000894625 -0.000877174 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000139414 0.000147377 2.91637e-05 2.32388e-05 2.92167e-05 2.3302e-05 0.000133692 0.00012757 0.0366122 0.0340339 0.0366133 0.0340348 0.0326069 0.0326594 0.0516447 0.0514158 0.0516447 0.0514148 0.0863078 0.086212 7.17132e-10 4.20169e-10 7.17435e-10 4.20662e-10 3.0311e-09 2.67943e-09 0 0 2.25259e-06 2.3734e-06 0 0 0 0 0 0 0 0
156 15385000 0.698399 0.685719 0.00046223 0.000796937 -0.0131721 -0.0132032 0.715587 0.727747 0.00206348 0.00450779 0.00617334 0.00671952 -0.0798755 -0.0958849 0.000560163 0.00338905 -0.000132269 -0.0011193 -365.49 -365.507 -1.30334e-05 -1.56795e-05 -5.922e-05 -5.68044e-05 -4.03228e-05 -0.000116538 0 0 -0.000902037 -0.00088571 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000138554 0.000146229 2.63531e-05 2.08964e-05 2.64073e-05 2.09618e-05 0.000132926 0.000126834 0.0321158 0.0298332 0.0321169 0.0298343 0.0311294 0.0311903 0.0452515 0.0451048 0.0452515 0.0451042 0.0843152 0.0842318 6.63192e-10 3.88397e-10 6.63465e-10 3.88865e-10 2.95387e-09 2.60926e-09 0 0 2.24869e-06 2.3692e-06 0 0 0 0 0 0 0 0
157 15485000 0.698396 0.685906 0.000480042 0.000819444 -0.013178 -0.0132084 0.71559 0.72757 0.00312033 0.00549699 0.00598519 0.0067817 -0.0811926 -0.0973026 0.000816452 0.00390729 0.000457692 -0.000456841 -365.496 -365.514 -1.30217e-05 -1.56332e-05 -5.92302e-05 -5.68494e-05 -3.97522e-05 -0.000114109 0 0 -0.000902634 -0.000886208 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000137772 0.000145259 2.75811e-05 2.17284e-05 2.76353e-05 2.17943e-05 0.000132222 0.000126119 0.0355445 0.0327892 0.0355459 0.0327908 0.0313806 0.0314558 0.0514027 0.0510863 0.0514028 0.0510857 0.0852467 0.0851713 6.63261e-10 3.88473e-10 6.63541e-10 3.88942e-10 2.87888e-09 2.54143e-09 0 0 2.24727e-06 2.36768e-06 0 0 0 0 0 0 0 0
158 15585000 0.698418 0.686096 0.000460738 0.000813922 -0.0131367 -0.0131633 0.71557 0.727392 0.00154487 0.00328493 0.00542695 0.00650018 -0.0782144 -0.0936118 -0.0013042 0.00123005 0.000186476 -0.000562505 -365.496 -365.513 -1.31116e-05 -1.57072e-05 -5.93181e-05 -5.69499e-05 -3.89671e-05 -0.000111582 0 0 -0.000908289 -0.000892957 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000136926 0.000144148 2.49902e-05 1.9616e-05 2.50453e-05 1.96835e-05 0.000131462 0.000125393 0.0312479 0.0288223 0.0312491 0.0288238 0.0299729 0.0300537 0.045093 0.0448851 0.045093 0.0448846 0.0833192 0.0832539 6.14148e-10 3.60246e-10 6.14398e-10 3.60688e-10 2.80597e-09 2.47556e-09 0 0 2.24375e-06 2.36391e-06 0 0 0 0 0 0 0 0
159 15685000 0.698518 0.686378 0.00046992 0.000828451 -0.0131615 -0.0131876 0.715472 0.727125 0.00174218 0.00335619 0.00561706 0.00693773 -0.0803813 -0.0959546 -0.00115832 0.0015627 0.000745068 0.000119947 -365.5 -365.518 -1.30915e-05 -1.56558e-05 -5.93357e-05 -5.70002e-05 -3.79816e-05 -0.000108874 0 0 -0.000909544 -0.000894134 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000136144 0.000143193 2.6146e-05 2.03947e-05 2.62011e-05 2.04627e-05 0.000130756 0.000124686 0.0345471 0.0316395 0.0345485 0.0316414 0.0301665 0.0302606 0.0511537 0.0507535 0.0511539 0.0507531 0.0841607 0.0841042 6.14219e-10 3.60323e-10 6.14475e-10 3.60766e-10 2.73512e-09 2.41182e-09 0 0 2.24243e-06 2.36249e-06 0 0 0 0 0 0 0 0
160 15785000 0.698623 0.686649 0.000431131 0.000805671 -0.0131802 -0.0132034 0.715368 0.726869 0.00222204 0.00326544 0.00335811 0.00500629 -0.0804873 -0.0954359 -0.00096147 0.00128024 -0.000820818 -0.00129945 -365.504 -365.521 -1.30882e-05 -1.5647e-05 -5.95302e-05 -5.71851e-05 -3.70099e-05 -0.000106268 0 0 -0.000913219 -0.000898669 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000135302 0.000142106 2.37491e-05 1.84816e-05 2.38048e-05 1.85508e-05 0.000130013 0.000123979 0.0304428 0.0278925 0.030444 0.0278944 0.0288318 0.0289292 0.044928 0.0446604 0.0449281 0.0446601 0.0822989 0.0822504 5.69353e-10 3.35092e-10 5.69581e-10 3.35508e-10 2.66631e-09 2.34997e-09 0 0 2.23926e-06 2.3591e-06 0 0 0 0 0 0 0 0
161 15885000 0.69862 0.686713 0.000388497 0.000770178 -0.0131811 -0.0132044 0.715371 0.726808 0.00318639 0.0040573 0.00333888 0.00528625 -0.0817568 -0.0968351 -0.000661345 0.00168818 -0.000496013 -0.000791109 -365.508 -365.526 -1.30765e-05 -1.56129e-05 -5.95404e-05 -5.72185e-05 -3.64353e-05 -0.000104471 0 0 -0.000914503 -0.000899935 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000135513 0.000142209 2.48388e-05 1.92131e-05 2.48942e-05 1.92825e-05 0.000130235 0.000124111 0.0336145 0.0305774 0.0336161 0.0305797 0.0293699 0.0294815 0.0509019 0.0504208 0.0509021 0.0504206 0.0848499 0.0848094 5.69433e-10 3.35176e-10 5.69665e-10 3.35593e-10 2.61604e-09 2.30496e-09 0 0 2.23836e-06 2.35813e-06 0 0 0 0 0 0 0 0
162 15985000 0.698823 0.687069 0.000307465 0.00070037 -0.0131737 -0.0131952 0.715174 0.726472 0.00319422 0.00358842 0.00186444 0.00404178 -0.0773149 -0.091931 -0.000617319 0.00134236 -0.00173975 -0.00195992 -365.502 -365.519 -1.30774e-05 -1.5598e-05 -5.97092e-05 -5.73898e-05 -3.48764e-05 -0.000101418 0 0 -0.000921744 -0.000908058 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000134679 0.000141144 2.26133e-05 1.74725e-05 2.26693e-05 1.75429e-05 0.00012948 0.000123397 0.029684 0.0270283 0.0296853 0.0270303 0.0280776 0.0281907 0.0447595 0.0444335 0.0447597 0.0444334 0.0829762 0.0829423 5.28333e-10 3.12494e-10 5.28538e-10 3.12884e-10 2.55063e-09 2.24639e-09 0 0 2.23547e-06 2.35506e-06 0 0 0 0 0 0 0 0
163 16085000 0.698997 0.687408 0.000308229 0.000706993 -0.0131936 -0.0132145 0.715003 0.726151 0.00466736 0.00484692 0.00207817 0.00459487 -0.0766579 -0.0914839 -0.000221717 0.0017825 -0.00156228 -0.00154465 -365.5 -365.518 -1.30526e-05 -1.55465e-05 -5.97306e-05 -5.74402e-05 -3.36688e-05 -9.87048e-05 0 0 -0.000925194 -0.000911535 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000133893 0.000140211 2.36415e-05 1.81616e-05 2.36976e-05 1.82325e-05 0.000128772 0.000122702 0.0327428 0.0295975 0.0327444 0.0296 0.0281923 0.0283174 0.0506499 0.0500908 0.0506502 0.0500908 0.0837131 0.0836893 5.28408e-10 3.12575e-10 5.28617e-10 3.12965e-10 2.48708e-09 2.18973e-09 0 0 2.23435e-06 2.35386e-06 0 0 0 0 0 0 0 0
164 16185000 0.699177 0.687735 0.000300031 0.000701833 -0.0131554 -0.0131717 0.714828 0.725842 0.00489952 0.00470555 0.00195609 0.00453347 -0.0740028 -0.0883341 -0.000324601 0.00137027 -0.00138547 -0.00140275 -365.496 -365.513 -1.30762e-05 -1.55412e-05 -5.97686e-05 -5.75185e-05 -3.23609e-05 -9.59817e-05 0 0 -0.000931432 -0.000918607 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000133065 0.000139171 2.15682e-05 1.6571e-05 2.16246e-05 1.66426e-05 0.000128037 0.000122008 0.0289744 0.0262303 0.0289758 0.0262327 0.0269723 0.0270974 0.0445895 0.0442064 0.0445897 0.0442064 0.0819073 0.0818885 4.90665e-10 2.92075e-10 4.90848e-10 2.9244e-10 2.42539e-09 2.13471e-09 0 0 2.23176e-06 2.35111e-06 0 0 0 0 0 0 0 0
165 16285000 0.699426 0.688148 0.000313594 0.00072134 -0.013173 -0.0131884 0.714584 0.725451 0.00671146 0.00628658 0.0016541 0.00459219 -0.0764785 -0.0910586 0.000270144 0.00194676 -0.00118705 -0.000924823 -365.501 -365.519 -1.30476e-05 -1.54883e-05 -5.9794e-05 -5.75713e-05 -3.09393e-05 -9.31428e-05 0 0 -0.000931945 -0.000919072 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000132284 0.000138257 2.25398e-05 1.72222e-05 2.25963e-05 1.72942e-05 0.000127337 0.000121328 0.0319259 0.0286926 0.0319276 0.0286954 0.0270509 0.0271874 0.0504 0.0497656 0.0504003 0.0497658 0.0825793 0.0825708 4.90741e-10 2.92157e-10 4.90929e-10 2.92521e-10 2.36546e-09 2.08149e-09 0 0 2.23072e-06 2.35e-06 0 0 0 0 0 0 0 0
166 16385000 0.699475 0.688339 0.000271217 0.000679739 -0.0131771 -0.0131892 0.714536 0.725269 0.00594947 0.00527138 0.000570128 0.00348767 -0.0746054 -0.0885703 6.80717e-05 0.0015092 -0.00103798 -0.000857448 -365.499 -365.516 -1.31019e-05 -1.55029e-05 -5.98132e-05 -5.76345e-05 -3.0299e-05 -9.11315e-05 0 0 -0.000937431 -0.000925345 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000131464 0.000137241 2.06026e-05 1.57628e-05 2.06594e-05 1.58353e-05 0.000126619 0.000120653 0.0283053 0.0254902 0.0283067 0.0254926 0.0259005 0.0260357 0.0444194 0.0439806 0.0444196 0.0439807 0.0808402 0.0808352 4.56009e-10 2.73539e-10 4.56172e-10 2.73878e-10 2.30727e-09 2.02979e-09 0 0 2.22838e-06 2.34754e-06 0 0 0 0 0 0 0 0
167 16485000 0.699552 0.688575 0.000273836 0.00068719 -0.013129 -0.0131403 0.714461 0.725046 0.0050905 0.00412251 0.00129895 0.00450164 -0.0784057 -0.0924558 0.000596383 0.00196435 -0.000941249 -0.00045331 -365.506 -365.524 -1.3087e-05 -1.54636e-05 -5.98264e-05 -5.76739e-05 -2.95555e-05 -8.90133e-05 0 0 -0.000937399 -0.000925298 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000130695 0.000136349 2.15212e-05 1.63795e-05 2.15781e-05 1.64525e-05 0.000125926 0.000119985 0.0311584 0.0278566 0.03116 0.0278594 0.0259488 0.0260946 0.0501533 0.0494465 0.0501537 0.0494469 0.0814512 0.0814567 4.56086e-10 2.73622e-10 4.56254e-10 2.7396e-10 2.25075e-09 1.97977e-09 0 0 2.22742e-06 2.34652e-06 0 0 0 0 0 0 0 0
168 16585000 0.699707 0.68878 0.000412812 0.000813405 -0.0130764 -0.0130837 0.71431 0.724852 0.00236102 0.00141268 0.00255164 0.00547648 -0.078973 -0.0925765 -0.00201834 -0.000731396 0.00159293 0.00184818 -365.505 -365.523 -1.33009e-05 -1.55899e-05 -5.96565e-05 -5.75958e-05 -2.8599e-05 -8.71112e-05 0 0 -0.000941308 -0.000929993 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00013079 0.000136294 1.97061e-05 1.5035e-05 1.97629e-05 1.51079e-05 0.000126075 0.000120087 0.0276777 0.0248073 0.027679 0.0248098 0.0251851 0.025331 0.0442505 0.0437574 0.0442507 0.0437577 0.0814005 0.081409 4.24078e-10 2.56641e-10 4.24223e-10 2.56956e-10 2.20944e-09 1.94314e-09 0 0 2.22554e-06 2.34455e-06 0 0 0 0 0 0 0 0
169 16685000 0.69974 0.688962 0.000412153 0.000817767 -0.0130659 -0.0130726 0.714278 0.72468 0.00271479 0.00148326 0.00307726 0.00631391 -0.0782812 -0.0919029 -0.00174963 -0.000564023 0.00187981 0.00244366 -365.503 -365.52 -1.32911e-05 -1.55563e-05 -5.96645e-05 -5.76287e-05 -2.81405e-05 -8.5348e-05 0 0 -0.000945146 -0.000933932 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000130013 0.000135405 2.05759e-05 1.56209e-05 2.06328e-05 1.56941e-05 0.000125384 0.000119425 0.0304379 0.0270855 0.0304394 0.0270885 0.0252127 0.0253687 0.0499114 0.0491352 0.0499118 0.0491357 0.0819772 0.0819967 4.24156e-10 2.56725e-10 4.24306e-10 2.57039e-10 2.15572e-09 1.89574e-09 0 0 2.22466e-06 2.34361e-06 0 0 0 0 0 0 0 0
170 16785000 0.69984 0.689199 0.000448129 0.000840854 -0.0130335 -0.0130378 0.71418 0.724454 -6.74756e-06 -0.00122122 0.00422397 0.00718573 -0.0769606 -0.0900876 -0.00391672 -0.00278732 0.00385253 0.00418605 -365.5 -365.517 -1.34669e-05 -1.56481e-05 -5.95311e-05 -5.75826e-05 -2.73878e-05 -8.3365e-05 0 0 -0.000949612 -0.000939123 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000129206 0.000134428 1.88702e-05 1.43767e-05 1.89272e-05 1.44501e-05 0.00012468 0.000118769 0.0270803 0.0241711 0.0270816 0.0241737 0.0241719 0.0243247 0.0440836 0.043538 0.0440839 0.0435384 0.0803003 0.080321 3.94603e-10 2.41164e-10 3.94732e-10 2.41456e-10 2.10358e-09 1.84967e-09 0 0 2.22275e-06 2.34162e-06 0 0 0 0 0 0 0 0
171 16885000 0.699872 0.689374 0.000461469 0.000858334 -0.0129819 -0.0129852 0.71415 0.724289 -0.000237618 -0.00175083 0.00522412 0.00847404 -0.0769538 -0.090133 -0.00391343 -0.00291266 0.00428825 0.00493291 -365.499 -365.516 -1.3454e-05 -1.56133e-05 -5.9542e-05 -5.7617e-05 -2.67682e-05 -8.15202e-05 0 0 -0.000952598 -0.000942196 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000128451 0.000133569 1.96939e-05 1.4934e-05 1.9751e-05 1.50078e-05 0.000123988 0.000118112 0.0297522 0.0263681 0.0297536 0.026371 0.0241767 0.0243389 0.0496743 0.0488319 0.0496747 0.0488326 0.0808212 0.0808528 3.94683e-10 2.41249e-10 3.94816e-10 2.4154e-10 2.05292e-09 1.80509e-09 0 0 2.22193e-06 2.34076e-06 0 0 0 0 0 0 0 0
172 16985000 0.699886 0.689524 0.00040717 0.000805397 -0.0129054 -0.0129118 0.714138 0.724147 5.81336e-05 -0.00157257 0.00310717 0.00649695 -0.0757767 -0.0884211 -0.00440293 -0.00349588 0.00231352 0.00291587 -365.498 -365.515 -1.35145e-05 -1.56281e-05 -5.96962e-05 -5.77741e-05 -2.63531e-05 -7.99146e-05 0 0 -0.000955743 -0.000945865 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000127659 0.00013262 1.80879e-05 1.37786e-05 1.81451e-05 1.38524e-05 0.000123294 0.000117467 0.0265101 0.0235779 0.0265114 0.0235806 0.0231945 0.0233527 0.0439191 0.043323 0.0439194 0.0433234 0.0791955 0.0792273 3.67378e-10 2.26942e-10 3.67493e-10 2.27213e-10 2.00369e-09 1.76172e-09 0 0 2.22021e-06 2.33896e-06 0 0 0 0 0 0 0 0
173 17085000 0.699998 0.689778 0.000373067 0.000777586 -0.0129949 -0.013001 0.714026 0.723904 0.000874377 -0.00106785 0.00396353 0.00769023 -0.0767932 -0.0895319 -0.00436107 -0.00362687 0.00264688 0.00360545 -365.502 -365.52 -1.34992e-05 -1.55926e-05 -5.97096e-05 -5.78099e-05 -2.55946e-05 -7.80014e-05 0 0 -0.000956544 -0.000946715 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000126908 0.000131775 1.88694e-05 1.43106e-05 1.89266e-05 1.43847e-05 0.000122619 0.00011683 0.0290949 0.0256973 0.0290964 0.0257005 0.0231795 0.0233464 0.0494421 0.0485372 0.0494425 0.0485379 0.0796639 0.0797066 3.67459e-10 2.27028e-10 3.67578e-10 2.27298e-10 1.95592e-09 1.71978e-09 0 0 2.21946e-06 2.33818e-06 0 0 0 0 0 0 0 0
174 17185000 0.700107 0.689937 0.000373151 0.000778457 -0.012937 -0.0129452 0.71392 0.723753 0.00135925 -0.000698941 0.00413155 0.00794456 -0.0774255 -0.0897836 -0.00475761 -0.00406644 0.00104126 0.00190565 -365.507 -365.524 -1.35574e-05 -1.5608e-05 -5.98513e-05 -5.79553e-05 -2.48932e-05 -7.64793e-05 0 0 -0.000957787 -0.000948393 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000126974 0.000131715 1.73549e-05 1.32343e-05 1.74118e-05 1.3308e-05 0.000122737 0.000116908 0.0259632 0.0230233 0.0259645 0.0230261 0.0225434 0.0227086 0.043757 0.0431126 0.0437573 0.0431131 0.0796708 0.079715 3.4222e-10 2.13837e-10 3.4232e-10 2.14087e-10 1.921e-09 1.68905e-09 0 0 2.21808e-06 2.33675e-06 0 0 0 0 0 0 0 0
175 17285000 0.700168 0.690129 0.000345042 0.000755007 -0.0129079 -0.0129159 0.713861 0.723571 0.00356562 0.00118159 0.00518211 0.00938278 -0.0751206 -0.0875363 -0.00450789 -0.00403356 0.00149884 0.00276342 -365.502 -365.519 -1.35441e-05 -1.55753e-05 -5.98625e-05 -5.79875e-05 -2.42573e-05 -7.47557e-05 0 0 -0.000961773 -0.000952497 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000126228 0.000130883 1.80955e-05 1.37417e-05 1.81525e-05 1.38158e-05 0.000122057 0.000116271 0.0284712 0.0250759 0.0284728 0.0250793 0.0225167 0.0226903 0.0492147 0.0482512 0.0492151 0.048252 0.0801078 0.0801631 3.42302e-10 2.13923e-10 3.42406e-10 2.14173e-10 1.87559e-09 1.64926e-09 0 0 2.21738e-06 2.33602e-06 0 0 0 0 0 0 0 0
176 17385000 0.700309 0.690386 0.000317067 0.000727116 -0.0128539 -0.012862 0.713724 0.723327 0.00420906 0.00170033 0.00452158 0.0087462 -0.072437 -0.0844514 -0.00377815 -0.00334601 5.99869e-05 0.00119051 -365.498 -365.514 -1.35405e-05 -1.554e-05 -6.00036e-05 -5.81402e-05 -2.35075e-05 -7.29845e-05 0 0 -0.000966768 -0.000957912 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00012545 0.000129968 1.66639e-05 1.27347e-05 1.67209e-05 1.28086e-05 0.000121383 0.000115648 0.0254456 0.0225107 0.0254469 0.0225137 0.0216346 0.0218032 0.0435977 0.0429077 0.043598 0.0429083 0.0785466 0.0786005 3.18947e-10 2.01717e-10 3.19036e-10 2.01948e-10 1.83145e-09 1.61052e-09 0 0 2.21596e-06 2.33455e-06 0 0 0 0 0 0 0 0
177 17485000 0.700408 0.690615 0.000316597 0.000731853 -0.0128583 -0.0128658 0.713627 0.723108 0.0048287 0.00201772 0.00414323 0.0087232 -0.0721325 -0.0842212 -0.00334643 -0.00317622 0.000492533 0.00206206 -365.498 -365.515 -1.3527e-05 -1.55083e-05 -6.00153e-05 -5.81719e-05 -2.28452e-05 -7.12875e-05 0 0 -0.000968698 -0.000959927 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000124714 0.000129153 1.73669e-05 1.32202e-05 1.74239e-05 1.32944e-05 0.000120719 0.000115029 0.0278778 0.0244994 0.0278793 0.0245029 0.0215946 0.0217711 0.0489928 0.0479749 0.0489933 0.0479759 0.0789368 0.0790015 3.1903e-10 2.01805e-10 3.19122e-10 2.02035e-10 1.7886e-09 1.57305e-09 0 0 2.21532e-06 2.33389e-06 0 0 0 0 0 0 0 0
178 17585000 0.700487 0.690802 0.000245829 0.000659323 -0.0128349 -0.0128433 0.713549 0.72293 0.00590885 0.00306182 0.00282347 0.00738575 -0.0665637 -0.0782611 -0.00282877 -0.00264033 -0.000796712 0.000585012 -365.489 -365.505 -1.35364e-05 -1.54809e-05 -6.01365e-05 -5.83107e-05 -2.21557e-05 -6.96376e-05 0 0 -0.00097494 -0.000966574 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000123962 0.000128273 1.60119e-05 1.22753e-05 1.60689e-05 1.23492e-05 0.000120049 0.000114411 0.0249464 0.02203 0.0249477 0.0220331 0.0207675 0.0209387 0.0434412 0.0427084 0.0434415 0.0427091 0.0774379 0.0775006 2.97413e-10 1.90483e-10 2.97491e-10 1.90695e-10 1.74695e-09 1.53655e-09 0 0 2.21403e-06 2.33256e-06 0 0 0 0 0 0 0 0
179 17685000 0.700588 0.691029 0.000210093 0.000628565 -0.0128205 -0.0128289 0.71345 0.722713 0.00709285 0.00389992 0.00354296 0.0084842 -0.0684163 -0.080204 -0.00217013 -0.00228045 -0.000477627 0.00137874 -365.492 -365.508 -1.3522e-05 -1.54495e-05 -6.01491e-05 -5.83423e-05 -2.14394e-05 -6.79427e-05 0 0 -0.000975859 -0.000967574 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000123243 0.000127482 1.66792e-05 1.274e-05 1.67362e-05 1.28143e-05 0.000119393 0.000113803 0.0273096 0.0239623 0.0273112 0.023966 0.0207178 0.0208964 0.0487758 0.0477081 0.0487763 0.0477091 0.0777849 0.0778583 2.97497e-10 1.90571e-10 2.97578e-10 1.90783e-10 1.70651e-09 1.50125e-09 0 0 2.21343e-06 2.33195e-06 0 0 0 0 0 0 0 0
180 17785000 0.700813 0.691365 0.000129807 0.000545321 -0.0128217 -0.0128245 0.713229 0.722392 0.00907765 0.00574675 0.00318311 0.00794956 -0.0680458 -0.0796019 -0.00141495 -0.00155372 -0.000486093 0.0010768 -365.494 -365.51 -1.3444e-05 -1.53597e-05 -6.0198e-05 -5.84344e-05 -2.02728e-05 -6.5882e-05 0 0 -0.000978179 -0.000970271 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000122506 0.000126628 1.5395e-05 1.18505e-05 1.5452e-05 1.19244e-05 0.000118737 0.000113199 0.0244699 0.0215835 0.0244713 0.0215867 0.0199432 0.0201165 0.0432874 0.0425152 0.0432878 0.0425159 0.076346 0.0764168 2.77483e-10 1.80046e-10 2.77551e-10 1.80241e-10 1.66719e-09 1.46686e-09 0 0 2.21226e-06 2.33075e-06 0 0 0 0 0 0 0 0
181 17885000 0.700873 0.691475 0.000138442 0.00056022 -0.0128113 -0.0128134 0.713171 0.722287 0.0106645 0.00700852 0.00256612 0.00772534 -0.069129 -0.0807611 -0.000438568 -0.000921338 -0.000171134 0.0018911 -365.497 -365.514 -1.34351e-05 -1.5338e-05 -6.02068e-05 -5.84562e-05 -1.98017e-05 -6.47109e-05 0 0 -0.000979081 -0.000971238 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00012257 0.000126636 1.6029e-05 1.22963e-05 1.60858e-05 1.23703e-05 0.000118828 0.000113256 0.0267635 0.0234604 0.0267651 0.0234641 0.0201349 0.0203183 0.0485636 0.0474509 0.0485641 0.047452 0.0781509 0.078236 2.77573e-10 1.80138e-10 2.77641e-10 1.80332e-10 1.63847e-09 1.44182e-09 0 0 2.21185e-06 2.33034e-06 0 0 0 0 0 0 0 0
182 17985000 0.701032 0.69174 8.32411e-05 0.000499173 -0.012799 -0.012797 0.713015 0.722033 0.0121377 0.0084988 0.000476838 0.00542093 -0.0666199 -0.0779221 -1.49526e-05 -0.000433179 -0.000274746 0.00146122 -365.495 -365.511 -1.34022e-05 -1.52794e-05 -6.02361e-05 -5.85308e-05 -1.91283e-05 -6.31622e-05 0 0 -0.000982789 -0.000975287 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000121826 0.000125783 1.48106e-05 1.14565e-05 1.48672e-05 1.153e-05 0.000118186 0.000112667 0.0240088 0.0211638 0.0240101 0.021167 0.0193941 0.019572 0.0431364 0.0423281 0.0431368 0.0423289 0.0767154 0.0767973 2.59043e-10 1.70335e-10 2.59096e-10 1.70513e-10 1.60106e-09 1.40913e-09 0 0 2.21077e-06 2.32924e-06 0 0 0 0 0 0 0 0
183 18085000 0.701007 0.691832 8.48627e-05 0.000506023 -0.0128128 -0.0128102 0.713039 0.721945 0.0127987 0.00880945 0.000282852 0.0055874 -0.066218 -0.0774805 0.0012337 0.000440384 -0.000281268 0.00196798 -365.492 -365.508 -1.3399e-05 -1.52592e-05 -6.02391e-05 -5.85507e-05 -1.89684e-05 -6.20921e-05 0 0 -0.000985482 -0.000978039 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000121122 0.000125016 1.54129e-05 1.18842e-05 1.54695e-05 1.1958e-05 0.000117548 0.000112081 0.0262393 0.0229919 0.0262408 0.0229955 0.0193318 0.0195164 0.048356 0.0472032 0.0483565 0.0472044 0.0769969 0.0770895 2.59132e-10 1.70424e-10 2.59181e-10 1.70602e-10 1.56474e-09 1.37751e-09 0 0 2.21026e-06 2.32872e-06 0 0 0 0 0 0 0 0
184 18185000 0.701169 0.692096 4.20295e-05 0.000453591 -0.012781 -0.0127765 0.712881 0.721692 0.0133795 0.00948439 0.000763104 0.00579549 -0.064108 -0.0750915 0.00197879 0.00135802 -0.000215056 0.00166981 -365.489 -365.505 -1.34102e-05 -1.52273e-05 -6.02528e-05 -5.86125e-05 -1.82226e-05 -6.05212e-05 0 0 -0.000988974 -0.000981876 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.0001204 0.000124191 1.42557e-05 1.10891e-05 1.43122e-05 1.11623e-05 0.000116914 0.000111502 0.0235663 0.0207721 0.0235675 0.0207753 0.0186382 0.0188173 0.042988 0.0421472 0.0429884 0.0421481 0.0756194 0.0757084 2.41973e-10 1.61278e-10 2.42007e-10 1.61441e-10 1.52942e-09 1.34668e-09 0 0 2.20929e-06 2.32773e-06 0 0 0 0 0 0 0 0
185 18285000 0.701255 0.692298 -2.07853e-05 0.000395181 -0.0127381 -0.0127339 0.712797 0.721499 0.0135538 0.0093139 0.000305133 0.00568464 -0.0643757 -0.0753712 0.00331531 0.00229483 -0.000162761 0.00224602 -365.489 -365.506 -1.34039e-05 -1.5205e-05 -6.02595e-05 -5.86347e-05 -1.78791e-05 -5.93211e-05 0 0 -0.000990517 -0.000983497 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.0001197 0.000123435 1.48279e-05 1.14996e-05 1.48845e-05 1.15732e-05 0.000116296 0.000110937 0.025733 0.0225521 0.0257344 0.0225556 0.0185681 0.0187534 0.0481526 0.046965 0.048153 0.0469663 0.0758548 0.0759543 2.42062e-10 1.61368e-10 2.42094e-10 1.6153e-10 1.49509e-09 1.31681e-09 0 0 2.20881e-06 2.32726e-06 0 0 0 0 0 0 0 0
186 18385000 0.701456 0.692597 -2.26624e-05 0.000383578 -0.0127555 -0.0127497 0.712599 0.721212 0.0148173 0.0106979 0.00167603 0.00679477 -0.0623832 -0.073132 0.00379132 0.00298555 -6.81337e-05 0.00196127 -365.485 -365.501 -1.34258e-05 -1.5181e-05 -6.02754e-05 -5.86972e-05 -1.7074e-05 -5.77415e-05 0 0 -0.000994194 -0.000987508 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000118991 0.000122632 1.37284e-05 1.07454e-05 1.37847e-05 1.08183e-05 0.000115678 0.000110373 0.0231379 0.0204036 0.0231391 0.0204068 0.0179189 0.0180987 0.0428421 0.0419726 0.0428424 0.0419736 0.0745332 0.0746288 2.26173e-10 1.52822e-10 2.26192e-10 1.5297e-10 1.46171e-09 1.28771e-09 0 0 2.20792e-06 2.32636e-06 0 0 0 0 0 0 0 0
187 18485000 0.701553 0.692739 4.15687e-06 0.000416214 -0.0127444 -0.0127378 0.712503 0.721076 0.015897 0.011416 0.00192767 0.00741507 -0.0642955 -0.0751395 0.00536709 0.00414013 0.000104625 0.00267173 -365.486 -365.502 -1.34161e-05 -1.51602e-05 -6.02856e-05 -5.8718e-05 -1.65434e-05 -5.66189e-05 0 0 -0.000995307 -0.000988712 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000119032 0.000122628 1.4273e-05 1.11404e-05 1.43291e-05 1.12134e-05 0.000115748 0.000110417 0.0252475 0.0221416 0.0252488 0.0221453 0.018068 0.018257 0.0479532 0.0467361 0.0479536 0.0467375 0.0761719 0.0762825 2.26265e-10 1.52915e-10 2.26283e-10 1.53063e-10 1.43733e-09 1.26652e-09 0 0 2.20759e-06 2.32603e-06 0 0 0 0 0 0 0 0
188 18585000 0.701729 0.693013 -2.0575e-05 0.000377826 -0.0126725 -0.0126689 0.712331 0.720814 0.015174 0.0110198 0.00176594 0.0069782 -0.0643185 -0.074923 0.0043803 0.00349058 3.22818e-05 0.00221009 -365.487 -365.503 -1.35214e-05 -1.51975e-05 -6.03103e-05 -5.87844e-05 -1.58146e-05 -5.51419e-05 0 0 -0.000997548 -0.000991245 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000118332 0.000121837 1.32268e-05 1.04226e-05 1.32827e-05 1.04949e-05 0.000115132 0.000109856 0.0227249 0.0200578 0.022726 0.020061 0.0174474 0.0176307 0.0426983 0.0418042 0.0426987 0.0418052 0.0748548 0.0749611 2.1155e-10 1.4492e-10 2.11557e-10 1.45054e-10 1.40556e-09 1.23883e-09 0 0 2.20677e-06 2.3252e-06 0 0 0 0 0 0 0 0
189 18685000 0.701779 0.693176 -6.682e-05 0.00033636 -0.0126954 -0.0126918 0.712281 0.720657 0.0155873 0.0110955 0.00133024 0.00688728 -0.0672119 -0.077857 0.00591545 0.00459882 0.000220175 0.0029397 -365.495 -365.511 -1.35142e-05 -1.51758e-05 -6.03179e-05 -5.88063e-05 -1.5413e-05 -5.39571e-05 0 0 -0.000997066 -0.000990848 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000117662 0.000121119 1.3745e-05 1.08025e-05 1.38009e-05 1.08751e-05 0.000114519 0.000109299 0.0247743 0.0217523 0.0247755 0.0217559 0.0173732 0.0175622 0.0477573 0.0465162 0.0477578 0.0465176 0.0750377 0.0751543 2.1164e-10 1.45011e-10 2.11646e-10 1.45145e-10 1.37466e-09 1.212e-09 0 0 2.20636e-06 2.3248e-06 0 0 0 0 0 0 0 0
190 18785000 0.701817 0.693309 -5.30234e-05 0.000336677 -0.0126709 -0.0126692 0.712245 0.720529 0.0144443 0.0102832 0.00114713 0.0063889 -0.0658912 -0.0762025 0.00483857 0.00386244 0.00019333 0.00249327 -365.495 -365.51 -1.36241e-05 -1.522e-05 -6.03285e-05 -5.88601e-05 -1.51279e-05 -5.29356e-05 0 0 -0.000999646 -0.000993644 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000116979 0.000120353 1.27496e-05 1.01186e-05 1.28054e-05 1.01905e-05 0.000113915 0.000108748 0.0223195 0.0197273 0.0223206 0.0197304 0.0167916 0.016975 0.0425566 0.0416417 0.0425569 0.0416428 0.0737741 0.0738863 1.98016e-10 1.37524e-10 1.98014e-10 1.37646e-10 1.34463e-09 1.18583e-09 0 0 2.20561e-06 2.32405e-06 0 0 0 0 0 0 0 0
191 18885000 0.701998 0.69359 -5.05171e-05 0.000343381 -0.0126486 -0.0126466 0.712067 0.720259 0.0151874 0.0106774 0.00180308 0.00739872 -0.0666923 -0.0771371 0.00630795 0.00490864 0.000365724 0.00321553 -365.495 -365.511 -1.36093e-05 -1.5192e-05 -6.03437e-05 -5.88878e-05 -1.43228e-05 -5.14267e-05 0 0 -0.00100091 -0.000995055 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000116323 0.000119653 1.32428e-05 1.04842e-05 1.32985e-05 1.05564e-05 0.000113315 0.000108205 0.0243149 0.0213837 0.024316 0.0213872 0.0167167 0.0169056 0.0475643 0.0463045 0.0475648 0.046306 0.0739302 0.0740525 1.98107e-10 1.37616e-10 1.98103e-10 1.37737e-10 1.31541e-09 1.16048e-09 0 0 2.20523e-06 2.32367e-06 0 0 0 0 0 0 0 0
192 18985000 0.702092 0.693779 -4.53294e-05 0.000339542 -0.0126461 -0.0126411 0.711974 0.720077 0.0161509 0.0117486 0.00237069 0.00765857 -0.0674722 -0.0776833 0.00731979 0.00612847 0.000296304 0.00272488 -365.496 -365.511 -1.3595e-05 -1.51456e-05 -6.03662e-05 -5.89525e-05 -1.37471e-05 -5.01614e-05 0 0 -0.00100265 -0.000997052 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000115662 0.000118914 1.22952e-05 9.83112e-06 1.23508e-05 9.90259e-06 0.000112718 0.000107662 0.0219294 0.0194169 0.0219303 0.01942 0.0161723 0.0163558 0.0424163 0.0414849 0.0424167 0.041486 0.0727177 0.0728355 1.85494e-10 1.30599e-10 1.85484e-10 1.3071e-10 1.287e-09 1.13574e-09 0 0 2.20454e-06 2.32299e-06 0 0 0 0 0 0 0 0
193 19085000 0.702188 0.693969 -6.79405e-05 0.00032069 -0.0125935 -0.0125884 0.71188 0.719894 0.016979 0.0122225 0.00306618 0.00869816 -0.0653955 -0.0756579 0.00895076 0.00730858 0.000589842 0.00356787 -365.492 -365.508 -1.3585e-05 -1.51229e-05 -6.03761e-05 -5.89747e-05 -1.32144e-05 -4.89507e-05 0 0 -0.00100516 -0.000999671 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000115022 0.000118234 1.27649e-05 1.01832e-05 1.28204e-05 1.02549e-05 0.00011213 0.000107131 0.0238693 0.0210345 0.0238704 0.0210381 0.0160972 0.0162857 0.047374 0.0461009 0.0473745 0.0461024 0.0728498 0.0729775 1.85585e-10 1.30691e-10 1.85574e-10 1.30801e-10 1.25936e-09 1.11176e-09 0 0 2.20419e-06 2.32265e-06 0 0 0 0 0 0 0 0
194 19185000 0.702233 0.694049 -6.6168e-05 0.000312578 -0.0124892 -0.0124823 0.711838 0.719819 0.0166591 0.0120823 0.002951 0.00825509 -0.0663602 -0.0763696 0.00951948 0.00813614 0.000474912 0.00302454 -365.493 -365.509 -1.35939e-05 -1.50979e-05 -6.04008e-05 -5.90356e-05 -1.2881e-05 -4.81216e-05 0 0 -0.00100673 -0.00100143 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000115031 0.000118172 1.18623e-05 9.55845e-06 1.19174e-05 9.62917e-06 0.000112178 0.000107158 0.0215475 0.0191199 0.0215484 0.0191229 0.0157689 0.0159553 0.0422775 0.0413335 0.0422779 0.0413347 0.0729941 0.0731222 1.73912e-10 1.24113e-10 1.73897e-10 1.24213e-10 1.23914e-09 1.09415e-09 0 0 2.20364e-06 2.3221e-06 0 0 0 0 0 0 0 0
195 19285000 0.702231 0.694142 -3.31694e-05 0.000349197 -0.0124379 -0.0124302 0.711841 0.719731 0.0170243 0.0121181 0.00238119 0.00800865 -0.0653113 -0.0752782 0.0111697 0.00931578 0.000744195 0.00383891 -365.489 -365.505 -1.35903e-05 -1.50818e-05 -6.04041e-05 -5.90512e-05 -1.27015e-05 -4.72687e-05 0 0 -0.00100924 -0.001004 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000114395 0.0001175 1.23099e-05 9.89791e-06 1.2365e-05 9.96877e-06 0.000111595 0.000106633 0.0234377 0.0207037 0.0234386 0.0207071 0.0156949 0.0158861 0.047186 0.0459047 0.0471865 0.0459063 0.0731085 0.0732468 1.74004e-10 1.24206e-10 1.73987e-10 1.24305e-10 1.21279e-09 1.0713e-09 0 0 2.20332e-06 2.32178e-06 0 0 0 0 0 0 0 0
196 19385000 0.702346 0.694338 -5.64474e-05 0.000311523 -0.0123801 -0.0123761 0.711728 0.719543 0.0150285 0.0105623 0.00129492 0.00658758 -0.060999 -0.0707297 0.00928122 0.00786582 0.000578917 0.00322509 -365.482 -365.497 -1.37089e-05 -1.51353e-05 -6.04253e-05 -5.91099e-05 -1.21761e-05 -4.61307e-05 0 0 -0.00101294 -0.0010079 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000113752 0.000116787 1.14503e-05 9.29964e-06 1.15052e-05 9.3698e-06 0.00011102 0.000106111 0.0211737 0.0188349 0.0211745 0.0188378 0.0152061 0.015392 0.0421398 0.0411872 0.0421402 0.0411884 0.07195 0.0720832 1.63198e-10 1.18033e-10 1.63178e-10 1.18123e-10 1.18716e-09 1.049e-09 0 0 2.20273e-06 2.3212e-06 0 0 0 0 0 0 0 0
197 19485000 0.70252 0.694609 -4.28683e-05 0.000329248 -0.0123955 -0.012391 0.711556 0.71928 0.0143196 0.00954847 0.000297879 0.00589193 -0.0648167 -0.0746593 0.0107217 0.00885193 0.000639502 0.00383371 -365.488 -365.504 -1.36967e-05 -1.51116e-05 -6.04376e-05 -5.91335e-05 -1.15111e-05 -4.48433e-05 0 0 -0.0010126 -0.00100773 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000113127 0.00011613 1.18775e-05 9.62733e-06 1.19323e-05 9.69765e-06 0.000110453 0.000105601 0.0230158 0.0203863 0.0230166 0.0203895 0.0151336 0.0153241 0.0469998 0.0457155 0.0470003 0.0457171 0.0720442 0.0721873 1.6329e-10 1.18125e-10 1.63269e-10 1.18215e-10 1.16222e-09 1.02737e-09 0 0 2.20242e-06 2.32091e-06 0 0 0 0 0 0 0 0
198 19585000 0.702673 0.694844 7.71625e-07 0.000358534 -0.0123071 -0.0123044 0.711407 0.719055 0.0125291 0.00816233 -0.000782291 0.00445804 -0.0647099 -0.0743937 0.00896289 0.00750825 0.00047532 0.00320172 -365.489 -365.504 -1.37914e-05 -1.51486e-05 -6.0453e-05 -5.91877e-05 -1.07968e-05 -4.35493e-05 0 0 -0.00101425 -0.00100963 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000112503 0.000115441 1.10583e-05 9.05359e-06 1.11129e-05 9.12314e-06 0.000109885 0.000105085 0.0208133 0.0185653 0.020814 0.018568 0.0146736 0.014859 0.0420031 0.0410457 0.0420034 0.0410469 0.0709227 0.0710607 1.5329e-10 1.12331e-10 1.53267e-10 1.12413e-10 1.13793e-09 1.00623e-09 0 0 2.20188e-06 2.32038e-06 0 0 0 0 0 0 0 0
199 19685000 0.702691 0.694955 -8.91074e-06 0.000353036 -0.0123491 -0.0123461 0.711388 0.718947 0.0133002 0.00866493 -0.00314915 0.00241317 -0.0640855 -0.0737302 0.0102456 0.00834331 0.000279009 0.00354429 -365.49 -365.506 -1.37884e-05 -1.51343e-05 -6.04559e-05 -5.92018e-05 -1.06421e-05 -4.27758e-05 0 0 -0.00101534 -0.00101078 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000111892 0.000114801 1.14662e-05 9.36993e-06 1.15207e-05 9.43966e-06 0.000109331 0.000104588 0.0226032 0.020081 0.0226039 0.0200839 0.0146021 0.0147919 0.0468154 0.0455327 0.0468158 0.0455343 0.0709988 0.0711464 1.53382e-10 1.12425e-10 1.53359e-10 1.12506e-10 1.1143e-09 9.85751e-10 0 0 2.2016e-06 2.32011e-06 0 0 0 0 0 0 0 0
200 19785000 0.702762 0.695056 4.27016e-05 0.000391761 -0.0123409 -0.0123384 0.711318 0.71885 0.0108002 0.00654909 -0.00425144 0.000900354 -0.063609 -0.0730292 0.00856005 0.00705724 0.000182456 0.00294692 -365.49 -365.505 -1.38785e-05 -1.51736e-05 -6.04464e-05 -5.92317e-05 -1.03378e-05 -4.20457e-05 0 0 -0.00101722 -0.00101285 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000111888 0.000114735 1.06861e-05 8.81978e-06 1.07403e-05 8.88862e-06 0.000109369 0.000104609 0.0204582 0.0183035 0.0204588 0.0183059 0.0143334 0.0145212 0.0418671 0.0409087 0.0418674 0.0409099 0.0711752 0.0713236 1.44133e-10 1.06988e-10 1.44107e-10 1.07061e-10 1.09701e-09 9.70694e-10 0 0 2.20117e-06 2.31969e-06 0 0 0 0 0 0 0 0
201 19885000 0.702963 0.695343 -3.23091e-06 0.000348836 -0.0122824 -0.0122802 0.71112 0.718573 0.00985662 0.00530756 -0.00461077 0.000823758 -0.0632787 -0.0728283 0.00960537 0.00766969 -0.000274078 0.00302463 -365.491 -365.507 -1.38644e-05 -1.51495e-05 -6.04602e-05 -5.92556e-05 -9.58182e-06 -4.07383e-05 0 0 -0.00101807 -0.00101388 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000111286 0.000114106 1.10753e-05 9.12485e-06 1.11294e-05 9.19382e-06 0.000108817 0.000104114 0.0222025 0.0197888 0.0222031 0.0197915 0.014264 0.014456 0.0466323 0.0453559 0.0466327 0.0453574 0.0712372 0.0713954 1.44225e-10 1.07081e-10 1.44199e-10 1.07154e-10 1.07446e-09 9.51148e-10 0 0 2.2009e-06 2.31943e-06 0 0 0 0 0 0 0 0
202 19985000 0.703149 0.695604 -4.3428e-05 0.000295529 -0.0122708 -0.0122691 0.710936 0.71832 0.00738411 0.00318577 -0.00559686 -0.000584073 -0.0608006 -0.0702021 0.00801275 0.00645535 -0.00030909 0.00248058 -365.487 -365.502 -1.3927e-05 -1.51655e-05 -6.04501e-05 -5.92874e-05 -8.90317e-06 -3.95348e-05 0 0 -0.00102053 -0.0010166 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000110678 0.000113441 1.03317e-05 8.59612e-06 1.03856e-05 8.66443e-06 0.000108272 0.000103619 0.020112 0.0180513 0.0201124 0.0180536 0.0138506 0.0140376 0.0417316 0.0407756 0.0417319 0.0407768 0.0701658 0.0703186 1.35665e-10 1.01975e-10 1.35637e-10 1.0204e-10 1.05249e-09 9.32035e-10 0 0 2.20044e-06 2.31898e-06 0 0 0 0 0 0 0 0
203 20085000 0.703386 0.695921 -6.74623e-05 0.000274689 -0.012241 -0.0122394 0.710703 0.718014 0.00716654 0.00270829 -0.00736569 -0.00206098 -0.0611394 -0.0707023 0.00874538 0.00676173 -0.000940182 0.00237136 -365.486 -365.502 -1.39104e-05 -1.51396e-05 -6.04662e-05 -5.93128e-05 -8.01766e-06 -3.81364e-05 0 0 -0.00102164 -0.00101792 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000110092 0.00011283 1.07037e-05 8.89101e-06 1.07576e-05 8.95944e-06 0.00010773 0.000103135 0.0218137 0.0195088 0.0218143 0.0195112 0.0137839 0.0139752 0.0464503 0.0451843 0.0464507 0.0451859 0.0702127 0.0703752 1.35758e-10 1.02068e-10 1.3573e-10 1.02134e-10 1.03111e-09 9.13504e-10 0 0 2.20019e-06 2.31875e-06 0 0 0 0 0 0 0 0
204 20185000 0.7035 0.696104 2.1982e-05 0.000349672 -0.0122242 -0.0122226 0.71059 0.717836 0.00516792 0.00111808 -0.00827666 -0.00339473 -0.0580926 -0.067452 0.00633228 0.00477272 -0.000849558 0.00193254 -365.481 -365.496 -1.40048e-05 -1.5182e-05 -6.04372e-05 -5.93269e-05 -7.52234e-06 -3.71359e-05 0 0 -0.00102453 -0.00102103 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.0001095 0.000112185 9.99488e-06 8.38269e-06 1.00485e-05 8.45042e-06 0.000107195 0.000102649 0.0197765 0.01781 0.0197769 0.017812 0.0133957 0.0135821 0.0415966 0.0406463 0.0415968 0.0406475 0.0691837 0.0693408 1.27837e-10 9.72728e-11 1.27808e-10 9.73318e-11 1.01028e-09 8.95378e-10 0 0 2.19975e-06 2.31833e-06 0 0 0 0 0 0 0 0
205 20285000 0.703619 0.696309 -1.01397e-05 0.000320454 -0.0122054 -0.0122039 0.710472 0.717638 0.00433775 3.3465e-05 -0.00995076 -0.00480368 -0.0606378 -0.07004 0.00680011 0.00482576 -0.00176448 0.00152071 -365.485 -365.501 -1.39965e-05 -1.51641e-05 -6.04452e-05 -5.93445e-05 -7.08113e-06 -3.61695e-05 0 0 -0.00102474 -0.00102137 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000108925 0.000111587 1.03509e-05 8.66782e-06 1.04044e-05 8.73566e-06 0.000106669 0.000102179 0.0214363 0.0192397 0.0214368 0.0192418 0.0133318 0.0135223 0.0462697 0.045018 0.04627 0.0450196 0.0692175 0.0693841 1.2793e-10 9.73669e-11 1.27901e-10 9.7426e-11 9.90006e-10 8.77798e-10 0 0 2.19952e-06 2.31811e-06 0 0 0 0 0 0 0 0
206 20385000 0.703687 0.696445 -3.63353e-06 0.000313669 -0.012248 -0.0122459 0.710404 0.717505 0.00173626 -0.00220572 -0.0108765 -0.00618774 -0.057671 -0.0667968 0.00469223 0.00310358 -0.00154112 0.00120236 -365.479 -365.494 -1.40714e-05 -1.51939e-05 -6.03988e-05 -5.93424e-05 -6.85772e-06 -3.54482e-05 0 0 -0.00102791 -0.00102469 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000108342 0.000110954 9.67513e-06 8.1789e-06 9.72851e-06 8.24612e-06 0.000106151 0.00010171 0.0194514 0.0175782 0.0194517 0.0175799 0.012967 0.0131528 0.0414621 0.0405205 0.0414623 0.0405217 0.0682288 0.0683902 1.206e-10 9.28627e-11 1.2057e-10 9.29156e-11 9.70239e-10 8.60599e-10 0 0 2.19912e-06 2.31773e-06 0 0 0 0 0 0 0 0
207 20485000 0.703759 0.696555 3.34153e-05 0.000354428 -0.0122585 -0.0122559 0.710333 0.717399 0.00150653 -0.00269471 -0.011862 -0.00690951 -0.0589446 -0.0680802 0.00484299 0.00284804 -0.00267403 0.000551954 -365.483 -365.499 -1.40672e-05 -1.51827e-05 -6.04028e-05 -5.93534e-05 -6.63748e-06 -3.48429e-05 0 0 -0.00102808 -0.00102495 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000108337 0.000110927 1.00162e-05 8.45501e-06 1.00694e-05 8.52217e-06 0.000106181 0.000101732 0.0210677 0.0189786 0.0210681 0.0189806 0.0130484 0.0132411 0.0460901 0.0448564 0.0460904 0.0448579 0.0694358 0.0696131 1.20695e-10 9.29584e-11 1.20666e-10 9.30114e-11 9.55778e-10 8.48062e-10 0 0 2.19896e-06 2.31758e-06 0 0 0 0 0 0 0 0
208 20585000 0.703764 0.69664 5.52011e-05 0.000364711 -0.0123198 -0.0123139 0.710327 0.717316 0.0015338 -0.00243378 -0.011993 -0.007472 -0.0611083 -0.0699772 0.00409159 0.00239319 -0.00231849 0.000367795 -365.486 -365.502 -1.40848e-05 -1.5169e-05 -6.03485e-05 -5.93441e-05 -6.53719e-06 -3.42365e-05 0 0 -0.00102891 -0.00102598 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000107764 0.000110306 9.37183e-06 7.98433e-06 9.42482e-06 8.05091e-06 0.000105664 0.000101263 0.0191352 0.0173543 0.0191356 0.0173559 0.0126989 0.0128869 0.0413281 0.0403981 0.0413283 0.0403992 0.0684524 0.0686242 1.13911e-10 8.87278e-11 1.13882e-10 8.87752e-11 9.36889e-10 8.31621e-10 0 0 2.19858e-06 2.31722e-06 0 0 0 0 0 0 0 0
209 20685000 0.703876 0.696827 7.43758e-05 0.000386796 -0.0123398 -0.0123332 0.710216 0.717133 0.00176867 -0.00245079 -0.0134501 -0.00867475 -0.0608738 -0.0697437 0.00425382 0.00214157 -0.00356883 -0.000421789 -365.484 -365.5 -1.40781e-05 -1.51538e-05 -6.0354e-05 -5.93588e-05 -6.20793e-06 -3.34282e-05 0 0 -0.00103046 -0.00102762 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000107203 0.000109729 9.69858e-06 8.25145e-06 9.7515e-06 8.31815e-06 0.000105158 0.000100812 0.0207133 0.0187296 0.0207137 0.0187313 0.0126403 0.0128319 0.0459119 0.0446993 0.0459122 0.0447007 0.0684647 0.068646 1.14004e-10 8.88223e-11 1.13976e-10 8.88698e-11 9.18499e-10 8.1567e-10 0 0 2.19838e-06 2.31703e-06 0 0 0 0 0 0 0 0
210 20785000 0.703971 0.696995 9.82836e-05 0.000398567 -0.0123285 -0.0123187 0.710122 0.71697 0.000371716 -0.00362549 -0.0125886 -0.008276 -0.0601958 -0.0688686 0.00355783 0.00175056 -0.00302454 -0.00041374 -365.484 -365.499 -1.40888e-05 -1.51349e-05 -6.0297e-05 -5.93458e-05 -5.88509e-06 -3.26425e-05 0 0 -0.00103193 -0.00102933 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000106642 0.000109124 9.0835e-06 7.79773e-06 9.13628e-06 7.86382e-06 0.000104656 0.000100356 0.0188266 0.0171365 0.0188269 0.017138 0.012311 0.012498 0.0411945 0.0402786 0.0411947 0.0402797 0.0675195 0.0676953 1.07723e-10 8.48479e-11 1.07697e-10 8.48902e-11 9.00561e-10 8.00054e-10 0 0 2.19803e-06 2.3167e-06 0 0 0 0 0 0 0 0
211 20885000 0.704144 0.697244 8.21981e-05 0.000384887 -0.012319 -0.0123087 0.70995 0.716728 6.94866e-05 -0.00415686 -0.0151616 -0.0106218 -0.0614726 -0.0702143 0.00359283 0.00136723 -0.00440407 -0.00135668 -365.487 -365.503 -1.40784e-05 -1.51169e-05 -6.03057e-05 -5.93634e-05 -5.36809e-06 -3.16739e-05 0 0 -0.00103227 -0.00102985 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000106095 0.000108562 9.39679e-06 8.05632e-06 9.4495e-06 8.12251e-06 0.000104159 9.99133e-05 0.0203661 0.018486 0.0203664 0.0184875 0.012254 0.0124443 0.0457347 0.0445459 0.045735 0.0445472 0.0675147 0.0676998 1.07816e-10 8.49427e-11 1.07792e-10 8.49851e-11 8.83082e-10 7.84889e-10 0 0 2.19784e-06 2.31653e-06 0 0 0 0 0 0 0 0
212 20985000 0.70421 0.697378 8.90125e-05 0.000380881 -0.0123436 -0.012329 0.709885 0.716598 -0.000425406 -0.00444744 -0.0159445 -0.011866 -0.0601554 -0.0686823 0.00473075 0.0027783 -0.0038227 -0.00130375 -365.486 -365.501 -1.40513e-05 -1.50678e-05 -6.02413e-05 -5.93425e-05 -5.09658e-06 -3.09619e-05 0 0 -0.00103404 -0.00103182 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00010555 0.000107975 8.81e-06 7.61917e-06 8.86259e-06 7.68481e-06 0.000103666 9.94654e-05 0.0185259 0.0169249 0.0185262 0.0169261 0.0119439 0.0121298 0.0410614 0.0401617 0.0410616 0.0401628 0.066606 0.0667857 1.02001e-10 8.12092e-11 1.01977e-10 8.12468e-11 8.66041e-10 7.70048e-10 0 0 2.19751e-06 2.31622e-06 0 0 0 0 0 0 0 0
213 21085000 0.704358 0.697558 7.38275e-05 0.000368725 -0.0123386 -0.0123236 0.709738 0.716423 -0.000247448 -0.00449367 -0.0185608 -0.014259 -0.0606056 -0.0691717 0.00468606 0.0023153 -0.00554863 -0.00261468 -365.488 -365.504 -1.40443e-05 -1.50552e-05 -6.02472e-05 -5.93547e-05 -4.74784e-06 -3.02885e-05 0 0 -0.00103463 -0.00103252 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000105537 0.000107944 9.11097e-06 7.86994e-06 9.16332e-06 7.93552e-06 0.000103692 9.94859e-05 0.0200281 0.0182492 0.0200283 0.0182504 0.0120188 0.0122109 0.0455584 0.044396 0.0455586 0.0443973 0.0677288 0.0679247 1.02096e-10 8.13055e-11 1.02074e-10 8.13432e-11 8.53574e-10 7.59231e-10 0 0 2.19738e-06 2.3161e-06 0 0 0 0 0 0 0 0
214 21185000 0.704402 0.697672 0.000105193 0.000388759 -0.0123475 -0.0123281 0.709694 0.716311 0.000108643 -0.00394655 -0.017748 -0.0138939 -0.0604632 -0.0687918 0.00570505 0.00362565 -0.00477776 -0.00236919 -365.491 -365.506 -1.40209e-05 -1.50092e-05 -6.0168e-05 -5.93192e-05 -4.60687e-06 -2.97103e-05 0 0 -0.00103567 -0.00103379 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000104995 0.000107363 8.55086e-06 7.44846e-06 8.60315e-06 7.51351e-06 0.000103206 9.90446e-05 0.0182334 0.016719 0.0182336 0.01672 0.011721 0.0119086 0.0409285 0.0400472 0.0409287 0.0400482 0.0668249 0.0670152 9.67112e-11 7.77983e-11 9.6689e-11 7.78316e-11 8.3727e-10 7.45027e-10 0 0 2.19707e-06 2.31582e-06 0 0 0 0 0 0 0 0
215 21285000 0.704608 0.697947 0.000137119 0.000422581 -0.0123084 -0.012288 0.70949 0.716044 -0.000503822 -0.00479393 -0.0198387 -0.0157927 -0.0598446 -0.0682225 0.00568648 0.00318262 -0.00664409 -0.0038452 -365.489 -365.505 -1.4011e-05 -1.49924e-05 -6.01763e-05 -5.93355e-05 -4.11939e-06 -2.88134e-05 0 0 -0.0010369 -0.00103516 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000104462 0.000106819 8.83983e-06 7.6914e-06 8.89203e-06 7.75649e-06 0.00010273 9.86213e-05 0.0197006 0.0180198 0.0197007 0.0180208 0.0116698 0.0118606 0.0453831 0.0442492 0.0453833 0.0442504 0.0668051 0.0670046 9.68047e-11 7.78935e-11 9.67845e-11 7.7927e-11 8.21375e-10 7.31228e-10 0 0 2.1969e-06 2.31566e-06 0 0 0 0 0 0 0 0
216 21385000 0.704605 0.698012 0.000178318 0.000450431 -0.0123112 -0.0122869 0.709492 0.715981 -0.00147599 -0.00548746 -0.0195591 -0.0160172 -0.058931 -0.0670685 0.00477557 0.00261644 -0.00481277 -0.00257711 -365.49 -365.505 -1.40198e-05 -1.49727e-05 -6.00567e-05 -5.9264e-05 -4.01522e-06 -2.82886e-05 0 0 -0.00103814 -0.00103667 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000103938 0.000106258 8.30508e-06 7.2849e-06 8.35723e-06 7.3495e-06 0.00010225 9.81857e-05 0.0179495 0.016519 0.0179496 0.0165198 0.011389 0.0115753 0.0407961 0.0399349 0.0407963 0.0399358 0.0659357 0.0661296 9.18163e-11 7.45986e-11 9.1796e-11 7.4628e-11 8.05872e-10 7.17716e-10 0 0 2.19661e-06 2.3154e-06 0 0 0 0 0 0 0 0
217 21485000 0.70472 0.698198 0.000187693 0.00046159 -0.012289 -0.012264 0.709379 0.7158 -0.00180256 -0.00605546 -0.0209257 -0.0172029 -0.0596828 -0.0678355 0.0045801 0.00200152 -0.00682169 -0.00422657 -365.492 -365.507 -1.40128e-05 -1.49586e-05 -6.00627e-05 -5.92778e-05 -3.66715e-06 -2.75352e-05 0 0 -0.00103871 -0.00103739 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000103424 0.000105733 8.58313e-06 7.52071e-06 8.6352e-06 7.58536e-06 0.000101778 9.77666e-05 0.0193831 0.0177971 0.0193833 0.017798 0.011341 0.0115302 0.0452088 0.0441053 0.0452091 0.0441064 0.0659099 0.0661129 9.19102e-11 7.4694e-11 9.18916e-11 7.47236e-11 7.90755e-10 7.04586e-10 0 0 2.19645e-06 2.31525e-06 0 0 0 0 0 0 0 0
218 21585000 0.704758 0.698302 0.000188803 0.000449885 -0.0122663 -0.0122381 0.709341 0.715698 -0.00274742 -0.00677293 -0.0182966 -0.0150493 -0.0591462 -0.0670811 0.00380764 0.00156904 -0.00492811 -0.00286146 -365.494 -365.509 -1.40131e-05 -1.49327e-05 -5.99467e-05 -5.92066e-05 -3.52856e-06 -2.69954e-05 0 0 -0.00103974 -0.0010387 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.00010291 0.000105184 8.07228e-06 7.12843e-06 8.12433e-06 7.19261e-06 0.000101313 9.73437e-05 0.0176747 0.0163251 0.0176749 0.0163259 0.0110761 0.0112609 0.0406642 0.0398245 0.0406643 0.0398253 0.0650733 0.0652708 8.7287e-11 7.15982e-11 8.72682e-11 7.1624e-11 7.76007e-10 6.91726e-10 0 0 2.19618e-06 2.31501e-06 0 0 0 0 0 0 0 0
219 21685000 0.704811 0.698424 0.000185725 0.000448945 -0.0123032 -0.0122744 0.709288 0.715579 -0.00253758 -0.00679483 -0.0197306 -0.0163082 -0.0580984 -0.066006 0.00353934 0.000882067 -0.00684451 -0.004446 -365.495 -365.51 -1.40086e-05 -1.49211e-05 -5.99505e-05 -5.92178e-05 -3.3096e-06 -2.63811e-05 0 0 -0.00104049 -0.00103956 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000102411 0.000104675 8.34027e-06 7.35763e-06 8.39224e-06 7.42191e-06 0.00010085 9.69321e-05 0.019074 0.0175793 0.0190741 0.0175801 0.011031 0.0112185 0.0450357 0.043964 0.0450359 0.043965 0.0650427 0.0652489 8.73812e-11 7.16937e-11 8.7364e-11 7.17198e-11 7.61622e-10 6.79226e-10 0 0 2.19603e-06 2.31487e-06 0 0 0 0 0 0 0 0
220 21785000 0.70481 0.698452 0.000186714 0.000435589 -0.0123096 -0.0122776 0.70929 0.715551 -0.00334907 -0.00732696 -0.0152906 -0.012401 -0.0588635 -0.0665522 0.00202997 -0.000236719 -0.00307859 -0.00126261 -365.499 -365.514 -1.40384e-05 -1.4921e-05 -5.97771e-05 -5.90942e-05 -3.28272e-06 -2.60592e-05 0 0 -0.00104106 -0.00104048 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000102392 0.000104618 7.85245e-06 6.97928e-06 7.90427e-06 7.04302e-06 0.000100863 9.69338e-05 0.0174077 0.0161359 0.0174078 0.0161366 0.0108906 0.0110767 0.0405327 0.0397159 0.0405329 0.0397166 0.0652857 0.0654939 8.30962e-11 6.87859e-11 8.30784e-11 6.88085e-11 7.51079e-10 6.70021e-10 0 0 2.19581e-06 2.31467e-06 0 0 0 0 0 0 0 0
221 21885000 0.704881 0.698594 0.000188307 0.000438268 -0.0122609 -0.0122281 0.709219 0.715414 -0.00295138 -0.0071682 -0.0156702 -0.0126227 -0.058616 -0.0662538 0.00171332 -0.000967461 -0.00462167 -0.00250963 -365.502 -365.517 -1.40354e-05 -1.49109e-05 -5.97796e-05 -5.9104e-05 -3.13591e-06 -2.55246e-05 0 0 -0.0010415 -0.00104103 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000101893 0.000104111 8.11048e-06 7.2017e-06 8.16221e-06 7.26546e-06 0.00010041 9.65316e-05 0.0187763 0.0173691 0.0187764 0.01737 0.0108482 0.011037 0.0448639 0.0438251 0.0448641 0.043826 0.0652498 0.0654669 8.31907e-11 6.88817e-11 8.31743e-11 6.89045e-11 7.37298e-10 6.5804e-10 0 0 2.19567e-06 2.31455e-06 0 0 0 0 0 0 0 0
222 21985000 0.704967 0.698741 0.000201427 0.000438489 -0.0123098 -0.0122746 0.709133 0.715269 -0.00380169 -0.00772131 -0.0134143 -0.0108312 -0.0574144 -0.0648683 0.000514542 -0.00178652 -0.00129182 0.00031392 -365.503 -365.518 -1.40533e-05 -1.49002e-05 -5.96339e-05 -5.90026e-05 -2.89806e-06 -2.49241e-05 -1.62879e-11 -1.90541e-11 1.58225e-11 1.81222e-11 -0.00104258 -0.0010425 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000101396 0.000103584 7.64419e-06 6.83647e-06 7.69597e-06 6.8999e-06 9.99594e-05 9.61225e-05 0.0171847 0.0159877 0.0171849 0.0159883 0.0106073 0.0107917 0.0404019 0.0396088 0.0404021 0.0396095 0.0644486 0.06466 7.92142e-11 6.61478e-11 7.91977e-11 6.61675e-11 7.23847e-10 6.463e-10 4e-06 4e-06 2.19542e-06 2.31433e-06 0 0 0 0 0 0 0 0
223 22085000 0.705021 0.698864 0.000210126 0.000448397 -0.0122971 -0.0122611 0.70908 0.71515 -0.0039799 -0.00814833 -0.012685 -0.00997192 -0.0594155 -0.0668188 0.000147636 -0.00256234 -0.00258509 -0.000714823 -365.506 -365.521 -1.40503e-05 -1.48903e-05 -5.96365e-05 -5.90122e-05 -2.74704e-06 -2.44016e-05 -1.03547e-09 -1.4181e-09 1.00589e-09 1.34865e-09 -0.00104293 -0.00104297 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000100912 0.000103092 7.89334e-06 7.0529e-06 7.94506e-06 7.11637e-06 9.95139e-05 9.5727e-05 0.0191662 0.0178425 0.0191663 0.0178433 0.0105686 0.0107555 0.0446959 0.0436908 0.0446961 0.0436917 0.0644092 0.0646293 7.93089e-11 6.62437e-11 7.92938e-11 6.62637e-11 7.10722e-10 6.34884e-10 4.00001e-06 4.00001e-06 2.19529e-06 2.31421e-06 0 0 0 0 0 0 0 0
224 22185000 0.705101 0.699002 0.000192579 0.000422512 -0.0122755 -0.012239 0.709 0.715015 -0.00382299 -0.0077524 -0.0115975 -0.00915171 -0.0577274 -0.0649445 9.47774e-05 -0.00228188 -0.00225686 -0.000696539 -365.507 -365.522 -1.40349e-05 -1.48546e-05 -5.95974e-05 -5.89975e-05 -2.53026e-06 -2.38405e-05 -2.76197e-06 -2.19424e-06 9.07748e-07 1.8249e-06 -0.00104415 -0.00104438 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 0.000100427 0.000102577 7.44828e-06 6.70088e-06 7.50005e-06 6.76401e-06 9.90727e-05 9.53264e-05 0.0188341 0.0177193 0.0188341 0.0177198 0.0103405 0.010523 0.0402786 0.0395106 0.0402787 0.0395112 0.063631 0.0638455 7.5624e-11 6.3678e-11 7.56088e-11 6.36953e-11 6.979e-10 6.23688e-10 3.98838e-06 3.98832e-06 3.98838e-06 3.98832e-06 2.19506e-06 2.314e-06 0 0 0 0 0 0 0 0
225 22285000 0.705104 0.699072 0.000228279 0.000459725 -0.0123102 -0.0122726 0.708997 0.714946 -0.00510452 -0.00923831 -0.0124877 -0.00994351 -0.0581571 -0.0652974 -0.000348747 -0.00313184 -0.00346638 -0.00165638 -365.51 -365.525 -1.40335e-05 -1.48465e-05 -5.95986e-05 -5.90054e-05 -2.46116e-06 -2.34106e-05 -2.7727e-06 -2.20881e-06 9.18226e-07 1.84004e-06 -0.00104458 -0.0010449 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.99565e-05 0.0001021 7.68919e-06 6.91169e-06 7.7409e-06 6.97489e-06 9.86345e-05 9.49373e-05 0.0222919 0.0210651 0.0222919 0.0210656 0.0103054 0.0104903 0.0445866 0.0436178 0.0445867 0.0436186 0.0635888 0.0638118 7.5719e-11 6.37741e-11 7.5705e-11 6.37917e-11 6.85395e-10 6.12803e-10 3.98839e-06 3.98833e-06 3.98839e-06 3.98833e-06 2.19492e-06 2.31389e-06 0 0 0 0 0 0 0 0
226 22385000 0.705145 0.699129 0.000214669 0.000439082 -0.0123069 -0.0122688 0.708956 0.71489 -0.0058768 -0.00969301 -0.0115126 -0.0092817 -0.0562673 -0.0632331 -0.000365091 -0.00280171 -0.00303582 -0.00152907 -365.508 -365.523 -1.40142e-05 -1.48101e-05 -5.95603e-05 -5.89881e-05 -2.27974e-06 -2.29908e-05 -9.13711e-06 -7.28363e-06 3.77942e-06 6.90639e-06 -0.00104631 -0.00104676 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.9939e-05 0.00010205 7.27436e-06 6.58074e-06 7.326e-06 6.64351e-06 9.86408e-05 9.4934e-05 0.0227892 0.021795 0.0227891 0.0217952 0.010191 0.0103743 0.0402177 0.0394803 0.0402178 0.0394809 0.0638486 0.0640738 7.23572e-11 6.14052e-11 7.2343e-11 6.14203e-11 6.76229e-10 6.04789e-10 3.92483e-06 3.9242e-06 3.92483e-06 3.9242e-06 2.19474e-06 2.31372e-06 0 0 0 0 0 0 0 0
227 22485000 0.705214 0.699258 0.000222742 0.000448134 -0.012273 -0.0122341 0.708888 0.714765 -0.00631716 -0.010328 -0.0114185 -0.00909499 -0.0554022 -0.0623154 -0.00096942 -0.00380106 -0.00420697 -0.00247264 -365.506 -365.521 -1.40103e-05 -1.48e-05 -5.95638e-05 -5.89978e-05 -2.08419e-06 -2.24623e-05 -9.20578e-06 -7.36244e-06 3.84652e-06 6.986e-06 -0.0010476 -0.00104813 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.94724e-05 0.000101577 7.50738e-06 6.78601e-06 7.55895e-06 6.8488e-06 9.82093e-05 9.45512e-05 0.0275237 0.0264394 0.0275235 0.0264395 0.0101594 0.010345 0.0446589 0.0437365 0.044659 0.0437372 0.063803 0.0640368 7.24524e-11 6.15014e-11 7.24393e-11 6.15168e-11 6.64234e-10 5.94344e-10 3.92484e-06 3.92421e-06 3.92484e-06 3.92421e-06 2.19462e-06 2.31361e-06 0 0 0 0 0 0 0 0
228 22585000 0.70529 0.69939 0.000195997 0.000413562 -0.012251 -0.0122113 0.708813 0.714636 -0.00584474 -0.00942537 -0.00988571 -0.00793334 -0.0555487 -0.0622894 -0.00159774 -0.00406933 -0.00266104 -0.00125941 -365.507 -365.521 -1.39857e-05 -1.47585e-05 -5.95049e-05 -5.89633e-05 -1.87403e-06 -2.19324e-05 -2.51683e-05 -2.14701e-05 1.54059e-05 2.19648e-05 -0.00104862 -0.00104939 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.90054e-05 0.000101085 7.14175e-06 6.49251e-06 7.19337e-06 6.55501e-06 9.77814e-05 9.41625e-05 0.028047 0.0272231 0.0280468 0.027223 0.00995254 0.0101338 0.0403104 0.0396167 0.0403105 0.0396172 0.0630571 0.0632851 6.9493e-11 5.9393e-11 6.94801e-11 5.94066e-11 6.52511e-10 5.84097e-10 3.78292e-06 3.78036e-06 3.78292e-06 3.78036e-06 2.19441e-06 2.31343e-06 0 0 0 0 0 0 0 0
229 22685000 0.705364 0.699523 0.000234229 0.00045316 -0.0122781 -0.0122372 0.708739 0.714505 -0.00685839 -0.0105946 -0.00974077 -0.00773124 -0.0547416 -0.0614444 -0.00221396 -0.00505521 -0.00364634 -0.00204649 -365.507 -365.522 -1.39815e-05 -1.47484e-05 -5.95087e-05 -5.89731e-05 -1.66296e-06 -2.14002e-05 -2.52559e-05 -2.15769e-05 1.54927e-05 2.20764e-05 -0.00104943 -0.00105032 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.85501e-05 0.000100624 7.36859e-06 6.69356e-06 7.42016e-06 6.75613e-06 9.73589e-05 9.37877e-05 0.0337563 0.0328688 0.033756 0.0328684 0.0099243 0.0101076 0.0450232 0.0441672 0.0450233 0.0441678 0.0630102 0.0632465 6.95884e-11 5.94894e-11 6.95766e-11 5.95032e-11 6.41072e-10 5.7413e-10 3.78293e-06 3.78037e-06 3.78293e-06 3.78037e-06 2.19429e-06 2.31333e-06 0 0 0 0 0 0 0 0
230 22785000 0.705288 0.6995 0.000218855 0.000431532 -0.0122596 -0.0122193 0.708815 0.714528 -0.00704193 -0.0102308 -0.0075004 -0.00583424 -0.0531268 -0.0595012 -0.00359141 -0.00599992 -0.00301375 -0.00169031 -365.503 -365.517 -1.39895e-05 -1.47374e-05 -5.94762e-05 -5.89575e-05 -1.89535e-06 -2.13044e-05 -3.48997e-05 -2.92215e-05 2.09686e-05 3.14098e-05 -0.00105169 -0.00105253 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.80919e-05 0.000100142 7.0755e-06 6.45819e-06 7.12711e-06 6.52052e-06 9.69429e-05 9.34096e-05 0.0334795 0.0328594 0.0334791 0.0328588 0.0097283 0.00990735 0.0406205 0.0399889 0.0406206 0.0399893 0.0622913 0.0625218 6.71202e-11 5.77154e-11 6.71087e-11 5.77277e-11 6.2989e-10 5.6435e-10 3.55842e-06 3.55196e-06 3.55842e-06 3.55195e-06 2.19409e-06 2.31315e-06 0 0 0 0 0 0 0 0
231 22885000 0.705348 0.699619 0.000231472 0.00044503 -0.0122367 -0.0121956 0.708755 0.714412 -0.00809997 -0.011401 -0.00715915 -0.00545792 -0.0519585 -0.0582586 -0.00433617 -0.00707148 -0.00374258 -0.00224943 -365.502 -365.516 -1.39875e-05 -1.47295e-05 -5.94782e-05 -5.89652e-05 -1.79238e-06 -2.08874e-05 -3.50525e-05 -2.94002e-05 2.11164e-05 3.15909e-05 -0.00105266 -0.00105358 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.76447e-05 9.96906e-05 7.29746e-06 6.6559e-06 7.349e-06 6.71825e-06 9.65329e-05 9.3046e-05 0.0397924 0.0391344 0.0397919 0.0391336 0.00970318 0.0098841 0.045712 0.0449471 0.0457121 0.0449476 0.0622436 0.0624822 6.72159e-11 5.7812e-11 6.72054e-11 5.78245e-11 6.18977e-10 5.54834e-10 3.55843e-06 3.55196e-06 3.55842e-06 3.55196e-06 2.19397e-06 2.31306e-06 0 0 0 0 0 0 0 0
232 22985000 0.705405 0.699724 0.000219545 0.000428521 -0.0122238 -0.012183 0.708699 0.714309 -0.00777917 -0.0104551 -0.00644932 -0.00509388 -0.0501863 -0.0562932 -0.005285 -0.00757673 -0.00309559 -0.0018673 -365.498 -365.512 -1.39826e-05 -1.47098e-05 -5.94612e-05 -5.89619e-05 -1.65506e-06 -2.04574e-05 -4.334e-05 -3.56968e-05 2.88868e-05 4.33477e-05 -0.00105448 -0.0010555 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.7199e-05 9.92223e-05 7.09366e-06 6.49413e-06 7.14518e-06 6.55626e-06 9.61245e-05 9.26749e-05 0.0381117 0.0376946 0.0381113 0.0376937 0.00951675 0.00969341 0.0411466 0.0405946 0.0411466 0.0405949 0.0615503 0.0617832 6.52827e-11 5.64145e-11 6.52727e-11 5.64262e-11 6.08307e-10 5.45497e-10 3.26864e-06 3.25645e-06 3.26864e-06 3.25643e-06 2.19379e-06 2.31289e-06 0 0 0 0 0 0 0 0
233 23085000 0.705415 0.699759 0.000181529 0.000391739 -0.0121762 -0.012135 0.70869 0.714276 -0.00808459 -0.0108276 -0.00624929 -0.00486821 -0.0509233 -0.0569539 -0.0060758 -0.00863951 -0.00371035 -0.00234347 -365.497 -365.511 -1.39819e-05 -1.47048e-05 -5.94622e-05 -5.8967e-05 -1.61248e-06 -2.01885e-05 -4.35683e-05 -3.59477e-05 2.91051e-05 4.3594e-05 -0.00105557 -0.00105661 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.71841e-05 9.91985e-05 7.31301e-06 6.69024e-06 7.3643e-06 6.75224e-06 9.61296e-05 9.26805e-05 0.0446495 0.0442146 0.0446489 0.0442135 0.00958538 0.00976647 0.0466603 0.0460071 0.0466603 0.0460075 0.0624628 0.062712 6.53795e-11 5.6512e-11 6.53703e-11 5.65239e-11 6.00492e-10 5.38682e-10 3.26865e-06 3.25645e-06 3.26864e-06 3.25644e-06 2.19371e-06 2.31283e-06 0 0 0 0 0 0 0 0
234 23185000 0.705465 0.699855 0.000232204 0.000438046 -0.0121419 -0.0121017 0.708641 0.714182 -0.0115916 -0.0136595 -0.0059897 -0.00492399 -0.048861 -0.0546868 -0.0102456 -0.0123096 -0.00302201 -0.00190716 -365.492 -365.506 -1.40215e-05 -1.47257e-05 -5.94486e-05 -5.89642e-05 -1.52659e-06 -1.98182e-05 -5.18446e-05 -4.29741e-05 6.20277e-06 2.40628e-05 -0.0010576 -0.00105872 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.67426e-05 9.87354e-05 7.20274e-06 6.6069e-06 7.25395e-06 6.66867e-06 9.57267e-05 9.23144e-05 0.0413559 0.0411087 0.0413553 0.0411076 0.00940434 0.00958106 0.0418255 0.0413639 0.0418256 0.0413641 0.0617729 0.0620161 6.39587e-11 5.54835e-11 6.39501e-11 5.54948e-11 5.90244e-10 5.29709e-10 2.94348e-06 2.9246e-06 2.94348e-06 2.92458e-06 2.19353e-06 2.31267e-06 0 0 0 0 0 0 0 0
235 23285000 0.705493 0.699941 0.000166433 0.000373336 -0.0121557 -0.0121152 0.708612 0.714098 -0.0120803 -0.0141544 -0.00718765 -0.00611042 -0.0487263 -0.0544955 -0.011421 -0.0136928 -0.00368616 -0.00246213 -365.494 -365.507 -1.40191e-05 -1.47179e-05 -5.94509e-05 -5.89719e-05 -1.40342e-06 -1.94024e-05 -5.1972e-05 -4.31416e-05 6.32777e-06 2.42399e-05 -0.00105809 -0.00105935 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.63159e-05 9.83055e-05 7.42155e-06 6.80306e-06 7.47269e-06 6.8649e-06 9.53247e-05 9.1958e-05 0.0477903 0.0475384 0.0477897 0.047537 0.00938438 0.00956267 0.0477371 0.0472051 0.0477371 0.0472053 0.0617235 0.0619746 6.40548e-11 5.55803e-11 6.4047e-11 5.55918e-11 5.80238e-10 5.20973e-10 2.94348e-06 2.9246e-06 2.94348e-06 2.92458e-06 2.19342e-06 2.31259e-06 0 0 0 0 0 0 0 0
236 23385000 0.705558 0.700059 0.000230719 0.000434666 -0.0121133 -0.0120727 0.708549 0.713983 -0.0146988 -0.0161932 -0.00622682 -0.00542907 -0.0493573 -0.0549594 -0.0147584 -0.0165914 -0.00291151 -0.0019189 -365.496 -365.51 -1.40361e-05 -1.47218e-05 -5.94399e-05 -5.89706e-05 -1.29262e-06 -1.9011e-05 -6.0889e-05 -5.10498e-05 -1.11602e-05 9.58379e-06 -0.00105876 -0.00106019 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.58849e-05 9.78544e-05 7.39706e-06 6.7924e-06 7.44806e-06 6.854e-06 9.49308e-05 9.16001e-05 0.0430552 0.0429294 0.0430546 0.0429281 0.00921149 0.0093855 0.0425655 0.0421955 0.0425655 0.0421956 0.0610576 0.0613028 6.30702e-11 5.48708e-11 6.3063e-11 5.4882e-11 5.70451e-10 5.12398e-10 2.61345e-06 2.58802e-06 2.61345e-06 2.588e-06 2.19325e-06 2.31244e-06 0 0 0 0 0 0 0 0
237 23485000 0.705652 0.700206 0.00236412 0.00255251 -0.00994815 -0.00989051 0.708484 0.713867 -0.021495 -0.0229812 -0.00689338 -0.00618616 -0.0816976 -0.0872772 -0.0165025 -0.0184849 -0.00356254 -0.0024922 -365.498 -365.512 -1.40316e-05 -1.47123e-05 -5.94444e-05 -5.89803e-05 -1.051e-06 -1.84977e-05 -6.10876e-05 -5.1305e-05 -1.09657e-05 9.84323e-06 -0.00105933 -0.00106093 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.54718e-05 9.74381e-05 7.6107e-06 6.98444e-06 7.6604e-06 7.04296e-06 9.45469e-05 9.12616e-05 0.0491681 0.0490425 0.0491673 0.0490408 0.00919554 0.00937175 0.0488019 0.0483875 0.0488019 0.0483875 0.0610033 0.061256 6.31664e-11 5.49677e-11 6.316e-11 5.49791e-11 5.60886e-10 5.04042e-10 2.61345e-06 2.58802e-06 2.61345e-06 2.588e-06 2.19315e-06 2.31236e-06 0 0 0 0 0 0 0 0
238 23585000 0.705276 0.69987 0.00769787 0.00782847 -0.00231594 -0.00221733 0.708887 0.714224 -0.0294683 -0.0305039 -0.0033721 -0.00306107 -0.112659 -0.118017 -0.0147614 -0.0164002 -0.00135392 -0.000496471 -365.499 -365.512 -1.40002e-05 -1.46766e-05 -5.94291e-05 -5.89748e-05 -1.04112e-06 -1.82227e-05 -7.95938e-05 -6.87331e-05 7.06788e-06 3.05554e-05 -0.00106118 -0.00106278 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.51044e-05 9.70448e-05 7.64566e-06 7.02524e-06 7.68756e-06 7.06984e-06 9.41394e-05 9.08972e-05 0.0433899 0.0433367 0.0433888 0.0433349 0.00903167 0.00920448 0.0432808 0.0429954 0.0432808 0.0429954 0.0603608 0.0606078 6.25166e-11 5.45055e-11 6.25105e-11 5.45165e-11 5.51534e-10 4.95843e-10 2.30182e-06 2.27079e-06 2.30182e-06 2.27077e-06 2.193e-06 2.31224e-06 0 0 0 0 0 0 0 0
239 23685000 0.704658 0.699272 0.00754414 0.00763165 0.0039297 0.00402623 0.709496 0.714804 -0.0599138 -0.0608144 -0.0111757 -0.01131 -0.162192 -0.167502 -0.0191178 -0.0208552 -0.00199448 -0.00112659 -365.51 -365.523 -1.39988e-05 -1.46715e-05 -5.9431e-05 -5.89806e-05 -9.53141e-07 -1.79322e-05 -7.97356e-05 -6.89338e-05 7.20007e-06 3.07454e-05 -0.00106155 -0.00106324 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.51681e-05 9.70937e-05 7.86691e-06 7.2244e-06 7.89294e-06 7.25076e-06 9.40812e-05 9.08498e-05 0.04903 0.0489786 0.0490302 0.0489781 0.00910128 0.00927925 0.0497487 0.0494382 0.0497485 0.0494381 0.0612373 0.0615005 6.2614e-11 5.46034e-11 6.26081e-11 5.46142e-11 5.44686e-10 4.89859e-10 2.30182e-06 2.27079e-06 2.30182e-06 2.27077e-06 2.19293e-06 2.31218e-06 0 0 0 0 0 0 0 0
240 23785000 0.704381 0.699028 0.00470269 0.00481654 0.000972266 0.0010485 0.709806 0.715077 -0.078436 -0.0788057 -0.0199229 -0.0205319 -0.21522 -0.220348 -0.0161564 -0.0176057 -0.000278692 0.000435372 -365.519 -365.532 -1.395e-05 -1.46225e-05 -5.94242e-05 -5.89817e-05 -8.184e-07 -1.75591e-05 -0.00010232 -9.06779e-05 6.36216e-05 8.93739e-05 -0.00106315 -0.00106479 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.47911e-05 9.66937e-05 7.96508e-06 7.31699e-06 7.99626e-06 7.35126e-06 9.36573e-05 9.0465e-05 0.0426462 0.0426298 0.0426479 0.042631 0.00894496 0.0091201 0.043911 0.0436981 0.0439109 0.043698 0.0605981 0.0608555 6.2203e-11 5.43189e-11 6.21975e-11 5.43296e-11 5.35693e-10 4.81971e-10 2.02206e-06 1.98673e-06 2.02208e-06 1.98672e-06 2.19283e-06 2.3121e-06 0 0 0 0 0 0 0 0
241 23885000 0.704259 0.698959 0.00202476 0.00218729 -0.0051025 -0.00504586 0.709922 0.71514 -0.0951437 -0.0953607 -0.0288531 -0.0296747 -0.268852 -0.27395 -0.0249425 -0.0264198 -0.0027536 -0.00211029 -365.541 -365.554 -1.39468e-05 -1.46146e-05 -5.94277e-05 -5.89903e-05 -6.42405e-07 -1.71253e-05 -0.00010244 -9.08692e-05 6.37306e-05 8.95533e-05 -0.00106338 -0.00106517 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.43981e-05 9.62984e-05 8.19696e-06 7.52474e-06 8.2384e-06 7.57316e-06 9.32449e-05 9.00956e-05 0.0477505 0.0477358 0.0477531 0.0477378 0.00893583 0.00911361 0.0505108 0.0502861 0.0505107 0.0502859 0.0605463 0.0608114 6.22995e-11 5.44161e-11 6.22944e-11 5.44267e-11 5.26902e-10 4.74281e-10 2.02206e-06 1.98673e-06 2.02208e-06 1.98672e-06 2.19275e-06 2.31203e-06 0 0 0 0 0 0 0 0
242 23985000 0.704202 0.698942 0.000582864 0.000782645 -0.00982684 -0.0097795 0.709931 0.715111 -0.0939153 -0.0938745 -0.031636 -0.0324078 -0.321065 -0.325983 -0.028195 -0.0294321 -0.00584517 -0.00526498 -365.563 -365.576 -1.39168e-05 -1.45828e-05 -5.94387e-05 -5.90056e-05 -5.53778e-07 -1.6799e-05 -0.000108927 -9.74821e-05 8.60986e-05 0.000113009 -0.00106404 -0.00106574 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.39837e-05 9.58621e-05 8.3487e-06 7.66548e-06 8.39463e-06 7.72128e-06 9.28486e-05 8.97363e-05 0.0411545 0.0411526 0.041156 0.0411537 0.00879099 0.00896598 0.0444202 0.0442661 0.04442 0.0442659 0.0599295 0.060189 6.2051e-11 5.4253e-11 6.20466e-11 5.42639e-11 5.183e-10 4.66729e-10 1.77919e-06 1.74083e-06 1.77922e-06 1.74084e-06 2.19267e-06 2.31198e-06 0 0 0 0 0 0 0 0
243 24085000 0.704267 0.699051 0.00178118 0.00197491 -0.0087971 -0.00874025 0.709878 0.715016 -0.0952397 -0.0951832 -0.0314357 -0.0321878 -0.369437 -0.374326 -0.0376042 -0.0388358 -0.0089777 -0.00846605 -365.589 -365.601 -1.39132e-05 -1.45748e-05 -5.94442e-05 -5.90156e-05 -3.15166e-07 -1.63249e-05 -0.0001094 -9.79767e-05 8.65438e-05 0.000113516 -0.00106513 -0.00106691 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.35919e-05 9.54681e-05 8.57693e-06 7.87092e-06 8.62185e-06 7.92485e-06 9.24796e-05 8.94107e-05 0.0457186 0.0457175 0.0457197 0.0457181 0.00878639 0.00896387 0.0510612 0.0509036 0.051061 0.0509033 0.0598804 0.0601476 6.21476e-11 5.43503e-11 6.21439e-11 5.43613e-11 5.09892e-10 4.59369e-10 1.77919e-06 1.74083e-06 1.77922e-06 1.74084e-06 2.19261e-06 2.31193e-06 0 0 0 0 0 0 0 0
244 24185000 0.704292 0.699098 0.00290646 0.00308515 -0.0064028 -0.00633641 0.709876 0.714991 -0.0949421 -0.0947257 -0.0310701 -0.031809 -0.416458 -0.421157 -0.0386713 -0.039714 -0.0107252 -0.0102584 -365.613 -365.626 -1.38805e-05 -1.45414e-05 -5.94539e-05 -5.90295e-05 -1.73918e-07 -1.59768e-05 -0.000119792 -0.000108405 0.000112434 0.000140241 -0.00106546 -0.00106691 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.31987e-05 9.50511e-05 8.74135e-06 8.02179e-06 8.78348e-06 8.07134e-06 9.2118e-05 8.90889e-05 0.0392087 0.0392089 0.0392091 0.039209 0.00864917 0.00882385 0.0447944 0.044686 0.0447941 0.0446857 0.0592851 0.0595469 6.20067e-11 5.4268e-11 6.20035e-11 5.42791e-11 5.01665e-10 4.52141e-10 1.57263e-06 1.53234e-06 1.57266e-06 1.53235e-06 2.19255e-06 2.31188e-06 0 0 0 0 0 0 0 0
245 24285000 0.704215 0.699074 0.00342361 0.00359782 -0.0054877 -0.00541728 0.709957 0.71502 -0.104895 -0.104606 -0.0348194 -0.0356583 -0.471759 -0.476364 -0.0486415 -0.0496577 -0.0140178 -0.013623 -365.655 -365.667 -1.38814e-05 -1.45376e-05 -5.94539e-05 -5.90343e-05 -2.00901e-07 -1.57524e-05 -0.000119947 -0.000108575 0.00011256 0.000140422 -0.00106578 -0.00106724 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.28181e-05 9.46682e-05 8.97569e-06 8.23262e-06 9.01644e-06 8.28022e-06 9.1752e-05 8.8766e-05 0.0432633 0.0432636 0.0432633 0.00864868 0.00882597 0.051403 0.0512959 0.0514027 0.0512954 0.0592388 0.0595084 6.21034e-11 5.43654e-11 6.21006e-11 5.43764e-11 4.9362e-10 4.45093e-10 1.57262e-06 1.53233e-06 1.57266e-06 1.53235e-06 2.19251e-06 2.31185e-06 0 0 0 0 0 0 0 0
246 24385000 0.704178 0.699045 0.00354592 0.00372571 -0.00574822 -0.00567662 0.709992 0.715046 -0.112784 -0.112379 -0.0457663 -0.046625 -0.523364 -0.527811 -0.0555005 -0.0563597 -0.0278853 -0.0275081 -365.697 -365.709 -1.38631e-05 -1.45184e-05 -5.94874e-05 -5.90675e-05 -1.50492e-07 -1.55427e-05 -9.10184e-05 -7.9782e-05 0.000118843 0.000146556 -0.00106537 -0.00106652 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.27948e-05 9.46151e-05 9.16781e-06 8.40761e-06 9.20832e-06 8.45513e-06 9.17454e-05 8.87606e-05 0.0370314 0.0370281 0.0370315 0.0370279 0.00859489 0.00877193 0.045035 0.044961 0.0450347 0.0449606 0.0595374 0.0598104 6.20335e-11 5.43366e-11 6.20309e-11 5.43476e-11 4.87719e-10 4.39903e-10 1.39906e-06 1.35768e-06 1.3991e-06 1.3577e-06 2.19246e-06 2.3118e-06 0 0 0 0 0 0 0 0
247 24485000 0.704225 0.699139 0.00437618 0.00453004 -0.00177671 -0.00169905 0.709961 0.714969 -0.125435 -0.124954 -0.0505768 -0.0515638 -0.574587 -0.578957 -0.0673312 -0.0681457 -0.0326426 -0.0323492 -365.745 -365.757 -1.38635e-05 -1.45143e-05 -5.94892e-05 -5.90738e-05 -1.17198e-07 -1.52745e-05 -9.13699e-05 -8.01401e-05 0.000119139 0.000146902 -0.00106596 -0.00106708 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.24149e-05 9.42335e-05 9.40329e-06 8.6194e-06 9.4377e-06 8.65867e-06 9.13998e-05 8.8458e-05 0.0406226 0.0406184 0.0406227 0.0406183 0.00859672 0.00877624 0.0515556 0.0514852 0.0515552 0.0514846 0.0594931 0.059774 6.21303e-11 5.4434e-11 6.2128e-11 5.4445e-11 4.79975e-10 4.33114e-10 1.39906e-06 1.35768e-06 1.3991e-06 1.3577e-06 2.19243e-06 2.31179e-06 0 0 0 0 0 0 0 0
248 24585000 0.704352 0.699291 0.00492857 0.00505932 0.00205839 0.00214061 0.709831 0.714816 -0.137214 -0.136587 -0.0631403 -0.0642307 -0.623782 -0.62804 -0.0705142 -0.0712117 -0.042885 -0.0425966 -365.796 -365.807 -1.38385e-05 -1.44883e-05 -5.95122e-05 -5.90992e-05 1.28688e-07 -1.48394e-05 -8.07877e-05 -6.96195e-05 0.000145126 0.00017291 -0.00106369 -0.00106441 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.20237e-05 9.38164e-05 9.60879e-06 8.80603e-06 9.63515e-06 8.83546e-06 9.10542e-05 8.81544e-05 0.0347777 0.0347694 0.0347783 0.0347699 0.00847143 0.00864816 0.0451523 0.0451034 0.045152 0.0451029 0.0589214 0.059197 6.21057e-11 5.44395e-11 6.21034e-11 5.44502e-11 4.72393e-10 4.26445e-10 1.25412e-06 1.21224e-06 1.25415e-06 1.21226e-06 2.19235e-06 2.31169e-06 0 0 0 0 0 0 0 0
249 24685000 0.704411 0.699396 0.00497559 0.00510275 0.00312904 0.0032117 0.709768 0.714709 -0.161429 -0.160627 -0.0765661 -0.0779268 -0.703894 -0.708157 -0.0853986 -0.0860241 -0.0498537 -0.0496789 -365.858 -365.87 -1.38349e-05 -1.44809e-05 -5.95169e-05 -5.91084e-05 3.44896e-07 -1.44051e-05 -8.09306e-05 -6.97751e-05 0.0001453 0.000173168 -0.00106379 -0.0010646 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.16512e-05 9.34419e-05 9.85533e-06 9.02767e-06 9.87896e-06 9.05402e-06 9.07014e-05 8.78436e-05 0.037952 0.037943 0.0379539 0.0379447 0.00848508 0.00866525 0.0515447 0.0514999 0.0515443 0.0514994 0.0588808 0.0591642 6.22027e-11 5.45371e-11 6.22007e-11 5.45477e-11 4.64977e-10 4.19938e-10 1.25412e-06 1.21224e-06 1.25415e-06 1.21226e-06 2.19235e-06 2.31169e-06 0 0 0 0 0 0 0 0
250 24785000 0.704354 0.699376 0.00472834 0.00486928 0.00192048 0.00200132 0.70983 0.714734 -0.176428 -0.175522 -0.0876361 -0.0890703 -0.791218 -0.7953 -0.0922133 -0.0927619 -0.0599205 -0.059715 -365.927 -365.938 -1.38238e-05 -1.44677e-05 -5.95551e-05 -5.91464e-05 3.08515e-07 -1.42287e-05 -9.54201e-05 -8.42488e-05 0.000172291 0.000200296 -0.00106212 -0.00106248 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.12644e-05 9.30272e-05 1.00767e-05 9.22768e-06 1.01024e-05 9.25687e-06 9.03455e-05 8.75297e-05 0.0325373 0.0325256 0.0325397 0.0325279 0.00837955 0.00855828 0.0451606 0.0451293 0.0451602 0.0451288 0.0583248 0.058603 6.22098e-11 5.45666e-11 6.22076e-11 5.45769e-11 4.5771e-10 4.13541e-10 1.13354e-06 1.09156e-06 1.13357e-06 1.09157e-06 2.19221e-06 2.31152e-06 0 0 0 0 0 0 0 0
251 24885000 0.704325 0.699394 0.00637177 0.00650584 0.00345234 0.00354459 0.709841 0.714698 -0.197512 -0.196469 -0.0986156 -0.100263 -0.814518 -0.818538 -0.110852 -0.111303 -0.0691991 -0.0691374 -366.004 -366.015 -1.3824e-05 -1.44639e-05 -5.95561e-05 -5.91518e-05 3.25785e-07 -1.39893e-05 -9.55858e-05 -8.43961e-05 0.000172426 0.000200504 -0.00106222 -0.00106253 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.08969e-05 9.26565e-05 1.03297e-05 9.45576e-06 1.03526e-05 9.48061e-06 9.00015e-05 8.72277e-05 0.0353611 0.0353481 0.0353645 0.0353514 0.008377 0.00855703 0.051398 0.0513706 0.0513976 0.05137 0.0582892 0.0585753 6.2307e-11 5.46643e-11 6.2305e-11 5.46744e-11 4.50606e-10 4.07303e-10 1.13354e-06 1.09156e-06 1.13358e-06 1.09158e-06 2.19221e-06 2.31153e-06 0 0 0 0 0 0 0 0
252 24985000 0.704265 0.699337 0.00829955 0.00842529 0.00541568 0.0055207 0.709868 0.714721 -0.210796 -0.209721 -0.103526 -0.10528 -0.869701 -0.87353 -0.112441 -0.112852 -0.0753107 -0.0751988 -366.08 -366.091 -1.38202e-05 -1.44584e-05 -5.95906e-05 -5.91849e-05 2.45314e-07 -1.39293e-05 -0.000125078 -0.000113611 0.000223834 0.000252042 -0.00105827 -0.00105787 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.08587e-05 9.25841e-05 1.05635e-05 9.66796e-06 1.05827e-05 9.68721e-06 8.99976e-05 8.72312e-05 0.0303999 0.0303854 0.0304044 0.0303898 0.00833832 0.0085182 0.0450746 0.0450553 0.0450742 0.0450549 0.0586029 0.058893 6.23362e-11 5.47108e-11 6.23341e-11 5.47206e-11 4.45393e-10 4.02709e-10 1.0331e-06 9.91252e-07 1.03313e-06 9.91265e-07 2.19201e-06 2.31128e-06 0 0 0 0 0 0 0 0
253 25085000 0.70425 0.699367 0.00869337 0.00882681 0.00492078 0.00502793 0.709882 0.714691 -0.240444 -0.23926 -0.114113 -0.116177 -0.920426 -0.924199 -0.135004 -0.135303 -0.086163 -0.0862311 -366.164 -366.175 -1.38209e-05 -1.44552e-05 -5.95922e-05 -5.91905e-05 2.62543e-07 -1.36995e-05 -0.00012536 -0.000113854 0.000224053 0.000252329 -0.00105827 -0.00105775 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.04937e-05 9.22164e-05 1.08219e-05 9.9001e-06 1.08422e-05 9.92053e-06 8.96542e-05 8.69289e-05 0.0329053 0.0328903 0.0329124 0.0328972 0.00834866 0.00853081 0.0511378 0.0511218 0.0511375 0.0511215 0.0585702 0.0588685 6.24336e-11 5.48086e-11 6.24316e-11 5.48182e-11 4.38547e-10 3.96694e-10 1.0331e-06 9.91252e-07 1.03313e-06 9.9127e-07 2.19202e-06 2.31129e-06 0 0 0 0 0 0 0 0
254 25185000 0.704284 0.699429 0.00821891 0.008368 0.00339467 0.00349814 0.709863 0.714645 -0.265043 -0.263933 -0.129788 -0.131857 -0.969985 -0.97365 -0.156112 -0.156399 -0.114098 -0.11409 -366.249 -366.259 -1.3807e-05 -1.44399e-05 -5.9633e-05 -5.92311e-05 3.86327e-07 -1.33937e-05 -0.000102361 -9.14905e-05 0.000226867 0.000254499 -0.00105479 -0.00105367 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 9.01114e-05 9.18036e-05 1.10641e-05 1.01181e-05 1.10868e-05 1.01419e-05 8.9307e-05 8.66255e-05 0.0283814 0.0283663 0.0283889 0.0283737 0.0082397 0.00841889 0.044908 0.0448968 0.0449077 0.0448964 0.0580357 0.0583286 6.24786e-11 5.48671e-11 6.24764e-11 5.48763e-11 4.31831e-10 3.90774e-10 9.49343e-07 9.0776e-07 9.49362e-07 9.07772e-07 2.19174e-06 2.31093e-06 0 0 0 0 0 0 0 0
255 25285000 0.704355 0.69954 0.0100211 0.0101306 0.0098549 0.00996991 0.709709 0.714452 -0.293015 -0.291838 -0.138988 -0.141314 -1.02487 -1.02852 -0.183915 -0.18409 -0.127463 -0.127661 -366.342 -366.353 -1.38062e-05 -1.44355e-05 -5.96369e-05 -5.92387e-05 5.02759e-07 -1.30803e-05 -0.000102663 -9.17445e-05 0.000227147 0.000254851 -0.00105451 -0.00105325 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 8.97478e-05 9.14363e-05 1.13322e-05 1.03604e-05 1.13401e-05 1.03659e-05 8.89851e-05 8.63463e-05 0.0306163 0.0306012 0.0306264 0.0306111 0.00825419 0.00843574 0.0507872 0.0507785 0.0507872 0.0507784 0.0580076 0.0583085 6.2576e-11 5.4965e-11 6.25739e-11 5.4974e-11 4.25269e-10 3.85004e-10 9.49341e-07 9.07759e-07 9.49366e-07 9.07777e-07 2.19174e-06 2.31093e-06 0 0 0 0 0 0 0 0
256 25385000 0.704437 0.699644 0.0115014 0.0115712 0.0166403 0.0167642 0.709478 0.714201 -0.320791 -0.319554 -0.159332 -0.161801 -1.07341 -1.07696 -0.195955 -0.196129 -0.148198 -0.148305 -366.438 -366.448 -1.37992e-05 -1.44259e-05 -5.96686e-05 -5.92708e-05 6.29559e-07 -1.27873e-05 -0.000101771 -9.10425e-05 0.000265565 0.000292879 -0.00104819 -0.00104613 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 8.93526e-05 9.10086e-05 1.1597e-05 1.06011e-05 1.15843e-05 1.05829e-05 8.86562e-05 8.60641e-05 0.0265035 0.0264894 0.0265157 0.0265013 0.00815004 0.00832863 0.0446747 0.0446686 0.0446746 0.0446684 0.0574913 0.0577868 6.26339e-11 5.50332e-11 6.26317e-11 5.5042e-11 4.18827e-10 3.79321e-10 8.79356e-07 8.38099e-07 8.79367e-07 8.38108e-07 2.19136e-06 2.31046e-06 0 0 0 0 0 0 0 0
257 25485000 0.704494 0.699745 0.0117962 0.0118623 0.0181509 0.0182757 0.70938 0.71406 -0.368761 -0.367289 -0.182756 -0.185717 -1.12709 -1.13068 -0.230422 -0.230464 -0.165273 -0.165636 -366.547 -366.557 -1.37961e-05 -1.44193e-05 -5.96718e-05 -5.9278e-05 7.93083e-07 -1.24306e-05 -0.000101732 -9.09493e-05 0.000265617 0.000293003 -0.00104803 -0.00104596 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 8.89979e-05 9.06501e-05 1.18699e-05 1.08465e-05 1.18526e-05 1.0823e-05 8.83278e-05 8.57766e-05 0.0285074 0.0284938 0.0285264 0.0285122 0.0081658 0.00834658 0.0503653 0.0503609 0.0503659 0.0503615 0.0574677 0.0577713 6.27311e-11 5.51309e-11 6.27293e-11 5.51398e-11 4.12535e-10 3.73783e-10 8.79354e-07 8.38098e-07 8.79373e-07 8.38114e-07 2.19135e-06 2.31044e-06 0 0 0 0 0 0 0 0
258 25585000 0.704609 0.699894 0.0113228 0.0114096 0.0161772 0.0162977 0.709321 0.713969 -0.408792 -0.407274 -0.214739 -0.217806 -1.18191 -1.18544 -0.259077 -0.259143 -0.20478 -0.205022 -366.658 -366.668 -1.37832e-05 -1.44049e-05 -5.97167e-05 -5.93218e-05 9.17692e-07 -1.21287e-05 -8.26061e-05 -7.24207e-05 0.000279767 0.000306482 -0.00104447 -0.00104185 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 8.86203e-05 9.02405e-05 1.21247e-05 1.10747e-05 1.21142e-05 1.10591e-05 8.79966e-05 8.54896e-05 0.0247744 0.0247626 0.0247951 0.0247826 0.00806858 0.00824652 0.0443866 0.0443836 0.044387 0.0443839 0.0569687 0.057267 6.27997e-11 5.52074e-11 6.27978e-11 5.52159e-11 4.06347e-10 3.6832e-10 8.20754e-07 7.79829e-07 8.20759e-07 7.79837e-07 2.19085e-06 2.30982e-06 0 0 0 0 0 0 0 0
259 25685000 0.704566 0.699874 0.0147117 0.0147628 0.0224799 0.0226218 0.70913 0.713755 -0.456173 -0.454489 -0.23504 -0.238563 -1.23505 -1.2386 -0.302218 -0.302127 -0.22723 -0.227787 -366.779 -366.789 -1.37818e-05 -1.44009e-05 -5.97178e-05 -5.93258e-05 9.84476e-07 -1.1918e-05 -8.25498e-05 -7.23043e-05 0.000279768 0.00030654 -0.00104445 -0.0010418 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 8.85809e-05 9.01916e-05 1.24211e-05 1.13446e-05 1.23918e-05 1.13059e-05 8.79883e-05 8.549e-05 0.0265808 0.0265699 0.0266092 0.0265973 0.00815354 0.00833599 0.0498883 0.0498864 0.04989 0.049888 0.0577728 0.0580885 6.28977e-11 5.53057e-11 6.28962e-11 5.53143e-11 4.01831e-10 3.64347e-10 8.20754e-07 7.7983e-07 8.20766e-07 7.79845e-07 2.19082e-06 2.30978e-06 0 0 0 0 0 0 0 0
260 25785000 0.704512 0.699843 0.0175736 0.0175878 0.0293275 0.0294854 0.708868 0.713471 -0.498519 -0.496777 -0.26063 -0.264407 -1.282 -1.2855 -0.318031 -0.317987 -0.255635 -0.256044 -366.898 -366.908 -1.37845e-05 -1.43999e-05 -5.97596e-05 -5.9366e-05 1.15896e-06 -1.15881e-05 -9.57638e-05 -8.54993e-05 0.000341236 0.000367592 -0.00103806 -0.00103462 0.208824 0.2098 0.00201103 0.00202043 0.434169 0.432662 0 0 0 0 0 8.81767e-05 8.97509e-05 1.27209e-05 1.16186e-05 1.26667e-05 1.15513e-05 8.76392e-05 8.51905e-05 0.0231949 0.0231861 0.0232286 0.0232184 0.00805618 0.00823551 0.0440544 0.0440531 0.0440556 0.0440543 0.0572762 0.0575864 6.29753e-11 5.53891e-11 6.29738e-11 5.53974e-11 3.95852e-10 3.59064e-10 7.71612e-07 7.30989e-07 7.71608e-07 7.30995e-07 2.19019e-06 2.30901e-06 0 0 0 0 0 0 0 0
261 25885000 0.711586 0.711372 0.018271 0.0184771 0.0298283 0.029872 0.701728 0.701938 -0.568851 -0.567156 -0.28921 -0.292964 -1.33231 -1.33567 -0.371397 -0.371179 -0.283154 -0.283941 -367.027 -367.037 -1.37848e-05 -1.44004e-05 -5.976e-05 -5.93665e-05 1.15827e-06 -1.15913e-05 -9.58354e-05 -8.56003e-05 0.000341278 0.000367643 -0.00103786 -0.00103428 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000907149 0.000909679 1.43032e-05 1.32027e-05 1.33082e-05 1.22049e-05 0.000934441 0.000933193 0.0250694 0.025042 0.0251275 0.0250987 0.00796736 0.00813145 0.0493685 0.0493679 0.0493718 0.0493712 0.0572455 0.057565 6.30751e-11 5.54889e-11 6.30735e-11 5.54972e-11 3.95951e-10 3.59155e-10 7.71612e-07 7.3099e-07 7.71615e-07 7.31003e-07 2.19013e-06 2.30892e-06 0 0 0 0 0 0 0 0
262 25985000 0.710523 0.710277 0.0172662 0.017479 0.02657 0.0266134 0.70296 0.703201 -0.622475 -0.62108 -0.327381 -0.330616 -1.38778 -1.39095 -0.412239 -0.412094 -0.340748 -0.341345 -367.16 -367.169 -1.37858e-05 -1.44016e-05 -5.98119e-05 -5.94123e-05 1.15901e-06 -1.15982e-05 -7.44503e-05 -6.47036e-05 0.000371609 0.000397017 -0.00103849 -0.00103469 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000695764 0.000698319 1.37391e-05 1.26361e-05 1.3177e-05 1.20718e-05 0.000715536 0.000715072 0.0223857 0.0223281 0.0224761 0.0224171 0.00863776 0.00882953 0.0436855 0.0436852 0.0436881 0.0436877 0.0567229 0.0570356 6.31376e-11 5.55612e-11 6.31349e-11 5.55687e-11 3.96011e-10 3.59198e-10 7.27314e-07 6.8724e-07 7.27302e-07 6.87244e-07 2.19e-06 2.30876e-06 0 0 0 0 0 0 0 0
263 26085000 0.705234 0.704954 0.0218323 0.0220478 0.0359739 0.0360173 0.707725 0.707995 -0.687779 -0.686491 -0.353683 -0.356786 -1.41477 -1.41782 -0.477649 -0.47737 -0.374785 -0.375697 -367.299 -367.309 -1.37863e-05 -1.44021e-05 -5.98124e-05 -5.94129e-05 1.15201e-06 -1.16071e-05 -7.46285e-05 -6.49063e-05 0.000371604 0.000397021 -0.00103838 -0.00103446 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000570796 0.000573289 1.42558e-05 1.31552e-05 1.33593e-05 1.22529e-05 0.000576535 0.000576512 0.0244946 0.0243872 0.0246392 0.0245298 0.0103064 0.0105801 0.0488253 0.0488248 0.0488314 0.0488309 0.0566417 0.0569572 6.32374e-11 5.5661e-11 6.32345e-11 5.56685e-11 3.96108e-10 3.59286e-10 7.27315e-07 6.8724e-07 7.27309e-07 6.87252e-07 2.18998e-06 2.30873e-06 0 0 0 0 0 0 0 0
264 26185000 0.703039 0.702729 0.0244735 0.0246929 0.046011 0.0460582 0.709239 0.709535 -0.735817 -0.734832 -0.386159 -0.38889 -1.38352 -1.38633 -0.500518 -0.500328 -0.416882 -0.417595 -367.432 -367.441 -1.38675e-05 -1.44726e-05 -5.99125e-05 -5.94993e-05 1.14595e-06 -1.16258e-05 -9.617e-05 -8.53923e-05 0.000463239 0.000487555 -0.00105279 -0.00104957 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000483696 0.00048611 1.48163e-05 1.37204e-05 1.34406e-05 1.2336e-05 0.000484658 0.000484898 0.0222155 0.0220692 0.0224024 0.0222533 0.0125395 0.0129263 0.0432986 0.043298 0.0433034 0.0433028 0.0561515 0.0564588 6.32301e-11 5.56813e-11 6.32256e-11 5.56877e-11 3.96175e-10 3.5934e-10 6.8398e-07 6.44967e-07 6.83956e-07 6.44964e-07 2.18596e-06 2.30435e-06 0 0 0 0 0 0 0 0
265 26285000 0.702681 0.702337 0.0254755 0.0257011 0.0486901 0.0487366 0.70938 0.709709 -0.828113 -0.82724 -0.427116 -0.429743 -1.37233 -1.37504 -0.578652 -0.57837 -0.457549 -0.458528 -367.569 -367.578 -1.38678e-05 -1.4473e-05 -5.9913e-05 -5.94998e-05 1.14135e-06 -1.16317e-05 -9.63354e-05 -8.55705e-05 0.000463216 0.000487536 -0.00105287 -0.00104964 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000433844 0.000436231 1.48857e-05 1.37884e-05 1.34961e-05 1.23897e-05 0.000435206 0.00043557 0.0244964 0.0242789 0.0247909 0.0245686 0.0158877 0.016447 0.0483018 0.0482978 0.048314 0.0483099 0.0569896 0.0573112 6.333e-11 5.57812e-11 6.33254e-11 5.57875e-11 3.9627e-10 3.59429e-10 6.83981e-07 6.44969e-07 6.83965e-07 6.44973e-07 2.18595e-06 2.30435e-06 0 0 0 0 0 0 0 0
266 26385000 0.703562 0.703193 0.0245822 0.0248158 0.0451126 0.0451583 0.708775 0.709129 -0.908211 -0.907601 -0.485465 -0.487734 -1.37655 -1.37908 -0.646189 -0.645986 -0.545464 -0.546272 -367.703 -367.712 -1.38428e-05 -1.44513e-05 -5.9997e-05 -5.9575e-05 1.12605e-06 -1.16501e-05 -6.22011e-05 -5.14446e-05 0.000481504 0.000505075 -0.00105075 -0.00104768 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000381153 0.000383455 1.44231e-05 1.333e-05 1.34135e-05 1.23117e-05 0.000383811 0.000384288 0.022479 0.0222244 0.0228075 0.0225471 0.0194804 0.0202167 0.0429244 0.0429209 0.0429338 0.0429302 0.0566643 0.056983 6.32322e-11 5.57336e-11 6.32256e-11 5.57386e-11 3.96342e-10 3.5949e-10 6.41693e-07 6.04154e-07 6.41638e-07 6.04117e-07 2.17162e-06 2.28865e-06 0 0 0 0 0 0 0 0
267 26485000 0.703678 0.703276 0.0320856 0.0323191 0.0599683 0.0600168 0.707256 0.707641 -1.00147 -1.00101 -0.523632 -0.525768 -1.38084 -1.38323 -0.741433 -0.741178 -0.595941 -0.596966 -367.839 -367.847 -1.38432e-05 -1.44517e-05 -5.99981e-05 -5.95759e-05 1.11943e-06 -1.16594e-05 -6.2502e-05 -5.1751e-05 0.00048145 0.000505021 -0.00105143 -0.00104851 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000339942 0.000342197 1.53167e-05 1.42279e-05 1.37349e-05 1.26332e-05 0.000344254 0.000344825 0.0248948 0.024551 0.0253234 0.0249707 0.0243103 0.0252979 0.0478338 0.0478209 0.047856 0.0478429 0.0570599 0.0573993 6.33321e-11 5.58335e-11 6.33253e-11 5.58383e-11 3.9643e-10 3.59571e-10 6.41682e-07 6.04144e-07 6.41646e-07 6.04125e-07 2.17124e-06 2.28827e-06 0 0 0 0 0 0 0 0
268 26585000 0.703185 0.702756 0.0387911 0.0390253 0.0768185 0.0768788 0.70578 0.706188 -1.08983 -1.08982 -0.575297 -0.577346 -1.36882 -1.37088 -0.783005 -0.782884 -0.661224 -0.662087 -367.972 -367.98 -1.40169e-05 -1.46027e-05 -6.01878e-05 -5.97408e-05 1.08681e-06 -1.16905e-05 -8.92433e-05 -7.63399e-05 0.000589056 0.000610944 -0.00106238 -0.00106048 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000305635 0.000307775 1.63415e-05 1.52722e-05 1.39809e-05 1.28937e-05 0.000311367 0.000311962 0.0229928 0.0226271 0.0234868 0.0231107 0.028594 0.0297649 0.0425902 0.0425795 0.0426073 0.0425964 0.0570606 0.0574082 6.31379e-11 5.5713e-11 6.31294e-11 5.57168e-11 3.96503e-10 3.59638e-10 6.00833e-07 5.65049e-07 6.00707e-07 5.64934e-07 2.14139e-06 2.25553e-06 0 0 0 0 0 0 0 0
269 26685000 0.704121 0.703662 0.0402449 0.0404874 0.0802667 0.0803254 0.70438 0.704818 -1.23522 -1.23537 -0.636065 -0.638045 -1.35857 -1.36045 -0.899233 -0.899122 -0.721747 -0.722806 -368.108 -368.115 -1.4017e-05 -1.4603e-05 -6.01879e-05 -5.97408e-05 1.08844e-06 -1.16904e-05 -8.91943e-05 -7.62908e-05 0.000589085 0.00061097 -0.00106291 -0.00106135 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000279287 0.000281393 1.64107e-05 1.53379e-05 1.40575e-05 1.29677e-05 0.000285962 0.00028661 0.0255326 0.0250697 0.026223 0.0257433 0.034578 0.0360489 0.0474462 0.0474182 0.0474854 0.0474568 0.0580677 0.058462 6.32378e-11 5.58129e-11 6.32289e-11 5.58166e-11 3.96584e-10 3.59715e-10 6.00806e-07 5.65024e-07 6.00712e-07 5.64939e-07 2.13982e-06 2.25388e-06 0 0 0 0 0 0 0 0
270 26785000 0.705006 0.704523 0.0383351 0.0385924 0.0744649 0.0745221 0.704239 0.704702 -1.35473 -1.35521 -0.721066 -0.722795 -1.36141 -1.363 -0.994692 -0.994658 -0.853316 -0.85421 -368.245 -368.253 -1.40632e-05 -1.46432e-05 -6.02533e-05 -5.98e-05 1.03732e-06 -1.17366e-05 -3.33236e-05 -2.01145e-05 0.000633361 0.00065395 -0.00105995 -0.00105909 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000256397 0.000258377 1.56409e-05 1.45797e-05 1.38534e-05 1.27746e-05 0.000263335 0.00026396 0.0236406 0.0231763 0.0243639 0.0238833 0.0388231 0.0404184 0.042315 0.0422924 0.0423448 0.0423219 0.0584574 0.0588681 6.29541e-11 5.56242e-11 6.29444e-11 5.56276e-11 3.96654e-10 3.59783e-10 5.61993e-07 5.28102e-07 5.61721e-07 5.27832e-07 2.09164e-06 2.20114e-06 0 0 0 0 0 0 0 0
271 26885000 0.704552 0.704034 0.0468241 0.0470774 0.0950203 0.0950807 0.701701 0.702197 -1.49818 -1.49888 -0.77815 -0.77977 -1.37409 -1.37548 -1.13703 -1.13706 -0.928127 -0.92918 -368.383 -368.39 -1.40632e-05 -1.46433e-05 -6.02529e-05 -5.97997e-05 1.03939e-06 -1.17342e-05 -3.32425e-05 -2.00219e-05 0.000633401 0.000653988 -0.00105921 -0.00105879 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000237204 0.00023914 1.70132e-05 1.59582e-05 1.42843e-05 1.32093e-05 0.000244717 0.000245366 0.0262473 0.0256792 0.0271547 0.0265632 0.0456756 0.0475916 0.0471534 0.0471043 0.0472172 0.0471669 0.0602635 0.0607514 6.30541e-11 5.57242e-11 6.30437e-11 5.57271e-11 3.96727e-10 3.59854e-10 5.6194e-07 5.28052e-07 5.6172e-07 5.27831e-07 2.08786e-06 2.19712e-06 0 0 0 0 0 0 0 0
272 26985000 0.703818 0.703264 0.0540117 0.0542658 0.117597 0.117679 0.698494 0.699019 -1.61883 -1.62042 -0.853443 -0.855321 -1.34827 -1.34898 -1.195 -1.1953 -1.02627 -1.02723 -368.517 -368.523 -1.45195e-05 -1.50422e-05 -6.05178e-05 -6.00287e-05 9.95114e-07 -1.17638e-05 -6.00733e-05 -4.36352e-05 0.000804013 0.000821175 -0.00109256 -0.0010946 0.216913 0.217062 0.00208893 0.00209036 0.427651 0.427576 0 0 0 0 0 0.000221978 0.000223761 1.85392e-05 1.75183e-05 1.45677e-05 1.35215e-05 0.00023025 0.000230813 0.0242939 0.0237527 0.0252802 0.0247176 0.0490556 0.0509774 0.042109 0.0420705 0.0421581 0.0421188 0.0619052 0.0624203 6.26971e-11 5.54789e-11 6.26885e-11 5.54834e-11 3.96799e-10 3.59928e-10 5.25798e-07 4.93797e-07 5.25241e-07 4.93234e-07 2.02355e-06 2.12702e-06 0 0 0 0 0 0 0 0
273 27085000 0.704456 0.703857 0.0552057 0.0554671 0.122529 0.122609 0.696908 0.697478 -1.82308 -1.82488 -0.943109 -0.945037 -1.3201 -1.32048 -1.36704 -1.36751 -1.11607 -1.11723 -368.647 -368.654 -1.45193e-05 -1.5042e-05 -6.05183e-05 -6.0029e-05 9.93428e-07 -1.17677e-05 -6.01135e-05 -4.36756e-05 0.00080389 0.000821028 -0.001096 -0.00109867 0.213385 0.213575 0.00204254 0.00204508 0.429843 0.429749 -0.00188059 -0.00177554 0.0039054 0.00386709 0.00110385 0.00110396 0 0 0.000221138 0.000222923 1.91069e-05 1.80823e-05 1.4754e-05 1.3705e-05 0.000230519 0.000231036 0.0269874 0.0263494 0.0284045 0.0277353 0.0560294 0.0582424 0.0469582 0.0468838 0.0470675 0.0469911 0.0646437 0.0652645 6.27971e-11 5.55789e-11 6.27884e-11 5.55833e-11 3.96898e-10 3.60022e-10 5.25807e-07 4.93806e-07 5.25243e-07 4.93235e-07 2.01734e-06 2.12043e-06 0.00139139 0.00139134 1.86108e-05 1.86354e-05 0.0013943 0.00139453 0.000554898 0.000554546 0.00139003 0.00138999 0.00138818 0.0013885 0 0
274 27185000 0.706572 0.70594 0.0520049 0.052278 0.112534 0.112613 0.696698 0.697305 -2.02291 -2.02469 -1.00349 -1.00574 -1.3014 -1.3015 -1.5633 -1.56378 -1.19227 -1.19359 -368.774 -368.78 -1.44765e-05 -1.50082e-05 -6.07952e-05 -6.02729e-05 9.83893e-07 -1.17785e-05 -0.000120135 -0.0001023 0.000794429 0.000812759 -0.00109783 -0.00110103 0.213731 0.213923 0.00204324 0.00204595 0.429892 0.429798 -0.00223744 -0.00211267 0.00358796 0.00354791 0.00122433 0.00122585 0 0 0.000218665 0.000220323 1.79429e-05 1.69337e-05 1.44349e-05 1.33963e-05 0.000228508 0.000228889 0.0269278 0.0263141 0.0285171 0.0278809 0.057524 0.0595845 0.0495089 0.0494345 0.0496193 0.0495439 0.0654425 0.0660518 6.24183e-11 5.53151e-11 6.24175e-11 5.5326e-11 3.96994e-10 3.60115e-10 5.0359e-07 4.73097e-07 5.02376e-07 4.71882e-07 1.93899e-06 2.03562e-06 0.00132629 0.00132623 1.84754e-05 1.84998e-05 0.0013294 0.00132965 0.000344982 0.000344557 0.00132461 0.00132457 0.00132249 0.00132284 0 0
275 27285000 0.708082 0.707411 0.0463619 0.0466593 0.0974785 0.0975493 0.697832 0.698482 -2.18556 -2.18758 -1.0714 -1.07362 -1.29135 -1.29113 -1.77404 -1.77471 -1.29615 -1.2977 -368.904 -368.909 -1.44765e-05 -1.50081e-05 -6.07952e-05 -6.02729e-05 9.83759e-07 -1.17792e-05 -0.000120136 -0.000102302 0.000794415 0.000812718 -0.00109814 -0.00110192 0.213326 0.213521 0.00204124 0.00204405 0.430332 0.430238 -0.00192503 -0.00179055 0.00385903 0.00381684 0.00174723 0.00174776 0 0 0.000219285 0.000220954 1.6861e-05 1.58318e-05 1.42583e-05 1.32043e-05 0.000229308 0.000229652 0.0296849 0.0289715 0.0316754 0.0309338 0.0643252 0.0666299 0.0551955 0.0550702 0.0554134 0.0552858 0.0689623 0.0696888 6.25181e-11 5.5415e-11 6.25174e-11 5.5426e-11 3.97093e-10 3.60211e-10 5.03599e-07 4.73107e-07 5.02366e-07 4.71871e-07 1.92973e-06 2.02581e-06 0.00130129 0.00130123 1.83521e-05 1.83763e-05 0.00130436 0.00130463 0.000265289 0.000264814 0.00129957 0.00129954 0.00129776 0.00129813 0 0
276 27385000 0.709614 0.708914 0.0401533 0.0404755 0.0813765 0.0814613 0.698722 0.699405 -2.2765 -2.27944 -1.08607 -1.08882 -1.28141 -1.28051 -1.96142 -1.96249 -1.36546 -1.36726 -369.032 -369.037 -1.49162e-05 -1.53973e-05 -6.12432e-05 -6.06645e-05 9.70962e-07 -1.17727e-05 -0.000214078 -0.000193214 0.000886921 0.000903495 -0.00112712 -0.00113306 0.212947 0.213153 0.00203565 0.00203864 0.430173 0.430079 -0.00225152 -0.00210179 0.00429191 0.00424315 0.00191714 0.00191405 0 0 0.000216661 0.000218191 1.55652e-05 1.45462e-05 1.38798e-05 1.28364e-05 0.000226242 0.000226441 0.0290543 0.0283868 0.0309147 0.0302366 0.0638407 0.065871 0.0576508 0.0575348 0.0578459 0.0577299 0.0695276 0.0702054 6.21084e-11 5.51256e-11 6.21258e-11 5.51509e-11 3.97188e-10 3.60303e-10 4.82215e-07 4.53125e-07 4.79873e-07 4.508e-07 1.84501e-06 1.93484e-06 0.00128375 0.00128371 1.8232e-05 1.82562e-05 0.00128593 0.00128621 0.000222152 0.000221668 0.00128213 0.00127986 0.00128023 0 0
277 27485000 0.710186 0.709447 0.0343738 0.0347199 0.0662803 0.0663567 0.700043 0.700769 -2.36274 -2.36604 -1.12299 -1.12561 -1.26728 -1.26611 -2.19366 -2.19504 -1.47605 -1.47811 -369.162 -369.167 -1.49171e-05 -1.5398e-05 -6.12431e-05 -6.06646e-05 9.72309e-07 -1.1771e-05 -0.000214105 -0.000193242 0.000887155 0.000903699 -0.00112303 -0.0011294 0.2127 0.21291 0.00203248 0.00203558 0.430026 0.429934 -0.00233105 -0.00217321 0.004443 0.0043946 0.00214326 0.00213515 0 0 0.000217304 0.000218839 1.48955e-05 1.38557e-05 1.38077e-05 1.27505e-05 0.000226488 0.000226649 0.0317177 0.0309498 0.0337477 0.0329685 0.0699397 0.0721505 0.0641673 0.0639866 0.064506 0.0643249 0.0736138 0.0744049 6.22078e-11 5.52253e-11 6.22258e-11 5.52509e-11 3.97287e-10 3.604e-10 4.82224e-07 4.53134e-07 4.79845e-07 4.50772e-07 1.83314e-06 1.92234e-06 0.00126637 0.00126635 1.81133e-05 1.81374e-05 0.00126699 0.0012673 0.000195791 0.000195287 0.00126483 0.00126486 0.00126144 0.00126181 0 0
278 27585000 0.710944 0.710175 0.0296593 0.0300155 0.0536904 0.0537493 0.700569 0.701329 -2.44741 -2.45021 -1.13285 -1.13519 -1.28317 -1.2825 -2.46428 -2.46534 -1.57602 -1.57814 -369.301 -369.305 -1.4621e-05 -1.51426e-05 -6.13686e-05 -6.07808e-05 9.51331e-07 -1.1807e-05 -0.00023931 -0.000218836 0.000826936 0.000846318 -0.00107121 -0.0010758 0.212688 0.212895 0.00202864 0.00203175 0.430255 0.430165 -0.00262999 -0.00246961 0.00400464 0.00396395 0.00199258 0.0019784 0 0 0.000214541 0.000215937 1.41928e-05 1.31625e-05 1.35739e-05 1.25301e-05 0.000223095 0.000223108 0.0305652 0.0298638 0.0322335 0.0315381 0.0682099 0.0701064 0.0663955 0.066237 0.0666791 0.0665232 0.0751073 0.0758405 6.1791e-11 5.49283e-11 6.1837e-11 5.49761e-11 3.97379e-10 3.6049e-10 4.62238e-07 4.34389e-07 4.58397e-07 4.30591e-07 1.75219e-06 1.83605e-06 0.00125202 1.80253e-05 1.80493e-05 0.00125076 0.00125106 0.000180674 0.000180179 0.00125052 0.00125059 0.0012455 0.00124585 0 0
279 27685000 0.710776 0.709963 0.0287447 0.0291106 0.0514766 0.0515324 0.700943 0.701747 -2.48598 -2.48916 -1.14649 -1.14856 -1.28412 -1.28317 -2.71102 -2.71238 -1.68999 -1.69233 -369.429 -369.433 -1.4621e-05 -1.51425e-05 -6.13686e-05 -6.07808e-05 9.51279e-07 -1.18074e-05 -0.000239311 -0.000218831 0.000826931 0.000846281 -0.0010713 -0.0010764 0.212605 0.212818 0.00202658 0.00202981 0.430177 0.430093 -0.00276506 -0.0025965 0.00399167 0.00395217 0.00212497 0.00210481 0 0 0.000214683 0.000216076 1.42542e-05 1.32116e-05 1.36855e-05 1.26312e-05 0.000222952 0.00022292 0.0331377 0.0323382 0.0348163 0.0340239 0.0735682 0.0755933 0.0737021 0.0734673 0.0741409 0.0739099 0.0796669 0.0805037 6.18902e-11 5.50276e-11 6.19369e-11 5.5076e-11 3.97478e-10 3.60588e-10 4.62247e-07 4.34398e-07 4.58352e-07 4.30547e-07 1.73927e-06 1.82255e-06 0.00123351 0.00123354 1.79089e-05 1.79328e-05 0.0012299 0.00123022 0.000166527 0.000166021 0.00123203 0.00123214 0.00122488 0.00122522 0 0
280 27785000 0.710988 0.710139 0.0292283 0.0295914 0.0533919 0.0534421 0.700565 0.701406 -2.53724 -2.54017 -1.1482 -1.15004 -1.28793 -1.28709 -2.97817 -2.97928 -1.78739 -1.7898 -369.561 -369.565 -1.44852e-05 -1.50275e-05 -6.15202e-05 -6.09177e-05 9.18216e-07 -1.18484e-05 -0.000269163 -0.00024857 0.000799891 0.000820964 -0.00104841 -0.00105303 0.212504 0.212718 0.00202198 0.00202526 0.429864 0.429785 -0.00326708 -0.00309156 0.00406427 0.00403064 0.00232739 0.00230145 0 0 0.000211928 0.000213187 1.41602e-05 1.31348e-05 1.35959e-05 1.25571e-05 0.000219911 0.000219722 0.0316078 0.0308947 0.0329113 0.0322165 0.0696233 0.0712863 0.0755966 0.075399 0.0759553 0.0757645 0.0791218 0.0798428 6.14875e-11 5.47392e-11 6.15682e-11 5.48146e-11 3.97563e-10 3.6067e-10 4.43923e-07 4.1713e-07 4.3842e-07 4.1169e-07 1.66094e-06 1.73975e-06 0.00122045 0.0012205 1.77951e-05 1.78189e-05 0.00121509 0.0012154 0.000155126 0.000154625 0.001219 0.00121914 0.00121024 0.00121056 0 0
281 27885000 0.711029 0.710136 0.0286042 0.028977 0.0516625 0.0517101 0.700679 0.701565 -2.57486 -2.57817 -1.16297 -1.16452 -1.29047 -1.28944 -3.2339 -3.23533 -1.90301 -1.90559 -369.695 -369.699 -1.44876e-05 -1.50295e-05 -6.15204e-05 -6.09182e-05 9.20369e-07 -1.18461e-05 -0.000269287 -0.000248693 0.000800463 0.000821502 -0.00104051 -0.00104542 0.212629 0.212846 0.00202401 0.0020274 0.429808 0.429733 -0.00324822 -0.00306395 0.00416707 0.00413302 0.002203 0.00217148 0 0 0.000211956 0.000213213 1.42521e-05 1.32134e-05 1.3724e-05 1.26737e-05 0.000219888 0.00021965 0.0341198 0.0333169 0.0354129 0.0346293 0.0739264 0.0756666 0.083637 0.0833547 0.0841458 0.083873 0.083728 0.0845311 6.15862e-11 5.48382e-11 6.16682e-11 5.49145e-11 3.97662e-10 3.60769e-10 4.4393e-07 4.17137e-07 4.38358e-07 4.11628e-07 1.6473e-06 1.72558e-06 0.0012106 0.00121067 1.76836e-05 1.77073e-05 0.00120411 0.00120443 0.000147073 0.000146562 0.00120919 0.00120936 0.00119933 0.00119964 0 0
282 27985000 0.711411 0.710481 0.027604 0.0279783 0.0477341 0.0477643 0.70061 0.701536 -2.64229 -2.64478 -1.17094 -1.17198 -1.29917 -1.2984 -3.54185 -3.54265 -2.0171 -2.01964 -369.828 -369.832 -1.41044e-05 -1.4695e-05 -6.15307e-05 -6.09316e-05 8.83059e-07 -1.18936e-05 -0.000271057 -0.000251215 0.000725513 0.000749142 -0.00101172 -0.00101561 0.212583 0.212795 0.00202286 0.00202621 0.429546 0.429479 -0.00335282 -0.00316395 0.00419603 0.00416903 0.00234596 0.0023108 0 0 0.00020992 0.000211066 1.40027e-05 1.29737e-05 1.36121e-05 1.25738e-05 0.000217603 0.000217218 0.0323011 0.0315983 0.033278 0.0325997 0.0689919 0.0703972 0.0851215 0.0848916 0.0855353 0.0853169 0.0825219 0.0831971 6.12148e-11 5.45717e-11 6.13323e-11 5.46766e-11 3.97736e-10 3.6084e-10 4.27436e-07 4.01509e-07 4.20286e-07 3.94428e-07 1.57789e-06 1.65273e-06 0.00120133 0.00120142 1.75737e-05 1.75973e-05 0.00119349 0.00119379 0.000139798 0.000139287 0.00119993 0.00120012 0.00118879 0.00118907 0 0
283 28085000 0.710933 0.709955 0.0330703 0.0334352 0.0601792 0.0602149 0.699899 0.700872 -2.6786 -2.68142 -1.18224 -1.18293 -1.31191 -1.3109 -3.80767 -3.80873 -2.13468 -2.13731 -369.959 -369.962 -1.41045e-05 -1.4695e-05 -6.15308e-05 -6.09316e-05 8.83078e-07 -1.18938e-05 -0.000271064 -0.000251214 0.000725532 0.000749131 -0.00101148 -0.00101575 0.21259 0.212808 0.00202131 0.00202479 0.429517 0.429454 -0.00356783 -0.00337065 0.00415773 0.0041334 0.00240131 0.00236148 0 0 0.000209616 0.000210753 1.45452e-05 1.35135e-05 1.38745e-05 1.28271e-05 0.000217416 0.000216975 0.0347408 0.0339562 0.0356944 0.0349349 0.0723396 0.0737873 0.0938312 0.0935116 0.0943813 0.0940772 0.086961 0.0876971 6.13132e-11 5.46705e-11 6.14323e-11 5.47765e-11 3.97835e-10 3.60939e-10 4.27441e-07 4.01514e-07 4.20213e-07 3.94356e-07 1.56441e-06 1.63881e-06 0.00119563 0.00119573 1.74659e-05 1.74894e-05 0.00118703 0.00118732 0.00013461 0.000134089 0.00119427 0.00119447 0.00118237 0.00118264 0 0
284 28185000 0.710784 0.709762 0.0385506 0.0388961 0.0744156 0.0744487 0.698399 0.699416 -2.74655 -2.7487 -1.19658 -1.19709 -1.07578 -1.07487 -4.1124 -4.11296 -2.24774 -2.25038 -370.09 -370.093 -1.38671e-05 -1.4488e-05 -6.15646e-05 -6.09637e-05 8.45392e-07 -1.19334e-05 -0.000277492 -0.000257899 0.000679623 0.000704848 -0.000996122 -0.000999919 0.212637 0.212851 0.00202121 0.00202469 0.429486 0.429426 -0.00365367 -0.00344982 0.00411507 0.00409478 0.00235135 0.00231253 0 0 0.000207456 0.000208493 1.49781e-05 1.3968e-05 1.3934e-05 1.29008e-05 0.00021561 0.00021502 0.0325025 0.0318389 0.0332252 0.0325866 0.0661662 0.067312 0.0948579 0.0946045 0.0953084 0.0950711 0.0851628 0.0857721 6.09858e-11 5.44362e-11 6.11389e-11 5.45699e-11 3.97896e-10 3.60998e-10 4.12844e-07 3.876e-07 4.04177e-07 3.78992e-07 1.50505e-06 1.57686e-06 0.00119414 0.00119424 1.73605e-05 1.73839e-05 0.00118535 0.00118564 0.000129752 0.000129224 0.0011928 0.00119302 0.00118079 0.00118105 0 0
285 28285000 0.712703 0.711643 0.0314857 0.0318633 0.0588677 0.0588888 0.698282 0.699343 -2.7459 -2.74783 -1.20799 -1.2086 -0.218058 -0.217017 -4.38714 -4.3879 -2.36799 -2.37069 -370.156 -370.159 -1.38674e-05 -1.44881e-05 -6.15646e-05 -6.09638e-05 8.45536e-07 -1.19334e-05 -0.000277507 -0.00025791 0.000679681 0.000704884 -0.000995432 -0.000999471 0.212687 0.212905 0.00202057 0.00202417 0.429543 0.429484 -0.00376237 -0.00355257 0.00401985 0.00400171 0.00238242 0.00234258 0 0 0.000207442 0.000208496 1.45386e-05 1.35003e-05 1.39227e-05 1.28709e-05 0.000216594 0.000215958 0.0340484 0.0333559 0.0346661 0.0339923 0.0671091 0.0682594 0.104135 0.103792 0.104704 0.104382 0.0911759 0.0918554 6.10844e-11 5.45352e-11 6.12388e-11 5.46698e-11 3.97995e-10 3.61098e-10 4.12849e-07 3.87605e-07 4.04121e-07 3.78938e-07 1.49556e-06 1.56712e-06 0.00119303 0.00119314 1.72825e-05 1.7306e-05 0.00118422 0.0011845 0.000127076 0.000126538 0.00119172 0.00119195 0.00117968 0.00117994 0 0
286 28385000 0.715112 0.714029 0.0154512 0.0158761 0.0277144 0.0277004 0.698289 0.699388 -2.77526 -2.77605 -1.21372 -1.21431 0.641418 0.642293 -4.72085 -4.72096 -2.48906 -2.49176 -370.143 -370.145 -1.34734e-05 -1.41408e-05 -6.15549e-05 -6.09586e-05 8.02533e-07 -1.19874e-05 -0.00027558 -0.00025654 0.000606368 0.000633479 -0.000960363 -0.000963378 0.212389 0.212607 0.0020152 0.00201881 0.429649 0.429598 -0.0038281 -0.00361456 0.00351504 0.00350471 0.00248284 0.00243818 0 0 0.000206676 0.000207691 1.38631e-05 1.27985e-05 1.37121e-05 1.26523e-05 0.000216758 0.000216028 0.031361 0.0307968 0.0317471 0.0311944 0.0669295 0.0680569 0.104726 0.104457 0.105197 0.104948 0.0950242 0.0957344 6.07564e-11 5.42995e-11 6.09352e-11 5.44549e-11 3.98055e-10 3.61164e-10 3.98962e-07 3.74383e-07 3.89246e-07 3.64695e-07 1.4795e-06 1.55046e-06 0.00118328 0.00118343 1.71777e-05 1.7201e-05 0.0011738 0.00117407 0.000123264 0.000122716 0.00118199 0.00118226 0.00116911 0.00116935 0 0
287 28485000 0.715457 0.714338 0.00584394 0.00630458 0.00844385 0.00841466 0.698581 0.699722 -2.73311 -2.73406 -1.20562 -1.2058 0.97149 0.972496 -4.99669 -4.99689 -2.61024 -2.61299 -370.06 -370.062 -1.34759e-05 -1.41428e-05 -6.15555e-05 -6.09593e-05 8.03523e-07 -1.19875e-05 -0.000275737 -0.000256692 0.000606892 0.000633971 -0.000954357 -0.000957604 0.211528 0.211756 0.00200375 0.00200747 0.429617 0.429579 -0.0037931 -0.00357255 0.0027695 0.00276547 0.00287124 0.00281286 0 0 0.000206745 0.000207771 1.40126e-05 1.29183e-05 1.38735e-05 1.27957e-05 0.000216832 0.000216057 0.0331869 0.0325746 0.0334485 0.0328421 0.0677771 0.0688983 0.114452 0.114098 0.115011 0.114681 0.0985985 0.0993331 6.08538e-11 5.43975e-11 6.1035e-11 5.45546e-11 3.98155e-10 3.61264e-10 3.98962e-07 3.74382e-07 3.8914e-07 3.64591e-07 1.46423e-06 1.53474e-06 0.00115464 0.00115484 1.707e-05 1.70932e-05 0.00114319 0.00114346 0.000120209 0.000119657 0.00115319 0.00115354 0.00113798 0.00113819 0 0
288 28585000 0.71481 0.713652 0.00408359 0.00454918 0.00481784 0.00477765 0.699291 0.70047 -2.70246 -2.70307 -1.18482 -1.18411 0.863885 0.864695 -5.33242 -5.33205 -2.73082 -2.73357 -369.977 -369.979 -1.30586e-05 -1.37734e-05 -6.1539e-05 -6.09476e-05 7.55786e-07 -1.20465e-05 -0.000272709 -0.000254125 0.000531448 0.00056028 -0.000919202 -0.000921216 0.211835 0.212066 0.00200704 0.00201091 0.430033 0.430012 -0.00376709 -0.00354091 0.00271438 0.00271913 0.00229311 0.0022207 0 0 0.000206799 0.000207779 1.4095e-05 1.29923e-05 1.39308e-05 1.28469e-05 0.000216004 0.000215139 0.0312416 0.0307111 0.0313265 0.030794 0.0691543 0.070263 0.114648 0.114373 0.115131 0.114876 0.101936 0.102686 6.05263e-11 5.41616e-11 6.07255e-11 5.43343e-11 3.98205e-10 3.61321e-10 3.856e-07 3.61662e-07 3.75105e-07 3.51157e-07 1.44581e-06 1.51561e-06 0.00112184 0.0011221 1.69625e-05 1.69856e-05 0.00110814 0.0011084 0.00011714 0.000116581 0.00112017 0.00112059 0.00110238 0.00110254 0 0
289 28685000 0.713822 0.712618 0.00333977 0.00381197 0.00382037 0.0037785 0.700309 0.701532 -2.63253 -2.63352 -1.16612 -1.16464 0.859864 0.860756 -5.59922 -5.59895 -2.84839 -2.85103 -369.899 -369.901 -1.30628e-05 -1.37771e-05 -6.15403e-05 -6.0949e-05 7.57034e-07 -1.20478e-05 -0.00027299 -0.000254401 0.000532325 0.000561123 -0.000909392 -0.000911544 0.211709 0.211949 0.00200592 0.00200992 0.429681 0.429673 -0.00374961 -0.00351394 0.00276333 0.00277288 0.00263228 0.00254392 0 0 0.000207367 0.000208344 1.42809e-05 1.31618e-05 1.41094e-05 1.30097e-05 0.000215563 0.000214648 0.0332294 0.0326466 0.0332362 0.032642 0.069841 0.0709277 0.124845 0.124485 0.125369 0.125034 0.105026 0.105786 6.0623e-11 5.4259e-11 6.08252e-11 5.4434e-11 3.98304e-10 3.61421e-10 3.85595e-07 3.61657e-07 3.74974e-07 3.51028e-07 1.42814e-06 1.49737e-06 0.00109281 0.00109311 1.6857e-05 1.68801e-05 0.00107715 0.00107741 0.000114772 0.000114212 0.00109086 0.00109133 0.00107097 0.00107109 0 0
290 28785000 0.713199 0.711955 0.00316389 0.00363362 0.00363656 0.00358744 0.700945 0.702207 -2.60647 -2.60702 -1.1466 -1.14453 0.864564 0.865208 -5.92995 -5.92908 -2.96118 -2.96403 -369.817 -369.819 -1.26672e-05 -1.34262e-05 -6.15479e-05 -6.09569e-05 6.81328e-07 -1.21252e-05 -0.000274503 -0.000255922 0.000459824 0.000490057 -0.000885294 -0.000886106 0.211583 0.211827 0.00200294 0.00200707 0.429894 0.429903 -0.00381929 -0.00357712 0.00233863 0.00235871 0.00245355 0.00235191 0 0 0.000207543 0.000208502 1.43323e-05 1.32077e-05 1.41564e-05 1.30507e-05 0.000214929 0.000213928 0.0311466 0.0306475 0.0311235 0.030607 0.0628005 0.0636455 0.124581 0.124304 0.125074 0.124821 0.0999488 0.10054 6.03584e-11 5.4071e-11 6.0574e-11 5.42577e-11 3.98316e-10 3.61431e-10 3.73734e-07 3.50266e-07 3.62678e-07 3.39163e-07 1.3696e-06 1.43619e-06 0.00106799 0.00106832 1.67535e-05 1.67765e-05 0.00105065 0.0010509 0.000112516 0.000111951 0.00106576 0.00106627 0.00104421 0.00104428 0 0
291 28885000 0.712693 0.711403 0.00311522 0.00358968 0.00381405 0.00376489 0.701459 0.702765 -2.54069 -2.5416 -1.12962 -1.12675 0.850404 0.851096 -6.18732 -6.18654 -3.07501 -3.07762 -369.737 -369.739 -1.26702e-05 -1.34287e-05 -6.15488e-05 -6.09578e-05 6.8209e-07 -1.21263e-05 -0.0002747 -0.000256116 0.000460429 0.000490639 -0.000878618 -0.000879528 0.211472 0.211719 0.00200191 0.0020061 0.42958 0.4296 -0.00378921 -0.00353949 0.00238459 0.00240631 0.00276214 0.00264901 0 0 0.00020797 0.00020893 1.45146e-05 1.33735e-05 1.43398e-05 1.32175e-05 0.000214847 0.000213794 0.0330815 0.0325363 0.0330657 0.0324921 0.0643539 0.0652049 0.135188 0.13483 0.135682 0.13535 0.10534 0.10597 6.04563e-11 5.41693e-11 6.06738e-11 5.43575e-11 3.98416e-10 3.61531e-10 3.73734e-07 3.50267e-07 3.62599e-07 3.39087e-07 1.35882e-06 1.42513e-06 0.00105181 0.00105215 1.66772e-05 1.67001e-05 0.00103345 0.0010337 0.000111124 0.000110558 0.00104937 0.00104991 0.00102682 0.00102687 0 0
292 28985000 0.712446 0.711115 0.00343704 0.00390625 0.00438796 0.00433127 0.701705 0.703051 -2.53159 -2.53195 -1.11634 -1.11297 0.843341 0.843813 -6.53062 -6.52913 -3.19194 -3.19488 -369.656 -369.658 -1.22182e-05 -1.30262e-05 -6.15173e-05 -6.09304e-05 5.93364e-07 -1.22144e-05 -0.000269093 -0.000250442 0.00037628 0.000407713 -0.000852993 -0.000852365 0.211092 0.211341 0.00199583 0.00200008 0.429547 0.429585 -0.00381666 -0.00356024 0.001767 0.00179886 0.00293338 0.00280879 0 0 0.000208132 0.000209098 1.45574e-05 1.3411e-05 1.43865e-05 1.32577e-05 0.000214651 0.000213531 0.0309833 0.0305188 0.0310125 0.0305158 0.0582142 0.0588885 0.134497 0.134226 0.135002 0.134755 0.100478 0.100976 6.0257e-11 5.40318e-11 6.04768e-11 5.42228e-11 3.98386e-10 3.61507e-10 3.63286e-07 3.40152e-07 3.52187e-07 3.2896e-07 1.31316e-06 1.37757e-06 0.00103313 0.00103348 1.65766e-05 1.65995e-05 0.00101359 0.00101383 0.000109366 0.000108795 0.00103045 0.00103102 0.0010068 0.00100682 0 0
293 29085000 0.712291 0.710914 0.0035501 0.00402389 0.00474729 0.00469127 0.701859 0.703252 -2.4723 -2.473 -1.10046 -1.09629 0.832525 0.833062 -6.78084 -6.7794 -3.30279 -3.30535 -369.577 -369.579 -1.22207e-05 -1.30284e-05 -6.15181e-05 -6.09312e-05 5.93922e-07 -1.22156e-05 -0.00026926 -0.000250604 0.000376787 0.000408195 -0.000847428 -0.000846946 0.210972 0.211227 0.0019943 0.00199866 0.429255 0.429306 -0.00382457 -0.00355808 0.00178251 0.00181785 0.00323146 0.00309209 0 0 0.000208399 0.000209366 1.47463e-05 1.35826e-05 1.45771e-05 1.34309e-05 0.000214761 0.000213584 0.0328504 0.0323457 0.0329546 0.032406 0.0584158 0.0590769 0.145464 0.145115 0.145937 0.145614 0.102876 0.103378 6.03546e-11 5.41299e-11 6.05766e-11 5.43225e-11 3.98486e-10 3.61607e-10 3.63285e-07 3.40151e-07 3.52099e-07 3.28874e-07 1.30126e-06 1.36539e-06 0.00101718 0.00101754 1.64774e-05 1.65002e-05 0.00099671 0.000996939 0.000107867 0.000107293 0.0010143 0.00101489 0.000989769 0.000989754 0 0
294 29185000 0.712247 0.710828 0.00377694 0.00424926 0.00514497 0.00508668 0.7019 0.703335 -2.44101 -2.4416 -1.08748 -1.08297 0.820699 0.82112 -7.07301 -7.07122 -3.41672 -3.41975 -369.503 -369.505 -1.2023e-05 -1.28521e-05 -6.14972e-05 -6.09108e-05 5.50152e-07 -1.2262e-05 -0.000265438 -0.000246268 0.000339107 0.000370929 -0.000825459 -0.000824079 0.211378 0.211632 0.00200011 0.00200462 0.429481 0.429549 -0.00374648 -0.00346927 0.00195148 0.00198918 0.00281658 0.00266365 0 0 0.000208461 0.00020945 1.47896e-05 1.36201e-05 1.46263e-05 1.34732e-05 0.000214736 0.000213509 0.0307431 0.0303146 0.0309198 0.0304468 0.0531707 0.0537047 0.144376 0.144114 0.144898 0.144661 0.0984408 0.0988445 6.0216e-11 5.40397e-11 6.04324e-11 5.42287e-11 3.98414e-10 3.61549e-10 3.54203e-07 3.31282e-07 3.43392e-07 3.20333e-07 1.26586e-06 1.32862e-06 0.00100341 0.00100377 1.638e-05 1.64027e-05 0.000982129 0.000982353 0.000106495 0.000105916 0.00100035 0.00100095 0.000975096 0.000975054 0 0
295 29285000 0.712178 0.710713 0.00406931 0.00454545 0.0059139 0.00585675 0.701962 0.703443 -2.38734 -2.38823 -1.07435 -1.06906 0.842875 0.843332 -7.31447 -7.31275 -3.52484 -3.52737 -369.427 -369.428 -1.20261e-05 -1.28547e-05 -6.14982e-05 -6.09118e-05 5.50708e-07 -1.22638e-05 -0.000265643 -0.000246469 0.000339718 0.000371518 -0.000818709 -0.000817424 0.211329 0.21159 0.00199936 0.00200402 0.42937 0.42945 -0.00376516 -0.00347795 0.0019528 0.00199455 0.00291711 0.00274986 0 0 0.000208727 0.000209718 1.49831e-05 1.37957e-05 1.48243e-05 1.36528e-05 0.00021494 0.000213654 0.032515 0.0320524 0.0328151 0.0322965 0.0531548 0.0536785 0.155654 0.15532 0.156116 0.155807 0.10049 0.100898 6.0314e-11 5.41381e-11 6.05322e-11 5.43285e-11 3.98514e-10 3.61648e-10 3.54204e-07 3.31283e-07 3.4332e-07 3.20264e-07 1.25593e-06 1.31847e-06 0.000991522 0.000991892 1.62841e-05 1.63068e-05 0.000969598 0.000969817 0.000105296 0.000104712 0.0009883 0.000988921 0.000962459 0.000962392 0 0
296 29385000 0.712202 0.710696 0.0046108 0.00508169 0.00737777 0.00731735 0.701921 0.703443 -2.37433 -2.37497 -1.0669 -1.06139 0.849737 0.850063 -7.6183 -7.61612 -3.64214 -3.64528 -369.35 -369.352 -1.17858e-05 -1.26398e-05 -6.14587e-05 -6.08749e-05 4.98095e-07 -1.232e-05 -0.000258063 -0.000238303 0.000292429 0.000324504 -0.000791825 -0.000789352 0.211523 0.211791 0.00200099 0.00200584 0.429343 0.429438 -0.0038441 -0.00354788 0.00191892 0.00197229 0.00283925 0.0026607 0 0 0.000208676 0.000209701 1.50211e-05 1.38278e-05 1.48765e-05 1.36974e-05 0.000214899 0.000213576 0.0304029 0.0300114 0.0307658 0.0303212 0.0486367 0.0490672 0.154205 0.153955 0.154752 0.154527 0.0964308 0.0967628 6.02277e-11 5.40888e-11 6.04357e-11 5.42719e-11 3.98403e-10 3.61557e-10 3.46373e-07 3.23567e-07 3.36082e-07 3.13102e-07 1.22808e-06 1.28959e-06 0.000981528 0.000981901 1.61898e-05 1.62124e-05 0.000959074 0.000959289 0.000104205 0.000103616 0.000978178 0.000978813 0.000951881 0.000951789 0 0
297 29485000 0.712231 0.710679 0.00507304 0.00554714 0.00848419 0.00842542 0.701876 0.703444 -2.32838 -2.32934 -1.05683 -1.05054 0.845834 0.846188 -7.85342 -7.85132 -3.74832 -3.75087 -369.267 -369.269 -1.17865e-05 -1.26403e-05 -6.14589e-05 -6.08751e-05 4.98203e-07 -1.23205e-05 -0.000258112 -0.000238347 0.00029257 0.000324633 -0.00079025 -0.00078789 0.211613 0.211882 0.00200265 0.0020076 0.429292 0.4294 -0.00379144 -0.00348437 0.00204254 0.00209493 0.00283436 0.00264227 0 0 0.000208926 0.000209953 1.52221e-05 1.40101e-05 1.5082e-05 1.38839e-05 0.000215195 0.00021381 0.0321285 0.0317065 0.0326448 0.0321586 0.0485483 0.0489707 0.16575 0.165433 0.166214 0.165922 0.0981766 0.0985115 6.0326e-11 5.41875e-11 6.05355e-11 5.43717e-11 3.98503e-10 3.61656e-10 3.46375e-07 3.23569e-07 3.36025e-07 3.13046e-07 1.21974e-06 1.28107e-06 0.000973112 0.000973485 1.60969e-05 1.61195e-05 0.000950245 0.000950456 0.000103225 0.000102631 0.000969639 0.000970288 0.000942992 0.000942879 0 0
298 29585000 0.712219 0.71063 0.00542937 0.00590021 0.00951682 0.00945959 0.701872 0.703478 -2.30192 -2.30289 -1.0454 -1.03911 0.836751 0.837021 -8.11463 -8.11228 -3.85018 -3.85352 -369.189 -369.19 -1.16948e-05 -1.25587e-05 -6.14708e-05 -6.08826e-05 4.41548e-07 -1.23721e-05 -0.000260745 -0.000240105 0.000273526 0.000305745 -0.000778545 -0.000775645 0.211629 0.211899 0.00200284 0.00200781 0.429111 0.429229 -0.00378374 -0.00346915 0.00205718 0.00211292 0.00297514 0.00277482 0 0 0.000208766 0.000209833 1.52684e-05 1.40498e-05 1.5139e-05 1.39328e-05 0.000215055 0.000213643 0.0300524 0.0296949 0.0306056 0.0301897 0.0454122 0.0457726 0.163975 0.16374 0.164556 0.164346 0.0967366 0.0970269 6.02866e-11 5.41753e-11 6.04837e-11 5.43501e-11 3.98358e-10 3.61537e-10 3.39732e-07 3.1696e-07 3.30098e-07 3.07123e-07 1.19936e-06 1.25995e-06 0.000967607 0.000967983 1.60285e-05 1.6051e-05 0.000944488 0.000944697 0.000102547 0.000101949 0.000964072 0.00096473 0.000937218 0.000937092 0 0
299 29685000 0.712352 0.710718 0.00568821 0.00616337 0.0101615 0.0101056 0.701726 0.703377 -2.26323 -2.26452 -1.03626 -1.0292 0.829105 0.829387 -8.34288 -8.34065 -3.95425 -3.95692 -369.107 -369.108 -1.16955e-05 -1.25592e-05 -6.1471e-05 -6.08828e-05 4.41631e-07 -1.23726e-05 -0.00026079 -0.000240146 0.000273656 0.000305865 -0.000777083 -0.00077427 0.211543 0.21182 0.00200155 0.00200666 0.429106 0.429234 -0.00380181 -0.00347746 0.00197644 0.00203637 0.00301653 0.00280383 0 0 0.000208992 0.00021006 1.5482e-05 1.42435e-05 1.53533e-05 1.41272e-05 0.000215434 0.000213959 0.0317162 0.0313314 0.0324363 0.0319831 0.0452675 0.0456216 0.175751 0.175455 0.176229 0.175957 0.0982991 0.0985922 6.03852e-11 5.42742e-11 6.05835e-11 5.445e-11 3.98458e-10 3.61636e-10 3.39736e-07 3.16963e-07 3.30052e-07 3.07079e-07 1.19233e-06 1.25278e-06 0.000961163 0.000961539 1.59379e-05 1.59604e-05 0.000937754 0.000937963 0.000101717 0.000101112 0.000957526 0.000958198 0.000930449 0.000930306 0 0
300 29785000 0.712428 0.710759 0.00592035 0.00639211 0.0106234 0.0105672 0.70164 0.703327 -2.25095 -2.25216 -1.0282 -1.02122 0.816184 0.816406 -8.61313 -8.61053 -4.05876 -4.06233 -369.027 -369.028 -1.15792e-05 -1.24552e-05 -6.14683e-05 -6.08778e-05 3.78747e-07 -1.24269e-05 -0.000260397 -0.000238892 0.000247989 0.000280219 -0.000767304 -0.00076385 0.211317 0.21159 0.00199907 0.00200421 0.429221 0.429363 -0.00368325 -0.00335044 0.00162479 0.00168417 0.00301553 0.00279274 0 0 0.00020864 0.000209753 1.55353e-05 1.42897e-05 1.54132e-05 1.41789e-05 0.000215193 0.000213695 0.0296755 0.029349 0.0303961 0.030009 0.0418246 0.0421238 0.173685 0.173466 0.174311 0.174115 0.0947051 0.09495 6.03856e-11 5.42936e-11 6.0572e-11 5.44603e-11 3.98284e-10 3.61492e-10 3.34195e-07 3.11389e-07 3.25245e-07 3.0222e-07 1.17443e-06 1.23426e-06 0.000955449 0.00095583 1.58483e-05 1.58708e-05 0.000931813 0.000932021 0.000100942 0.000100332 0.000951749 0.000952435 0.000924496 0.000924337 0 0
301 29885000 0.712512 0.710798 0.0059399 0.00641725 0.010752 0.0106965 0.701553 0.703285 -2.21804 -2.21957 -1.0203 -1.01258 0.800708 0.800909 -8.83664 -8.83418 -4.16123 -4.16406 -368.954 -368.955 -1.15823e-05 -1.24579e-05 -6.14694e-05 -6.08788e-05 3.78951e-07 -1.24299e-05 -0.000260611 -0.000239102 0.000248598 0.000280811 -0.000760409 -0.000756965 0.211295 0.211576 0.00199845 0.0020038 0.429287 0.429439 -0.00371878 -0.00337653 0.00156457 0.00162992 0.00294818 0.00271331 0 0 0.000208919 0.000210031 1.57593e-05 1.44927e-05 1.56356e-05 1.43805e-05 0.000215572 0.00021401 0.0312813 0.0309303 0.0321732 0.0317526 0.0416269 0.0419209 0.185658 0.185383 0.186163 0.185911 0.0960353 0.0962827 6.04844e-11 5.43927e-11 6.06719e-11 5.45601e-11 3.98384e-10 3.61591e-10 3.34199e-07 3.11393e-07 3.25208e-07 3.02185e-07 1.16846e-06 1.22817e-06 0.000950347 0.000950729 1.57597e-05 1.57821e-05 0.000926492 0.000926699 0.000100232 9.9616e-05 0.000946562 0.000947263 0.000919158 0.000918984 0 0
302 29985000 0.712564 0.710819 0.00598596 0.00646176 0.0108526 0.0108001 0.701498 0.703262 -2.19356 -2.19515 -1.00967 -1.00214 0.785491 0.78565 -9.07422 -9.07151 -4.25625 -4.26009 -368.877 -1.15464e-05 -1.24264e-05 -6.1485e-05 -6.08897e-05 3.24269e-07 -1.24737e-05 -0.000264483 -0.000242061 0.000239789 0.00027214 -0.000756909 -0.000753231 0.21132 0.211604 0.00199882 0.0020043 0.429341 0.429504 -0.00369523 -0.00334462 0.0015183 0.00158692 0.00288565 0.00263983 0 0 0.000208462 0.000209618 1.58153e-05 1.45413e-05 1.56969e-05 1.44337e-05 0.00021521 0.000213628 0.029281 0.0289824 0.0301456 0.0297863 0.0386211 0.0388725 0.183337 0.183134 0.184017 0.183837 0.0927002 0.092909 6.05181e-11 5.44387e-11 6.06951e-11 5.4598e-11 3.98185e-10 3.61426e-10 3.29656e-07 3.06766e-07 3.21375e-07 2.9826e-07 1.1541e-06 1.21334e-06 0.000945656 0.000946045 1.56722e-05 1.56946e-05 0.000921639 0.000921847 9.95579e-05 9.89349e-05 0.000941823 0.00094254 0.000914302 0.000914115 0 0
303 30085000 0.712679 0.71089 0.00592752 0.00640958 0.0107236 0.0106715 0.701384 0.703193 -2.16251 -2.16443 -1.00248 -0.994208 0.772386 0.77253 -9.29204 -9.28951 -4.35687 -4.35992 -368.8 -368.801 -1.15469e-05 -1.24268e-05 -6.14851e-05 -6.08899e-05 3.24278e-07 -1.24741e-05 -0.000264513 -0.000242089 0.000239873 0.000272216 -0.000755956 -0.00075233 0.211509 0.2118 0.0020011 0.00200677 0.429328 0.429501 -0.00372696 -0.00336613 0.00168461 0.00175787 0.00280773 0.00254966 0 0 0.00020875 0.000209905 1.60473e-05 1.47515e-05 1.59266e-05 1.46418e-05 0.00021563 0.000213981 0.030832 0.0305111 0.0318734 0.0314835 0.0383882 0.0386356 0.195476 0.195223 0.196018 0.195788 0.0938298 0.0940409 6.0617e-11 5.45379e-11 6.07949e-11 5.46979e-11 3.98285e-10 3.61525e-10 3.29661e-07 3.06771e-07 3.21346e-07 2.98232e-07 1.14902e-06 1.20816e-06 0.000941356 0.000941749 1.55859e-05 1.56082e-05 0.000917164 0.000917374 9.89516e-05 9.83221e-05 0.000937443 0.000938177 0.00090982 0.000909621 0 0
304 30185000 0.712764 0.710946 0.00590855 0.0063884 0.0105346 0.0104839 0.7013 0.70314 -2.14724 -2.14912 -0.99402 -0.985994 0.762695 0.762807 -9.53727 -9.53439 -4.45423 -4.45837 -368.718 -1.14963e-05 -1.23817e-05 -6.14895e-05 -6.08915e-05 2.6583e-07 -1.25165e-05 -0.000265882 -0.000242599 0.000226005 0.000258338 -0.00075667 -0.000752729 0.211769 0.212053 0.00200512 0.00201077 0.429249 0.429433 -0.00363691 -0.00326926 0.00189773 0.00196694 0.0027736 0.00250774 0 0 0.000208183 0.000209382 1.61046e-05 1.48013e-05 1.59881e-05 1.46953e-05 0.000215191 0.000213523 0.0288754 0.0286015 0.0298592 0.0295259 0.036337 0.0365554 0.192934 0.192747 0.193679 0.193513 0.0928793 0.0930681 6.06771e-11 5.46051e-11 6.08463e-11 5.47583e-11 3.98066e-10 3.61344e-10 3.25993e-07 3.02981e-07 3.18346e-07 2.95112e-07 1.13857e-06 1.19736e-06 0.000938269 0.000938669 1.55222e-05 1.55445e-05 0.00091399 0.000914202 9.84981e-05 9.7863e-05 0.000934335 0.000935082 0.000906644 0.000906436 0 0
305 30285000 0.712886 0.711024 0.00576888 0.00625521 0.0103266 0.0102763 0.70118 0.703065 -2.11633 -2.11855 -0.988766 -0.980004 0.753128 0.753231 -9.75037 -9.74769 -4.55336 -4.55666 -368.636 -1.14943e-05 -1.23799e-05 -6.14888e-05 -6.08908e-05 2.65886e-07 -1.25139e-05 -0.000265741 -0.00024246 0.000225622 0.000257958 -0.000761051 -0.000757207 0.211827 0.212117 0.00200579 0.0020116 0.429279 0.429472 -0.00364478 -0.00326725 0.00193173 0.00200429 0.00273443 0.00245637 0 0 0.00020849 0.000209686 1.63436e-05 1.50178e-05 1.62248e-05 1.49097e-05 0.000215639 0.000213903 0.0303742 0.0300796 0.031541 0.0311794 0.0360904 0.0363056 0.205212 0.20498 0.205803 0.205593 0.0938819 0.0940732 6.07762e-11 5.47044e-11 6.09462e-11 5.48582e-11 3.98166e-10 3.61443e-10 3.25999e-07 3.02987e-07 3.18323e-07 2.9509e-07 1.13423e-06 1.19293e-06 0.000934409 0.000934815 1.54378e-05 1.54601e-05 0.000909983 0.000910197 9.79688e-05 9.73275e-05 0.000930396 0.000931161 0.00090263 0.000902411 0 0
306 30385000 0.712961 0.71107 0.00565948 0.00614574 0.0100664 0.0100195 0.701109 0.703023 -2.08905 -2.09133 -0.982408 -0.97391 0.739835 0.739919 -9.96671 -9.96372 -4.65234 -4.65679 -368.56 -368.561 -1.14863e-05 -1.23732e-05 -6.14877e-05 -6.08875e-05 2.58733e-07 -1.25081e-05 -0.000265512 -0.000241319 0.000223053 0.000255596 -0.000762219 -0.000758342 0.211711 0.212002 0.00200449 0.0020103 0.429174 0.429379 -0.00362432 -0.00323952 0.00186367 0.00193775 0.00288691 0.00259782 0 0 0.000207872 0.000209108 1.64003e-05 1.50673e-05 1.62854e-05 1.49627e-05 0.000215063 0.000213306 0.0284685 0.0282161 0.0295587 0.0292489 0.0337215 0.0339093 0.202482 0.20231 0.203302 0.203149 0.0908966 0.0910612 6.08551e-11 5.4787e-11 6.1019e-11 5.49358e-11 3.9793e-10 3.61247e-10 3.23081e-07 2.99924e-07 3.16001e-07 2.92632e-07 1.12476e-06 1.18315e-06 0.000930691 0.000931109 1.53544e-05 1.53767e-05 0.000906172 0.000906388 9.74346e-05 9.67853e-05 0.00092664 0.000927426 0.000898814 0.000898586 0 0
307 30485000 0.713033 0.711098 0.00550885 0.00600178 0.00979218 0.00974558 0.701041 0.703 -2.06106 -2.06368 -0.976365 -0.967144 0.727573 0.727642 -10.1741 -10.1714 -4.75027 -4.75384 -368.482 -1.14846e-05 -1.23718e-05 -6.14871e-05 -6.0887e-05 2.58845e-07 -1.25058e-05 -0.000265395 -0.000241204 0.000222742 0.000255288 -0.000765797 -0.000761998 0.211712 0.212005 0.00200468 0.00201059 0.429197 0.429412 -0.00359913 -0.00320417 0.00186155 0.00193566 0.00287641 0.00257485 0 0 0.000208225 0.000209458 1.6646e-05 1.52897e-05 1.65287e-05 1.5183e-05 0.000215506 0.00021368 0.0299233 0.0296513 0.0311905 0.0308544 0.0334642 0.0336493 0.214874 0.214663 0.215524 0.215333 0.0917427 0.0919096 6.09544e-11 5.48864e-11 6.11189e-11 5.50357e-11 3.9803e-10 3.61345e-10 3.23088e-07 2.9993e-07 3.15983e-07 2.92615e-07 1.12105e-06 1.17937e-06 0.000927215 0.000927641 1.52719e-05 1.52941e-05 0.00090257 0.00090279 9.69703e-05 9.63146e-05 0.000923084 0.000923891 0.000895212 0.000894974 0 0
308 30585000 0.713349 0.711422 0.00531841 0.00581004 0.00938623 0.00934111 0.700726 0.702679 -2.0407 -2.0433 -0.971117 -0.962253 0.691831 0.691899 -10.3984 -10.3953 -4.85047 -4.85517 -368.406 -1.14721e-05 -1.23608e-05 -6.14767e-05 -6.08753e-05 3.07439e-07 -1.24368e-05 -0.000262447 -0.000237156 0.00021679 0.000249442 -0.000768395 -0.000764553 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000197978 0.000199267 1.6701e-05 1.5338e-05 1.65872e-05 1.52344e-05 0.000204942 0.000203277 0.0280864 0.0278511 0.0292007 0.0289136 0.0313942 0.0315571 0.211978 0.21182 0.212838 0.212697 0.0889769 0.089122 6.10445e-11 5.49781e-11 6.1197e-11 5.51177e-11 3.96945e-10 3.60449e-10 3.20262e-07 2.96952e-07 3.14107e-07 2.90602e-07 1.11339e-06 1.17147e-06 0 0 0 0 0 0 0 0
309 30685000 0.713477 0.711549 0.00509688 0.00559536 0.00901206 0.00896698 0.700602 0.702557 -2.01262 -2.01554 -0.964383 -0.95492 0.684686 0.684731 -10.6011 -10.5983 -4.94717 -4.95086 -368.336 -368.337 -1.14723e-05 -1.23614e-05 -6.14753e-05 -6.08728e-05 3.19278e-07 -1.24135e-05 -0.000262135 -0.000236516 0.000216873 0.000249672 -0.000769017 -0.000765235 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000186934 0.000188241 1.69531e-05 1.55661e-05 1.68369e-05 1.54605e-05 0.00019353 0.000192017 0.0294865 0.0292325 0.0306913 0.0303833 0.0311278 0.0312886 0.224457 0.224265 0.2251 0.224925 0.0896908 0.089838 6.11422e-11 5.50763e-11 6.12854e-11 5.52082e-11 3.96008e-10 3.59691e-10 3.19613e-07 2.96314e-07 3.13944e-07 2.9045e-07 1.11022e-06 1.16825e-06 0 0 0 0 0 0 0 0
310 30785000 0.713468 0.711555 0.00495096 0.00544794 0.0086212 0.00858037 0.700617 0.702557 -1.98731 -1.9902 -0.955463 -0.946486 0.681619 0.681647 -10.8055 -10.8023 -5.03774 -5.04263 -368.258 -368.259 -1.14672e-05 -1.23576e-05 -6.14776e-05 -6.08731e-05 2.75714e-07 -1.24261e-05 -0.000264065 -0.000237487 0.000214623 0.000247794 -0.00077548 -0.000771711 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000176383 0.000177725 1.70044e-05 1.56115e-05 1.68915e-05 1.55088e-05 0.000182597 0.000181243 0.0276722 0.0274522 0.0287122 0.0284494 0.0292759 0.0294187 0.221426 0.22128 0.222266 0.222134 0.0871209 0.0872499 6.12387e-11 5.51735e-11 6.13728e-11 5.52978e-11 3.94834e-10 3.5872e-10 3.17407e-07 2.93951e-07 3.12548e-07 2.88917e-07 1.10403e-06 1.16187e-06 0 0 0 0 0 0 0 0
311 30885000 0.713478 0.711548 0.00471362 0.00521769 0.00815792 0.00811703 0.700615 0.702571 -1.95904 -1.96228 -0.948671 -0.93907 0.66972 0.669711 -11.0028 -11 -5.13284 -5.13673 -368.189 -368.19 -1.14672e-05 -1.23578e-05 -6.14763e-05 -6.08711e-05 2.87595e-07 -1.24063e-05 -0.000263753 -0.000236969 0.000214664 0.00024793 -0.000776518 -0.000772796 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000169967 0.000171308 1.72626e-05 1.58451e-05 1.71473e-05 1.57404e-05 0.00017589 0.000174603 0.0290402 0.0288018 0.0301791 0.0298953 0.0294648 0.0296086 0.233984 0.233809 0.234631 0.23447 0.0896847 0.0898217 6.13374e-11 5.52724e-11 6.14661e-11 5.53923e-11 3.94259e-10 3.58261e-10 3.17046e-07 2.93595e-07 3.12457e-07 2.88833e-07 1.10199e-06 1.1598e-06 0 0 0 0 0 0 0 0
312 30985000 0.713529 0.711609 0.00455945 0.00506104 0.00758536 0.00754656 0.700569 0.702517 -1.93907 -1.94222 -0.941688 -0.932557 0.664973 0.664944 -11.215 -11.2118 -5.22541 -5.23052 -368.118 -1.14695e-05 -1.23598e-05 -6.14742e-05 -6.08687e-05 2.68327e-07 -1.2399e-05 -0.000263897 -0.000236269 0.000210324 0.000243651 -0.000778568 -0.000774745 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000161362 0.000162722 1.73104e-05 1.58878e-05 1.71981e-05 1.57857e-05 0.000166952 0.000165785 0.0272817 0.0270737 0.0282662 0.0280223 0.0277795 0.0279081 0.230847 0.230711 0.231691 0.231566 0.0871856 0.0873067 6.14344e-11 5.53702e-11 6.15578e-11 5.54856e-11 3.93214e-10 3.57397e-10 3.15437e-07 2.91833e-07 3.11463e-07 2.87706e-07 1.09687e-06 1.15453e-06 0 0 0 0 0 0 0 0
313 31085000 0.713566 0.711636 0.00429662 0.00480552 0.00702503 0.00698611 0.70054 0.702498 -1.91172 -1.91521 -0.934814 -0.925097 0.653666 0.653596 -11.4076 -11.4047 -5.31928 -5.32336 -368.054 -368.055 -1.147e-05 -1.23606e-05 -6.14749e-05 -6.08684e-05 2.6339e-07 -1.23941e-05 -0.000264045 -0.000236164 0.000210399 0.00024384 -0.000777163 -0.000773341 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.0001543 0.000155655 1.75745e-05 1.61267e-05 1.74599e-05 1.60228e-05 0.000159633 0.000158546 0.0286121 0.0283858 0.0296718 0.0294081 0.0275251 0.0276521 0.243463 0.243304 0.244113 0.243965 0.0877049 0.0878281 6.15329e-11 5.54691e-11 6.16507e-11 5.55798e-11 3.9251e-10 3.56829e-10 3.15063e-07 2.91467e-07 3.11365e-07 2.87615e-07 1.09455e-06 1.15216e-06 0 0 0 0 0 0 0 0
314 31185000 0.713651 0.711725 0.00406226 0.00457015 0.00663094 0.00659536 0.700459 0.702413 -1.88462 -1.88807 -0.929669 -0.920407 0.643372 0.643259 -11.5979 -11.5945 -5.41373 -5.41906 -367.997 -1.14728e-05 -1.2363e-05 -6.14749e-05 -6.08683e-05 2.8508e-07 -1.23586e-05 -0.000263543 -0.000234813 0.000210954 0.000244711 -0.000772736 -0.000768891 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000147333 0.000148696 1.76176e-05 1.61655e-05 1.75057e-05 1.60642e-05 0.000152378 0.000151379 0.0269081 0.0267092 0.027825 0.0275965 0.026024 0.0261384 0.240243 0.240116 0.241087 0.240969 0.0853764 0.085486 6.1625e-11 5.55631e-11 6.17405e-11 5.56718e-11 3.91572e-10 3.56053e-10 3.13925e-07 2.90185e-07 3.10685e-07 2.86812e-07 1.09038e-06 1.14787e-06 0 0 0 0 0 0 0 0
315 31285000 0.713764 0.711826 0.00379038 0.00430559 0.00604462 0.00600889 0.70035 0.702317 -1.85589 -1.85969 -0.921693 -0.911849 0.644365 0.64421 -11.785 -11.782 -5.50614 -5.51043 -367.935 -1.1474e-05 -1.23644e-05 -6.1473e-05 -6.08657e-05 3.08063e-07 -1.23284e-05 -0.000263109 -0.000234158 0.000211281 0.000245133 -0.000771606 -0.000767799 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000141573 0.000142926 1.78872e-05 1.64095e-05 1.77732e-05 1.63064e-05 0.000146406 0.000145468 0.0281985 0.0279818 0.0291856 0.0289381 0.0257664 0.0258795 0.252904 0.252758 0.253564 0.253426 0.0857888 0.0859003 6.17238e-11 5.56622e-11 6.18346e-11 5.5767e-11 3.90937e-10 3.55543e-10 3.13635e-07 2.89901e-07 3.10608e-07 2.86742e-07 1.08839e-06 1.14585e-06 0 0 0 0 0 0 0 0
316 31385000 0.713809 0.711873 0.00351514 0.00402824 0.00543799 0.00540336 0.70031 0.702276 -1.83273 -1.83643 -0.916721 -0.907326 0.642927 0.642736 -11.9831 -11.9796 -5.6026 -5.60817 -367.87 -1.14881e-05 -1.23762e-05 -6.1477e-05 -6.08704e-05 3.0963e-07 -1.2308e-05 -0.000262277 -0.000232549 0.000209406 0.000243249 -0.0007701 -0.000766169 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000135815 0.000137169 1.79251e-05 1.64443e-05 1.78138e-05 1.63436e-05 0.000140413 0.00013954 0.026546 0.0263542 0.0274039 0.0271877 0.0244238 0.0245263 0.249622 0.249501 0.250473 0.250359 0.0836156 0.0837156 6.1806e-11 5.57484e-11 6.19168e-11 5.5853e-11 3.90076e-10 3.5483e-10 3.12846e-07 2.88984e-07 3.10163e-07 2.86188e-07 1.08497e-06 1.14234e-06 0 0 0 0 0 0 0 0
317 31485000 0.713728 0.711771 0.00326555 0.00378621 0.00475359 0.0047189 0.700399 0.702386 -1.8034 -1.80746 -0.909686 -0.89969 0.638355 0.638111 -12.1649 -12.1618 -5.6941 -5.69864 -367.807 -1.14877e-05 -1.23761e-05 -6.1479e-05 -6.08716e-05 2.86e-07 -1.23226e-05 -0.000262735 -0.000232848 0.000209248 0.000243169 -0.00076948 -0.000765521 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000132288 0.000133632 1.82e-05 1.66931e-05 1.80869e-05 1.6591e-05 0.000136727 0.000135877 0.0278172 0.027607 0.0287508 0.0285149 0.0245422 0.0246454 0.262316 0.26218 0.262996 0.262868 0.0857675 0.0858738 6.19053e-11 5.58478e-11 6.20131e-11 5.595e-11 3.89659e-10 3.54501e-10 3.12672e-07 2.88815e-07 3.10119e-07 2.86148e-07 1.0837e-06 1.14104e-06 0 0 0 0 0 0 0 0
318 31585000 0.71377 0.711811 0.00305191 0.00356924 0.00428031 0.00424993 0.700361 0.702349 -1.77543 -1.77942 -0.89862 -0.889111 0.635439 0.63516 -12.3462 -12.3426 -5.77742 -5.78327 -367.744 -1.14917e-05 -1.23788e-05 -6.14679e-05 -6.08636e-05 2.86729e-07 -1.23039e-05 -0.000263217 -0.000232909 0.000209134 0.000243278 -0.000769204 -0.00076529 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000127361 0.000128702 1.82313e-05 1.67225e-05 1.81206e-05 1.66227e-05 0.000131583 0.000130786 0.0262188 0.0260314 0.0270298 0.026822 0.0233109 0.0234048 0.258992 0.258875 0.259862 0.259752 0.083648 0.0837438 6.19728e-11 5.59224e-11 6.20823e-11 5.60257e-11 3.88847e-10 3.5383e-10 3.12137e-07 2.8817e-07 3.09845e-07 2.85785e-07 1.08085e-06 1.13812e-06 0 0 0 0 0 0 0 0
319 31685000 0.713821 0.711847 0.00276289 0.00328772 0.00358542 0.00355488 0.700314 0.702318 -1.74786 -1.7522 -0.89167 -0.881602 0.64087 0.640548 -12.5224 -12.5192 -5.86673 -5.87152 -367.679 -1.14924e-05 -1.23797e-05 -6.14654e-05 -6.08605e-05 3.1607e-07 -1.22666e-05 -0.00026269 -0.000232198 0.000209352 0.000243581 -0.000769573 -0.000765713 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000123266 0.000124595 1.85113e-05 1.6976e-05 1.83988e-05 1.68748e-05 0.000127304 0.000126543 0.0274588 0.0272526 0.028327 0.0280999 0.0230754 0.0231683 0.271702 0.271575 0.2724 0.27228 0.0839301 0.0840278 6.20719e-11 5.60217e-11 6.2178e-11 5.61222e-11 3.8829e-10 3.53383e-10 3.11945e-07 2.87984e-07 3.09795e-07 2.85739e-07 1.07939e-06 1.13663e-06 0 0 0 0 0 0 0 0
320 31785000 0.71389 0.711912 0.0024206 0.00294115 0.00281619 0.00278689 0.700248 0.702257 -1.72512 -1.72933 -0.883304 -0.873712 0.641293 0.640938 -12.7118 -12.708 -5.9527 -5.95883 -367.618 -1.15216e-05 -1.24043e-05 -6.14589e-05 -6.08578e-05 3.2127e-07 -1.22451e-05 -0.000262468 -0.000231579 0.000208526 0.000242578 -0.000767037 -0.000763115 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000119083 0.000120405 1.85347e-05 1.69989e-05 1.84249e-05 1.69003e-05 0.000122943 0.000122222 0.025906 0.025721 0.0266618 0.0264603 0.0219675 0.0220525 0.268353 0.268239 0.269237 0.269128 0.0819465 0.0820351 6.21207e-11 5.60814e-11 6.22299e-11 5.61841e-11 3.8752e-10 3.52747e-10 3.11596e-07 2.87546e-07 3.0964e-07 2.85515e-07 1.07705e-06 1.13424e-06 0 0 0 0 0 0 0 0
321 31885000 0.713951 0.711956 0.00210928 0.00263744 0.00205784 0.00202838 0.70019 0.702216 -1.6939 -1.69848 -0.874152 -0.863979 0.637377 0.636979 -12.8828 -12.8795 -6.0405 -6.04555 -367.555 -1.15219e-05 -1.24049e-05 -6.14582e-05 -6.08564e-05 3.30054e-07 -1.22272e-05 -0.000262326 -0.000231259 0.000208623 0.000242757 -0.000766784 -0.000762886 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000115578 0.000116889 1.88195e-05 1.72569e-05 1.87082e-05 1.71571e-05 0.000119312 0.000118621 0.0271391 0.0269341 0.0279519 0.02773 0.0217497 0.0218338 0.281071 0.280951 0.281788 0.281674 0.0821702 0.0822605 6.222e-11 5.61808e-11 6.2326e-11 5.62809e-11 3.86985e-10 3.52319e-10 3.11438e-07 2.87394e-07 3.09599e-07 2.85478e-07 1.0758e-06 1.13297e-06 0 0 0 0 0 0 0 0
322 31985000 0.713881 0.711884 0.00184769 0.00237259 0.00145899 0.0014351 0.700263 0.702292 -1.66115 -1.66565 -0.863562 -0.85388 0.633563 0.633132 -13.0455 -13.0416 -6.11947 -6.12587 -367.493 -1.15112e-05 -1.23936e-05 -6.14427e-05 -6.0846e-05 3.00329e-07 -1.22358e-05 -0.000263032 -0.000231751 0.000208686 0.00024318 -0.000766611 -0.000762769 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000111993 0.000113295 1.88336e-05 1.72722e-05 1.87247e-05 1.71747e-05 0.00011556 0.000114899 0.0256377 0.0254521 0.0263479 0.0261492 0.0207539 0.0208311 0.277713 0.2776 0.278614 0.278505 0.0803111 0.0803936 6.22455e-11 5.62217e-11 6.23561e-11 5.63252e-11 3.86244e-10 3.51707e-10 3.11217e-07 2.87109e-07 3.09521e-07 2.85354e-07 1.07389e-06 1.13101e-06 0 0 0 0 0 0 0 0
323 32085000 0.71381 0.711796 0.00151212 0.00204465 0.000687266 0.000663058 0.700337 0.702384 -1.63138 -1.63624 -0.85517 -0.844935 0.639771 0.639294 -13.2102 -13.2068 -6.20551 -6.21083 -367.434 -1.15117e-05 -1.23943e-05 -6.14439e-05 -6.08463e-05 2.88215e-07 -1.22382e-05 -0.000263281 -0.000231819 0.000208753 0.000243328 -0.000764819 -0.000760965 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000108993 0.000110283 1.9123e-05 1.75344e-05 1.90128e-05 1.74359e-05 0.000112416 0.000111778 0.0268441 0.0266383 0.0276045 0.0273852 0.0205438 0.0206202 0.290429 0.290313 0.291168 0.291057 0.0804855 0.0805697 6.23449e-11 5.63212e-11 6.24526e-11 5.64224e-11 3.85723e-10 3.5129e-10 3.11084e-07 2.86982e-07 3.09488e-07 2.85324e-07 1.07282e-06 1.12993e-06 0 0 0 0 0 0 0 0
324 32185000 0.713716 0.71169 0.00115218 0.00168032 -0.000241088 -0.000263189 0.700434 0.702492 -1.60526 -1.60998 -0.846596 -0.836831 0.641261 0.640752 -13.382 -13.3779 -6.28752 -6.29422 -367.373 -1.15363e-05 -1.24139e-05 -6.1439e-05 -6.08467e-05 2.26919e-07 -1.22785e-05 -0.000264001 -0.000232347 0.000208406 0.000242855 -0.000763195 -0.000759248 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000106638 0.000107919 1.91263e-05 1.75408e-05 1.9019e-05 1.74452e-05 0.000109964 0.000109333 0.0253812 0.0251939 0.0260504 0.0258527 0.0199086 0.0199802 0.287078 0.286963 0.288003 0.287892 0.0803208 0.0804012 6.2344e-11 5.63409e-11 6.24581e-11 5.64468e-11 3.85155e-10 3.50822e-10 3.10973e-07 2.86831e-07 3.09456e-07 2.85271e-07 1.07149e-06 1.12856e-06 0 0 0 0 0 0 0 0
325 32285000 0.713713 0.711669 0.000850556 0.00138631 -0.00105434 -0.00107662 0.700437 0.702513 -1.57375 -1.57886 -0.838045 -0.827713 0.635541 0.634983 -13.541 -13.5375 -6.37183 -6.37744 -367.314 -367.315 -1.15371e-05 -1.24149e-05 -6.14397e-05 -6.08465e-05 2.23041e-07 -1.22736e-05 -0.000264132 -0.000232306 0.000208555 0.000243077 -0.000761186 -0.000757236 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000103977 0.000105247 1.94201e-05 1.78071e-05 1.93116e-05 1.77106e-05 0.000107197 0.000106585 0.0265902 0.026381 0.0273075 0.0270876 0.0197158 0.0197867 0.299782 0.29967 0.300549 0.30044 0.0804583 0.0805402 6.24434e-11 5.64404e-11 6.25548e-11 5.65441e-11 3.8464e-10 3.5041e-10 3.10859e-07 2.86722e-07 3.09429e-07 2.85247e-07 1.07057e-06 1.12763e-06 0 0 0 0 0 0 0 0
326 32385000 0.713745 0.711695 0.000564701 0.00109761 -0.00177927 -0.00179546 0.700403 0.702485 -1.53669 -1.54171 -0.827774 -0.81792 0.637204 0.636631 -13.6868 -13.6826 -6.45067 -6.45763 -367.246 -1.15093e-05 -1.23871e-05 -6.14248e-05 -6.08383e-05 2.58447e-07 -1.22189e-05 -0.000263552 -0.000231602 0.000208398 0.00024335 -0.000763616 -0.000759806 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 0.000101223 0.000102482 1.94111e-05 1.78034e-05 1.93054e-05 1.77096e-05 0.000104307 0.000103714 0.0251706 0.0249789 0.0257995 0.0255998 0.018881 0.0189467 0.29645 0.296331 0.297393 0.297278 0.0787508 0.0788263 6.24117e-11 5.64351e-11 6.25298e-11 5.65438e-11 3.8393e-10 3.49824e-10 3.1075e-07 2.86603e-07 3.09393e-07 2.85217e-07 1.06926e-06 1.1263e-06 0 0 0 0 0 0 0 0
327 32485000 0.713692 0.711623 0.000388373 0.000927309 -0.00209114 -0.0021071 0.700457 0.702558 -1.50473 -1.51013 -0.818068 -0.807664 0.64378 0.643171 -13.8389 -13.8352 -6.53282 -6.53869 -367.182 -367.183 -1.15099e-05 -1.23879e-05 -6.14233e-05 -6.08362e-05 2.80012e-07 -1.21881e-05 -0.000263274 -0.00023117 0.000208552 0.000243574 -0.000763452 -0.000759687 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 9.89145e-05 0.000100161 1.97095e-05 1.80739e-05 1.96022e-05 1.79788e-05 0.000101866 0.000101287 0.0263618 0.0261476 0.0270344 0.026812 0.0186968 0.0187617 0.309133 0.309021 0.309923 0.309814 0.0788512 0.0789283 6.25112e-11 5.65347e-11 6.26265e-11 5.66412e-11 3.83417e-10 3.49414e-10 3.10651e-07 2.86509e-07 3.0937e-07 2.85198e-07 1.06848e-06 1.12551e-06 0 0 0 0 0 0 0 0
328 32585000 0.713599 0.711523 0.000307673 0.000840228 -0.00239118 -0.00240439 0.700551 0.702658 -1.47669 -1.48193 -0.809254 -0.799335 0.644656 0.644037 -13.9947 -13.9903 -6.61491 -6.62215 -367.112 -1.15309e-05 -1.24031e-05 -6.1426e-05 -6.08448e-05 2.61676e-07 -1.21815e-05 -0.000263374 -0.000231085 0.000208641 0.000243547 -0.000765092 -0.000761301 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 9.64958e-05 9.77319e-05 1.96883e-05 1.80601e-05 1.95829e-05 1.7967e-05 9.93195e-05 9.87557e-05 0.0249801 0.0247828 0.0255664 0.0253633 0.0179364 0.0179967 0.305832 0.305708 0.306795 0.306675 0.0772323 0.0773036 6.24459e-11 5.65021e-11 6.25689e-11 5.66145e-11 3.82714e-10 3.48834e-10 3.10545e-07 2.8642e-07 3.09312e-07 2.85173e-07 1.06741e-06 1.12442e-06 0 0 0 0 0 0 0 0
329 32685000 0.71355 0.711456 0.000222274 0.000760288 -0.00250694 -0.00251957 0.700599 0.702726 -1.44573 -1.45136 -0.800678 -0.790215 0.642152 0.641499 -14.1408 -14.137 -6.69534 -6.70147 -367.044 -1.15305e-05 -1.2403e-05 -6.14251e-05 -6.08432e-05 2.70116e-07 -1.21604e-05 -0.000263218 -0.000230782 0.000208588 0.000243571 -0.000766331 -0.000762577 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 9.44542e-05 9.56786e-05 1.99908e-05 1.83344e-05 1.98837e-05 1.82399e-05 9.7174e-05 9.66214e-05 0.0261794 0.0259575 0.0268045 0.0265767 0.0177692 0.0178288 0.318488 0.318374 0.319301 0.319191 0.0773014 0.0773741 6.25455e-11 5.66018e-11 6.26658e-11 5.6712e-11 3.82198e-10 3.4842e-10 3.10458e-07 2.86339e-07 3.09294e-07 2.85158e-07 1.06675e-06 1.12375e-06 0 0 0 0 0 0 0 0
330 32785000 0.713516 0.711408 0.000182561 0.000713866 -0.00254833 -0.00255477 0.700634 0.702774 -1.41368 -1.41918 -0.790374 -0.780405 0.639553 0.638884 -14.2782 -14.2736 -6.77008 -6.77759 -366.978 -1.1511e-05 -1.23813e-05 -6.14075e-05 -6.08344e-05 2.72349e-07 -1.21388e-05 -0.000262782 -0.000230437 0.000208114 0.000243321 -0.000767415 -0.000763718 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 9.28612e-05 9.40751e-05 1.99555e-05 1.83089e-05 1.9849e-05 1.82151e-05 9.54985e-05 9.49438e-05 0.0248323 0.024627 0.0253795 0.0251703 0.0173015 0.0173579 0.315233 0.315101 0.31622 0.316092 0.0772512 0.0773214 6.24426e-11 5.65386e-11 6.25724e-11 5.6656e-11 3.81652e-10 3.47972e-10 3.10347e-07 2.86274e-07 3.09194e-07 2.85121e-07 1.06603e-06 1.12302e-06 0 0 0 0 0 0 0 0
331 32885000 0.713378 0.711251 0.000199802 0.000736344 -0.00254431 -0.00254999 0.700775 0.702933 -1.38563 -1.39153 -0.781871 -0.771389 0.641207 0.640504 -14.418 -14.414 -6.84889 -6.8553 -366.914 -366.915 -1.15105e-05 -1.23811e-05 -6.14094e-05 -6.08353e-05 2.45057e-07 -1.21517e-05 -0.00026311 -0.000230599 0.000207976 0.000243263 -0.000767208 -0.000763502 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 9.10297e-05 9.22317e-05 2.02618e-05 1.85869e-05 2.01534e-05 1.84915e-05 9.35648e-05 9.30191e-05 0.0260237 0.0257927 0.0266024 0.0263676 0.0171425 0.0171983 0.327852 0.327735 0.328693 0.32858 0.0772959 0.0773675 6.25423e-11 5.66383e-11 6.26693e-11 5.67535e-11 3.81131e-10 3.47554e-10 3.10269e-07 2.86202e-07 3.09179e-07 2.85109e-07 1.06546e-06 1.12244e-06 0 0 0 0 0 0 0 0
332 32985000 0.713332 0.711195 0.000259423 0.000786918 -0.00257911 -0.00258226 0.700822 0.702989 -1.36054 -1.36623 -0.774967 -0.764988 0.63814 0.637427 -14.5643 -14.5595 -6.9262 -6.93398 -366.85 -366.851 -1.15464e-05 -1.24086e-05 -6.14059e-05 -6.08399e-05 2.74571e-07 -1.21026e-05 -0.000262626 -0.000230123 0.000209115 0.00024409 -0.000767019 -0.000763324 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 8.91107e-05 9.03012e-05 2.02108e-05 1.85484e-05 2.01024e-05 1.84531e-05 9.15289e-05 9.09916e-05 0.0247035 0.0244892 0.0252055 0.0249891 0.0164971 0.0165492 0.32465 0.324509 0.325654 0.325517 0.0758008 0.0758675 6.23992e-11 5.65423e-11 6.25359e-11 5.66649e-11 3.80429e-10 3.46976e-10 3.10083e-07 2.86094e-07 3.09004e-07 2.85027e-07 1.06474e-06 1.12171e-06 0 0 0 0 0 0 0 0
333 33085000 0.713415 0.711259 0.000182163 0.000714758 -0.00263535 -0.00263789 0.700737 0.702925 -1.33274 -1.33882 -0.768035 -0.757546 0.633124 0.632375 -14.6991 -14.6949 -7.00284 -7.0095 -366.785 -1.15478e-05 -1.24101e-05 -6.14005e-05 -6.08342e-05 3.4972e-07 -1.20203e-05 -0.000261757 -0.000229136 0.000209483 0.000244512 -0.000767559 -0.00076397 0.211801 0.212092 0.0020058 0.00201174 0.429283 0.429502 -0.00357704 -0.00318353 0.00185401 0.00192901 0.00278088 0.00247787 0 0 8.74721e-05 8.86512e-05 2.05202e-05 1.88293e-05 2.041e-05 1.87326e-05 8.98126e-05 8.92818e-05 0.0259056 0.0256635 0.0264354 0.0261915 0.0163526 0.0164041 0.337226 0.337104 0.33809 0.337972 0.0758227 0.0758907 6.24989e-11 5.6642e-11 6.26329e-11 5.67624e-11 3.79899e-10 3.4655e-10 3.10014e-07 2.8603e-07 3.08992e-07 2.85018e-07 1.06426e-06 1.12123e-06 0 0 0 0 0 0 0 0
334 33185000 0.710518 0.708352 0.0027164 0.00324443 -0.00201737 -0.00201279 0.703671 0.705849 -1.30425 -1.31018 -0.757692 -0.747607 0.584181 0.583422 -14.8263 -14.8213 -7.07256 -7.08058 -366.719 -1.15107e-05 -1.2371e-05 -6.13303e-05 -6.07674e-05 3.7355e-07 -1.19734e-05 -0.000257086 -0.000223933 0.000207365 0.000242635 -0.000772823 -0.00076957 0.212736 0.213051 0.00204054 0.00205611 0.429649 0.429845 -0.0034029 -0.00295159 0.000968559 0.00101891 0.00314204 0.00281275 0 0 8.54001e-05 8.65325e-05 2.021e-05 1.85732e-05 2.01077e-05 1.84818e-05 8.6722e-05 8.62203e-05 0.0246348 0.02441 0.0251115 0.0248869 0.0157769 0.0158252 0.334079 0.333928 0.335128 0.334978 0.0744066 0.0744702 6.20938e-11 5.63376e-11 6.1897e-11 5.61946e-11 3.79244e-10 3.46015e-10 3.05175e-07 2.8203e-07 3.0711e-07 2.8354e-07 1.05367e-06 1.10949e-06 0.00060864 0.000608854 1.49367e-05 1.49583e-05 0.000595381 0.000595554 8.73297e-05 8.67775e-05 0.000607356 0.000607694 0.000592997 0.000593018 0 0
335 33285000 0.662159 0.65983 0.0157315 0.0162645 -0.000861251 -0.000857578 0.749198 0.751238 -1.29984 -1.30622 -0.740735 -0.730111 0.55226 0.551485 -14.9563 -14.9519 -7.14746 -7.15439 -366.661 -1.15169e-05 -1.23771e-05 -6.12967e-05 -6.0725e-05 4.0363e-07 -1.19332e-05 -0.000254051 -0.000219987 0.000208034 0.00024335 -0.000771881 -0.000768616 0.212415 0.212726 0.0020591 0.0020837 0.429418 0.429611 -0.00327646 -0.00276926 0.00117507 0.00118195 0.00288241 0.0025399 0 0 9.11555e-05 9.20941e-05 2.03653e-05 1.87291e-05 2.02447e-05 1.86218e-05 7.76754e-05 7.73441e-05 0.0258725 0.0256176 0.0263398 0.0260894 0.015653 0.015701 0.346605 0.346478 0.347533 0.347406 0.0744124 0.0744771 6.21399e-11 5.63949e-11 6.14614e-11 5.58679e-11 3.78919e-10 3.45763e-10 3.00825e-07 2.78361e-07 3.06703e-07 2.83203e-07 1.05106e-06 1.10663e-06 0.00053927 0.000539282 1.46464e-05 1.46668e-05 0.000528295 0.000528481 7.85182e-05 7.80376e-05 0.000538515 0.000538585 0.000527001 0.000527103 0 0
336 33385000 0.561476 0.558889 0.0139696 0.0144886 -0.00160798 -0.00167722 0.827374 0.829114 -1.29732 -1.30328 -0.728382 -0.718349 0.744786 0.744014 -15.0883 -15.0831 -7.22101 -7.22938 -366.594 -366.595 -1.15579e-05 -1.24084e-05 -6.12686e-05 -6.07006e-05 4.27301e-07 -1.1891e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771796 -0.00076844 0.211456 0.21172 0.00206972 0.0021007 0.429737 0.429935 -0.00302184 -0.00247926 0.00158205 0.00147872 0.00310191 0.00275289 0 0 0.000103463 0.000104046 2.02247e-05 1.8614e-05 1.99951e-05 1.84167e-05 6.31865e-05 6.32028e-05 0.0243538 0.0241309 0.0247251 0.0245097 0.0150406 0.0150844 0.343545 0.343381 0.344661 0.344498 0.0730756 0.0731364 6.18716e-11 5.61965e-11 6.08864e-11 5.54242e-11 3.78527e-10 3.45447e-10 2.97605e-07 2.75732e-07 3.06039e-07 2.82743e-07 1.04974e-06 1.10523e-06 0.000494909 0.000494268 1.44466e-05 1.44665e-05 0.000504484 0.000504672 7.26033e-05 7.21863e-05 0.000493038 0.000492414 0.000503604 0.000503735 0 0
337 33485000 0.42554 0.422672 0.00753177 0.00802672 0.00102094 0.000849355 0.904908 0.906247 -1.28087 -1.28708 -0.723965 -0.713152 0.772925 0.772114 -15.2173 -15.2127 -7.29356 -7.30088 -366.515 -366.516 -1.15474e-05 -1.23996e-05 -6.12883e-05 -6.07131e-05 4.08746e-07 -1.19021e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771796 -0.00076844 0.211918 0.212157 0.00206136 0.00209564 0.429854 0.43005 -0.00311574 -0.00256599 0.00196912 0.00176699 0.003227 0.00287734 0 0 0.000118123 0.000118239 2.05724e-05 1.89256e-05 2.01632e-05 1.858e-05 4.85261e-05 4.8983e-05 0.0256965 0.0254064 0.0260526 0.0257755 0.0150225 0.0150711 0.355983 0.355846 0.35698 0.356844 0.0744047 0.0744687 6.19395e-11 5.62711e-11 6.08399e-11 5.54082e-11 3.78495e-10 3.45438e-10 0 0 0 0.000451062 0.000449978 1.43482e-05 1.43681e-05 0.000494815 0.000495006 7.06886e-05 7.03101e-05 0.000442535 0.000441375 0.000494096 0.000494241 0 0
338 33585000 0.269154 0.266081 0.00144077 0.00190197 -0.00138751 -0.00164767 0.963095 0.963947 -1.2402 -1.24612 -0.721793 -0.710955 0.737243 0.736403 -15.3273 -15.3219 -7.35345 -7.36218 -366.443 -366.444 -1.14954e-05 -1.23462e-05 -6.12438e-05 -6.06767e-05 3.64493e-07 -1.19308e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771796 -0.00076844 0.210631 0.210825 0.00203516 0.00207425 0.42973 0.429929 -0.00286776 -0.00232732 0.0015041 0.00116275 0.00314504 0.00279552 0 0 0.000129456 0.000129098 2.04108e-05 1.87897e-05 1.98433e-05 1.83149e-05 3.66109e-05 3.75317e-05 0.0247676 0.0244463 0.0250568 0.0247536 0.0146634 0.0147258 0.35313 0.352951 0.354306 0.354128 0.073066 0.0731262 6.15658e-11 5.59876e-11 6.03928e-11 5.50654e-11 3.78236e-10 3.45235e-10 0 0 0 0.000348899 0.000347295 1.42224e-05 1.42422e-05 0.000486555 0.000486749 6.8346e-05 6.80301e-05 0.000336603 0.000335041 0.000485952 0.000486109 0 0
339 33685000 0.102898 0.0996947 -0.00196709 -0.00154355 -0.00455184 -0.00490065 0.99468 0.995005 -1.18759 -1.19376 -0.719653 -0.707437 0.744722 0.743833 -15.4486 -15.4439 -7.42561 -7.43318 -366.367 -366.368 -1.15094e-05 -1.23583e-05 -6.12524e-05 -6.06756e-05 3.55088e-07 -1.19293e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771796 -0.00076844 0.210098 0.210301 0.00202476 0.00207007 0.429808 0.430013 -0.00283364 -0.00232543 0.00103822 0.000615571 0.00324299 0.00288759 0 0 0.000135926 0.000135127 2.06419e-05 1.90001e-05 1.98882e-05 1.83725e-05 2.99634e-05 3.12896e-05 0.0263535 0.0259397 0.0266553 0.0262673 0.0148941 0.0149833 0.365224 0.365083 0.366285 0.366143 0.0729727 0.0730344 6.16114e-11 5.60445e-11 6.03247e-11 5.50313e-11 3.78151e-10 3.4518e-10 0 0 0 0.000256747 0.000255171 1.40799e-05 1.40988e-05 0.000481083 0.000481278 6.64495e-05 6.61697e-05 0.00024025 0.000238854 0.000480549 0.000480706 0 0
340 33785000 -0.0669402 -0.0701547 -0.00362399 -0.00326829 -0.00638425 -0.00679412 0.99773 0.997508 -1.12766 -1.13361 -0.703097 -0.690426 0.728115 0.727214 -15.5703 -15.5648 -7.48589 -7.49502 -366.291 -1.15684e-05 -1.24021e-05 -6.12894e-05 -6.07109e-05 1.91894e-07 -1.2053e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771796 -0.00076844 0.209242 0.209483 0.00194993 0.00200491 0.42947 0.429686 -0.00253473 -0.00207367 0.000640432 0.000187295 0.00304236 0.00268099 0 0 0.000135394 0.000134273 2.01749e-05 1.85985e-05 1.92913e-05 1.78616e-05 2.92591e-05 3.08666e-05 0.0254602 0.0250264 0.0257097 0.0253074 0.0149875 0.0151101 0.36284 0.362646 0.364079 0.363885 0.0716963 0.0717553 6.10875e-11 5.56397e-11 5.96556e-11 5.45056e-11 3.77742e-10 3.44848e-10 0 0 0 0.000189673 0.00018836 1.38987e-05 1.39159e-05 0.00047712 0.000477316 6.37273e-05 6.34759e-05 0.00017061 0.000169576 0.000476643 0.000476799 0 0
341 33885000 -0.234586 -0.23772 -0.00481551 -0.00453364 -0.00707175 -0.00755229 0.972058 0.971294 -1.061 -1.06753 -0.681838 -0.667221 0.714785 0.713865 -15.6793 -15.6745 -7.55536 -7.56316 -366.219 -366.22 -1.15858e-05 -1.24167e-05 -6.14116e-05 -6.08032e-05 5.52318e-08 -1.21579e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771796 -0.00076844 0.208472 0.208765 0.00186615 0.00193341 0.429348 0.429574 -0.00223993 -0.00184151 0.000142155 -0.000306571 0.00304848 0.0026781 0 0 0.000128523 0.000127233 2.01535e-05 1.85873e-05 1.9179e-05 1.77756e-05 3.45802e-05 3.63137e-05 0.0272541 0.0267127 0.0274843 0.0269886 0.0156799 0.0158514 0.374608 0.37446 0.375725 0.375575 0.0715861 0.0716488 6.11658e-11 5.57223e-11 5.94302e-11 5.43426e-11 3.77426e-10 3.44599e-10 0 0 0 0.000145742 0.000144643 1.36823e-05 1.36971e-05 0.000474167 0.00047436 5.99393e-05 5.97152e-05 0.000125528 0.000124809 0.000473737 0.000473888 0 0
342 33985000 -0.382463 -0.385413 -0.00340854 -0.0032094 -0.0105638 -0.0110588 0.923904 0.922673 -1.00678 -1.01325 -0.644403 -0.629328 0.687296 0.686395 -15.808 -15.8026 -7.61325 -7.62281 -366.149 -1.17758e-05 -1.25772e-05 -6.14164e-05 -6.08066e-05 -9.98074e-08 -1.22583e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771796 -0.00076844 0.208799 0.209111 0.00182533 0.00190895 0.429252 0.429492 -0.00197847 -0.00164648 0.000395802 -4.10564e-05 0.00303195 0.00265416 0 0 0.000116657 0.000115388 1.92683e-05 1.78199e-05 1.83689e-05 1.70705e-05 4.35952e-05 4.5262e-05 0.0263641 0.0258174 0.0265038 0.0260118 0.0161819 0.0164033 0.372652 0.37244 0.373949 0.37374 0.0704004 0.0704624 6.04808e-11 5.51867e-11 5.84693e-11 5.35767e-11 3.76709e-10 3.44008e-10 2.97609e-07 2.75736e-07 3.06043e-07 2.82747e-07 1.04974e-06 1.10523e-06 0.000117343 0.000116439 1.34455e-05 1.34574e-05 0.000471803 0.000471993 5.54644e-05 5.52702e-05 9.74032e-05 9.69209e-05 0.000471415 0.000471562 0 0
343 34085000 -0.490811 -0.493595 -0.00223198 -0.00209451 -0.0122743 -0.012791 0.871177 0.869595 -0.952057 -0.95951 -0.599918 -0.58299 0.689449 0.688554 -15.9056 -15.901 -7.67556 -7.68351 -366.077 -366.078 -1.1779e-05 -1.25797e-05 -6.14593e-05 -6.08286e-05 -1.53756e-07 -1.22854e-05 -0.000251454 -0.000216975 0.000211013 0.000246008 -0.000771808 -0.000768452 0.208691 0.209022 0.00179608 0.00189159 0.429322 0.429569 -0.00188067 -0.00160204 0.000279749 -0.000134496 0.0031297 0.00274436 0 0 0.000105703 0.000104534 1.89966e-05 1.75874e-05 1.82419e-05 1.69638e-05 5.28733e-05 5.43911e-05 0.0283218 0.0276568 0.0283865 0.0277951 0.0175871 0.0178857 0.384111 0.383956 0.38528 0.385122 0.071619 0.0716922 6.0575e-11 5.5282e-11 5.82764e-11 5.34385e-11 3.76363e-10 3.43734e-10 2.97619e-07 2.75746e-07 3.06053e-07 2.82757e-07 1.04975e-06 1.10524e-06 0.000103215 0.000102381 1.32692e-05 1.32786e-05 0.00047037 0.000470558 5.20409e-05 5.18667e-05 8.35495e-05 8.31872e-05 0.000470011 0.000470155 0 0
344 34185000 -0.562266 -0.56488 -0.00201989 -0.00196039 -0.0109501 -0.0114489 0.826882 0.825092 -0.926243 -0.933464 -0.555452 -0.538315 0.692021 0.691229 -16.0474 -16.0423 -7.74292 -7.75291 -366.006 -1.21872e-05 -1.29355e-05 -6.15765e-05 -6.09394e-05 -2.50239e-07 -1.23242e-05 -0.000254041 -0.000219489 0.000213264 0.000247872 -0.000772326 -0.000769038 0.209138 0.209453 0.00177649 0.00188856 0.429189 0.429452 -0.00169085 -0.00147785 0.000322683 -6.26847e-05 0.0030385 0.00265235 0 0 9.58704e-05 9.48358e-05 1.79107e-05 1.66387e-05 1.73192e-05 1.61522e-05 5.92214e-05 6.05543e-05 0.0273762 0.0267242 0.0273213 0.0267505 0.0186646 0.0190383 0.382545 0.382317 0.383888 0.383665 0.0705124 0.0705881 5.97306e-11 5.46159e-11 5.72173e-11 5.25874e-11 3.75507e-10 3.4303e-10 2.97567e-07 2.75703e-07 3.05998e-07 2.82711e-07 1.04939e-06 1.10484e-06 8.96435e-05 8.89249e-05 1.30451e-05 1.30517e-05 0.000468704 0.000468889 4.77934e-05 4.76417e-05 7.09629e-05 7.0718e-05 0.000468376 0.000468516 0 0
345 34285000 -0.606777 -0.609284 -0.00289676 -0.0028846 -0.0080422 -0.00855504 0.794826 0.792901 -0.876518 -0.884816 -0.507721 -0.488711 0.69107 0.690312 -16.1374 -16.1331 -7.79613 -7.80431 -365.936 -365.937 -1.21854e-05 -1.29339e-05 -6.16366e-05 -6.09746e-05 -3.35935e-07 -1.23752e-05 -0.000254031 -0.000219483 0.000213271 0.000247876 -0.000772338 -0.000769054 0.209276 0.209595 0.00173786 0.00186372 0.429165 0.429433 -0.00144727 -0.00129532 0.00034778 -2.85577e-06 0.00305025 0.00265943 0 0 8.93155e-05 8.83751e-05 1.76281e-05 1.63937e-05 1.71354e-05 1.59925e-05 6.34095e-05 6.46023e-05 0.02953 0.0287483 0.0293463 0.0286707 0.0206625 0.0211491 0.393716 0.393552 0.394934 0.394769 0.0706023 0.0706951 5.98286e-11 5.47143e-11 5.70109e-11 5.24364e-11 3.7502e-10 3.42638e-10 2.97577e-07 2.75713e-07 3.06008e-07 2.82721e-07 1.04939e-06 1.10484e-06 8.08055e-05 8.01209e-05 1.28467e-05 1.28502e-05 0.000467426 0.000467609 4.41248e-05 4.39897e-05 6.25894e-05 6.24155e-05 0.000467119 0.000467257 0 0
346 34385000 -0.633752 -0.636172 -0.00355405 -0.00359253 -0.00530465 -0.00578582 0.77351 0.771517 -0.847956 -0.855823 -0.467722 -0.448801 0.690961 0.690297 -16.2695 -16.2647 -7.85681 -7.86718 -365.868 -365.869 -1.26148e-05 -1.33081e-05 -6.17591e-05 -6.11003e-05 -4.10656e-07 -1.23952e-05 -0.000259203 -0.00022469 0.000219131 0.000252811 -0.00077155 -0.00076832 0.209729 0.210017 0.00173061 0.00187022 0.429037 0.429317 -0.00129189 -0.00119208 0.00037354 4.94095e-05 0.00292223 0.00253549 0 0 8.43144e-05 8.34375e-05 1.65725e-05 1.5467e-05 1.61643e-05 1.51347e-05 6.52657e-05 6.63363e-05 0.0284971 0.0277489 0.0282296 0.0275885 0.022222 0.022799 0.392494 0.392252 0.393872 0.393637 0.0696506 0.0697502 5.88565e-11 5.3942e-11 5.59808e-11 5.16034e-11 3.74165e-10 3.41937e-10 2.97262e-07 2.75443e-07 3.05676e-07 2.82438e-07 1.04726e-06 1.10249e-06 7.3905e-05 7.33029e-05 1.26678e-05 1.26694e-05 0.000466247 0.000466425 4.10585e-05 4.09353e-05 5.66731e-05 5.65512e-05 0.000465951 0.000466084 0 0
347 34485000 -0.650127 -0.652509 -0.00450327 -0.00456697 -0.00306532 -0.00355405 0.759806 0.757759 -0.793715 -0.802591 -0.425781 -0.405067 0.690391 0.68975 -16.3514 -16.3475 -7.90153 -7.90992 -365.801 -1.26149e-05 -1.33083e-05 -6.18043e-05 -6.11276e-05 -4.83138e-07 -1.24393e-05 -0.000259172 -0.000224672 0.000219142 0.000252816 -0.000771429 -0.000768197 0.209672 0.209956 0.0016985 0.00184838 0.429047 0.429328 -0.00119066 -0.00113721 0.000233853 -6.12799e-05 0.00294812 0.00256066 0 0 8.1402e-05 8.05528e-05 1.6366e-05 1.52882e-05 1.59923e-05 1.49854e-05 6.64908e-05 6.74837e-05 0.0307878 0.0299043 0.0303892 0.0296377 0.0248591 0.025578 0.403401 0.40323 0.404657 0.404485 0.0699757 0.0701046 5.89562e-11 5.40418e-11 5.58829e-11 5.15404e-11 3.73753e-10 3.41608e-10 2.97272e-07 2.75453e-07 3.05686e-07 2.82448e-07 1.04719e-06 1.10241e-06 6.92783e-05 6.86892e-05 1.25142e-05 1.25135e-05 0.000465325 0.000465502 3.85143e-05 3.83993e-05 5.23526e-05 5.2262e-05 0.000465035 0.000465166 0 0
348 34585000 -0.660054 -0.662401 -0.00466438 -0.00476809 -0.0018088 -0.00225781 0.751202 0.749131 -0.772388 -0.780331 -0.398924 -0.378408 0.690337 0.689832 -16.4915 -16.4872 -7.97099 -7.98177 -365.731 -1.32365e-05 -1.38567e-05 -6.20504e-05 -6.13748e-05 -4.72174e-07 -1.2381e-05 -0.000271173 -0.000236581 0.000231243 0.000263368 -0.000770898 -0.000767761 0.210088 0.21033 0.00171625 0.00187661 0.428995 0.429288 -0.00118811 -0.00117446 0.000113838 -0.000159947 0.0028832 0.00250488 0 0 7.87129e-05 7.78727e-05 1.5352e-05 1.43934e-05 1.50126e-05 1.41163e-05 6.64654e-05 6.73796e-05 0.0296033 0.0287773 0.0291681 0.0284673 0.0266545 0.0274601 0.402481 0.402229 0.403885 0.403641 0.0692015 0.0693413 5.7895e-11 5.31929e-11 5.4891e-11 5.07338e-11 3.7292e-10 3.40926e-10 2.96559e-07 2.74838e-07 3.04937e-07 2.81805e-07 1.04208e-06 1.09676e-06 6.50375e-05 6.45197e-05 1.23722e-05 1.23703e-05 0.000464376 0.000464545 3.63985e-05 3.62893e-05 4.90318e-05 4.8967e-05 0.000464087 0.00046421 0 0
349 34685000 -0.666253 -0.668595 -0.00504 -0.0051553 -0.000988871 -0.00144096 0.745708 0.743607 -0.71614 -0.725003 -0.357857 -0.33562 0.687085 0.686615 -16.5658 -16.5624 -8.00885 -8.01748 -365.658 -365.659 -1.32369e-05 -1.38573e-05 -6.20762e-05 -6.13883e-05 -5.31669e-07 -1.24146e-05 -0.000271132 -0.000236559 0.000231263 0.000263381 -0.00077165 -0.000768557 0.210325 0.210561 0.0016981 0.00186655 0.429 0.429294 -0.000978358 -0.00100105 0.000224081 -2.79185e-05 0.00284591 0.00246776 0 0 7.73587e-05 7.65105e-05 1.519e-05 1.42531e-05 1.4858e-05 1.39825e-05 6.66871e-05 6.75551e-05 0.0319989 0.0310361 0.0314355 0.0306214 0.0298061 0.030773 0.413148 0.41297 0.414432 0.414255 0.0698475 0.0700313 5.79947e-11 5.32926e-11 5.48683e-11 5.07322e-11 3.72567e-10 3.40647e-10 2.96569e-07 2.74847e-07 3.04947e-07 2.81815e-07 1.04181e-06 1.09647e-06 6.22539e-05 6.17418e-05 1.22503e-05 1.22469e-05 0.000463655 0.000463823 3.46266e-05 3.45212e-05 4.64474e-05 4.63978e-05 0.000463367 0.000463487 0 0
350 34785000 -0.67018 -0.672514 -0.00459426 -0.00473808 -0.00060649 -0.00101469 0.742184 0.740069 -0.696521 -0.704236 -0.335482 -0.313667 0.684794 0.68455 -16.6981 -16.6943 -8.07461 -8.08576 -365.587 -1.38906e-05 -1.44368e-05 -6.23793e-05 -6.16963e-05 -5.68825e-07 -1.24057e-05 -0.00028647 -0.000251969 0.000248103 0.000278233 -0.000775333 -0.000772532 0.210938 0.211134 0.00170048 0.0018759 0.428869 0.429175 -0.000808441 -0.000855537 0.000148214 -9.24999e-05 0.00266367 0.00229678 0 0 7.5806e-05 7.49359e-05 1.42215e-05 1.33934e-05 1.39089e-05 1.31357e-05 6.62105e-05 6.70188e-05 0.0306313 0.0297501 0.030079 0.0293318 0.0317779 0.0328129 0.412492 0.412232 0.413911 0.413663 0.0704678 0.0706712 5.68872e-11 5.24007e-11 5.39318e-11 4.99668e-11 3.7185e-10 3.40063e-10 2.95384e-07 2.7382e-07 3.0371e-07 2.80747e-07 1.03293e-06 1.08667e-06 5.97853e-05 5.93363e-05 1.21598e-05 1.21562e-05 0.000463006 0.000463163 3.34767e-05 3.33737e-05 4.48253e-05 4.47876e-05 0.000462717 0.000462827 0 0
351 34885000 -0.672706 -0.67505 -0.00463453 -0.00478378 -0.000488549 -0.000897592 0.739896 0.737756 -0.642261 -0.650774 -0.297572 -0.274118 0.683623 0.683418 -16.7649 -16.762 -8.10628 -8.11515 -365.516 -365.517 -1.38891e-05 -1.44356e-05 -6.2401e-05 -6.17088e-05 -6.17084e-07 -1.24318e-05 -0.000286404 -0.000251931 0.000248119 0.000278241 -0.000776114 -0.000773355 0.210911 0.211101 0.00168269 0.00186448 0.428861 0.429167 -0.000758075 -0.000834862 6.39403e-05 -0.000159071 0.00266454 0.00229903 0 0 7.50817e-05 7.4188e-05 1.40877e-05 1.32776e-05 1.37739e-05 1.3019e-05 6.61297e-05 6.69043e-05 0.0330765 0.0320617 0.0323994 0.0315403 0.0352914 0.0364959 0.422941 0.422758 0.424245 0.424065 0.0715307 0.0717958 5.69861e-11 5.24998e-11 5.39521e-11 5.00004e-11 3.71525e-10 3.39808e-10 2.95394e-07 2.7383e-07 3.0372e-07 2.80757e-07 1.03237e-06 1.08606e-06 5.78468e-05 5.7401e-05 1.20569e-05 1.2052e-05 0.000462417 0.000462572 3.21455e-05 3.20442e-05 4.30356e-05 4.30065e-05 0.000462128 0.000462235 0 0
352 34985000 -0.675853 -0.678192 -0.0112604 -0.0114315 -0.00283111 -0.00321707 0.736945 0.734788 0.322697 0.311685 0.328894 0.358451 -0.101465 -0.101127 -16.8367 -16.8339 -8.13297 -8.14399 -365.51 -1.46984e-05 -1.516e-05 -6.2786e-05 -6.20959e-05 -5.86002e-07 -1.23606e-05 -0.000309513 -0.000274947 0.000273477 0.000301041 -0.000780454 -0.000777969 0.211519 0.211667 0.00170702 0.00189484 0.428801 0.429124 -0.000707991 -0.000804968 -7.89808e-05 -0.000291883 0.00259987 0.00224284 0 0 7.35784e-05 7.26584e-05 1.31435e-05 1.24331e-05 1.2926e-05 1.22606e-05 6.5591e-05 6.63008e-05 0.0332822 0.032333 0.0341203 0.0332428 0.0379574 0.0392105 0.422434 0.422173 0.423775 0.423529 0.0711367 0.0714144 5.58744e-11 5.15987e-11 5.30416e-11 4.92522e-11 3.70796e-10 3.39213e-10 0 0 0 5.55012e-05 5.5114e-05 1.19631e-05 1.19583e-05 0.000461671 0.000461811 3.12202e-05 3.11208e-05 4.15683e-05 4.1548e-05 0.000461375 0.000461468 0 0
353 35085000 -0.676011 -0.678371 -0.0116462 -0.0118188 -0.00323003 -0.00361701 0.736792 0.734615 0.540888 0.529302 0.349347 0.381555 -0.204258 -0.203858 -16.7849 -16.7832 -8.09975 -8.10762 -365.521 -365.522 -1.46942e-05 -1.51564e-05 -6.28078e-05 -6.21106e-05 -6.44539e-07 -1.23965e-05 -0.000309513 -0.000274947 0.000273477 0.000301041 -0.000780454 -0.000777969 0.211491 0.211634 0.00168643 0.00187956 0.428791 0.42912 -0.000657 -0.00077942 -0.000184325 -0.00038288 0.00265324 0.00229121 0 0 7.32634e-05 7.23096e-05 1.30321e-05 1.23369e-05 1.28151e-05 1.21657e-05 6.53151e-05 6.59988e-05 0.0356394 0.0345809 0.0368506 0.0358652 0.0402655 0.0416141 0.432613 0.432433 0.433706 0.433533 0.0726946 0.0730493 5.5972e-11 5.16966e-11 5.3091e-11 4.93099e-11 3.70479e-10 3.38964e-10 0 0 0 5.41195e-05 5.37333e-05 1.1874e-05 1.18683e-05 0.000461122 0.000461256 3.01941e-05 3.00953e-05 4.03052e-05 4.02897e-05 0.000460821 0.000460905 0 0
354 35185000 -0.676064 -0.678448 -0.0116743 -0.011848 -0.00326444 -0.00365064 0.736743 0.734544 0.570353 0.558047 0.387156 0.420682 -0.189577 -0.188723 -16.7291 -16.7287 -8.06302 -8.06759 -365.523 -1.46753e-05 -1.51394e-05 -6.28148e-05 -6.2113e-05 -7.02569e-07 -1.24405e-05 -0.000309513 -0.000274947 0.000273477 0.000301041 -0.000780454 -0.000777969 0.211647 0.211788 0.00166838 0.00186693 0.428981 0.429319 -0.000554747 -0.000701387 -0.000196302 -0.000382857 0.00287439 0.00251051 0 0 7.25557e-05 7.15382e-05 1.29249e-05 1.2245e-05 1.27061e-05 1.2072e-05 6.45468e-05 6.51482e-05 0.0378434 0.0366776 0.0389646 0.037889 0.0394291 0.0406734 0.443434 0.443317 0.444298 0.444183 0.0722424 0.0725957 5.60653e-11 5.17909e-11 5.31488e-11 4.93749e-11 3.70169e-10 3.38722e-10 0 0 0 5.28196e-05 5.24206e-05 1.17908e-05 1.17844e-05 0.000460435 0.000460547 2.92994e-05 2.92008e-05 3.92275e-05 3.92158e-05 0.000460128 0.000460189 0 0
355 35285000 -0.67611 -0.678519 -0.0116906 -0.011866 -0.00333742 -0.00372272 0.7367 0.734478 0.601321 0.588349 0.425228 0.46013 -0.184891 -0.183918 -16.6704 -16.6712 -8.02247 -8.02359 -365.532 -1.46708e-05 -1.51354e-05 -6.28338e-05 -6.21265e-05 -7.79632e-07 -1.24945e-05 -0.000309513 -0.000274947 0.000273477 0.000301041 -0.000780454 -0.000777969 0.211694 0.21183 0.001647 0.00184997 0.429013 0.429355 -0.000456638 -0.000625161 -0.000252569 -0.000427854 0.00295607 0.00258792 0 0 7.23675e-05 7.13115e-05 1.28258e-05 1.21601e-05 1.26033e-05 1.1984e-05 6.4342e-05 6.49169e-05 0.0401398 0.0388628 0.0411653 0.0399964 0.0412516 0.0425642 0.454962 0.454889 0.455618 0.455541 0.0740151 0.0744471 5.61613e-11 5.18875e-11 5.32154e-11 4.9447e-11 3.69866e-10 3.38485e-10 0 0 0 5.17882e-05 5.13891e-05 1.17126e-05 1.17055e-05 0.000459976 0.000460082 2.85125e-05 2.84137e-05 3.82977e-05 3.82888e-05 0.000459664 0.000459718 0 0
356 35385000 -0.6762 -0.678639 -0.0117338 -0.0119096 -0.00332148 -0.00370504 0.736617 0.734366 0.631641 0.617934 0.462817 0.499048 -0.169735 -0.168389 -16.6086 -16.6108 -7.97827 -7.97584 -365.531 -365.53 -1.46551e-05 -1.51214e-05 -6.28505e-05 -6.21398e-05 -8.70434e-07 -1.25741e-05 -0.000309513 -0.000274947 0.000273477 0.000301041 -0.000780454 -0.000777969 0.211794 0.21193 0.00162088 0.00182732 0.429079 0.429427 -0.000352427 -0.000536904 -0.000336674 -0.00050472 0.0030895 0.00272147 0 0 7.18928e-05 7.07696e-05 1.27307e-05 1.20793e-05 1.25083e-05 1.19031e-05 6.37684e-05 6.4264e-05 0.0425284 0.0411354 0.0434479 0.0421816 0.0404923 0.0417015 0.467265 0.467212 0.46773 0.46767 0.0748701 0.0753035 5.62547e-11 5.19819e-11 5.32935e-11 4.95289e-11 3.69665e-10 3.38333e-10 0 0 0 5.09782e-05 5.05658e-05 1.1657e-05 1.16494e-05 0.000459464 0.000459551 2.79819e-05 2.78828e-05 3.76796e-05 3.76724e-05 0.000459148 0.000459184 0 0
357 35485000 -0.676329 -0.678793 -0.0117596 -0.011937 -0.0033271 -0.00370936 0.736498 0.734223 0.662788 0.648419 0.499668 0.537281 -0.165778 -0.164333 -16.5438 -16.5474 -7.93034 -7.92419 -365.538 -365.537 -1.46505e-05 -1.51173e-05 -6.28701e-05 -6.21547e-05 -9.67454e-07 -1.26472e-05 -0.000309513 -0.000274947 0.000273477 0.000301041 -0.000780454 -0.000777969 0.211846 0.211978 0.00159679 0.00180704 0.429089 0.429442 -0.000240005 -0.000444008 -0.000400606 -0.000559252 0.0031576 0.00278584 0 0 7.17684e-05 7.06044e-05 1.26399e-05 1.20021e-05 1.24148e-05 1.18237e-05 6.36299e-05 6.40981e-05 0.045008 0.0434951 0.0458146 0.0444481 0.0421914 0.0434567 0.480414 0.480354 0.480702 0.480634 0.0768415 0.0773534 5.6349e-11 5.2077e-11 5.33703e-11 4.96095e-11 3.69363e-10 3.38097e-10 0 0 0 5.01486e-05 4.97358e-05 1.15857e-05 1.15776e-05 0.000459064 0.000459145 2.7342e-05 2.72423e-05 3.69439e-05 3.69385e-05 0.000458744 0.000458772 0 0
358 35585000 0.686275 0.692836 0.0117155 0.0118653 0.00351855 0.00396658 -0.72724 -0.720986 0.0368605 0.0357919 0.0353775 0.0368406 -0.000929043 -0.000926509 -11.5844 -17.2182 -17.2181 -365.535 -365.534 -1.46466e-05 -1.51137e-05 -6.28793e-05 -6.21626e-05 -9.99507e-07 -1.26731e-05 -0.000309513 -0.000274947 0.000273477 0.000301041 -0.000780456 -0.000777971 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00139393 0.00137012 1.27121e-05 1.2084e-05 1.27991e-05 1.22183e-05 0.00124103 0.00126413 0.0346583 0.0346564 0.0346489 0.0346459 0.0375565 0.0375612 0.12528 0.12528 0.0723287 0.0727829 5.64472e-11 5.21754e-11 5.34651e-11 4.97052e-11 3.69362e-10 3.38113e-10 2.93716e-07 2.72368e-07 3.01976e-07 2.79243e-07 1.01968e-06 1.07212e-06 0 0 0 0 0 0 0 0
359 35685000 0.686261 0.692865 0.0117247 0.0118738 0.00349247 0.00393577 -0.727253 -0.720959 0.0667464 0.0644995 0.0742966 0.0773805 -0.00067699 -0.000674672 -11.5792 -11.5794 -17.2127 -17.2124 -365.53 -365.529 -1.46455e-05 -1.51128e-05 -6.28786e-05 -6.21619e-05 -9.98297e-07 -1.2672e-05 -0.000309513 -0.000274946 0.000273476 0.000301041 -0.000780493 -0.000778009 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00139402 0.00137006 1.27721e-05 1.21434e-05 1.286e-05 1.22789e-05 0.00124102 0.00126427 0.0350349 0.0350241 0.034993 0.0349773 0.0381125 0.0381386 0.12625 0.126249 0.068388 0.0687823 5.6547e-11 5.22752e-11 5.35649e-11 4.98051e-11 3.69462e-10 3.38213e-10 2.93726e-07 2.72378e-07 3.01986e-07 2.79253e-07 1.01969e-06 1.07213e-06 0 0 0 0 0 0 0 0
360 35785000 0.686246 0.692892 0.0117416 0.0118904 0.00353142 0.00396973 -0.727266 -0.720932 0.0899857 0.0868615 0.103525 0.107841 -0.000306539 -0.000305553 -11.5758 -11.5762 -17.2087 -17.2083 -365.524 -365.523 -1.4644e-05 -1.51114e-05 -6.28773e-05 -6.21609e-05 -9.9685e-07 -1.26708e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000780851 -0.000778389 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00139359 0.00136947 1.28264e-05 1.21981e-05 1.29145e-05 1.23338e-05 0.00124057 0.00126395 0.031084 0.0310664 0.0310056 0.030978 0.0365336 0.0365932 0.0848515 0.0848512 0.0848505 0.0848501 0.0654108 0.0657557 5.66468e-11 5.2375e-11 5.36648e-11 4.9905e-11 3.69562e-10 3.38313e-10 0 0 1.01919e-06 1.07158e-06 0 0 0 0 0 0 0 0
361 35885000 0.686254 0.692942 0.0117573 0.0119046 0.00359646 0.00403009 -0.727258 -0.720884 0.119497 0.115188 0.14315 0.14907 0.000993592 0.000991605 -11.5654 -11.5661 -17.1964 -17.1954 -365.518 -1.46429e-05 -1.51104e-05 -6.28765e-05 -6.21603e-05 -9.95497e-07 -1.26696e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000781224 -0.000778778 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00139363 0.00136935 1.28926e-05 1.22636e-05 1.29815e-05 1.24001e-05 0.00124066 0.00126418 0.0316318 0.0316057 0.0314824 0.0314371 0.0376875 0.0378011 0.0865344 0.0865335 0.0865303 0.0865289 0.0634357 0.0637398 5.67466e-11 5.24749e-11 5.37647e-11 5.0005e-11 3.69662e-10 3.38412e-10 0 0 1.01918e-06 1.07157e-06 0 0 0 0 0 0 0 0
362 35985000 0.686269 0.693002 0.0116462 0.0117958 0.00360463 0.00403126 -0.727246 -0.720828 0.133464 0.12854 0.163025 0.169863 0.000632205 0.000628499 -11.5668 -11.5675 -17.1939 -17.1928 -365.515 -365.514 -1.46403e-05 -1.5108e-05 -6.28736e-05 -6.21576e-05 -9.94909e-07 -1.26691e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000780977 -0.000778534 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00139178 0.00136735 1.29286e-05 1.23017e-05 1.30079e-05 1.24287e-05 0.00123907 0.00126269 0.0284421 0.0284115 0.0282477 0.0281916 0.0366889 0.036855 0.0656419 0.0656409 0.0656364 0.0656346 0.0618668 0.062137 5.68464e-11 5.25747e-11 5.38646e-11 5.01048e-11 3.69761e-10 3.38512e-10 0 0 1.01692e-06 1.06906e-06 0 0 0 0 0 0 0 0
363 36085000 0.686269 0.693044 0.0116993 0.011848 0.00361933 0.00404163 -0.727244 -0.720786 0.162893 0.156799 0.202324 0.210758 0.00154791 0.00154293 -11.5519 -11.5533 -17.1756 -17.1737 -365.511 -365.51 -1.46395e-05 -1.51072e-05 -6.2873e-05 -6.21571e-05 -9.93967e-07 -1.26683e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000781696 -0.000779285 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00139186 0.00136727 1.29999e-05 1.23718e-05 1.30829e-05 1.25027e-05 0.00123915 0.00126291 0.0292015 0.029158 0.0289022 0.0288196 0.0384181 0.0386676 0.0678085 0.0678059 0.0677932 0.0677886 0.0621939 0.0624462 5.69463e-11 5.26746e-11 5.39645e-11 5.02048e-11 3.69861e-10 3.38612e-10 0 0 1.01684e-06 1.06898e-06 0 0 0 0 0 0 0 0
364 36185000 0.686222 0.693043 0.0115563 0.01171 0.00363509 0.0040489 -0.727291 -0.72079 0.171961 0.165463 0.216926 0.22604 0.00222865 0.00223467 -11.5539 -11.5553 -17.1751 -17.1732 -365.506 -365.505 -1.46329e-05 -1.51013e-05 -6.2865e-05 -6.21497e-05 -9.93512e-07 -1.26679e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000782287 -0.000779942 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00138827 0.00136351 1.30068e-05 1.23836e-05 1.30752e-05 1.25e-05 0.00123569 0.00125947 0.0265486 0.0265004 0.0262012 0.0261077 0.0377893 0.0380995 0.0549579 0.0549552 0.054941 0.054936 0.0614828 0.0617128 5.70458e-11 5.27743e-11 5.40642e-11 5.03045e-11 3.69961e-10 3.38712e-10 0 0 1.01178e-06 1.06339e-06 0 0 0 0 0 0 0 0
365 36285000 0.686238 0.6931 0.0116343 0.0117874 0.00362111 0.00403082 -0.727275 -0.720734 0.201046 0.193397 0.256076 0.266772 0.00485648 0.00486835 -11.5353 -11.5374 -17.1514 -17.1485 -365.496 -1.46313e-05 -1.50999e-05 -6.28639e-05 -6.21487e-05 -9.91713e-07 -1.26664e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000784986 -0.000782765 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00138831 0.00136339 1.30833e-05 1.24585e-05 1.31574e-05 1.25807e-05 0.00123584 0.00125976 0.0274997 0.0274348 0.0270156 0.0268879 0.0398713 0.0402885 0.0574959 0.0574902 0.0574584 0.0574478 0.0618518 0.0620712 5.71457e-11 5.28742e-11 5.41641e-11 5.04045e-11 3.70061e-10 3.38812e-10 0 0 1.01146e-06 1.06304e-06 0 0 0 0 0 0 0 0
366 36385000 0.686181 0.693088 0.0114606 0.0116216 0.00362972 0.00402901 -0.727332 -0.720748 0.208221 0.200413 0.264907 0.27611 0.00487025 0.00491309 -11.5361 -11.538 -17.1529 -17.15 -365.493 -365.492 -1.46195e-05 -1.50891e-05 -6.28482e-05 -6.21338e-05 -9.92616e-07 -1.26672e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000786546 -0.00078446 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00138225 0.00135716 1.30515e-05 1.24351e-05 1.31052e-05 1.25372e-05 0.00123038 0.00125424 0.0251926 0.0251235 0.0246803 0.0245438 0.0394029 0.0398772 0.0485456 0.0485401 0.0485081 0.0484976 0.0616939 0.0619014 5.72447e-11 5.29733e-11 5.42632e-11 5.05037e-11 3.70161e-10 3.38912e-10 0 0 1.00282e-06 1.0535e-06 0 0 0 0 0 0 0 0
367 36485000 0.686186 0.693135 0.0115272 0.0116869 0.00369263 0.00408775 -0.727325 -0.720702 0.23821 0.229285 0.303357 0.316155 0.00613785 0.00617921 -11.5137 -11.5165 -17.1245 -17.1204 -365.49 -365.489 -1.46192e-05 -1.50888e-05 -6.2848e-05 -6.21336e-05 -9.92253e-07 -1.26669e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000787493 -0.000785437 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00138235 0.0013571 1.3134e-05 1.25159e-05 1.3192e-05 1.26222e-05 0.0012305 0.0012545 0.0263105 0.0262213 0.0256449 0.0254677 0.0417791 0.0423766 0.051388 0.0513777 0.0513152 0.0512952 0.0628149 0.0630281 5.73446e-11 5.30732e-11 5.43632e-11 5.06037e-11 3.70261e-10 3.39012e-10 0 0 1.00207e-06 1.05268e-06 0 0 0 0 0 0 0 0
368 36585000 0.686138 0.693132 0.0112746 0.0114463 0.00365348 0.00403569 -0.727375 -0.720709 0.240543 0.231648 0.309 0.322137 0.00907068 0.00917558 -11.5171 -11.5197 -17.1289 -17.125 -365.485 -365.484 -1.4598e-05 -1.50695e-05 -6.28195e-05 -6.21065e-05 -9.94308e-07 -1.26688e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000790345 -0.000788507 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00137358 0.00134815 1.30555e-05 1.245e-05 1.3086e-05 1.25289e-05 0.00122288 0.00124673 0.0242424 0.0241515 0.023552 0.0233702 0.0412946 0.0419335 0.0445624 0.0445527 0.0444937 0.044475 0.0629546 0.0631628 5.74424e-11 5.31713e-11 5.44612e-11 5.0702e-11 3.70361e-10 3.39112e-10 0 0 9.89436e-07 1.03877e-06 0 0 0 0 0 0 0 0
369 36685000 0.686158 0.693193 0.0112683 0.0114394 0.00362594 0.00400328 -0.727356 -0.72065 0.269355 0.259371 0.347521 0.362228 0.0110925 0.0112088 -11.4916 -11.4952 -17.0961 -17.0908 -365.481 -365.48 -1.45976e-05 -1.50692e-05 -6.28192e-05 -6.21063e-05 -9.93836e-07 -1.26684e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000792227 -0.000790462 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00137365 0.00134805 1.31427e-05 1.25347e-05 1.31735e-05 1.26141e-05 0.00122307 0.00124705 0.0255138 0.0253999 0.0246417 0.0244139 0.044103 0.0448777 0.0476642 0.0476474 0.0475419 0.0475089 0.0657151 0.0659531 5.75423e-11 5.32713e-11 5.45612e-11 5.0802e-11 3.70461e-10 3.39212e-10 0 0 9.88464e-07 1.0377e-06 0 0 0 0 0 0 0 0
370 36785000 0.686124 0.693203 0.0109067 0.0110929 0.00362896 0.0039903 -0.727394 -0.720646 0.268263 0.25853 0.349485 0.364407 0.0127719 0.0129557 -11.4978 -11.501 -17.1033 -17.0982 -365.476 -365.475 -1.45638e-05 -1.50383e-05 -6.27741e-05 -6.20632e-05 -9.97614e-07 -1.26718e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000792385 -0.000790714 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00136217 0.00133637 1.30128e-05 1.24221e-05 1.30077e-05 1.24653e-05 0.00121309 0.00123681 0.0235912 0.0234786 0.0227188 0.0224921 0.0434743 0.044266 0.042072 0.042057 0.0419613 0.0419315 0.0659638 0.0661993 5.7638e-11 5.33676e-11 5.46573e-11 5.08986e-11 3.7056e-10 3.39312e-10 0 0 9.71882e-07 1.01949e-06 0 0 0 0 0 0 0 0
371 36885000 0.686142 0.693264 0.0109644 0.0111498 0.00364227 0.00399938 -0.727376 -0.720587 0.29635 0.285609 0.385806 0.402286 0.0143623 0.0145538 -11.4696 -11.4738 -17.0665 -17.0599 -365.472 -1.45636e-05 -1.50381e-05 -6.27739e-05 -6.2063e-05 -9.97336e-07 -1.26716e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000794061 -0.000792443 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00136225 0.00133628 1.31056e-05 1.25122e-05 1.31042e-05 1.25592e-05 0.00121328 0.00123713 0.0249794 0.024841 0.0239199 0.0236433 0.0461653 0.0470891 0.0453997 0.0453749 0.0452144 0.045165 0.068135 0.0684082 5.7738e-11 5.34676e-11 5.47573e-11 5.09986e-11 3.7066e-10 3.39412e-10 0 0 9.69879e-07 1.0173e-06 0 0 0 0 0 0 0 0
372 36985000 0.686054 0.693221 0.0104695 0.0106741 0.00354142 0.00387954 -0.727467 -0.720635 0.292029 0.281777 0.382416 0.399008 0.0143019 0.0145776 -11.4788 -11.4826 -17.0775 -17.0712 -365.47 -365.469 -1.45141e-05 -1.49929e-05 -6.27067e-05 -6.19987e-05 -1.00368e-06 -1.26773e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000793047 -0.000791476 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00134828 0.00132209 1.292e-05 1.23481e-05 1.28766e-05 1.23526e-05 0.00120098 0.00122444 0.0231344 0.0230008 0.0221103 0.0218417 0.0452753 0.0461852 0.0405432 0.0405216 0.0403808 0.0403373 0.0683294 0.0685978 5.78305e-11 5.35611e-11 5.48505e-11 5.10927e-11 3.7076e-10 3.39512e-10 0 0 9.49693e-07 9.95208e-07 0 0 0 0 0 0 0 0
373 37085000 0.686052 0.693262 0.0105025 0.0107066 0.00352773 0.0038614 -0.727468 -0.720596 0.320102 0.308886 0.418702 0.436853 0.0176583 0.0179449 -11.4482 -11.4531 -17.0374 -17.0294 -365.465 -1.45139e-05 -1.49928e-05 -6.27066e-05 -6.19986e-05 -1.00344e-06 -1.26771e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000794968 -0.000793452 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00134844 0.00132208 1.30177e-05 1.24428e-05 1.29767e-05 1.24497e-05 0.00120111 0.00122471 0.0246318 0.0244708 0.0234107 0.0230891 0.0479428 0.0489769 0.0440692 0.0440352 0.0438108 0.043742 0.0707868 0.0711044 5.79305e-11 5.36611e-11 5.49504e-11 5.11927e-11 3.7086e-10 3.39612e-10 0 0 9.46849e-07 9.92103e-07 0 0 0 0 0 0 0 0
374 37185000 0.685903 0.693162 0.00991746 0.0101431 0.00346399 0.0037765 -0.727617 -0.7207 0.312316 0.301822 0.40901 0.427179 0.019563 0.0199841 -11.4605 -11.4647 -17.0532 -17.0456 -365.464 -1.44458e-05 -1.49304e-05 -6.26109e-05 -6.19068e-05 -1.01308e-06 -1.26858e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000796466 -0.0007951 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00133204 0.00130542 1.27762e-05 1.22274e-05 1.26925e-05 1.21902e-05 0.00118682 0.00120992 0.0228134 0.0226611 0.0216667 0.0213613 0.0467288 0.0477169 0.0396491 0.0396201 0.0394284 0.0393694 0.0708097 0.071116 5.80185e-11 5.37508e-11 5.50394e-11 5.12831e-11 3.7096e-10 3.39712e-10 0 0 9.2377e-07 9.66953e-07 0 0 0 0 0 0 0 0
375 37285000 0.685899 0.6932 0.00993799 0.0101626 0.00350443 0.00381242 -0.727621 -0.720663 0.339409 0.328017 0.444488 0.464202 0.0216032 0.0220272 -11.428 -11.4333 -17.0105 -17.0011 -365.461 -365.46 -1.44457e-05 -1.49303e-05 -6.26108e-05 -6.19068e-05 -1.01295e-06 -1.26857e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000797877 -0.000796528 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00133222 0.00130544 1.28793e-05 1.23272e-05 1.27968e-05 1.22912e-05 0.00118695 0.00121018 0.024396 0.024215 0.0230469 0.0226868 0.0492917 0.0503904 0.0433494 0.0433051 0.043012 0.0429218 0.0734311 0.0737938 5.81185e-11 5.38508e-11 5.51394e-11 5.13831e-11 3.7106e-10 3.39812e-10 0 0 9.20089e-07 9.62953e-07 0 0 0 0 0 0 0 0
376 37385000 0.685709 0.693063 0.00925009 0.00949846 0.00338454 0.00366881 -0.727809 -0.720805 0.32698 0.316531 0.429337 0.448941 0.0224139 0.0229838 -11.4434 -11.448 -17.0303 -17.0215 -365.46 -365.459 -1.43558e-05 -1.48477e-05 -6.24841e-05 -6.1785e-05 -1.02562e-06 -1.26972e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000798334 -0.000797058 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00131396 0.00128688 1.25824e-05 1.20602e-05 1.24601e-05 1.19821e-05 0.00117101 0.00119362 0.0225717 0.0224028 0.0213304 0.0209952 0.048163 0.0491986 0.0391769 0.03914 0.038895 0.038819 0.0745704 0.0749255 5.82005e-11 5.39353e-11 5.52227e-11 5.14685e-11 3.7116e-10 3.39911e-10 0 0 8.95971e-07 9.36789e-07 0 0 0 0 0 0 0 0
377 37485000 0.685727 0.693122 0.00926934 0.00951713 0.00337791 0.00365767 -0.727792 -0.720748 0.35289 0.341588 0.465243 0.486373 0.0240669 0.0246126 -11.4094 -11.4151 -16.9856 -16.9747 -365.458 -365.457 -1.43558e-05 -1.48477e-05 -6.24842e-05 -6.1785e-05 -1.02565e-06 -1.26972e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000797771 -0.000796412 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00131409 0.00128684 1.26899e-05 1.21641e-05 1.2569e-05 1.20875e-05 0.00117123 0.00119396 0.0242276 0.0240297 0.0227704 0.0223802 0.0506143 0.0517461 0.0430295 0.0429745 0.0426113 0.0424988 0.0773552 0.0777724 5.83005e-11 5.40353e-11 5.53227e-11 5.15685e-11 3.7126e-10 3.40011e-10 0 0 8.91741e-07 9.32214e-07 0 0 0 0 0 0 0 0
378 37585000 0.685448 0.692897 0.00847519 0.00874692 0.00328104 0.0035347 -0.728065 -0.720975 0.336624 0.326413 0.446969 0.467857 0.0290833 0.0298347 -11.4281 -11.4327 -17.0093 -16.9992 -365.452 -365.451 -1.42426e-05 -1.47433e-05 -6.23232e-05 -6.163e-05 -1.04178e-06 -1.27118e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000804764 -0.000803655 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00129463 0.00126704 1.23413e-05 1.18487e-05 1.21869e-05 1.17351e-05 0.00115391 0.00117593 0.0223926 0.0222112 0.0210625 0.0207051 0.0487368 0.0497708 0.0389829 0.0389378 0.0386394 0.0385462 0.0768232 0.0772086 5.8375e-11 5.41133e-11 5.53987e-11 5.16475e-11 3.7136e-10 3.40111e-10 0 0 8.65571e-07 9.03966e-07 0 0 0 0 0 0 0 0
379 37685000 0.685439 0.692931 0.00852407 0.0087946 0.00333239 0.00358185 -0.728072 -0.720941 0.360932 0.349946 0.481774 0.504155 0.0344841 0.0352632 -11.3932 -11.3989 -16.9629 -16.9506 -365.443 -365.442 -1.42425e-05 -1.47432e-05 -6.23231e-05 -6.163e-05 -1.04153e-06 -1.27116e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000810108 -0.00080913 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00129486 0.00126709 1.24536e-05 1.19572e-05 1.23012e-05 1.18455e-05 0.00115405 0.00117619 0.0240925 0.0238816 0.022545 0.0221333 0.0509755 0.0520876 0.0429676 0.042902 0.0424698 0.0423351 0.0795883 0.0800351 5.8475e-11 5.42133e-11 5.54987e-11 5.17475e-11 3.7146e-10 3.40211e-10 0 0 8.60731e-07 8.98756e-07 0 0 0 0 0 0 0 0
380 37785000 0.685136 0.692684 0.00759148 0.00788486 0.00327038 0.00349134 -0.728368 -0.72119 0.341869 0.332105 0.459656 0.481678 0.0387038 0.0396668 -11.4147 -11.4194 -16.9904 -16.979 -365.436 -365.435 -1.41051e-05 -1.46161e-05 -6.21251e-05 -6.14388e-05 -1.06173e-06 -1.27299e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000815213 -0.000814307 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00127454 0.00124637 1.20579e-05 1.15972e-05 1.1882e-05 1.14573e-05 0.00113606 0.00115738 0.022227 0.0220363 0.0208374 0.0204659 0.0488209 0.0498204 0.038968 0.038915 0.0385648 0.0384547 0.0787339 0.0791392 5.85402e-11 5.42833e-11 5.55657e-11 5.18186e-11 3.7156e-10 3.40311e-10 0 0 8.34364e-07 8.7044e-07 0 0 0 0 0 0 0 0
381 37885000 0.685145 0.692734 0.00759944 0.00789217 0.00328172 0.00349817 -0.72836 -0.721142 0.365068 0.354624 0.492607 0.516108 0.0396757 0.0405769 -11.3793 -11.3851 -16.9428 -16.9291 -365.436 -365.435 -1.41051e-05 -1.46161e-05 -6.2125e-05 -6.14387e-05 -1.06185e-06 -1.273e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000811777 -0.000810667 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00127473 0.0012464 1.21744e-05 1.17096e-05 1.19995e-05 1.15706e-05 0.00113627 0.00115771 0.0239442 0.0237239 0.0223498 0.0219259 0.0508211 0.0518812 0.0430646 0.0429889 0.042492 0.0423366 0.0814128 0.0818757 5.86402e-11 5.43833e-11 5.56657e-11 5.19186e-11 3.7166e-10 3.40411e-10 0 0 8.29077e-07 8.6478e-07 0 0 0 0 0 0 0 0
382 37985000 0.684844 0.692494 0.00662911 0.00694334 0.00321946 0.00340623 -0.728652 -0.721382 0.343179 0.334055 0.467023 0.490047 0.0419787 0.0430176 -11.4044 -11.409 -16.9738 -16.9612 -365.433 -365.432 -1.39393e-05 -1.44621e-05 -6.18883e-05 -6.12097e-05 -1.08635e-06 -1.27523e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000809961 -0.000808635 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00125425 0.00122546 1.1738e-05 1.13104e-05 1.15559e-05 1.11585e-05 0.00111801 0.00113855 0.0220422 0.0218453 0.0206357 0.0202581 0.0490082 0.0499639 0.0390614 0.039001 0.0386035 0.038478 0.0819361 0.0823679 5.86947e-11 5.44439e-11 5.5722e-11 5.19803e-11 3.71759e-10 3.40511e-10 0 0 8.04601e-07 8.38628e-07 0 0 0 0 0 0 0 0
383 38085000 0.684812 0.692504 0.00665114 0.00696461 0.00324054 0.00342293 -0.728683 -0.721373 0.364449 0.354735 0.498244 0.522699 0.0487374 0.0497859 -11.369 -11.3746 -16.9256 -16.9106 -365.423 -365.421 -1.39393e-05 -1.44621e-05 -6.18884e-05 -6.12098e-05 -1.08622e-06 -1.27522e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000814991 -0.000813744 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.0012546 0.00122563 1.18587e-05 1.14267e-05 1.16776e-05 1.12758e-05 0.0011181 0.00113876 0.0237634 0.023537 0.0221611 0.0217335 0.0508236 0.0518264 0.04325 0.0431652 0.0426119 0.0424377 0.0845931 0.0850797 5.87947e-11 5.45439e-11 5.5822e-11 5.20803e-11 3.71859e-10 3.40611e-10 0 0 7.99222e-07 8.32896e-07 0 0 0 0 0 0 0 0
384 38185000 0.684467 0.692431 0.00560551 0.00669142 0.00309596 0.00336384 -0.729015 -0.721445 0.338904 0.359136 0.468958 0.532414 0.0483148 0.0480654 -11.3963 -11.3708 -16.9599 -16.9041 -365.421 -1.375e-05 -1.44263e-05 -6.16135e-05 -6.1155e-05 -1.11499e-06 -1.27572e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000809725 -0.000804962 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00123441 0.0012192 1.13892e-05 1.13918e-05 1.1218e-05 1.12406e-05 0.00110007 0.00113295 0.0218263 0.0235285 0.0204248 0.0216795 0.0482959 0.0491786 0.0392132 0.0407977 0.0387083 0.0400625 0.0831451 0.0835765 5.88367e-11 5.46361e-11 5.58658e-11 5.21723e-11 3.71959e-10 3.40711e-10 0 0 7.74463e-07 8.06579e-07 0 0 0 0 0 0 0 0
385 38285000 0.684473 0.692478 0.00562755 0.00671408 0.00311513 0.0033789 -0.72901 -0.7214 0.359964 0.380605 0.497625 0.563703 0.0501426 0.0499201 -11.3614 -11.3339 -16.9116 -16.8493 -365.418 -1.375e-05 -1.44263e-05 -6.16135e-05 -6.1155e-05 -1.115e-06 -1.27572e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000808757 -0.000803958 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00123465 0.00121927 1.15136e-05 1.1513e-05 1.13434e-05 1.13628e-05 0.00110029 0.00113329 0.0235325 0.025343 0.021965 0.023283 0.0498748 0.0507912 0.0434748 0.0454131 0.0427823 0.044419 0.0856388 0.0861184 5.89368e-11 5.47361e-11 5.59658e-11 5.22723e-11 3.72059e-10 3.40811e-10 0 0 7.68957e-07 8.0074e-07 0 0 0 0 0 0 0 0
386 38385000 0.684036 0.692363 0.00455432 0.00632848 0.00293022 0.00328223 -0.729428 -0.721514 0.33439 0.380591 0.466577 0.567115 0.0478172 0.0467284 -11.3895 -11.3353 -16.9488 -16.8503 -365.416 -365.417 -1.35431e-05 -1.43696e-05 -6.13029e-05 -6.10679e-05 -1.14731e-06 -1.27652e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000800487 -0.000793306 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00121529 0.00121084 1.10189e-05 1.14218e-05 1.08768e-05 1.12735e-05 0.00108298 0.00112562 0.0215799 0.0250781 0.0202228 0.0230233 0.0472807 0.0480815 0.0393889 0.0428061 0.0388462 0.0418432 0.0839779 0.0843999 5.89649e-11 5.48219e-11 5.59955e-11 5.23581e-11 3.72158e-10 3.40911e-10 0 0 7.45751e-07 7.76188e-07 0 0 0 0 0 0 0 0
387 38485000 0.684042 0.692411 0.00455393 0.00632991 0.00296154 0.00330944 -0.729422 -0.721468 0.354303 0.40174 0.494879 0.599102 0.0486815 0.0476756 -11.3551 -11.2962 -16.9007 -16.792 -365.413 -365.414 -1.35431e-05 -1.43696e-05 -6.13028e-05 -6.10678e-05 -1.14733e-06 -1.27653e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000798346 -0.00079116 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00121555 0.00121093 1.11468e-05 1.15478e-05 1.10061e-05 1.14004e-05 0.00108323 0.00112598 0.0232775 0.0270118 0.0217609 0.0247296 0.048637 0.0494605 0.0437062 0.0478638 0.0429731 0.0465911 0.0862942 0.0867574 5.90649e-11 5.49219e-11 5.60955e-11 5.24581e-11 3.72258e-10 3.41011e-10 0 0 7.40257e-07 7.70389e-07 0 0 0 0 0 0 0 0
388 38585000 0.683566 0.692228 0.00349608 0.0058631 0.00273836 0.00316513 -0.729875 -0.721648 0.328905 0.397822 0.461858 0.595131 0.0438979 0.0424034 -11.3847 -11.3035 -16.9402 -16.8012 -365.417 -365.418 -1.33161e-05 -1.42877e-05 -6.09569e-05 -6.09411e-05 -1.18388e-06 -1.27773e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000785994 -0.000777343 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00119734 0.00120063 1.0635e-05 1.13941e-05 1.05395e-05 1.12529e-05 0.00106678 0.00111643 0.0213083 0.0264362 0.0200174 0.0242311 0.0460313 0.0467473 0.0395657 0.0449136 0.0389958 0.0437247 0.0844697 0.0848753 5.90778e-11 5.4999e-11 5.61095e-11 5.25353e-11 3.72357e-10 3.4111e-10 0 0 7.18836e-07 7.47826e-07 0 0 0 0 0 0 0 0
389 38685000 0.683587 0.69229 0.00356364 0.00593383 0.00276643 0.00319015 -0.729855 -0.721588 0.346709 0.417641 0.486588 0.624438 0.0442958 0.0428928 -11.3509 -11.2627 -16.8928 -16.7402 -365.417 -365.419 -1.3316e-05 -1.42876e-05 -6.09567e-05 -6.09409e-05 -1.18388e-06 -1.27773e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000781936 -0.000773253 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00119759 0.00120071 1.07663e-05 1.15246e-05 1.06711e-05 1.13845e-05 0.00106711 0.00111687 0.022962 0.0284295 0.0215378 0.0260115 0.0477938 0.0485381 0.0439225 0.0503876 0.0431636 0.048845 0.0885208 0.0889807 5.91778e-11 5.5099e-11 5.62095e-11 5.26353e-11 3.72457e-10 3.4121e-10 0 0 7.14832e-07 7.43618e-07 0 0 0 0 0 0 0 0
390 38785000 0.683119 0.692069 0.00245486 0.0053188 0.00260209 0.00308721 -0.730298 -0.721805 0.319175 0.407979 0.450364 0.611648 0.0437452 0.0422422 -11.3826 -11.2762 -16.9353 -16.7587 -365.416 -365.417 -1.30652e-05 -1.41774e-05 -6.05744e-05 -6.07694e-05 -1.22444e-06 -1.27941e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000777119 -0.000767937 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00118074 0.00118869 1.02447e-05 1.13059e-05 1.02109e-05 1.11787e-05 0.00105188 0.00110573 0.020982 0.0275055 0.0197857 0.0252379 0.0451701 0.0458143 0.0397275 0.0470057 0.0391419 0.0456142 0.0864932 0.0868944 5.9174e-11 5.51651e-11 5.62063e-11 5.27014e-11 3.72556e-10 3.4131e-10 0 0 6.9512e-07 7.22936e-07 0 0 0 0 0 0 0 0
391 38885000 0.683124 0.692114 0.00261588 0.00548355 0.00267625 0.00315973 -0.730293 -0.72176 0.327185 0.417344 0.461722 0.626048 0.491287 0.48988 -11.3501 -11.2347 -16.8893 -16.6964 -365.399 -365.401 -1.30653e-05 -1.41774e-05 -6.05745e-05 -6.07695e-05 -1.22445e-06 -1.27941e-05 -0.000310941 -0.000276306 0.000274475 0.000301947 -0.000778857 -0.000769835 0.21181 0.211941 0.00158687 0.00179793 0.429054 0.429407 -0.00022441 -0.000432996 -0.000464628 -0.000621003 0.0031579 0.00278558 0 0 0.00118106 0.00118884 1.03787e-05 1.14405e-05 1.03429e-05 1.13138e-05 0.00105215 0.00110611 0.021903 0.0286556 0.0206462 0.0262794 0.045527 0.0461724 0.0440985 0.0528387 0.0433304 0.051063 0.0885263 0.0889576 5.9274e-11 5.52651e-11 5.63063e-11 5.28014e-11 3.72656e-10 3.4141e-10 0 0 6.9004e-07 7.17618e-07 0 0 0 0 0 0 0 0
+348 -348
View File
@@ -1,351 +1,351 @@
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
15000,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
85000,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
185000,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
285000,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
385000,0.982011,-0.00768853,-0.0134662,0.188184,0.000443332,0.000261826,-0.00515777,4.48561e-06,3.93582e-06,-7.479e-05,0,0,0,0,0,0,0.203397,0.00195875,0.43452,0,0,0,0,0,0.000177748,0.0024727,0.00247219,0.00482432,25.0004,25.0004,0.562573,0.259374,0.259374,4.00051,1e-06,1e-06,1e-06,0,0,4e-06,0,0,0,0,0,0,0,0
485000,0.982383,-0.0077361,-0.0138297,0.186204,0.00147596,0.000493386,-0.0226201,0.000128083,3.81988e-05,0.012004,2.01269e-08,3.33849e-11,8.41725e-07,0,0,5.50648e-08,0.203316,0.00195799,0.434329,0,0,0,0,0,0.00011506,0.0024946,0.00249436,0.00311143,25.009,25.009,0.56266,0.609397,0.609397,0.802449,1e-06,1e-06,9.99318e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
585000,0.982395,-0.00775776,-0.0140474,0.186127,0.000124163,0.000407154,-0.0407871,4.57057e-05,1.49825e-05,0.00559437,2.23668e-08,-1.4794e-10,9.35397e-07,0,0,1.69579e-07,0.203316,0.00195799,0.434329,0,0,0,0,0,7.46438e-05,0.0025641,0.00256402,0.00200975,7.81334,7.81334,0.561469,0.228164,0.228164,0.451638,9.99997e-07,1e-06,9.94889e-07,0,0,4e-06,0,0,0,0,0,0,0,0
685000,0.982306,-0.00778766,-0.014415,0.186564,0.00269711,0.00147583,-0.0490401,0.000225835,0.000114014,0.0168583,-1.70626e-08,-3.19376e-10,-6.75191e-07,0,0,-3.88272e-07,0.203316,0.00195799,0.434329,0,0,0,0,0,5.66967e-05,0.00268405,0.00268402,0.00151998,7.85185,7.85185,0.557235,0.486041,0.486041,0.322026,9.9999e-07,1e-06,9.84024e-07,0,0,3.99989e-06,0,0,0,0,0,0,0,0
785000,0.98226,-0.0077893,-0.0146418,0.186787,0.00367557,0.00336477,-0.0598107,0.00012,8.49913e-05,0.0131552,-4.88069e-08,-4.55154e-09,-1.999e-06,0,0,-6.61606e-07,0.203316,0.00195799,0.434329,0,0,0,0,0,4.72199e-05,0.00284792,0.00284792,0.00126121,2.59845,2.59845,0.548781,0.195719,0.195719,0.259034,9.99924e-07,9.99946e-07,9.65217e-07,0,0,3.99951e-06,0,0,0,0,0,0,0,0
885000,0.982158,-0.00783508,-0.0149921,0.187296,0.00529847,0.00620103,-0.0766202,0.000534645,0.000532679,-0.000215845,-1.88752e-07,-8.08544e-09,-7.49367e-06,0,0,9.87764e-08,0.203316,0.00195799,0.434329,0,0,0,0,0,4.19196e-05,0.0030677,0.00306771,0.00111513,2.66006,2.66007,0.534815,0.329467,0.329467,0.225286,9.99906e-07,9.99946e-07,9.36864e-07,0,0,3.99856e-06,0,0,0,0,0,0,0,0
985000,0.981971,-0.0077787,-0.0152895,0.188252,0.00814651,0.00897846,-0.0901035,0.00121988,0.00123072,-0.00832347,-4.98634e-07,-1.27859e-08,-1.95553e-05,0,0,-1.56181e-07,0.203316,0.00195799,0.434329,0,0,0,0,0,4.08581e-05,0.0033375,0.00333748,0.0010841,2.74789,2.74791,0.521629,0.517251,0.517252,0.218362,9.99888e-07,9.99946e-07,9.09096e-07,0,0,3.99721e-06,0,0,0,0,0,0,0,0
1085000,0.982058,-0.00788834,-0.0154754,0.187778,0.0140069,0.00747436,-0.109258,0.00131404,0.00114157,-0.0271122,-2.97538e-07,-6.23305e-08,-1.26407e-05,0,0,2.02264e-06,0.203316,0.00195799,0.434329,0,0,0,0,0,3.91193e-05,0.00362883,0.0036288,0.00103395,1.28867,1.28869,0.497697,0.244169,0.244169,0.207776,9.99213e-07,9.99301e-07,8.64086e-07,0,0,3.99418e-06,0,0,0,0,0,0,0,0
1185000,0.982103,-0.00785134,-0.0157472,0.187519,0.0199119,0.00773154,-0.109438,0.00297966,0.00189164,-0.0224504,-1.89472e-07,-4.93037e-08,-8.44625e-06,0,0,-3.17847e-06,0.203316,0.00195799,0.434329,0,0,0,0,0,3.83111e-05,0.00399723,0.00399715,0.00100838,1.41188,1.41193,0.469194,0.351603,0.351605,0.202802,9.99176e-07,9.99301e-07,8.11655e-07,0,0,3.98936e-06,0,0,0,0,0,0,0,0
1285000,0.982352,-0.00777499,-0.0159835,0.186195,0.0247828,0.00742468,-0.118105,0.00313056,0.00131659,-0.0274475,4.47778e-07,-3.26863e-07,1.34511e-05,0,0,-5.99233e-06,0.203316,0.00195799,0.434329,0,0,0,0,0,3.79059e-05,0.00431959,0.00431945,0.000995537,0.887165,0.887222,0.437027,0.196916,0.196917,0.200584,9.95592e-07,9.95759e-07,7.53272e-07,0,0,3.98218e-06,0,0,0,0,0,0,0,0
1385000,0.982423,-0.0077567,-0.0161987,0.185803,0.0335764,0.00818402,-0.117743,0.00607413,0.00212754,-0.0250334,5.75184e-07,-2.97805e-07,1.81008e-05,0,0,-1.31876e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.77201e-05,0.00478197,0.00478175,0.000988194,1.05544,1.05554,0.402817,0.273467,0.273471,0.199431,9.95546e-07,9.95759e-07,6.91415e-07,0,0,3.97225e-06,0,0,0,0,0,0,0,0
1485000,0.982344,-0.00774028,-0.0162312,0.186216,0.0328954,0.00736377,-0.131166,0.00539622,0.0016211,-0.0377946,2.88776e-07,-1.43042e-06,9.67851e-06,0,0,-1.3221e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.75599e-05,0.0050284,0.00502812,0.000982458,0.820131,0.82023,0.368572,0.171213,0.171216,0.198527,9.82897e-07,9.83154e-07,6.29097e-07,0,0,3.95945e-06,0,0,0,0,0,0,0,0
1585000,0.982341,-0.00783321,-0.0165968,0.186197,0.0407489,0.00831374,-0.142896,0.00907188,0.00237274,-0.048738,2.84346e-07,-1.419e-06,9.46092e-06,0,0,-1.50659e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.92088e-05,0.0055717,0.00557131,0.00102157,1.03987,1.04002,0.345437,0.237963,0.237971,0.207551,9.82862e-07,9.83154e-07,5.83132e-07,0,0,3.94785e-06,0,0,0,0,0,0,0,0
1685000,0.982369,-0.00794259,-0.0164903,0.186056,0.0398606,0.00805451,-0.149392,0.00741854,0.00180772,-0.0545571,9.14125e-09,-4.13421e-06,1.18544e-05,0,0,-2.08158e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.882e-05,0.00556111,0.00556075,0.00101071,0.88674,0.886892,0.313728,0.159531,0.159536,0.205396,9.50462e-07,9.5079e-07,5.24054e-07,0,0,3.92954e-06,0,0,0,0,0,0,0,0
1785000,0.982334,-0.00808799,-0.0167811,0.186205,0.0501565,0.00835837,-0.150958,0.0119658,0.00262719,-0.0574105,-9.86644e-08,-4.07221e-06,7.51234e-06,0,0,-2.95762e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.85692e-05,0.00615771,0.0061572,0.000996183,1.15403,1.15426,0.284485,0.227071,0.227085,0.202407,9.5042e-07,9.50789e-07,4.68638e-07,0,0,3.90791e-06,0,0,0,0,0,0,0,0
1885000,0.982456,-0.00803278,-0.0163404,0.185603,0.0442965,0.00911068,-0.152972,0.00912952,0.00192647,-0.0623763,-6.89113e-07,-9.08826e-06,1.6594e-05,0,0,-3.75606e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.77135e-05,0.00570546,0.00570506,0.000978666,0.975295,0.975496,0.258346,0.156401,0.15641,0.198874,8.88242e-07,8.88626e-07,4.1791e-07,0,0,3.88319e-06,0,0,0,0,0,0,0,0
1985000,0.982484,-0.00813573,-0.0167089,0.185416,0.0528511,0.010163,-0.151646,0.0140118,0.00284661,-0.0616876,-6.17211e-07,-8.97091e-06,1.83519e-05,0,0,-5.10329e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.72857e-05,0.006313,0.00631243,0.000958273,1.27231,1.2726,0.235187,0.228684,0.228705,0.194764,8.88209e-07,8.88624e-07,3.71907e-07,0,0,3.85509e-06,0,0,0,0,0,0,0,0
2085000,0.982403,-0.00820968,-0.01606,0.185902,0.0428688,0.00778176,-0.150045,0.00976408,0.00192821,-0.0592128,-2.06802e-06,-1.59782e-05,9.9021e-06,0,0,-6.74532e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.60425e-05,0.00539436,0.00539404,0.00093585,1.01533,1.01554,0.215118,0.156223,0.156234,0.190412,7.97339e-07,7.97744e-07,3.30791e-07,0,0,3.82386e-06,0,0,0,0,0,0,0,0
2185000,0.982422,-0.00817963,-0.0163991,0.185773,0.0506113,0.00855272,-0.151868,0.0144505,0.00280604,-0.0637389,-2.02821e-06,-1.58815e-05,1.05455e-05,0,0,-7.8001e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.54832e-05,0.00596901,0.0059685,0.000911938,1.31425,1.31455,0.197789,0.232007,0.232031,0.185808,7.97317e-07,7.97741e-07,2.94224e-07,0,0,3.78909e-06,0,0,0,0,0,0,0,0
2285000,0.982579,-0.00825584,-0.0156295,0.185004,0.0370421,0.00635088,-0.149355,0.00930094,0.00176835,-0.0631027,-3.25685e-06,-2.36858e-05,2.01746e-05,0,0,-9.45543e-05,0.203316,0.00195799,0.434329,0,0,0,0,0,3.53177e-05,0.00477762,0.00477742,0.000924776,0.983703,0.983879,0.188685,0.154751,0.154762,0.189826,6.92092e-07,6.92484e-07,2.69513e-07,0,0,3.76058e-06,0,0,0,0,0,0,0,0
2385000,0.982599,-0.00831892,-0.0158091,0.184876,0.0441957,0.00574252,-0.14923,0.0133974,0.0023617,-0.061494,-3.20528e-06,-2.35383e-05,2.07612e-05,0,0,-0.000112632,0.203316,0.00195799,0.434329,0,0,0,0,0,3.45463e-05,0.00529153,0.00529121,0.000897407,1.26229,1.26254,0.175646,0.230156,0.230178,0.184795,6.92077e-07,6.92481e-07,2.40119e-07,0,0,3.71943e-06,0,0,0,0,0,0,0,0
2485000,0.982738,-0.00824021,-0.0150709,0.184202,0.029843,0.00381465,-0.150946,0.00819469,0.00135768,-0.0648707,-4.52457e-06,-3.07403e-05,2.91336e-05,0,0,-0.000125966,0.203316,0.00195799,0.434329,0,0,0,0,0,3.29155e-05,0.00408311,0.00408302,0.000870016,0.904773,0.904906,0.164702,0.15059,0.150598,0.179987,5.8904e-07,5.89405e-07,2.14294e-07,0,0,3.67475e-06,0,0,0,0,0,0,0,0
2585000,0.982779,-0.00836863,-0.015207,0.18397,0.0330184,0.00233121,-0.153877,0.0113339,0.00170753,-0.0690052,-4.49709e-06,-3.06456e-05,2.91162e-05,0,0,-0.000139435,0.203316,0.00195799,0.434329,0,0,0,0,0,3.20634e-05,0.0045291,0.00452894,0.00084311,1.15084,1.15101,0.155525,0.222218,0.222236,0.175338,5.8903e-07,5.89402e-07,1.91636e-07,0,0,3.62596e-06,0,0,0,0,0,0,0,0
2685000,0.982848,-0.00842845,-0.0145921,0.183649,0.0221951,0.00155523,-0.153268,0.00671124,0.000897824,-0.0681768,-5.79852e-06,-3.6275e-05,3.16622e-05,0,0,-0.000161179,0.203316,0.00195799,0.434329,0,0,0,0,0,3.04881e-05,0.00345947,0.00345949,0.00081633,0.809423,0.809516,0.147823,0.144404,0.14441,0.170893,4.97368e-07,4.97698e-07,1.71663e-07,0,0,3.57283e-06,0,0,0,0,0,0,0,0
2785000,0.982827,-0.00838477,-0.0147521,0.183749,0.0276101,0.00122579,-0.150508,0.00933737,0.00104206,-0.0646975,-5.81706e-06,-3.60867e-05,2.79547e-05,0,0,-0.000187643,0.203316,0.00195799,0.434329,0,0,0,0,0,2.96653e-05,0.00384307,0.00384301,0.000790827,1.02279,1.02292,0.141516,0.210532,0.210546,0.166798,4.97361e-07,4.97696e-07,1.54221e-07,0,0,3.51578e-06,0,0,0,0,0,0,0,0
2885000,0.982922,-0.00839969,-0.0143121,0.183273,0.0198522,-0.00141653,-0.15202,0.0055695,0.000478032,-0.065987,-7.03735e-06,-4.04489e-05,3.08365e-05,0,0,-0.000207848,0.203316,0.00195799,0.434329,0,0,0,0,0,2.92205e-05,0.00295316,0.00295323,0.000794074,0.718518,0.718584,0.139979,0.137333,0.137338,0.169975,4.19026e-07,4.19319e-07,1.42494e-07,0,0,3.47018e-06,0,0,0,0,0,0,0,0
2985000,0.982996,-0.00843865,-0.0144084,0.182864,0.0228485,-0.00293635,-0.155032,0.00781168,0.000278074,-0.0702069,-6.94962e-06,-4.03976e-05,3.36889e-05,0,0,-0.000224422,0.203316,0.00195799,0.434329,0,0,0,0,0,2.84018e-05,0.00328368,0.00328371,0.000768599,0.903534,0.903622,0.135476,0.197647,0.197657,0.166181,4.19021e-07,4.19317e-07,1.28549e-07,0,0,3.40536e-06,0,0,0,0,0,0,0,0
3085000,0.982946,-0.00848459,-0.0145901,0.183117,0.0285875,-0.00550112,-0.158893,0.0104242,-0.000190947,-0.0749456,-6.95714e-06,-4.02863e-05,3.13527e-05,0,0,-0.000241952,0.203316,0.00195799,0.434329,0,0,0,0,0,2.77032e-05,0.00363514,0.00363513,0.000744046,1.1235,1.12362,0.131741,0.282762,0.282781,0.162668,4.19016e-07,4.19314e-07,1.16239e-07,0,0,3.3358e-06,0,0,0,0,0,0,0,0
3185000,0.982823,-0.00843186,-0.0142554,0.183809,0.0221182,-0.00765307,-0.160674,0.00680933,-0.000763218,-0.0803059,-8.53369e-06,-4.35952e-05,2.30248e-05,0,0,-0.000259189,0.203316,0.00195799,0.434329,0,0,0,0,0,2.64267e-05,0.00284016,0.00284023,0.000720579,0.802139,0.802201,0.128672,0.18515,0.185158,0.159519,3.52557e-07,3.52818e-07,1.05352e-07,0,0,3.26217e-06,0,0,0,0,0,0,0,0
3285000,0.982838,-0.00846252,-0.0142669,0.183726,0.0250887,-0.00862238,-0.164702,0.00920371,-0.0016296,-0.0887593,-8.5049e-06,-4.35361e-05,2.29562e-05,0,0,-0.000272964,0.203316,0.00195799,0.434329,0,0,0,0,0,2.57412e-05,0.00314379,0.00314384,0.000698263,0.994125,0.994215,0.126109,0.262082,0.262096,0.156631,3.52553e-07,3.52815e-07,9.5736e-08,0,0,3.18391e-06,0,0,0,0,0,0,0,0
3385000,0.982774,-0.00816739,-0.0139452,0.184104,0.0180715,-0.00714377,-0.163838,0.0059688,-0.00142476,-0.0871283,-1.0235e-05,-4.61096e-05,1.82849e-05,0,0,-0.000306313,0.203316,0.00195799,0.434329,0,0,0,0,0,2.4616e-05,0.0024836,0.0024837,0.000676979,0.719299,0.719352,0.123971,0.173738,0.173744,0.154066,2.95827e-07,2.96053e-07,8.71884e-08,0,0,3.10184e-06,0,0,0,0,0,0,0,0
3485000,0.982695,-0.00816339,-0.0139806,0.184525,0.0228884,-0.00568018,-0.162858,0.00812011,-0.00207703,-0.0876651,-1.02676e-05,-4.59447e-05,1.3348e-05,0,0,-0.00033625,0.203316,0.00195799,0.434329,0,0,0,0,0,2.39918e-05,0.00274646,0.00274653,0.000656757,0.889359,0.889446,0.122129,0.243681,0.243693,0.151722,2.95824e-07,2.96051e-07,7.96069e-08,0,0,3.01547e-06,0,0,0,0,0,0,0,0
3585000,0.982699,-0.00796598,-0.0136074,0.184537,0.0182781,-0.00508906,-0.169078,0.00551376,-0.00141354,-0.0958663,-1.18888e-05,-4.81556e-05,1.2233e-05,0,0,-0.000352539,0.203316,0.00195799,0.434329,0,0,0,0,0,2.36751e-05,0.00218659,0.00218671,0.000656709,0.651549,0.651602,0.123407,0.163606,0.163612,0.155467,2.4703e-07,2.47224e-07,7.44343e-08,0,0,2.94807e-06,0,0,0,0,0,0,0,0
3685000,0.982807,-0.0080029,-0.0136691,0.183957,0.0200469,-0.00584276,-0.166139,0.00757218,-0.00198029,-0.0948425,-1.17373e-05,-4.81215e-05,1.68549e-05,0,0,-0.000388329,0.203316,0.00195799,0.434329,0,0,0,0,0,2.30767e-05,0.00241387,0.00241399,0.000637289,0.80345,0.803521,0.121857,0.22766,0.22767,0.153422,2.47028e-07,2.47223e-07,6.82226e-08,0,0,2.85524e-06,0,0,0,0,0,0,0,0
3785000,0.982773,-0.00783102,-0.0135027,0.184156,0.0139712,-0.00151095,-0.168319,0.00497409,-0.00115701,-0.100561,-1.32045e-05,-5.0065e-05,1.45328e-05,0,0,-0.000410317,0.203316,0.00195799,0.434329,0,0,0,0,0,2.21955e-05,0.00192922,0.00192936,0.000618815,0.59437,0.594421,0.12042,0.154645,0.15465,0.151619,2.04919e-07,2.05084e-07,6.26475e-08,0,0,2.7598e-06,0,0,0,0,0,0,0,0
3885000,0.982817,-0.00781719,-0.0135686,0.183915,0.014566,-0.00151863,-0.166859,0.00653182,-0.00125161,-0.102401,-1.31226e-05,-5.00295e-05,1.64763e-05,0,0,-0.000440574,0.203316,0.00195799,0.434329,0,0,0,0,0,2.16606e-05,0.00212493,0.00212507,0.000601279,0.730692,0.73076,0.119002,0.213657,0.213667,0.149954,2.04918e-07,2.05083e-07,5.76622e-08,0,0,2.66147e-06,0,0,0,0,0,0,0,0
3985000,0.982709,-0.00776702,-0.0133656,0.184508,0.0126386,-0.000934107,-0.166913,0.00428869,-0.00075271,-0.102402,-1.42236e-05,-5.15936e-05,1.16033e-05,0,0,-0.000476228,0.203316,0.00195799,0.434329,0,0,0,0,0,2.08853e-05,0.00169953,0.00169969,0.000584443,0.54499,0.545035,0.117541,0.146667,0.146672,0.148396,1.68696e-07,1.68835e-07,5.31532e-08,0,0,2.56073e-06,0,0,0,0,0,0,0,0
4085000,0.982648,-0.00773488,-0.0133148,0.184838,0.0149281,-0.00193326,-0.156318,0.0058387,-0.000893984,-0.0921072,-1.42013e-05,-5.14546e-05,8.91686e-06,0,0,-0.000532892,0.203316,0.00195799,0.434329,0,0,0,0,0,2.03936e-05,0.001867,0.00186717,0.000568587,0.667582,0.667639,0.116076,0.20131,0.201318,0.147005,1.68695e-07,1.68834e-07,4.91159e-08,0,0,2.45891e-06,0,0,0,0,0,0,0,0
4185000,0.982688,-0.00779914,-0.013085,0.184642,0.0112228,-0.00234072,-0.158786,0.00388818,-0.000617489,-0.0991956,-1.50251e-05,-5.29285e-05,9.81956e-06,0,0,-0.000551482,0.203316,0.00195799,0.434329,0,0,0,0,0,2.01959e-05,0.00149113,0.00149132,0.000567924,0.500288,0.500321,0.117306,0.139474,0.139477,0.151261,1.37789e-07,1.37904e-07,4.63287e-08,0,0,2.38192e-06,0,0,0,0,0,0,0,0
4285000,0.982749,-0.00787293,-0.0131452,0.184307,0.0144245,-0.00203879,-0.16188,0.00525483,-0.000852316,-0.105809,-1.49612e-05,-5.29368e-05,1.21184e-05,0,0,-0.000571877,0.203316,0.00195799,0.434329,0,0,0,0,0,1.9722e-05,0.00163339,0.0016336,0.000552803,0.610603,0.610648,0.115631,0.190207,0.190214,0.149954,1.37788e-07,1.37904e-07,4.29434e-08,0,0,2.27865e-06,0,0,0,0,0,0,0,0
4385000,0.982828,-0.00776176,-0.013019,0.1839,0.0124399,-0.00346153,-0.153751,0.0037084,-0.00067106,-0.0968809,-1.56467e-05,-5.41978e-05,1.43912e-05,0,0,-0.000625187,0.203316,0.00195799,0.434329,0,0,0,0,0,1.90621e-05,0.00130143,0.00130163,0.000538313,0.459428,0.459452,0.113817,0.132893,0.132896,0.148671,1.11723e-07,1.11818e-07,3.98559e-08,0,0,2.17514e-06,0,0,0,0,0,0,0,0
4485000,0.982828,-0.00782965,-0.0129824,0.183897,0.0141738,-0.00156243,-0.150891,0.00514105,-0.000881406,-0.096137,-1.56186e-05,-5.41607e-05,1.42337e-05,0,0,-0.000659605,0.203316,0.00195799,0.434329,0,0,0,0,0,1.86222e-05,0.00142141,0.00142162,0.000524607,0.55811,0.558147,0.111927,0.180059,0.180064,0.147471,1.11722e-07,1.11818e-07,3.70696e-08,0,0,2.07269e-06,0,0,0,0,0,0,0,0
4585000,0.982769,-0.00778877,-0.0128696,0.184223,0.0115738,-0.00301001,-0.150869,0.00355612,-0.000624981,-0.0995391,-1.63456e-05,-5.5275e-05,1.18944e-05,0,0,-0.000685041,0.203316,0.00195799,0.434329,0,0,0,0,0,1.80533e-05,0.00112971,0.00112991,0.000511437,0.421112,0.421131,0.109892,0.126797,0.1268,0.14626,9.00265e-08,9.01039e-08,3.4518e-08,0,0,1.97113e-06,0,0,0,0,0,0,0,0
4685000,0.982839,-0.0077651,-0.0128331,0.183852,0.0119063,-0.00329666,-0.142687,0.00486118,-0.000875816,-0.0940319,-1.62797e-05,-5.52694e-05,1.36933e-05,0,0,-0.000728607,0.203316,0.00195799,0.434329,0,0,0,0,0,1.76337e-05,0.00123023,0.00123044,0.00049899,0.508956,0.50898,0.10778,0.170646,0.170651,0.145101,9.00258e-08,9.01034e-08,3.22061e-08,0,0,1.87163e-06,0,0,0,0,0,0,0,0
4785000,0.982797,-0.00759191,-0.0127674,0.184091,0.00365462,-0.00250183,-0.141589,0.00310044,-0.000630766,-0.0959576,-1.69028e-05,-5.61862e-05,1.21114e-05,0,0,-0.00075503,0.203316,0.00195799,0.434329,0,0,0,0,0,1.71256e-05,0.000975899,0.00097608,0.000486999,0.385058,0.385069,0.105532,0.121092,0.121094,0.143905,7.21994e-08,7.22617e-08,3.0081e-08,0,0,1.77399e-06,0,0,0,0,0,0,0,0
4885000,0.982832,-0.00754908,-0.0127995,0.183903,0.00488292,-0.00505069,-0.138381,0.00356151,-0.0010229,-0.0969377,-1.68643e-05,-5.61919e-05,1.32926e-05,0,0,-0.000782419,0.203316,0.00195799,0.434329,0,0,0,0,0,1.71264e-05,0.00105966,0.00105985,0.000486255,0.463103,0.463115,0.105757,0.161839,0.161842,0.14802,7.2199e-08,7.22613e-08,2.8613e-08,0,0,1.70227e-06,0,0,0,0,0,0,0,0
4985000,0.982821,-0.00747087,-0.0127045,0.183973,0.00406715,-0.00356345,-0.131602,0.00225841,-0.000807549,-0.0932238,-1.73753e-05,-5.67479e-05,1.23131e-05,0,0,-0.000818243,0.203316,0.00195799,0.434329,0,0,0,0,0,1.66374e-05,0.000839767,0.000839931,0.000474824,0.351274,0.351282,0.103268,0.115726,0.115728,0.14671,5.77202e-08,5.77699e-08,2.67904e-08,0,0,1.60915e-06,0,0,0,0,0,0,0,0
5085000,0.982772,-0.00735108,-0.0126438,0.184242,0.00500236,-0.00367886,-0.127284,0.00276879,-0.00121663,-0.0895953,-1.73888e-05,-5.67062e-05,1.0707e-05,0,0,-0.000852176,0.203316,0.00195799,0.434329,0,0,0,0,0,1.62858e-05,0.000909294,0.000909466,0.000463956,0.420474,0.420485,0.100736,0.153566,0.153568,0.145416,5.77197e-08,5.77694e-08,2.51274e-08,0,0,1.51946e-06,0,0,0,0,0,0,0,0
5185000,0.982766,-0.00721237,-0.0126904,0.184279,0.00308785,-0.00159753,-0.124137,0.00318584,-0.00149073,-0.0875634,-1.73778e-05,-5.66898e-05,1.04638e-05,0,0,-0.000881879,0.203316,0.00195799,0.434329,0,0,0,0,0,1.59508e-05,0.000981708,0.000981885,0.00045353,0.499458,0.499475,0.0981216,0.203083,0.203087,0.144061,5.77193e-08,5.7769e-08,2.35967e-08,0,0,1.43286e-06,0,0,0,0,0,0,0,0
5285000,0.982775,-0.00706961,-0.0126048,0.184242,0.00199042,0.00018851,-0.113361,0.00194215,-0.000840493,-0.0813374,-1.7769e-05,-5.70755e-05,1.06596e-05,0,0,-0.00091821,0.203316,0.00195799,0.434329,0,0,0,0,0,1.55333e-05,0.0007782,0.000778346,0.000443478,0.380941,0.380953,0.0954422,0.145796,0.145798,0.142645,4.60697e-08,4.6109e-08,2.21787e-08,0,0,1.34958e-06,0,0,0,0,0,0,0,0
5385000,0.98276,-0.00697843,-0.0126149,0.184324,-0.000279016,0.0022408,-0.108651,0.00207772,-0.000772074,-0.0762985,-1.77738e-05,-5.70491e-05,9.74502e-06,0,0,-0.000949966,0.203316,0.00195799,0.434329,0,0,0,0,0,1.52115e-05,0.00083807,0.000838223,0.000433923,0.450386,0.450402,0.0927601,0.19147,0.191473,0.141237,4.60693e-08,4.61086e-08,2.08787e-08,0,0,1.27023e-06,0,0,0,0,0,0,0,0
5485000,0.982743,-0.00697261,-0.0126441,0.184413,-0.000902453,0.00541753,-0.105568,0.00104033,-7.85796e-05,-0.0771071,-1.79882e-05,-5.72695e-05,8.95245e-06,0,0,-0.000969272,0.203316,0.00195799,0.434329,0,0,0,0,0,1.51269e-05,0.000665036,0.000665163,0.000433198,0.344901,0.344915,0.0923273,0.138496,0.138498,0.1449,3.67647e-08,3.67958e-08,1.99637e-08,0,0,1.21316e-06,0,0,0,0,0,0,0,0
5585000,0.982741,-0.00699505,-0.0126794,0.184419,-0.0012885,0.00832179,-0.0973984,0.00101659,0.000605647,-0.0694874,-1.79908e-05,-5.72528e-05,8.34106e-06,0,0,-0.00100264,0.203316,0.00195799,0.434329,0,0,0,0,0,1.48138e-05,0.000714483,0.000714619,0.000424054,0.405748,0.405768,0.089548,0.180623,0.180626,0.143333,3.67644e-08,3.67955e-08,1.88304e-08,0,0,1.14024e-06,0,0,0,0,0,0,0,0
5685000,0.982713,-0.00698514,-0.0125569,0.184579,-0.00165948,0.00999922,-0.0972876,0.000392444,0.00105634,-0.0690064,-1.7962e-05,-5.73749e-05,6.70077e-06,0,0,-0.00102142,0.203316,0.00195799,0.434329,0,0,0,0,0,1.44451e-05,0.000568092,0.000568206,0.000415232,0.312177,0.312192,0.0867608,0.131662,0.131664,0.14171,2.93695e-08,2.93941e-08,1.77755e-08,0,0,1.07091e-06,0,0,0,0,0,0,0,0
5785000,0.982762,-0.00685896,-0.0125348,0.184322,-0.00150466,0.011859,-0.0911082,0.000274827,0.00212665,-0.0629584,-1.79404e-05,-5.73892e-05,7.55155e-06,0,0,-0.00104932,0.203316,0.00195799,0.434329,0,0,0,0,0,1.4153e-05,0.00060894,0.000609059,0.000406809,0.36564,0.365659,0.084019,0.170526,0.170529,0.140101,2.93692e-08,2.93938e-08,1.68024e-08,0,0,1.00551e-06,0,0,0,0,0,0,0,0
5885000,0.982746,-0.00684875,-0.0125817,0.184403,0.000620451,0.0111966,-0.0875361,0.000152401,0.00217681,-0.0644408,-1.76779e-05,-5.75151e-05,7.05841e-06,0,0,-0.00106245,0.203316,0.00195799,0.434329,0,0,0,0,0,1.38389e-05,0.000485511,0.000485608,0.000398653,0.282384,0.282397,0.0812934,0.125278,0.125279,0.138444,2.35092e-08,2.35287e-08,1.58946e-08,0,0,9.43622e-07,0,0,0,0,0,0,0,0
5985000,0.982698,-0.00680083,-0.0127011,0.184653,0.00129749,0.012274,-0.0805704,0.000284545,0.00332648,-0.058574,-1.77095e-05,-5.74811e-05,5.39839e-06,0,0,-0.00108729,0.203316,0.00195799,0.434329,0,0,0,0,0,1.35771e-05,0.000519292,0.000519394,0.00039086,0.329247,0.329263,0.0786301,0.161139,0.161142,0.136806,2.35089e-08,2.35284e-08,1.50546e-08,0,0,8.85479e-07,0,0,0,0,0,0,0,0
6085000,0.982656,-0.00686316,-0.012627,0.184882,0.000399645,0.0109139,-0.0770647,0.000222145,0.0028136,-0.056762,-1.73881e-05,-5.76151e-05,3.03291e-06,0,0,-0.0011037,0.203316,0.00195799,0.434329,0,0,0,0,0,1.32608e-05,0.000415459,0.000415544,0.000383344,0.255618,0.255629,0.0760005,0.119317,0.119318,0.13513,1.88719e-08,1.88875e-08,1.42692e-08,0,0,8.30655e-07,0,0,0,0,0,0,0,0
6185000,0.982627,-0.00689007,-0.0125859,0.185036,-0.000350469,0.0124821,-0.0755668,0.000277192,0.00400324,-0.0563861,-1.74048e-05,-5.75985e-05,2.20694e-06,0,0,-0.00111726,0.203316,0.00195799,0.434329,0,0,0,0,0,1.32532e-05,0.000443452,0.000443544,0.000382728,0.296872,0.296886,0.0752292,0.152437,0.15244,0.138085,1.88718e-08,1.88874e-08,1.37171e-08,0,0,7.91674e-07,0,0,0,0,0,0,0,0
6285000,0.982602,-0.00692838,-0.0125973,0.185167,-0.00204504,0.0116086,-0.0764529,6.89575e-05,0.00324669,-0.0601447,-1.70111e-05,-5.7768e-05,1.65025e-06,0,0,-0.0011235,0.203316,0.00195799,0.434329,0,0,0,0,0,1.29903e-05,0.000356177,0.000356252,0.000375477,0.231725,0.231734,0.0726393,0.11377,0.113771,0.136286,1.5202e-08,1.52144e-08,1.30222e-08,0,0,7.42526e-07,0,0,0,0,0,0,0,0
6385000,0.982625,-0.00688028,-0.0125372,0.185051,-0.000945014,0.0131115,-0.0755588,-0.000122388,0.00447316,-0.0614791,-1.70012e-05,-5.77779e-05,2.13977e-06,0,0,-0.0011334,0.203316,0.00195799,0.434329,0,0,0,0,0,1.27608e-05,0.000379433,0.000379513,0.00036853,0.26802,0.268032,0.070135,0.144396,0.144398,0.134521,1.52018e-08,1.52142e-08,1.23757e-08,0,0,6.96595e-07,0,0,0,0,0,0,0,0
6485000,0.982296,-0.00688562,-0.0125388,0.186789,-0.00313811,0.00887285,-0.0715144,-0.000216531,0.00342089,-0.0582506,-1.65898e-05,-5.79154e-05,1.80064e-06,0,0,-0.00114972,0.204182,0.00196632,0.433697,0,0,0,0,0,8.81048e-05,0.000302622,0.000302446,0.00246226,0.204394,0.2044,0.0676886,0.108594,0.108595,0.132734,1.22936e-08,1.23035e-08,1.19163e-08,0,0,6.53496e-07,0,0,0,0,0,0,0,0
6585000,0.98221,-0.00684311,-0.0124982,0.187244,-0.00382721,0.00998736,-0.0725566,-0.000541158,0.00431743,-0.0600432,-1.65904e-05,-5.79156e-05,1.79328e-06,0,0,-0.00115795,0.204182,0.00196632,0.433697,0,0,0,0,0,6.06068e-05,0.000302985,0.000302892,0.00169441,0.206732,0.206739,0.0653048,0.135731,0.135733,0.130934,1.22937e-08,1.23036e-08,1.1916e-08,0,0,6.13103e-07,0,0,0,0,0,0,0,0
6685000,0.982156,-0.00675043,-0.0124725,0.187531,-0.00682235,0.0102012,-0.0737893,-0.000741562,0.00337511,-0.0598114,-1.62067e-05,-5.79859e-05,1.74968e-06,0,0,-0.0011692,0.204182,0.00196632,0.433697,0,0,0,0,0,4.6199e-05,0.000303538,0.000303487,0.00129208,0.14726,0.147265,0.0630121,0.10177,0.101771,0.129174,1.00668e-08,1.00748e-08,1.19135e-08,0,0,5.75445e-07,0,0,0,0,0,0,0,0
6785000,0.98214,-0.0067883,-0.0124082,0.187622,-0.00574505,0.0116209,-0.0704507,-0.00141342,0.00442825,-0.0592426,-1.62077e-05,-5.79862e-05,1.73838e-06,0,0,-0.00118033,0.204182,0.00196632,0.433697,0,0,0,0,0,3.92316e-05,0.000304838,0.000304811,0.00109743,0.155251,0.155256,0.0622365,0.123826,0.123827,0.131649,1.00669e-08,1.00749e-08,1.19118e-08,0,0,5.48844e-07,0,0,0,0,0,0,0,0
6885000,0.982133,-0.0066136,-0.0123239,0.187667,-0.00522643,0.00894474,-0.0668843,-0.00127005,0.00348281,-0.0579695,-1.5842e-05,-5.79961e-05,1.71753e-06,0,0,-0.00119171,0.204182,0.00196632,0.433697,0,0,0,0,0,3.26685e-05,0.000304279,0.000304269,0.000914263,0.120744,0.120747,0.0600308,0.0940814,0.0940822,0.129809,8.4379e-09,8.44446e-09,1.19071e-08,0,0,5.15385e-07,0,0,0,0,0,0,0,0
6985000,0.982177,-0.00657213,-0.0122854,0.187439,-0.00613563,0.00972837,-0.0629413,-0.00188596,0.00440964,-0.0551094,-1.58421e-05,-5.79972e-05,1.75447e-06,0,0,-0.00120451,0.204182,0.00196632,0.433697,0,0,0,0,0,2.80168e-05,0.000305936,0.000305939,0.000784113,0.133395,0.133397,0.0578957,0.112637,0.112638,0.12797,8.43799e-09,8.44455e-09,1.19013e-08,0,0,4.84094e-07,0,0,0,0,0,0,0,0
7085000,0.98216,-0.00649522,-0.0121931,0.187541,-0.00626568,0.0125995,-0.0626713,-0.00167256,0.00371238,-0.0560218,-1.54952e-05,-5.7979e-05,1.73677e-06,0,0,-0.00121168,0.204182,0.00196632,0.433697,0,0,0,0,0,2.45667e-05,0.00030191,0.000301922,0.000687036,0.113467,0.113468,0.0558521,0.0873495,0.0873503,0.126181,7.25076e-09,7.25628e-09,1.18924e-08,0,0,4.54968e-07,0,0,0,0,0,0,0,0
7185000,0.982138,-0.00643656,-0.0122594,0.187655,-0.00735696,0.0142704,-0.0610995,-0.00240364,0.0051097,-0.057747,-1.54966e-05,-5.79778e-05,1.68144e-06,0,0,-0.00121762,0.204182,0.00196632,0.433697,0,0,0,0,0,2.18858e-05,0.000303539,0.000303556,0.000612021,0.129944,0.129945,0.0538781,0.103923,0.103924,0.124397,7.25086e-09,7.25638e-09,1.18816e-08,0,0,4.27742e-07,0,0,0,0,0,0,0,0
7285000,0.982157,-0.0064183,-0.0122664,0.187555,-0.00710323,0.0170889,-0.0568271,-0.00320066,0.00665931,-0.0530881,-1.54966e-05,-5.79779e-05,1.71337e-06,0,0,-0.00123106,0.204182,0.00196632,0.433697,0,0,0,0,0,1.97539e-05,0.000305531,0.000305555,0.000552455,0.149159,0.149159,0.0519915,0.123665,0.123667,0.122664,7.25095e-09,7.25647e-09,1.18678e-08,0,0,4.02405e-07,0,0,0,0,0,0,0,0
7385000,0.982186,-0.00639496,-0.0122627,0.187402,-0.00823351,0.0175176,-0.0533787,-0.0028141,0.00610605,-0.0496037,-1.51335e-05,-5.79507e-05,1.74421e-06,0,0,-0.00124233,0.204182,0.00196632,0.433697,0,0,0,0,0,1.80181e-05,0.000295069,0.000295094,0.000504132,0.13684,0.136839,0.0501722,0.0980679,0.0980687,0.120941,6.38663e-09,6.39139e-09,1.18502e-08,0,0,3.78722e-07,0,0,0,0,0,0,0,0
7485000,0.982229,-0.00635757,-0.0122957,0.187178,-0.00628522,0.020183,-0.0488459,-0.00353862,0.00800403,-0.0460044,-1.51305e-05,-5.79528e-05,1.89798e-06,0,0,-0.00125296,0.204182,0.00196632,0.433697,0,0,0,0,0,1.69619e-05,0.000296717,0.000296743,0.000474392,0.158846,0.158845,0.0495034,0.117343,0.117344,0.122934,6.38672e-09,6.39149e-09,1.1835e-08,0,0,3.61992e-07,0,0,0,0,0,0,0,0
7585000,0.982256,-0.00651597,-0.0122756,0.187028,-0.00464342,0.0194101,-0.0443779,-0.00286472,0.00710875,-0.0396874,-1.4755e-05,-5.79379e-05,1.9735e-06,0,0,-0.001266,0.204182,0.00196632,0.433697,0,0,0,0,0,1.57166e-05,0.000278674,0.0002787,0.000439618,0.147972,0.14797,0.0477773,0.0948292,0.0948297,0.121171,5.76898e-09,5.77321e-09,1.18109e-08,0,0,3.40998e-07,0,0,0,0,0,0,0,0
7685000,0.982262,-0.00654217,-0.0123374,0.186991,-0.00525002,0.0226183,-0.0424011,-0.00336878,0.00926538,-0.0329992,-1.47548e-05,-5.79355e-05,1.9643e-06,0,0,-0.00127878,0.204182,0.00196632,0.433697,0,0,0,0,0,1.46695e-05,0.000279832,0.000279861,0.000410299,0.171837,0.171834,0.0461314,0.114556,0.114557,0.119463,5.76906e-09,5.7733e-09,1.17831e-08,0,0,3.21455e-07,0,0,0,0,0,0,0,0
7785000,0.982256,-0.0065264,-0.0123557,0.187022,-0.00272371,0.0205165,-0.0439841,-0.00260964,0.00805321,-0.0370073,-1.44004e-05,-5.79455e-05,1.90981e-06,0,0,-0.00127904,0.204182,0.00196632,0.433697,0,0,0,0,0,1.3776e-05,0.000253949,0.000253973,0.000385328,0.158545,0.158542,0.0445476,0.0935964,0.0935966,0.117771,5.3471e-09,5.35098e-09,1.17506e-08,0,0,3.03183e-07,0,0,0,0,0,0,0,0
7885000,0.982244,-0.00655322,-0.0124292,0.18708,-0.00432941,0.0240532,-0.0434957,-0.00305248,0.0102657,-0.0396511,-1.44004e-05,-5.79449e-05,1.90443e-06,0,0,-0.00128092,0.204182,0.00196632,0.433697,0,0,0,0,0,1.30252e-05,0.0002546,0.000254626,0.000363889,0.182878,0.182875,0.0430251,0.114199,0.114199,0.116098,5.34719e-09,5.35106e-09,1.17136e-08,0,0,2.86097e-07,0,0,0,0,0,0,0,0
7985000,0.98225,-0.00661143,-0.0123535,0.187053,-0.00313083,0.0214238,-0.0392903,-0.00238055,0.00874738,-0.0357985,-1.40866e-05,-5.79719e-05,1.98126e-06,0,0,-0.00128968,0.204182,0.00196632,0.433697,0,0,0,0,0,1.23678e-05,0.000222448,0.000222468,0.000345377,0.164684,0.16468,0.0415739,0.0935208,0.0935207,0.114479,5.07989e-09,5.08354e-09,1.16717e-08,0,0,2.7018e-07,0,0,0,0,0,0,0,0
8085000,0.982227,-0.00650469,-0.0123512,0.187177,-0.00225337,0.0244581,-0.0395193,-0.00261409,0.0110232,-0.0382627,-1.40917e-05,-5.79659e-05,1.72696e-06,0,0,-0.00129131,0.204182,0.00196632,0.433697,0,0,0,0,0,1.19741e-05,0.000222688,0.000222708,0.000334395,0.188331,0.188328,0.041031,0.114954,0.114953,0.116192,5.07998e-09,5.08363e-09,1.16371e-08,0,0,2.5894e-07,0,0,0,0,0,0,0,0
8185000,0.982214,-0.00668734,-0.012283,0.187245,-0.000974271,0.0247439,-0.0356833,-0.00185852,0.00935402,-0.0334855,-1.38418e-05,-5.79988e-05,1.60603e-06,0,0,-0.00130029,0.204182,0.00196632,0.433697,0,0,0,0,0,1.14568e-05,0.000187419,0.000187433,0.000319965,0.164628,0.164627,0.0396614,0.0937173,0.0937171,0.114553,4.92768e-09,4.93121e-09,1.15861e-08,0,0,2.44797e-07,0,0,0,0,0,0,0,0
8285000,0.982224,-0.00667846,-0.0122693,0.187191,0.00124337,0.0271871,-0.0329125,-0.00186266,0.0119308,-0.0319891,-1.38418e-05,-5.79956e-05,1.55955e-06,0,0,-0.00130516,0.204182,0.00196632,0.433697,0,0,0,0,0,1.10029e-05,0.000187424,0.000187439,0.000307371,0.186481,0.18648,0.0383461,0.115589,0.115589,0.112936,4.92776e-09,4.93128e-09,1.15296e-08,0,0,2.31558e-07,0,0,0,0,0,0,0,0
8385000,0.982225,-0.00677915,-0.0122594,0.187182,-0.000613645,0.023134,-0.0309678,-0.00119852,0.00982395,-0.0282536,-1.36519e-05,-5.80387e-05,1.59535e-06,0,0,-0.00131198,0.204182,0.00196632,0.433697,0,0,0,0,0,1.06089e-05,0.000152716,0.000152725,0.000296332,0.158345,0.158344,0.0370929,0.0934911,0.0934909,0.111374,4.85227e-09,4.85573e-09,1.14676e-08,0,0,2.19206e-07,0,0,0,0,0,0,0,0
8485000,0.982255,-0.00669197,-0.0122576,0.187032,-0.00101486,0.0257558,-0.03143,-0.00125372,0.0122288,-0.0322799,-1.36451e-05,-5.80463e-05,1.9329e-06,0,0,-0.00131104,0.204182,0.00196632,0.433697,0,0,0,0,0,1.02702e-05,0.000152698,0.000152707,0.000286646,0.177742,0.177741,0.0358896,0.115247,0.115246,0.109834,4.85234e-09,4.85579e-09,1.13999e-08,0,0,2.07635e-07,0,0,0,0,0,0,0,0
8585000,0.982266,-0.00678311,-0.0123527,0.186964,0.000301874,0.022059,-0.0259923,-0.000872753,0.00985418,-0.0268789,-1.35206e-05,-5.80767e-05,1.91856e-06,0,0,-0.00131883,0.204182,0.00196632,0.433697,0,0,0,0,0,9.95828e-06,0.000121556,0.000121558,0.000278144,0.147227,0.147227,0.0347431,0.0924779,0.0924777,0.108345,4.82128e-09,4.82471e-09,1.13265e-08,0,0,1.9683e-07,0,0,0,0,0,0,0,0
8685000,0.982297,-0.00683014,-0.0124405,0.186794,0.000255486,0.0226707,-0.0271191,-0.000883413,0.0120775,-0.0285384,-1.35163e-05,-5.80802e-05,2.11374e-06,0,0,-0.00131966,0.204182,0.00196632,0.433697,0,0,0,0,0,9.68807e-06,0.00012171,0.000121713,0.00027067,0.163891,0.163891,0.0336421,0.113567,0.113567,0.106878,4.82134e-09,4.82477e-09,1.12471e-08,0,0,1.86698e-07,0,0,0,0,0,0,0,0
8785000,0.982294,-0.00691172,-0.0123922,0.186806,0.00150029,0.0187933,-0.0259397,-0.000569335,0.00944472,-0.0250863,-1.34502e-05,-5.80953e-05,1.98842e-06,0,0,-0.0013252,0.204182,0.00196632,0.433697,0,0,0,0,0,9.56558e-06,9.58087e-05,9.58068e-05,0.000267345,0.13339,0.133391,0.033226,0.0906204,0.0906203,0.108316,4.8117e-09,4.81512e-09,1.11837e-08,0,0,1.79517e-07,0,0,0,0,0,0,0,0
8885000,0.982331,-0.00697661,-0.012388,0.186609,0.00185949,0.0205179,-0.0223575,-0.000380559,0.0114344,-0.0192377,-1.34395e-05,-5.80975e-05,2.37374e-06,0,0,-0.00133253,0.204182,0.00196632,0.433697,0,0,0,0,0,9.35499e-06,9.62846e-05,9.62839e-05,0.000261423,0.147333,0.147334,0.0321891,0.110626,0.110626,0.106843,4.81176e-09,4.81518e-09,1.10939e-08,0,0,1.70471e-07,0,0,0,0,0,0,0,0
8985000,0.982369,-0.00700141,-0.0123034,0.186416,0.00105636,0.018268,-0.0203317,-0.000196441,0.00890234,-0.0208571,-1.34014e-05,-5.81187e-05,2.91628e-06,0,0,-0.00133288,0.204182,0.00196632,0.433697,0,0,0,0,0,9.1703e-06,7.60225e-05,7.60185e-05,0.000256221,0.118545,0.118546,0.0312009,0.0880611,0.0880611,0.105421,4.81006e-09,4.81347e-09,1.09984e-08,0,0,1.62009e-07,0,0,0,0,0,0,0,0
9085000,0.982421,-0.00702819,-0.0123737,0.186134,0.00149625,0.0208119,-0.0215759,-7.48274e-05,0.0108097,-0.0204758,-1.33879e-05,-5.81294e-05,3.52793e-06,0,0,-0.00133492,0.204182,0.00196632,0.433697,0,0,0,0,0,9.006e-06,7.69191e-05,7.69155e-05,0.000251662,0.130092,0.130093,0.0302519,0.10672,0.10672,0.104021,4.81012e-09,4.81352e-09,1.0897e-08,0,0,1.54059e-07,0,0,0,0,0,0,0,0
9185000,0.982454,-0.00710584,-0.0124023,0.185954,0.00446131,0.0167888,-0.0195879,0.000133669,0.00856656,-0.0202305,-1.33729e-05,-5.81406e-05,4.07377e-06,0,0,-0.00133683,0.204182,0.00196632,0.433697,0,0,0,0,0,8.86454e-06,6.18534e-05,6.18473e-05,0.000247657,0.104164,0.104165,0.0293402,0.0850157,0.0850158,0.102644,4.81014e-09,4.81354e-09,1.07896e-08,0,0,1.46589e-07,0,0,0,0,0,0,0,0
9285000,0.982479,-0.00697071,-0.012228,0.185839,0.00667343,0.0180256,-0.0177532,0.000747894,0.0102872,-0.0174048,-1.33645e-05,-5.81431e-05,4.39401e-06,0,0,-0.00134063,0.204182,0.00196632,0.433697,0,0,0,0,0,8.74291e-06,6.32232e-05,6.32179e-05,0.000244163,0.113661,0.113662,0.0284713,0.102221,0.102221,0.101314,4.81019e-09,4.81359e-09,1.06769e-08,0,0,1.3959e-07,0,0,0,0,0,0,0,0
9385000,0.982472,-0.00687734,-0.012268,0.18588,0.00682212,0.0186499,-0.0161558,0.00145755,0.0121371,-0.0171797,-1.3369e-05,-5.81363e-05,4.13937e-06,0,0,-0.00134213,0.204182,0.00196632,0.433697,0,0,0,0,0,8.73208e-06,6.48349e-05,6.48291e-05,0.000243826,0.123601,0.123603,0.0281494,0.122426,0.122426,0.102593,4.81025e-09,4.81365e-09,1.05888e-08,0,0,1.34624e-07,0,0,0,0,0,0,0,0
9485000,0.982501,-0.00699011,-0.0123205,0.185719,0.00599315,0.0143852,-0.0137484,0.00154162,0.00952244,-0.0130986,-1.33693e-05,-5.81333e-05,4.42276e-06,0,0,-0.00134648,0.204182,0.00196632,0.433697,0,0,0,0,0,8.63023e-06,5.43905e-05,5.43833e-05,0.000241114,0.0989248,0.0989266,0.0273306,0.0974546,0.0974549,0.101263,4.8101e-09,4.81348e-09,1.04665e-08,0,0,1.28343e-07,0,0,0,0,0,0,0,0
9585000,0.982474,-0.00702805,-0.012298,0.185863,0.00546157,0.0134474,-0.014319,0.00203951,0.0109001,-0.0160404,-1.33784e-05,-5.81267e-05,4.01673e-06,0,0,-0.00134525,0.204182,0.00196632,0.433697,0,0,0,0,0,8.55295e-06,5.64979e-05,5.64917e-05,0.000238747,0.107213,0.107215,0.0265439,0.115812,0.115812,0.0999551,4.81014e-09,4.81352e-09,1.03389e-08,0,0,1.22429e-07,0,0,0,0,0,0,0,0
9685000,0.982486,-0.00708925,-0.0122321,0.185799,0.00467084,0.0108056,-0.0110338,0.00191255,0.00849878,-0.0135112,-1.33883e-05,-5.81159e-05,3.93213e-06,0,0,-0.00134813,0.204182,0.00196632,0.433697,0,0,0,0,0,8.47465e-06,4.95186e-05,4.95119e-05,0.00023671,0.086289,0.0862907,0.0257934,0.092674,0.0926743,0.0986914,4.80983e-09,4.8132e-09,1.02067e-08,0,0,1.16877e-07,0,0,0,0,0,0,0,0
9785000,0.982473,-0.00707295,-0.0121843,0.185874,0.00592486,0.0122593,-0.0115362,0.00246498,0.00967008,-0.0138284,-1.34001e-05,-5.81032e-05,3.34367e-06,0,0,-0.00134878,0.204182,0.00196632,0.433697,0,0,0,0,0,8.40834e-06,5.21248e-05,5.21189e-05,0.000234947,0.0933615,0.0933638,0.025072,0.10932,0.109321,0.0974496,4.80987e-09,4.81324e-09,1.00696e-08,0,0,1.11644e-07,0,0,0,0,0,0,0,0
9885000,0.982491,-0.00709079,-0.0121092,0.185782,0.00738789,0.0090907,-0.00983774,0.00224866,0.00742178,-0.0139179,-1.33978e-05,-5.81064e-05,3.69381e-06,0,0,-0.00134947,0.204182,0.00196632,0.433697,0,0,0,0,0,8.35733e-06,4.77869e-05,4.77807e-05,0.000233424,0.0758923,0.0758944,0.0243834,0.0880566,0.088057,0.0962491,4.80978e-09,4.81315e-09,9.92839e-09,0,0,1.06725e-07,0,0,0,0,0,0,0,0
9985000,0.982465,-0.00708801,-0.0121845,0.185916,0.00889065,0.00850377,-0.00874166,0.00304057,0.00824319,-0.0149381,-1.34092e-05,-5.80953e-05,3.14146e-06,0,0,-0.00134945,0.204182,0.00196632,0.433697,0,0,0,0,0,8.31419e-06,5.08839e-05,5.08777e-05,0.000232111,0.0821179,0.0821203,0.0237212,0.103175,0.103175,0.0950692,4.80982e-09,4.81318e-09,9.78291e-09,0,0,1.02084e-07,0,0,0,0,0,0,0,0
10085000,0.982457,-0.00707194,-0.0123241,0.185949,0.0070664,0.00382526,-0.00753524,0.00281245,0.00618643,-0.0133407,-1.34142e-05,-5.80877e-05,2.74839e-06,0,0,-0.00135113,0.204182,0.00196632,0.433697,0,0,0,0,0,8.36049e-06,4.85124e-05,4.85046e-05,0.000233473,0.0676838,0.0676857,0.0234824,0.0837195,0.08372,0.0961867,4.80982e-09,4.81317e-09,9.67125e-09,0,0,9.87784e-08,0,0,0,0,0,0,0,0
10185000,0.982419,-0.00704652,-0.0122432,0.186156,0.00489826,0.00415075,-0.0058436,0.00339016,0.00660014,-0.013354,-1.34311e-05,-5.80701e-05,1.90957e-06,0,0,-0.00135163,0.204182,0.00196632,0.433697,0,0,0,0,0,8.32954e-06,5.2084e-05,5.20771e-05,0.000232483,0.0734113,0.0734134,0.0228576,0.0975166,0.0975172,0.0950105,4.80985e-09,4.81319e-09,9.51928e-09,0,0,9.45884e-08,0,0,0,0,0,0,0,0
10285000,0.98245,-0.00711275,-0.0121508,0.185993,0.00438579,0.00276498,-0.00688634,0.00274617,0.00488916,-0.0132416,-1.34126e-05,-5.80895e-05,2.372e-06,0,0,-0.00135208,0.204182,0.00196632,0.433697,0,0,0,0,0,8.29916e-06,5.11401e-05,5.11338e-05,0.00023164,0.0615652,0.0615672,0.022261,0.0797412,0.0797416,0.0938733,4.8087e-09,4.81204e-09,9.36433e-09,0,0,9.06418e-08,0,0,0,0,0,0,0,0
10385000,0.982476,-0.00712362,-0.0120518,0.185865,0.00718801,0.00201435,-0.00298405,0.000774448,3.00987e-05,-0.0114163,-1.34045e-05,-5.80942e-05,2.72489e-06,0,0,-0.00135338,0.204182,0.00196632,0.433697,0,0,0,0,0,8.27429e-06,5.51688e-05,5.51636e-05,0.000230909,0.0347595,0.0347596,0.0374564,0.12528,0.12528,0.08678,4.80874e-09,4.81206e-09,9.20635e-09,0,0,8.71036e-08,0,0,0,0,0,0,0,0
10485000,0.982464,-0.00703651,-0.0120027,0.18593,0.00747662,0.0013724,-0.00193119,0.00149988,0.000196693,-0.00675368,-1.34135e-05,-5.80775e-05,2.18056e-06,0,0,-0.00135663,0.204182,0.00196632,0.433697,0,0,0,0,0,8.25018e-06,5.9438e-05,5.94331e-05,0.000230276,0.0354828,0.0354829,0.0375607,0.126254,0.126254,0.0808894,4.80877e-09,4.81209e-09,9.0457e-09,0,0,8.41249e-08,0,0,0,0,0,0,0,0
10585000,0.982484,-0.00698381,-0.0119454,0.185832,0.00609668,0.00064535,-0.00063084,0.00117096,-0.00344862,-0.00580416,-1.34295e-05,-5.81898e-05,2.73085e-06,0,0,-0.00135712,0.204182,0.00196632,0.433697,0,0,0,0,0,8.23836e-06,6.37568e-05,6.37522e-05,0.000229718,0.0320569,0.032057,0.0352721,0.084862,0.084862,0.0763588,4.79966e-09,4.80297e-09,8.88309e-09,0,0,8.1581e-08,0,0,0,0,0,0,0,0
10685000,0.982497,-0.00694293,-0.0119807,0.185761,0.00658377,-0.00169698,-0.000521176,0.00179782,-0.00350563,-0.00490566,-1.34307e-05,-5.81872e-05,2.6531e-06,0,0,-0.00135772,0.204182,0.00196632,0.433697,0,0,0,0,0,8.3052e-06,6.84941e-05,6.84894e-05,0.000231687,0.0336846,0.0336848,0.0353175,0.0865836,0.0865836,0.0744977,4.79971e-09,4.80302e-09,8.75997e-09,0,0,7.99102e-08,0,0,0,0,0,0,0,0
10785000,0.982505,-0.00694757,-0.012085,0.185714,0.0073339,-0.00294898,0.00036227,0.00171207,-0.00315653,-0.00196399,-1.33764e-05,-5.82904e-05,2.55649e-06,0,0,-0.0013595,0.204182,0.00196632,0.433697,0,0,0,0,0,8.28769e-06,7.26273e-05,7.26223e-05,0.000231244,0.0313817,0.0313821,0.0331901,0.0657142,0.0657142,0.0717274,4.76314e-09,4.76641e-09,8.59431e-09,0,0,7.79341e-08,0,0,0,0,0,0,0,0
10885000,0.982532,-0.00692748,-0.0121331,0.185566,0.00786231,-0.00296605,0.000563778,0.00247349,-0.0035085,-0.00134342,-1.33606e-05,-5.8305e-05,3.31707e-06,0,0,-0.0013598,0.204182,0.00196632,0.433697,0,0,0,0,0,8.28071e-06,7.77875e-05,7.77826e-05,0.000230826,0.0339912,0.0339918,0.0330662,0.0680221,0.0680221,0.0700823,4.76317e-09,4.76644e-09,8.42731e-09,0,0,7.62135e-08,0,0,0,0,0,0,0,0
10985000,0.982545,-0.0069214,-0.012237,0.185491,0.00618119,0.00252048,0.00256604,0.0022355,-0.00265984,0.00148578,-1.34575e-05,-5.83999e-05,3.2701e-06,0,0,-0.00136096,0.204182,0.00196632,0.433697,0,0,0,0,0,8.26318e-06,8.11031e-05,8.10977e-05,0.000230451,0.0323526,0.0323536,0.0310525,0.0552021,0.0552021,0.0684194,4.68114e-09,4.68433e-09,8.2596e-09,0,0,7.47012e-08,0,0,0,0,0,0,0,0
11085000,0.982504,-0.00705184,-0.0122209,0.185706,0.00703182,0.00480332,0.00444282,0.00286943,-0.00235468,0.00414787,-1.34728e-05,-5.8382e-05,2.48186e-06,0,0,-0.00136224,0.204182,0.00196632,0.433697,0,0,0,0,0,8.25648e-06,8.66061e-05,8.66024e-05,0.000230077,0.0359879,0.0359895,0.030787,0.058071,0.0580711,0.0678402,4.68117e-09,4.68436e-09,8.09124e-09,0,0,7.33767e-08,0,0,0,0,0,0,0,0
11185000,0.982505,-0.00707679,-0.0121803,0.185703,0.00680491,0.00654997,0.00767957,0.00327233,-0.00167144,0.00882245,-1.33744e-05,-5.83625e-05,2.03908e-06,0,0,-0.00136391,0.204182,0.00196632,0.433697,0,0,0,0,0,8.2374e-06,8.83792e-05,8.83764e-05,0.000229728,0.034579,0.0345808,0.0288837,0.0491241,0.0491242,0.0668009,4.53899e-09,4.54209e-09,7.92278e-09,0,0,7.22064e-08,0,0,0,0,0,0,0,0
11285000,0.982494,-0.00708448,-0.0122151,0.185756,0.00596352,0.00613038,0.00874235,0.00386831,-0.000981562,0.00862134,-1.33795e-05,-5.83589e-05,1.80869e-06,0,0,-0.00136344,0.204182,0.00196632,0.433697,0,0,0,0,0,8.2288e-06,9.41095e-05,9.41072e-05,0.000229364,0.0392336,0.0392359,0.0284959,0.0525789,0.0525792,0.0668742,4.53902e-09,4.54212e-09,7.75434e-09,0,0,7.11792e-08,0,0,0,0,0,0,0,0
11385000,0.982495,-0.00700845,-0.0121918,0.185756,0.00470355,0.00661387,0.00783225,0.00324165,-0.000615183,0.00675774,-1.33113e-05,-5.85916e-05,1.67622e-06,0,0,-0.00136216,0.204182,0.00196632,0.433697,0,0,0,0,0,8.30266e-06,9.36761e-05,9.36732e-05,0.00023144,0.0376083,0.0376106,0.0268577,0.0456633,0.0456635,0.0672766,4.3297e-09,4.33266e-09,7.62808e-09,0,0,7.04872e-08,0,0,0,0,0,0,0,0
11485000,0.98252,-0.00692363,-0.0121702,0.185629,0.00326696,0.00596444,0.00950627,0.00359244,3.5837e-05,0.00996826,-1.33078e-05,-5.85924e-05,1.81711e-06,0,0,-0.00136316,0.204182,0.00196632,0.433697,0,0,0,0,0,8.28447e-06,9.94889e-05,9.94863e-05,0.000231055,0.0432048,0.0432076,0.0263927,0.0497376,0.049738,0.0677365,4.32973e-09,4.33269e-09,7.4604e-09,0,0,6.96636e-08,0,0,0,0,0,0,0,0
11585000,0.98252,-0.00702696,-0.0121307,0.18563,0.0047724,0.00568865,0.0100175,0.00309687,0.000108956,0.0113204,-1.31866e-05,-5.8784e-05,1.68206e-06,0,0,-0.00136394,0.204182,0.00196632,0.433697,0,0,0,0,0,8.2689e-06,9.64227e-05,9.64208e-05,0.000230648,0.0409087,0.0409114,0.0247373,0.0438684,0.0438687,0.0671552,4.05678e-09,4.05954e-09,7.29362e-09,0,0,6.89325e-08,0,0,0,0,0,0,0,0
11685000,0.982529,-0.0069894,-0.0120789,0.185588,0.00513982,0.00806404,0.0117537,0.00360079,0.000793884,0.0115453,-1.31854e-05,-5.87861e-05,1.75475e-06,0,0,-0.00136358,0.204182,0.00196632,0.433697,0,0,0,0,0,8.2553e-06,0.000102163,0.000102162,0.000230214,0.047277,0.0472805,0.0242083,0.0485747,0.0485752,0.0677997,4.05681e-09,4.05957e-09,7.12795e-09,0,0,6.82922e-08,0,0,0,0,0,0,0,0
11785000,0.982552,-0.00711995,-0.0120276,0.185464,0.00358269,0.00798569,0.0125724,0.00291215,-0.000313071,0.0143129,-1.26871e-05,-5.91932e-05,2.30942e-06,0,0,-0.00136413,0.204182,0.00196632,0.433697,0,0,0,0,0,8.24052e-06,9.64471e-05,9.64463e-05,0.000229742,0.0439875,0.0439907,0.0226855,0.0431518,0.0431521,0.0672505,3.73506e-09,3.7376e-09,6.96335e-09,0,0,6.77224e-08,0,0,0,0,0,0,0,0
11885000,0.982544,-0.00720233,-0.0119275,0.185508,0.00624737,0.00826979,0.011607,0.00333238,0.000454994,0.0156383,-1.26948e-05,-5.91858e-05,1.93001e-06,0,0,-0.00136416,0.204182,0.00196632,0.433697,0,0,0,0,0,8.2218e-06,0.000101972,0.000101973,0.000229251,0.050946,0.0509501,0.0221237,0.0484674,0.048468,0.067945,3.73509e-09,3.73764e-09,6.80063e-09,0,0,6.72244e-08,0,0,0,0,0,0,0,0
11985000,0.982559,-0.00729453,-0.0119749,0.18542,0.00726238,0.00940221,0.0107314,0.00380247,-0.000355878,0.0130941,-1.25763e-05,-5.91508e-05,2.00245e-06,0,0,-0.00136326,0.204182,0.00196632,0.433697,0,0,0,0,0,8.28384e-06,9.39776e-05,9.39791e-05,0.000231167,0.0464759,0.0464793,0.0209221,0.0431063,0.0431067,0.0685375,3.38591e-09,3.38821e-09,6.67961e-09,0,0,6.68864e-08,0,0,0,0,0,0,0,0
12085000,0.982542,-0.0072135,-0.0120307,0.185509,0.0088651,0.00917182,0.0133305,0.00461834,0.000534116,0.0198603,-1.25812e-05,-5.9142e-05,1.72238e-06,0,0,-0.00136493,0.204182,0.00196632,0.433697,0,0,0,0,0,8.26888e-06,9.9176e-05,9.91773e-05,0.000230591,0.0537605,0.0537646,0.02036,0.0489704,0.0489711,0.0692188,3.38594e-09,3.38825e-09,6.52003e-09,0,0,6.64865e-08,0,0,0,0,0,0,0,0
12185000,0.982536,-0.00710327,-0.011986,0.185548,0.00828546,0.00862472,0.0126762,0.00369711,0.00147517,0.0215087,-1.27619e-05,-5.94359e-05,1.12704e-06,0,0,-0.00136506,0.204182,0.00196632,0.433697,0,0,0,0,0,8.23663e-06,8.95711e-05,8.95711e-05,0.000229983,0.0481608,0.0481638,0.0191127,0.0434395,0.04344,0.068574,3.03235e-09,3.0344e-09,6.36225e-09,0,0,6.61255e-08,0,0,0,0,0,0,0,0
12285000,0.982523,-0.00715516,-0.0119744,0.185619,0.00591851,0.00731018,0.0110873,0.00441827,0.00226493,0.0221197,-1.2769e-05,-5.94294e-05,7.77892e-07,0,0,-0.00136492,0.204182,0.00196632,0.433697,0,0,0,0,0,8.21566e-06,9.43709e-05,9.43721e-05,0.000229335,0.0555758,0.055579,0.0185641,0.0497621,0.0497629,0.0691649,3.03239e-09,3.03444e-09,6.20701e-09,0,0,6.58126e-08,0,0,0,0,0,0,0,0
12385000,0.982532,-0.00721463,-0.0118861,0.185576,0.00443037,0.00534219,0.0115774,0.00353873,0.00164408,0.0192355,-1.26225e-05,-5.97219e-05,5.32305e-07,0,0,-0.001364,0.204182,0.00196632,0.433697,0,0,0,0,0,8.18097e-06,8.38906e-05,8.38909e-05,0.00022865,0.0489925,0.0489947,0.0174551,0.0439446,0.0439452,0.0684559,2.69311e-09,2.6949e-09,6.05387e-09,0,0,6.55256e-08,0,0,0,0,0,0,0,0
12485000,0.982508,-0.0072159,-0.0118937,0.185699,0.00480927,0.0060953,0.0154454,0.00400904,0.00219853,0.0212804,-1.2628e-05,-5.97162e-05,2.5605e-07,0,0,-0.00136416,0.204182,0.00196632,0.433697,0,0,0,0,0,8.16335e-06,8.82616e-05,8.82625e-05,0.00022792,0.0563012,0.056304,0.0169371,0.0506205,0.0506213,0.0689302,2.69314e-09,2.69494e-09,5.90352e-09,0,0,6.52787e-08,0,0,0,0,0,0,0,0
12585000,0.982484,-0.00731744,-0.0118358,0.185829,0.0072385,0.00116227,0.0171169,0.00466632,0.000117224,0.0225911,-1.21185e-05,-5.97603e-05,-1.25778e-07,0,0,-0.00136407,0.204182,0.00196632,0.433697,0,0,0,0,0,8.13803e-06,7.75898e-05,7.75893e-05,0.000227147,0.0490494,0.0490512,0.0159606,0.044488,0.0444885,0.0681599,2.38116e-09,2.38271e-09,5.7555e-09,0,0,6.50458e-08,0,0,0,0,0,0,0,0
12685000,0.982485,-0.00729251,-0.0118498,0.185819,0.00739904,-0.000730671,0.0172547,0.0053434,0.000138297,0.0255163,-1.21218e-05,-5.97565e-05,-2.94973e-07,0,0,-0.00136433,0.204182,0.00196632,0.433697,0,0,0,0,0,8.19347e-06,8.15342e-05,8.15341e-05,0.000228733,0.0561851,0.0561868,0.0156487,0.0514146,0.0514153,0.0697032,2.38122e-09,2.38277e-09,5.64634e-09,0,0,6.48984e-08,0,0,0,0,0,0,0,0
12785000,0.98254,-0.00748164,-0.011725,0.18553,0.0081849,-0.0028314,0.0184451,0.00511594,-0.00263831,0.0271028,-1.15404e-05,-5.98123e-05,5.47455e-07,0,0,-0.00136425,0.204182,0.00196632,0.433697,0,0,0,0,0,8.15564e-06,7.11548e-05,7.11538e-05,0.000227877,0.048534,0.0485355,0.0147866,0.0449909,0.0449913,0.0688524,2.10242e-09,2.10373e-09,5.50304e-09,0,0,6.46982e-08,0,0,0,0,0,0,0,0
12885000,0.982578,-0.00746687,-0.011658,0.185333,0.00792096,-0.00432253,0.0192852,0.0059588,-0.00299578,0.0304504,-1.15318e-05,-5.98197e-05,9.64571e-07,0,0,-0.00136452,0.204182,0.00196632,0.433697,0,0,0,0,0,8.11881e-06,7.4695e-05,7.46949e-05,0.000226993,0.0553762,0.0553777,0.0143587,0.0520763,0.0520769,0.0690888,2.10246e-09,2.10378e-09,5.36282e-09,0,0,6.45338e-08,0,0,0,0,0,0,0,0
12985000,0.982616,-0.00745757,-0.0116275,0.185135,0.00626745,-0.00240633,0.0196646,0.00457545,-0.00227742,0.031983,-1.17496e-05,-6.0025e-05,1.31763e-06,0,0,-0.00136443,0.204182,0.00196632,0.433697,0,0,0,0,0,8.07539e-06,6.49314e-05,6.49292e-05,0.000226069,0.0475783,0.0475794,0.0136114,0.0454148,0.0454152,0.0681982,1.85828e-09,1.8594e-09,5.22524e-09,0,0,6.43596e-08,0,0,0,0,0,0,0,0
13085000,0.982629,-0.00746771,-0.0115491,0.185069,0.0072286,-0.00236348,0.0180851,0.00524507,-0.00247013,0.0319801,-1.1739e-05,-6.00357e-05,1.84695e-06,0,0,-0.00136406,0.204182,0.00196632,0.433697,0,0,0,0,0,8.04926e-06,6.81034e-05,6.81022e-05,0.000225093,0.0540906,0.054092,0.0132346,0.0525818,0.0525823,0.0683125,1.85833e-09,1.85945e-09,5.09062e-09,0,0,6.42225e-08,0,0,0,0,0,0,0,0
13185000,0.982638,-0.0074748,-0.0114919,0.185025,0.00333555,-0.00379023,0.0172117,0.00212525,-0.00343403,0.0329723,-1.17235e-05,-6.04258e-05,2.12066e-06,0,0,-0.00136391,0.204182,0.00196632,0.433697,0,0,0,0,0,8.01478e-06,5.91204e-05,5.9117e-05,0.000224092,0.046339,0.0463399,0.0125921,0.0457451,0.0457454,0.0673966,1.64702e-09,1.64798e-09,4.95895e-09,0,0,6.40632e-08,0,0,0,0,0,0,0,0
13285000,0.982641,-0.00748816,-0.011472,0.18501,0.00231159,-0.00477195,0.0154454,0.0023394,-0.00384679,0.0336136,-1.17251e-05,-6.04247e-05,2.04645e-06,0,0,-0.00136374,0.204182,0.00196632,0.433697,0,0,0,0,0,8.05947e-06,6.19645e-05,6.19617e-05,0.000225385,0.0524969,0.0524977,0.0124048,0.0529335,0.052934,0.0685768,1.64708e-09,1.64804e-09,4.86225e-09,0,0,6.3977e-08,0,0,0,0,0,0,0,0
13385000,0.982632,-0.00742959,-0.0115731,0.185057,0.00138613,-0.00323267,0.0145211,0.00180713,-0.00287214,0.0335471,-1.18971e-05,-6.04351e-05,1.72789e-06,0,0,-0.00136347,0.204182,0.00196632,0.433697,0,0,0,0,0,8.01642e-06,5.38224e-05,5.38168e-05,0.000224307,0.0449197,0.0449204,0.0118484,0.045982,0.0459823,0.0676172,1.46541e-09,1.46622e-09,4.73573e-09,0,0,6.3821e-08,0,0,0,0,0,0,0,0
13485000,0.982629,-0.00740202,-0.0115303,0.185077,0.00198935,-0.00148874,0.0152855,0.00197313,-0.00306066,0.0323361,-1.18984e-05,-6.04348e-05,1.67262e-06,0,0,-0.00136304,0.204182,0.00196632,0.433697,0,0,0,0,0,7.97887e-06,5.63778e-05,5.63728e-05,0.000223195,0.0506998,0.0507007,0.0115762,0.0531449,0.0531453,0.0675509,1.46546e-09,1.46628e-09,4.61221e-09,0,0,6.37155e-08,0,0,0,0,0,0,0,0
13585000,0.982601,-0.00740344,-0.0116106,0.185216,0.00570301,-0.00174755,0.016679,0.00457861,-0.00249259,0.0305556,-1.18266e-05,-6.00685e-05,1.36636e-06,0,0,-0.00136247,0.204182,0.00196632,0.433697,0,0,0,0,0,7.94207e-06,4.90699e-05,4.90634e-05,0.000222055,0.0433823,0.0433829,0.0111048,0.0461329,0.0461332,0.0665924,1.30968e-09,1.31037e-09,4.49168e-09,0,0,6.35578e-08,0,0,0,0,0,0,0,0
13685000,0.982632,-0.00734041,-0.0115226,0.185059,0.00506926,-0.00325554,0.0162843,0.00510945,-0.00274393,0.0329965,-1.18217e-05,-6.00728e-05,1.60642e-06,0,0,-0.00136257,0.204182,0.00196632,0.433697,0,0,0,0,0,7.89446e-06,5.13743e-05,5.13684e-05,0.0002209,0.0488277,0.0488282,0.0108838,0.0532352,0.0532355,0.0664607,1.30973e-09,1.31043e-09,4.37412e-09,0,0,6.3461e-08,0,0,0,0,0,0,0,0
13785000,0.982616,-0.00728972,-0.011642,0.185141,0.0116747,-6.68541e-05,0.0164236,0.00849679,-0.00059718,0.0326118,-1.19371e-05,-5.95712e-05,1.28709e-06,0,0,-0.00136215,0.204182,0.00196632,0.433697,0,0,0,0,0,7.85072e-06,4.48498e-05,4.48423e-05,0.000219717,0.0418452,0.0418458,0.0104879,0.0462088,0.046209,0.0655145,1.17601e-09,1.17661e-09,4.25953e-09,0,0,6.32948e-08,0,0,0,0,0,0,0,0
13885000,0.982643,-0.00721273,-0.0116095,0.185005,0.0127515,0.000860137,0.0176827,0.00968974,-0.000530422,0.0349857,-1.19269e-05,-5.95804e-05,1.78888e-06,0,0,-0.00136224,0.204182,0.00196632,0.433697,0,0,0,0,0,7.80976e-06,4.69372e-05,4.69299e-05,0.00021851,0.0469541,0.0469549,0.0103153,0.053228,0.0532283,0.0653345,1.17606e-09,1.17667e-09,4.14786e-09,0,0,6.32024e-08,0,0,0,0,0,0,0,0
13985000,0.982653,-0.0072678,-0.0113641,0.184964,0.0128276,0.00191553,0.016694,0.00757401,-0.00187512,0.0353357,-1.1842e-05,-5.99422e-05,2.11445e-06,0,0,-0.00136202,0.204182,0.00196632,0.433697,0,0,0,0,0,7.84784e-06,4.1123e-05,4.11153e-05,0.000219478,0.0403274,0.0403283,0.0100875,0.0462217,0.0462218,0.0654636,1.06091e-09,1.06142e-09,4.06595e-09,0,0,6.30463e-08,0,0,0,0,0,0,0,0
14085000,0.98259,-0.00725728,-0.0112979,0.185304,0.0101097,-0.00242113,0.0185164,0.00880965,-0.00192185,0.0338492,-1.18652e-05,-5.99218e-05,9.83529e-07,0,0,-0.00136157,0.204182,0.00196632,0.433697,0,0,0,0,0,7.80495e-06,4.30222e-05,4.30152e-05,0.000218208,0.0451243,0.0451248,0.0099574,0.053142,0.0531423,0.0652436,1.06096e-09,1.06148e-09,3.95929e-09,0,0,6.29553e-08,0,0,0,0,0,0,0,0
14185000,0.982546,-0.00723829,-0.0112358,0.185537,0.00787104,-0.00100823,0.0174774,0.00815018,-0.00140294,0.0316187,-1.19677e-05,-5.99492e-05,2.24132e-07,0,0,-0.00136064,0.204182,0.00196632,0.433697,0,0,0,0,0,7.76004e-06,3.78434e-05,3.78356e-05,0.000216924,0.0388482,0.0388485,0.00968046,0.0461826,0.0461828,0.064318,9.61338e-10,9.61784e-10,3.85548e-09,0,0,6.27542e-08,0,0,0,0,0,0,0,0
14285000,0.98254,-0.00716278,-0.0112253,0.185577,0.00887987,-0.001494,0.016328,0.00885494,-0.00158745,0.0353256,-1.19686e-05,-5.99479e-05,1.76348e-07,0,0,-0.00136094,0.204182,0.00196632,0.433697,0,0,0,0,0,7.71762e-06,3.958e-05,3.95722e-05,0.000215622,0.0433863,0.0433867,0.00959185,0.0529943,0.0529946,0.0640785,9.61396e-10,9.61848e-10,3.75445e-09,0,0,6.26614e-08,0,0,0,0,0,0,0,0
14385000,0.982544,-0.00724114,-0.0111723,0.185551,0.00967303,-0.00412453,0.0163774,0.00842342,-0.00275743,0.0388941,-1.18693e-05,-6.00415e-05,3.9593e-07,0,0,-0.0013611,0.204182,0.00196632,0.433697,0,0,0,0,0,7.67387e-06,3.49572e-05,3.49487e-05,0.0002143,0.0374551,0.0374554,0.00936514,0.046101,0.0461012,0.0631828,8.74685e-10,8.75074e-10,3.65607e-09,0,0,6.24357e-08,0,0,0,0,0,0,0,0
14485000,0.982516,-0.00734339,-0.0111373,0.185702,0.00767621,-0.0039139,0.0201286,0.00921442,-0.00316907,0.0411611,-1.18825e-05,-6.00293e-05,-2.58795e-07,0,0,-0.00136118,0.204182,0.00196632,0.433697,0,0,0,0,0,7.62459e-06,3.65519e-05,3.65444e-05,0.000212979,0.0417142,0.0417144,0.00931397,0.0527991,0.0527993,0.0629361,8.74746e-10,8.75141e-10,3.56049e-09,0,0,6.23381e-08,0,0,0,0,0,0,0,0
14585000,0.982501,-0.00741219,-0.0109908,0.185787,0.00601251,-0.00366664,0.0187514,0.00598216,-0.00385817,0.0390051,-1.19377e-05,-6.03504e-05,-4.69432e-07,0,0,-0.00136048,0.204182,0.00196632,0.433697,0,0,0,0,0,7.65354e-06,3.24192e-05,3.24112e-05,0.000213727,0.0361161,0.0361165,0.00921705,0.0459865,0.0459867,0.0630659,7.989e-10,7.99238e-10,3.49054e-09,0,0,6.21116e-08,0,0,0,0,0,0,0,0
14685000,0.982518,-0.00738582,-0.0110455,0.185695,0.00533071,-0.00370474,0.0184986,0.00654105,-0.0042086,0.0394784,-1.19341e-05,-6.03541e-05,-2.82455e-07,0,0,-0.00136024,0.204182,0.00196632,0.433697,0,0,0,0,0,7.60352e-06,3.38908e-05,3.38826e-05,0.000212359,0.040157,0.0401573,0.00919834,0.0525686,0.0525688,0.0628149,7.98963e-10,7.99307e-10,3.39953e-09,0,0,6.20083e-08,0,0,0,0,0,0,0,0
14785000,0.982553,-0.00737772,-0.0110302,0.185507,0.00684806,0.00241525,0.018237,0.0053319,0.000791459,0.0414323,-1.24154e-05,-6.02882e-05,1.31938e-07,0,0,-0.00136052,0.204182,0.00196632,0.433697,0,0,0,0,0,7.5494e-06,3.01819e-05,3.01734e-05,0.000210983,0.0348704,0.0348708,0.00904974,0.045846,0.0458461,0.0619784,7.32157e-10,7.32455e-10,3.311e-09,0,0,6.17219e-08,0,0,0,0,0,0,0,0
14885000,0.982588,-0.00730447,-0.0109547,0.18533,0.00547946,0.000381319,0.0218105,0.00593623,0.000935021,0.042366,-1.24063e-05,-6.02967e-05,5.83396e-07,0,0,-0.00136031,0.204182,0.00196632,0.433697,0,0,0,0,0,7.49823e-06,3.15445e-05,3.15363e-05,0.000209604,0.0386857,0.038686,0.00906121,0.0523124,0.0523125,0.06174,7.32222e-10,7.32526e-10,3.22506e-09,0,0,6.1609e-08,0,0,0,0,0,0,0,0
14985000,0.982591,-0.00743426,-0.0108444,0.185316,0.00482569,-0.00107573,0.02458,0.0047552,-0.000564214,0.04376,-1.23226e-05,-6.04545e-05,7.76036e-07,0,0,-0.00135956,0.204182,0.00196632,0.433697,0,0,0,0,0,7.45211e-06,2.82052e-05,2.81967e-05,0.000208209,0.0336803,0.0336806,0.00894489,0.0456855,0.0456856,0.0609512,6.73064e-10,6.73316e-10,3.14148e-09,0,0,6.12871e-08,0,0,0,0,0,0,0,0
15085000,0.982588,-0.00737588,-0.0109291,0.185329,0.00480158,-0.000329579,0.028448,0.00524649,-0.000667472,0.0461898,-1.23241e-05,-6.04531e-05,6.98739e-07,0,0,-0.00135952,0.204182,0.00196632,0.433697,0,0,0,0,0,7.40274e-06,2.94729e-05,2.94639e-05,0.000206819,0.037303,0.0373033,0.00898291,0.0520366,0.0520367,0.060733,6.7313e-10,6.73389e-10,3.06037e-09,0,0,6.1162e-08,0,0,0,0,0,0,0,0
15185000,0.982581,-0.00750359,-0.010984,0.185359,0.00338397,-0.00132198,0.0288288,0.00419679,-0.000644514,0.0467623,-1.23632e-05,-6.05315e-05,5.54586e-07,0,0,-0.00135881,0.204182,0.00196632,0.433697,0,0,0,0,0,7.35169e-06,2.64555e-05,2.64458e-05,0.000205423,0.03258,0.0325802,0.00889347,0.0455098,0.0455099,0.0599929,6.20434e-10,6.20656e-10,2.98153e-09,0,0,6.08019e-08,0,0,0,0,0,0,0,0
15285000,0.982598,-0.007603,-0.0110131,0.185263,0.00322842,-0.00197282,0.0286288,0.00454534,-0.00076312,0.0465829,-1.23568e-05,-6.05404e-05,9.43412e-07,0,0,-0.0013582,0.204182,0.00196632,0.433697,0,0,0,0,0,7.37418e-06,2.76385e-05,2.76286e-05,0.000205961,0.0360404,0.0360406,0.00902913,0.0517497,0.0517499,0.0607081,6.20517e-10,6.20729e-10,2.92391e-09,0,0,6.07004e-08,0,0,0,0,0,0,0,0
15385000,0.982564,-0.00767519,-0.0110278,0.18544,0.0041973,0.000429746,0.028267,0.00369142,-0.000496814,0.0458167,-1.24151e-05,-6.05896e-05,5.99532e-07,0,0,-0.00135701,0.204182,0.00196632,0.433697,0,0,0,0,0,7.32842e-06,2.48984e-05,2.48875e-05,0.000204532,0.0315666,0.031567,0.00895922,0.0453238,0.045324,0.0599957,5.73301e-10,5.73469e-10,2.84898e-09,0,0,6.03001e-08,0,0,0,0,0,0,0,0
15485000,0.982558,-0.00771345,-0.0109882,0.18547,0.00319801,-0.00190311,0.0282736,0.00405039,-0.000534119,0.0467003,-1.2414e-05,-6.05915e-05,6.72846e-07,0,0,-0.0013566,0.204182,0.00196632,0.433697,0,0,0,0,0,7.28266e-06,2.60052e-05,2.59942e-05,0.000203109,0.0348699,0.0348703,0.00903991,0.0514569,0.0514571,0.0598289,5.73379e-10,5.73536e-10,2.77629e-09,0,0,6.01469e-08,0,0,0,0,0,0,0,0
15585000,0.982556,-0.00780447,-0.010984,0.185478,0.00652792,-0.00443956,0.0278513,0.00594491,-0.00417758,0.0456801,-1.20737e-05,-6.05626e-05,8.94817e-07,0,0,-0.00135545,0.204182,0.00196632,0.433697,0,0,0,0,0,7.23792e-06,2.35053e-05,2.34935e-05,0.000201683,0.0306238,0.0306242,0.00898777,0.0451313,0.0451315,0.0591663,5.30838e-10,5.30962e-10,2.70567e-09,0,0,5.97042e-08,0,0,0,0,0,0,0,0
15685000,0.982584,-0.00777016,-0.0109755,0.185334,0.00822915,-0.00758044,0.0282308,0.00667003,-0.00478073,0.0467808,-1.20683e-05,-6.05694e-05,1.20948e-06,0,0,-0.00135505,0.204182,0.00196632,0.433697,0,0,0,0,0,7.18459e-06,2.45443e-05,2.4532e-05,0.000200267,0.0337828,0.0337832,0.00908448,0.0511616,0.0511619,0.0590292,5.30917e-10,5.31032e-10,2.63708e-09,0,0,5.95316e-08,0,0,0,0,0,0,0,0
15785000,0.982618,-0.0077929,-0.0108818,0.185155,0.00544488,-0.00772272,0.0276048,0.0052636,-0.0038577,0.0479756,-1.22018e-05,-6.0652e-05,1.68243e-06,0,0,-0.00135419,0.204182,0.00196632,0.433697,0,0,0,0,0,7.13209e-06,2.22542e-05,2.22417e-05,0.000198856,0.0297481,0.0297484,0.00904592,0.0449351,0.0449353,0.0584149,4.92412e-10,4.92501e-10,2.57053e-09,0,0,5.90451e-08,0,0,0,0,0,0,0,0
15885000,0.982587,-0.00783795,-0.0109289,0.185318,0.00406606,-0.00570848,0.0287368,0.00567068,-0.00453237,0.0480341,-1.22084e-05,-6.06451e-05,1.3294e-06,0,0,-0.00135353,0.204182,0.00196632,0.433697,0,0,0,0,0,7.15043e-06,2.32321e-05,2.32191e-05,0.000199258,0.032773,0.0327734,0.0092281,0.0508672,0.0508674,0.0591824,4.92496e-10,4.92581e-10,2.52193e-09,0,0,5.89046e-08,0,0,0,0,0,0,0,0
15985000,0.982591,-0.00766386,-0.0108872,0.185303,0.00268366,-0.00425408,0.0252175,0.00460038,-0.0035709,0.0457692,-1.23089e-05,-6.06792e-05,1.22658e-06,0,0,-0.00135133,0.204182,0.00196632,0.433697,0,0,0,0,0,7.09512e-06,2.11257e-05,2.11118e-05,0.000197834,0.0289345,0.0289348,0.00919774,0.0447373,0.0447375,0.0585975,4.57496e-10,4.57559e-10,2.45872e-09,0,0,5.83748e-08,0,0,0,0,0,0,0,0
16085000,0.982592,-0.007627,-0.0108759,0.1853,0.00113761,-0.00540286,0.0237569,0.00472703,-0.00407223,0.0472597,-1.23148e-05,-6.06728e-05,9.03042e-07,0,0,-0.00135109,0.204182,0.00196632,0.433697,0,0,0,0,0,7.0361e-06,2.20473e-05,2.2033e-05,0.000196418,0.0318493,0.0318496,0.00931958,0.0505762,0.0505765,0.0585333,4.57575e-10,4.57634e-10,2.39735e-09,0,0,5.81633e-08,0,0,0,0,0,0,0,0
16185000,0.982578,-0.00755065,-0.0108001,0.185383,-0.0022377,-0.00372685,0.0226045,0.00260748,-0.00316257,0.04408,-1.2443e-05,-6.07586e-05,5.30425e-07,0,0,-0.00134926,0.204182,0.00196632,0.433697,0,0,0,0,0,6.98197e-06,2.01009e-05,2.00862e-05,0.000195006,0.0281771,0.0281773,0.00929578,0.0445399,0.0445401,0.0579934,4.25626e-10,4.25667e-10,2.3378e-09,0,0,5.75891e-08,0,0,0,0,0,0,0,0
16285000,0.982573,-0.00760165,-0.0107312,0.185412,-0.00189515,-0.0051716,0.0221437,0.00238157,-0.00362146,0.045434,-1.24415e-05,-6.07605e-05,6.15853e-07,0,0,-0.00134903,0.204182,0.00196632,0.433697,0,0,0,0,0,6.93665e-06,2.09711e-05,2.09566e-05,0.000193591,0.0309793,0.0309796,0.00942591,0.0502898,0.05029,0.0579683,4.25706e-10,4.25743e-10,2.27998e-09,0,0,5.73543e-08,0,0,0,0,0,0,0,0
16385000,0.982584,-0.00755745,-0.0107217,0.185358,0.000173118,-0.00445104,0.0227469,0.00328933,-0.00288182,0.0453288,-1.24612e-05,-6.06577e-05,9.0641e-07,0,0,-0.001348,0.204182,0.00196632,0.433697,0,0,0,0,0,6.89e-06,1.91666e-05,1.91519e-05,0.000192187,0.0274656,0.027466,0.00940562,0.044344,0.0443442,0.0574703,3.96456e-10,3.9648e-10,2.22387e-09,0,0,5.67366e-08,0,0,0,0,0,0,0,0
16485000,0.98258,-0.00765914,-0.0107054,0.185374,0.00254609,-0.00590495,0.0246019,0.00342124,-0.00346512,0.0487125,-1.24634e-05,-6.06551e-05,7.80539e-07,0,0,-0.00134828,0.204182,0.00196632,0.433697,0,0,0,0,0,6.83862e-06,1.99901e-05,1.99754e-05,0.000190795,0.0301618,0.0301623,0.00954151,0.0500087,0.050009,0.0574835,3.96538e-10,3.96558e-10,2.16939e-09,0,0,5.64774e-08,0,0,0,0,0,0,0,0
16585000,0.982577,-0.00765259,-0.0107133,0.18539,0.00661121,-0.00672373,0.0280183,0.0030615,-0.0028056,0.0493777,-1.25441e-05,-6.06586e-05,7.15049e-07,0,0,-0.00134748,0.204182,0.00196632,0.433697,0,0,0,0,0,6.84824e-06,1.83117e-05,1.82968e-05,0.000191079,0.0267906,0.0267911,0.00959242,0.0441503,0.0441505,0.0578483,3.69688e-10,3.697e-10,2.12958e-09,0,0,5.5887e-08,0,0,0,0,0,0,0,0
16685000,0.982589,-0.00771091,-0.0106479,0.185328,0.00780197,-0.0104894,0.0282909,0.0037813,-0.00364539,0.0507336,-1.25406e-05,-6.06627e-05,9.1268e-07,0,0,-0.00134706,0.204182,0.00196632,0.433697,0,0,0,0,0,6.79933e-06,1.90917e-05,1.90769e-05,0.000189679,0.0293951,0.0293957,0.00973292,0.0497335,0.0497338,0.0578997,3.6977e-10,3.69779e-10,2.07785e-09,0,0,5.56074e-08,0,0,0,0,0,0,0,0
16785000,0.982609,-0.00757639,-0.0105521,0.185234,0.00928912,-0.0104852,0.0270243,0.00311503,-0.00288148,0.0498458,-1.26726e-05,-6.07014e-05,1.03215e-06,0,0,-0.00134544,0.204182,0.00196632,0.433697,0,0,0,0,0,6.74583e-06,1.75247e-05,1.75099e-05,0.000188295,0.0261714,0.026172,0.00971056,0.0439598,0.04396,0.0574619,3.45058e-10,3.45058e-10,2.02764e-09,0,0,5.49082e-08,0,0,0,0,0,0,0,0
16885000,0.98265,-0.00754548,-0.0106448,0.185013,0.00805512,-0.0105669,0.0282606,0.00397556,-0.00391738,0.0489862,-1.26654e-05,-6.07097e-05,1.43598e-06,0,0,-0.0013443,0.204182,0.00196632,0.433697,0,0,0,0,0,6.69155e-06,1.82653e-05,1.82497e-05,0.000186921,0.0286853,0.028686,0.00985229,0.0494661,0.0494664,0.0575487,3.45141e-10,3.45139e-10,1.97888e-09,0,0,5.46035e-08,0,0,0,0,0,0,0,0
16985000,0.982649,-0.00757604,-0.0106596,0.185014,0.00786908,-0.0108872,0.0283658,0.00361479,-0.00314265,0.0479709,-1.27508e-05,-6.06484e-05,1.51958e-06,0,0,-0.00134293,0.204182,0.00196632,0.433697,0,0,0,0,0,6.64457e-06,1.6798e-05,1.67826e-05,0.000185547,0.0255836,0.0255842,0.00982529,0.043773,0.0437732,0.0571371,3.22344e-10,3.22336e-10,1.93152e-09,0,0,5.38656e-08,0,0,0,0,0,0,0,0
17085000,0.98264,-0.00767854,-0.0105922,0.185059,0.0087498,-0.0134013,0.0285204,0.00445017,-0.00437343,0.0477499,-1.27532e-05,-6.06465e-05,1.4082e-06,0,0,-0.00134193,0.204182,0.00196632,0.433697,0,0,0,0,0,6.59647e-06,1.75006e-05,1.74855e-05,0.000184189,0.02802,0.0280207,0.00996632,0.049206,0.0492063,0.0572565,3.22428e-10,3.22419e-10,1.88556e-09,0,0,5.35361e-08,0,0,0,0,0,0,0,0
17185000,0.982595,-0.00776432,-0.0105028,0.1853,0.00824264,-0.0176217,0.0296571,0.0029245,-0.00762189,0.0503905,-1.27113e-05,-6.07217e-05,1.00403e-06,0,0,-0.00134137,0.204182,0.00196632,0.433697,0,0,0,0,0,6.61016e-06,1.61221e-05,1.61075e-05,0.000184391,0.0250331,0.0250337,0.0100086,0.0435903,0.0435905,0.0576971,3.01362e-10,3.01348e-10,1.85198e-09,0,0,5.28526e-08,0,0,0,0,0,0,0,0
17285000,0.982565,-0.00771931,-0.0104983,0.185462,0.00863591,-0.0182558,0.0291315,0.00375276,-0.00938531,0.0508785,-1.27189e-05,-6.07144e-05,6.12297e-07,0,0,-0.00134058,0.204182,0.00196632,0.433697,0,0,0,0,0,6.56311e-06,1.67902e-05,1.67753e-05,0.000183032,0.0273961,0.0273968,0.0101487,0.048954,0.0489542,0.0578501,3.01447e-10,3.01431e-10,1.80831e-09,0,0,5.25036e-08,0,0,0,0,0,0,0,0
17385000,0.982605,-0.00766416,-0.0104765,0.185253,0.00555052,-0.0191998,0.0291245,0.00508051,-0.00657591,0.051438,-1.29205e-05,-6.0571e-05,9.12368e-07,0,0,-0.00133929,0.204182,0.00196632,0.433697,0,0,0,0,0,6.50808e-06,1.5492e-05,1.54773e-05,0.000181691,0.0245165,0.0245168,0.0101083,0.0434125,0.0434127,0.0574773,2.81946e-10,2.81925e-10,1.76588e-09,0,0,5.17017e-08,0,0,0,0,0,0,0,0
17485000,0.982594,-0.0076651,-0.0105293,0.18531,0.00321561,-0.0201827,0.0285793,0.00545104,-0.00851748,0.0519005,-1.29235e-05,-6.05684e-05,7.65212e-07,0,0,-0.00133848,0.204182,0.00196632,0.433697,0,0,0,0,0,6.46083e-06,1.61278e-05,1.61127e-05,0.000180356,0.026809,0.0268093,0.0102444,0.0487098,0.0487101,0.0576565,2.82031e-10,2.8201e-10,1.7247e-09,0,0,5.13297e-08,0,0,0,0,0,0,0,0
17585000,0.982595,-0.00763376,-0.0104557,0.185311,0.00056702,-0.0167464,0.0275622,0.0022998,-0.00680065,0.0500065,-1.31518e-05,-6.06732e-05,7.66612e-07,0,0,-0.00133656,0.204182,0.00196632,0.433697,0,0,0,0,0,6.41354e-06,1.49024e-05,1.48875e-05,0.000179033,0.0240279,0.0240282,0.0101959,0.0432393,0.0432395,0.0573024,2.6396e-10,2.63934e-10,1.68468e-09,0,0,5.05019e-08,0,0,0,0,0,0,0,0
17685000,0.982622,-0.00773153,-0.0103749,0.185167,-0.000455949,-0.0175221,0.0288442,0.00232583,-0.00853626,0.0523348,-1.31507e-05,-6.06744e-05,8.27715e-07,0,0,-0.00133638,0.204182,0.00196632,0.433697,0,0,0,0,0,6.3589e-06,1.55072e-05,1.54926e-05,0.000177732,0.0262511,0.0262514,0.0103267,0.0484735,0.0484737,0.057504,2.64047e-10,2.6402e-10,1.64583e-09,0,0,5.01084e-08,0,0,0,0,0,0,0,0
17785000,0.982665,-0.0077298,-0.0103351,0.184938,0.00159701,-0.0161199,0.0286479,0.00307682,-0.00765746,0.0559784,-1.32866e-05,-6.05545e-05,9.42782e-07,0,0,-0.00133649,0.204182,0.00196632,0.433697,0,0,0,0,0,6.29999e-06,1.4348e-05,1.43338e-05,0.000176446,0.0235632,0.0235636,0.0102695,0.0430708,0.0430709,0.0571644,2.47285e-10,2.47254e-10,1.60806e-09,0,0,5e-08,0,0,0,0,0,0,0,0
17885000,0.982673,-0.00768031,-0.0104418,0.184894,0.0038321,-0.0186646,0.028136,0.0034048,-0.0094142,0.0609618,-1.32853e-05,-6.05554e-05,9.97957e-07,0,0,-0.00133723,0.204182,0.00196632,0.433697,0,0,0,0,0,6.30385e-06,1.4925e-05,1.49099e-05,0.000176586,0.0257292,0.0257297,0.0104742,0.0482447,0.0482449,0.0582194,2.47375e-10,2.47344e-10,1.58047e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
17985000,0.982681,-0.00756031,-0.0104224,0.184859,0.00296427,-0.0134579,0.0278582,0.00279763,-0.00434519,0.061064,-1.36241e-05,-6.04638e-05,9.68519e-07,0,0,-0.00133631,0.204182,0.00196632,0.433697,0,0,0,0,0,6.25435e-06,1.38263e-05,1.38113e-05,0.000175296,0.0231232,0.0231237,0.0104071,0.042907,0.0429071,0.0578807,2.31811e-10,2.31777e-10,1.54456e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18085000,0.982681,-0.00764889,-0.010385,0.184854,0.00314233,-0.0143415,0.0274841,0.00317561,-0.00576436,0.0604401,-1.36241e-05,-6.04643e-05,9.8789e-07,0,0,-0.00133509,0.204182,0.00196632,0.433697,0,0,0,0,0,6.20925e-06,1.43756e-05,1.43608e-05,0.000174016,0.0252258,0.0252263,0.0105266,0.0480232,0.0480234,0.0581214,2.31898e-10,2.31864e-10,1.50968e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18185000,0.982723,-0.00766464,-0.0104185,0.184633,0.00279857,-0.0129932,0.0281825,0.00363988,-0.00471407,0.0587499,-1.37066e-05,-6.04027e-05,1.44717e-06,0,0,-0.00133318,0.204182,0.00196632,0.433697,0,0,0,0,0,6.16147e-06,1.33328e-05,1.33182e-05,0.00017275,0.0226959,0.0226964,0.0104509,0.0427474,0.0427476,0.0577898,2.17442e-10,2.17407e-10,1.47577e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18285000,0.982721,-0.00770429,-0.0103918,0.184639,0.00358057,-0.0140812,0.0274469,0.00389815,-0.00605376,0.0577663,-1.3706e-05,-6.04038e-05,1.49633e-06,0,0,-0.00133178,0.204182,0.00196632,0.433697,0,0,0,0,0,6.11849e-06,1.38568e-05,1.38421e-05,0.000171492,0.0247419,0.0247425,0.0105625,0.0478075,0.0478077,0.0580358,2.1753e-10,2.17495e-10,1.4428e-09,0,0,5e-08,0,0,0,0,0,0,0,0
18385000,0.982702,-0.00762774,-0.0103975,0.184746,0.00379595,-0.012978,0.0272244,0.0053139,-0.00498142,0.0573674,-1.37762e-05,-6.02878e-05,1.3746e-06,0,0,-0.00133053,0.204182,0.00196632,0.433697,0,0,0,0,0,6.07779e-06,1.28656e-05,1.28511e-05,0.000170247,0.0222897,0.0222901,0.0104785,0.0425917,0.0425918,0.057708,2.04099e-10,2.04063e-10,1.41077e-09,0,0,5e-08,0,0,0,0,0,0,0,0
18485000,0.982709,-0.00766568,-0.0104105,0.184703,0.00663408,-0.0130352,0.0269218,0.00591875,-0.00628916,0.0599743,-1.3773e-05,-6.02909e-05,1.54156e-06,0,0,-0.00133052,0.204182,0.00196632,0.433697,0,0,0,0,0,6.08311e-06,1.33659e-05,1.33512e-05,0.000170343,0.0242829,0.0242835,0.0106688,0.0475984,0.0475986,0.0588183,2.0419e-10,2.04154e-10,1.38737e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
18585000,0.982686,-0.00750534,-0.0103028,0.184838,0.00562368,-0.0122435,0.0266036,0.00491616,-0.00523027,0.0616367,-1.38878e-05,-6.03084e-05,1.42123e-06,0,0,-0.00132975,0.204182,0.00196632,0.433697,0,0,0,0,0,6.04434e-06,1.24224e-05,1.24079e-05,0.000169104,0.0219015,0.021902,0.010576,0.04244,0.0424402,0.0584819,1.91705e-10,1.91669e-10,1.35687e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
18685000,0.982701,-0.00749169,-0.0102524,0.184763,0.00520073,-0.0116232,0.025119,0.00546192,-0.00642418,0.0610443,-1.38861e-05,-6.03105e-05,1.52451e-06,0,0,-0.00132858,0.204182,0.00196632,0.433697,0,0,0,0,0,5.99875e-06,1.28997e-05,1.28852e-05,0.000167883,0.0238433,0.0238439,0.0106755,0.0473949,0.0473952,0.0587454,1.91794e-10,1.91759e-10,1.32722e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18785000,0.982704,-0.00742789,-0.0101503,0.184754,0.00412983,-0.0111448,0.0244318,0.00550724,-0.00539145,0.0576987,-1.39648e-05,-6.02746e-05,1.55189e-06,0,0,-0.00132558,0.204182,0.00196632,0.433697,0,0,0,0,0,5.9555e-06,1.20008e-05,1.19868e-05,0.000166675,0.0215251,0.0215255,0.0105757,0.0422917,0.0422919,0.0584075,1.80187e-10,1.80151e-10,1.29839e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18885000,0.982699,-0.00738724,-0.010164,0.184782,0.00315581,-0.0111868,0.0229298,0.00584382,-0.00656836,0.0546483,-1.39675e-05,-6.02725e-05,1.43355e-06,0,0,-0.00132351,0.204182,0.00196632,0.433697,0,0,0,0,0,5.91145e-06,1.24571e-05,1.24427e-05,0.000165481,0.0234158,0.0234163,0.0106687,0.0471962,0.0471965,0.0586712,1.80276e-10,1.80242e-10,1.27035e-09,0,0,5e-08,0,0,0,0,0,0,0,0
18985000,0.982679,-0.00737064,-0.0102138,0.184886,0.00180488,-0.0109417,0.023467,0.00489899,-0.00549076,0.0574893,-1.40567e-05,-6.02749e-05,1.42639e-06,0,0,-0.00132319,0.204182,0.00196632,0.433697,0,0,0,0,0,5.87553e-06,1.16008e-05,1.15865e-05,0.000164292,0.0211622,0.0211626,0.0105629,0.0421466,0.0421468,0.0583301,1.69486e-10,1.69452e-10,1.24308e-09,0,0,5e-08,0,0,0,0,0,0,0,0
19085000,0.982685,-0.00744955,-0.0102228,0.184852,-0.000221638,-0.0114045,0.0239569,0.00501797,-0.00657033,0.0536318,-1.40547e-05,-6.02774e-05,1.55189e-06,0,0,-0.00132087,0.204182,0.00196632,0.433697,0,0,0,0,0,5.8351e-06,1.20369e-05,1.20225e-05,0.000163121,0.0230012,0.0230016,0.0106496,0.0470023,0.0470026,0.0585913,1.69577e-10,1.69543e-10,1.21655e-09,0,0,5e-08,0,0,0,0,0,0,0,0
19185000,0.982662,-0.00734403,-0.010356,0.184971,-0.00150161,-0.0109821,0.0239857,0.00420633,-0.00556291,0.0536503,-1.41402e-05,-6.0256e-05,1.30108e-06,0,0,-0.00131991,0.204182,0.00196632,0.433697,0,0,0,0,0,5.83771e-06,1.12206e-05,1.12057e-05,0.000163181,0.0208075,0.0208078,0.0106253,0.0420043,0.0420045,0.0591063,1.59548e-10,1.59515e-10,1.19715e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
19285000,0.982662,-0.00728831,-0.0103078,0.184978,-0.00263484,-0.0113048,0.0243331,0.00403438,-0.00667975,0.053699,-1.41418e-05,-6.02547e-05,1.22844e-06,0,0,-0.00131903,0.204182,0.00196632,0.433697,0,0,0,0,0,5.79489e-06,1.16375e-05,1.16225e-05,0.000162022,0.022603,0.0226032,0.0107079,0.0468123,0.0468125,0.0593703,1.59639e-10,1.59606e-10,1.17186e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
19385000,0.98266,-0.00737869,-0.0101981,0.184989,-0.00260618,-0.0076929,0.0260041,0.0034523,-0.00445228,0.0524692,-1.42592e-05,-6.02082e-05,1.10853e-06,0,0,-0.00131724,0.204182,0.00196632,0.433697,0,0,0,0,0,5.75124e-06,1.08573e-05,1.08433e-05,0.000160878,0.0204628,0.020463,0.010591,0.0418642,0.0418644,0.0590086,1.50314e-10,1.50282e-10,1.14726e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
19485000,0.982618,-0.00743404,-0.0101007,0.185213,-0.00356913,-0.00804589,0.0252806,0.0031083,-0.0052386,0.0521863,-1.42642e-05,-6.02036e-05,8.60062e-07,0,0,-0.00131614,0.204182,0.00196632,0.433697,0,0,0,0,0,5.71794e-06,1.12561e-05,1.12424e-05,0.000159736,0.0222154,0.0222156,0.0106684,0.0466253,0.0466256,0.0592659,1.50405e-10,1.50374e-10,1.12332e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
19585000,0.982598,-0.00735902,-0.010206,0.185319,-0.00557738,-0.0101351,0.0267258,0.00352987,-0.00548663,0.0523466,-1.42529e-05,-6.01458e-05,7.94168e-07,0,0,-0.00131488,0.204182,0.00196632,0.433697,0,0,0,0,0,5.68253e-06,1.05119e-05,1.04978e-05,0.000158608,0.0201311,0.0201312,0.0105471,0.0417262,0.0417264,0.0588923,1.41736e-10,1.41705e-10,1.1e-09,0,0,5e-08,0,0,0,0,0,0,0,0
19685000,0.982612,-0.00738251,-0.0102201,0.18524,-0.00698298,-0.00928341,0.0259687,0.00293593,-0.00646177,0.0521804,-1.42501e-05,-6.01488e-05,9.51233e-07,0,0,-0.00131379,0.204182,0.00196632,0.433697,0,0,0,0,0,5.64258e-06,1.08941e-05,1.08799e-05,0.000157499,0.0218412,0.0218413,0.0106199,0.0464418,0.0464421,0.0591413,1.41828e-10,1.41797e-10,1.07732e-09,0,0,5e-08,0,0,0,0,0,0,0,0
19785000,0.9826,-0.00745442,-0.0102161,0.185301,-0.00759621,-0.00749426,0.0247672,0.0051594,-0.00541513,0.0491278,-1.42712e-05,-6.00304e-05,8.4981e-07,0,0,-0.00131135,0.204182,0.00196632,0.433697,0,0,0,0,0,5.64487e-06,1.01827e-05,1.0169e-05,0.000157537,0.0198118,0.0198118,0.0105857,0.0415903,0.0415904,0.0596431,1.3377e-10,1.33741e-10,1.06073e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
19885000,0.982579,-0.00746628,-0.0103058,0.185411,-0.0073906,-0.00724743,0.0245093,0.00435778,-0.00611018,0.0479132,-1.4275e-05,-6.00269e-05,6.56827e-07,0,0,-0.00130997,0.204182,0.00196632,0.433697,0,0,0,0,0,5.60716e-06,1.05492e-05,1.05351e-05,0.000156436,0.0214798,0.0214798,0.0106558,0.0462617,0.0462619,0.0598902,1.33862e-10,1.33833e-10,1.03908e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
19985000,0.982599,-0.00748586,-0.0104323,0.185294,-0.00764407,-0.00688918,0.0219643,0.00464823,-0.0041927,0.0442495,-1.43382e-05,-5.99343e-05,7.30384e-07,0,0,-0.00130694,0.204182,0.00196632,0.433697,0,0,0,0,0,5.56325e-06,9.86975e-06,9.8555e-06,0.000155352,0.0195018,0.0195019,0.0105283,0.0414564,0.0414565,0.0594922,1.2637e-10,1.26342e-10,1.01799e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
20085000,0.982611,-0.00749516,-0.0104423,0.185234,-0.00720198,-0.00966194,0.0220634,0.00388267,-0.00504681,0.0474488,-1.43383e-05,-5.99341e-05,7.21927e-07,0,0,-0.00130731,0.204182,0.00196632,0.433697,0,0,0,0,0,5.52134e-06,1.02209e-05,1.02066e-05,0.000154281,0.0211323,0.0211323,0.010595,0.0460846,0.0460847,0.0597291,1.26462e-10,1.26435e-10,9.97468e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
20185000,0.982594,-0.00749104,-0.010542,0.185316,-0.00621488,-0.00745913,0.0228842,0.00497779,-0.00422856,0.0470485,-1.4376e-05,-5.98627e-05,5.19846e-07,-7.6708e-11,7.97556e-11,-0.00130601,0.204182,0.00196632,0.433697,0,0,0,0,0,5.48275e-06,9.571e-06,9.5565e-06,0.000153219,0.0194546,0.0194547,0.0104667,0.0413245,0.0413246,0.0593251,1.19495e-10,1.19468e-10,9.77468e-10,4.00001e-06,4.00001e-06,5e-08,0,0,0,0,0,0,0,0
20285000,0.982607,-0.00748659,-0.0105704,0.185246,-0.00936041,-0.00805778,0.023202,0.00423109,-0.00492915,0.047749,-1.43772e-05,-5.98616e-05,4.61609e-07,3.2967e-09,-3.42388e-09,-0.0013054,0.204182,0.00196632,0.433697,0,0,0,0,0,5.43993e-06,9.90804e-06,9.89334e-06,0.000152175,0.0220847,0.0220853,0.010531,0.0459191,0.0459192,0.0595515,1.19588e-10,1.19561e-10,9.57997e-10,4.00002e-06,4.00002e-06,5e-08,0,0,0,0,0,0,0,0
20385000,0.982602,-0.00742964,-0.0105603,0.185275,-0.010084,-0.00661706,0.022241,0.00521305,-0.00411811,0.047216,-1.43976e-05,-5.97939e-05,6.3277e-07,-3.22544e-06,-1.37292e-06,-0.00130364,0.204182,0.00196632,0.433697,0,0,0,0,0,5.40937e-06,9.28914e-06,9.2746e-06,0.00015113,0.0216937,0.0216949,0.0104035,0.0412081,0.0412083,0.059142,1.13133e-10,1.13107e-10,9.3902e-10,3.97883e-06,3.97883e-06,5e-08,0,0,0,0,0,0,0,0
20485000,0.98262,-0.00744543,-0.0105312,0.185182,-0.0144736,-0.00783378,0.0228495,0.00396049,-0.00481696,0.0468048,-1.43991e-05,-5.97926e-05,5.63883e-07,-3.20875e-06,-1.39009e-06,-0.00130262,0.204182,0.00196632,0.433697,0,0,0,0,0,5.40302e-06,9.6128e-06,9.59826e-06,0.000151157,0.025735,0.0257372,0.0105572,0.0458373,0.0458375,0.060252,1.13228e-10,1.13202e-10,9.25131e-10,3.97884e-06,3.97884e-06,5.0002e-08,0,0,0,0,0,0,0,0
20585000,0.982655,-0.00740911,-0.010535,0.184995,-0.0137785,-0.00808877,0.0225122,0.00503612,-0.00408673,0.0452012,-1.44054e-05,-5.97112e-05,8.75281e-07,-1.25669e-05,-2.63259e-06,-0.00130074,0.204182,0.00196632,0.433697,0,0,0,0,0,5.36419e-06,9.04217e-06,9.02775e-06,0.00015013,0.0259118,0.0259149,0.0104286,0.0411678,0.041168,0.0598254,1.07376e-10,1.07352e-10,9.06993e-10,3.89837e-06,3.89838e-06,5.0001e-08,0,0,0,0,0,0,0,0
20685000,0.982647,-0.00733779,-0.0105285,0.185039,-0.0158482,-0.00730354,0.0234777,0.00360233,-0.00481659,0.0455894,-1.44096e-05,-5.97072e-05,6.5739e-07,-1.25447e-05,-2.6574e-06,-0.00130003,0.204182,0.00196632,0.433697,0,0,0,0,0,5.32469e-06,9.35384e-06,9.33923e-06,0.000149118,0.0311224,0.0311271,0.0104919,0.045951,0.0459512,0.0600373,1.0747e-10,1.07446e-10,8.89327e-10,3.89838e-06,3.89839e-06,5.0001e-08,0,0,0,0,0,0,0,0
20785000,0.982671,-0.00686916,-0.010465,0.184934,-0.0169178,-0.00426918,0.011174,0.00296123,-0.00401814,0.0442285,-1.44273e-05,-5.96557e-05,7.46141e-07,-2.50134e-05,-4.13688e-06,-0.00129843,0.204182,0.00196632,0.433697,0,0,0,0,0,5.28537e-06,8.86095e-06,8.8458e-06,0.000148118,0.0310559,0.0310612,0.0103646,0.0412805,0.0412807,0.0596068,1.02384e-10,1.02361e-10,8.72101e-10,3.73907e-06,3.73907e-06,5.0001e-08,0,0,0,0,0,0,0,0
20885000,0.982732,0.00198829,-0.00678806,0.184899,-0.0232046,0.00722391,-0.102275,0.000887512,-0.00384167,0.0386654,-1.44271e-05,-5.96559e-05,7.60796e-07,-2.49636e-05,-4.18391e-06,-0.00129773,0.204182,0.00196632,0.433697,0,0,0,0,0,5.24823e-06,9.15277e-06,9.14325e-06,0.000147142,0.0372485,0.0372554,0.0104251,0.0463465,0.0463469,0.059803,1.02477e-10,1.02455e-10,8.55306e-10,3.73908e-06,3.73908e-06,5e-08,0,0,0,0,0,0,0,0
20985000,0.982733,0.0057307,-0.0030596,0.184916,-0.0320535,0.0248344,-0.243442,0.000584024,-0.00260979,0.0253246,-1.43896e-05,-5.95982e-05,7.33922e-07,-4.3257e-05,1.08967e-05,-0.00130087,0.204182,0.00196632,0.433697,0,0,0,0,0,5.21394e-06,8.75623e-06,8.75809e-06,0.000146162,0.0362639,0.0362693,0.010296,0.0415982,0.0415985,0.0593696,9.82596e-11,9.82401e-11,8.38937e-10,3.50408e-06,3.50408e-06,5e-08,0,0,0,0,0,0,0,0
21085000,0.982672,0.00430308,-0.00330179,0.185274,-0.0453716,0.04082,-0.361117,-0.00328351,0.000726793,-0.00403991,-1.43906e-05,-5.95972e-05,6.83072e-07,-4.32807e-05,1.09179e-05,-0.00130116,0.204182,0.00196632,0.433697,0,0,0,0,0,5.233e-06,9.05155e-06,9.05033e-06,0.000146151,0.0429065,0.0429116,0.0104447,0.0470527,0.0470533,0.0604622,9.83548e-11,9.8336e-11,8.26957e-10,3.50409e-06,3.50409e-06,5.0002e-08,0,0,0,0,0,0,0,0
21185000,0.982619,0.00152867,-0.00489183,0.185565,-0.0458106,0.043261,-0.486053,-0.00214019,9.61769e-05,-0.0377,-1.4247e-05,-5.95261e-05,7.66177e-07,-7.40221e-05,6.83868e-05,-0.00130905,0.204182,0.00196632,0.433697,0,0,0,0,0,5.21694e-06,8.78425e-06,8.77768e-06,0.000145159,0.0403364,0.0403404,0.0103155,0.0421073,0.0421077,0.0600135,9.50414e-11,9.50259e-11,8.11289e-10,3.21573e-06,3.21575e-06,5.0002e-08,0,0,0,0,0,0,0,0
21285000,0.982569,-0.000686723,-0.00626608,0.185793,-0.0455938,0.0462914,-0.616091,-0.0067397,0.00458862,-0.0938215,-1.4251e-05,-5.95224e-05,5.69743e-07,-7.39937e-05,6.83533e-05,-0.00130868,0.204182,0.00196632,0.433697,0,0,0,0,0,5.18985e-06,9.07778e-06,9.06804e-06,0.000144188,0.0470545,0.0470592,0.0103743,0.0479586,0.0479594,0.0601966,9.51349e-11,9.51207e-11,7.96011e-10,3.21573e-06,3.21576e-06,5.0001e-08,0,0,0,0,0,0,0,0
21385000,0.982523,-0.00215579,-0.00692837,0.185998,-0.0386956,0.0422437,-0.740305,-0.00501759,0.00753011,-0.155416,-1.42006e-05,-5.94488e-05,5.09404e-07,-0.000101372,8.72877e-05,-0.00131479,0.204182,0.00196632,0.433697,0,0,0,0,0,5.16581e-06,8.93294e-06,8.92241e-06,0.000143226,0.042888,0.0428923,0.0102477,0.0427292,0.0427297,0.0597468,9.268e-11,9.26691e-11,7.81111e-10,2.90409e-06,2.90412e-06,5.0001e-08,0,0,0,0,0,0,0,0
21485000,0.982497,-0.00300189,-0.00737092,0.18611,-0.0337097,0.0389534,-0.875698,-0.00870909,0.0116246,-0.240014,-1.41982e-05,-5.94505e-05,6.17736e-07,-0.000101185,8.71586e-05,-0.00131339,0.204182,0.00196632,0.433697,0,0,0,0,0,5.14144e-06,9.22344e-06,9.21252e-06,0.000142276,0.0493763,0.0493817,0.0103067,0.0489285,0.0489294,0.0599215,9.27739e-11,9.27643e-11,7.66579e-10,2.90409e-06,2.90412e-06,5e-08,0,0,0,0,0,0,0,0
21585000,0.982499,-0.00343534,-0.00735821,0.186093,-0.0250469,0.0350159,-0.998878,-0.00746324,0.013118,-0.325234,-1.41564e-05,-5.94209e-05,7.06419e-07,-0.0001069,8.4219e-05,-0.00132136,0.204182,0.00196632,0.433697,0,0,0,0,0,5.10988e-06,9.18941e-06,9.17908e-06,0.000141348,0.0439215,0.0439264,0.0101821,0.043376,0.0433766,0.0594715,9.1044e-11,9.10367e-11,7.52404e-10,2.59627e-06,2.5963e-06,5e-08,0,0,0,0,0,0,0,0
21685000,0.982488,-0.00378648,-0.00721072,0.186146,-0.0220413,0.0308525,-1.13227,-0.00981194,0.0164569,-0.439375,-1.41527e-05,-5.9423e-05,8.67113e-07,-0.000106494,8.39549e-05,-0.00131859,0.204182,0.00196632,0.433697,0,0,0,0,0,5.08425e-06,9.47988e-06,9.47041e-06,0.000140424,0.0499811,0.0499872,0.0102411,0.049838,0.0498392,0.0596387,9.11382e-11,9.11322e-11,7.38572e-10,2.59627e-06,2.59631e-06,5e-08,0,0,0,0,0,0,0,0
21785000,0.982505,-0.00415226,-0.00731874,0.186046,-0.0123405,0.0263065,-1.25994,-0.00246739,0.0150968,-0.552239,-1.4067e-05,-5.93626e-05,1.10599e-06,-0.000129509,7.84966e-05,-0.0013255,0.204182,0.00196632,0.433697,0,0,0,0,0,5.08567e-06,9.53928e-06,9.53001e-06,0.000140419,0.0436918,0.043697,0.0102062,0.0439754,0.0439762,0.0600784,8.99695e-11,8.99649e-11,7.28441e-10,2.31069e-06,2.31073e-06,5.0002e-08,0,0,0,0,0,0,0,0
21885000,0.982497,-0.00444152,-0.00743632,0.186076,-0.00870506,0.0219879,-1.38109,-0.00354198,0.0175554,-0.691792,-1.407e-05,-5.93587e-05,9.35857e-07,-0.0001292,7.8259e-05,-0.00132296,0.204182,0.00196632,0.433697,0,0,0,0,0,5.0499e-06,9.83405e-06,9.82489e-06,0.000139515,0.0492209,0.0492271,0.0102663,0.0506028,0.0506041,0.0602436,9.0064e-11,9.00606e-11,7.15186e-10,2.31069e-06,2.31074e-06,5.0001e-08,0,0,0,0,0,0,0,0
21985000,0.982514,-0.00512895,-0.00773443,0.185958,-0.00758989,0.0182301,-1.36906,0.000401991,0.014566,-0.826847,-1.39875e-05,-5.93263e-05,1.01084e-06,-0.000112861,5.50593e-05,-0.00132766,0.204182,0.00196632,0.433697,0,0,0,0,0,5.01357e-06,9.96621e-06,9.95736e-06,0.000138622,0.042511,0.0425163,0.0101441,0.0444774,0.0444784,0.0597823,8.92986e-11,8.92965e-11,7.02254e-10,2.05666e-06,2.05672e-06,5.0001e-08,0,0,0,0,0,0,0,0
22085000,0.982507,-0.00587051,-0.00852687,0.185939,-0.00446836,0.0145918,-1.34974,-0.000265676,0.0161636,-0.968664,-1.39835e-05,-5.93285e-05,1.18545e-06,-0.000112487,5.4838e-05,-0.00132536,0.204182,0.00196632,0.433697,0,0,0,0,0,4.98574e-06,1.0268e-05,1.02581e-05,0.000137729,0.0474613,0.0474677,0.0102046,0.0511614,0.051163,0.0599413,8.93935e-11,8.93923e-11,6.89628e-10,2.05666e-06,2.05672e-06,5.0001e-08,0,0,0,0,0,0,0,0
22185000,0.982523,-0.00631853,-0.00882939,0.185826,0.00146024,0.0108353,-1.36461,0.00628137,0.0117846,-1.10988,-1.38816e-05,-5.92799e-05,1.32213e-06,-0.000104565,3.38128e-05,-0.00132316,0.204182,0.00196632,0.433697,0,0,0,0,0,4.952e-06,1.0456e-05,1.0446e-05,0.000136854,0.0407627,0.0407682,0.0100841,0.044856,0.0448571,0.0594769,8.89191e-11,8.89176e-11,6.77297e-10,1.83469e-06,1.83475e-06,5e-08,0,0,0,0,0,0,0,0
22285000,0.98251,-0.00704307,-0.00907081,0.185856,0.00743231,0.00572912,-1.36261,0.00670892,0.012652,-1.25241,-1.38826e-05,-5.92773e-05,1.23474e-06,-0.000104253,3.35911e-05,-0.00132099,0.204182,0.00196632,0.433697,0,0,0,0,0,4.91997e-06,1.07626e-05,1.07533e-05,0.000135988,0.0451944,0.0452011,0.0101452,0.0515248,0.0515265,0.0596305,8.90147e-11,8.90131e-11,6.65264e-10,1.83469e-06,1.83476e-06,5e-08,0,0,0,0,0,0,0,0
22385000,0.98269,-0.0074254,-0.00926491,0.184878,0.00923438,-0.00350679,-1.36449,0.0120836,0.00314665,-1.39677,-1.37749e-05,-5.92294e-05,1.17017e-06,-7.66589e-05,2.7017e-05,-0.00131709,0.204241,0.0019669,0.43438,0,0,0,0,0,8.01411e-05,1.11295e-05,1.10525e-05,0.00228333,0.0387229,0.0387286,0.0101149,0.0451083,0.0451095,0.0600634,8.87281e-11,8.87262e-11,6.59402e-10,1.64419e-06,1.64427e-06,5.0002e-08,0,0,0,0,0,0,0,0
22485000,0.982381,-0.00758241,-0.00971006,0.186481,0.013749,-0.0100052,-1.36922,0.0132158,0.00245647,-1.53808,-1.37743e-05,-5.92286e-05,1.17079e-06,-7.64135e-05,2.68531e-05,-0.00131544,0.204241,0.0019669,0.43438,0,0,0,0,0,5.64374e-05,1.11419e-05,1.10766e-05,0.00160776,0.042855,0.0428617,0.0101774,0.0516733,0.0516752,0.0602168,8.8828e-11,8.88261e-11,6.59501e-10,1.64419e-06,1.64427e-06,5.0002e-08,0,0,0,0,0,0,0,0
22585000,0.982484,-0.00744103,-0.0102954,0.185914,0.0223125,-0.016438,-1.36893,0.0249696,-0.00549684,-1.68089,-1.36577e-05,-5.91737e-05,1.17347e-06,-8.12665e-05,1.47469e-05,-0.00131271,0.204241,0.0019669,0.43438,0,0,0,0,0,4.36124e-05,1.11824e-05,1.11125e-05,0.00124066,0.0371096,0.0371156,0.0100599,0.0452166,0.045218,0.0597455,8.86378e-11,8.86356e-11,6.59594e-10,1.47328e-06,1.47336e-06,5.0001e-08,0,0,0,0,0,0,0,0
22685000,0.982427,-0.00737165,-0.010495,0.186208,0.0246091,-0.0212905,-1.37237,0.0273088,-0.00743129,-1.82475,-1.36568e-05,-5.91723e-05,1.17368e-06,-8.09042e-05,1.45025e-05,-0.0013103,0.204241,0.0019669,0.43438,0,0,0,0,0,3.55477e-05,1.12296e-05,1.11661e-05,0.00101008,0.0412038,0.0412109,0.0101236,0.0516104,0.0516126,0.0598948,8.87377e-11,8.87355e-11,6.59686e-10,1.47328e-06,1.47336e-06,5.0001e-08,0,0,0,0,0,0,0,0
22785000,0.982376,-0.0073159,-0.0108837,0.186455,0.0277617,-0.0272632,-1.37645,0.0360714,-0.0165989,-1.97266,-1.35159e-05,-5.90869e-05,1.17294e-06,-6.20321e-05,-6.43153e-06,-0.00130571,0.204241,0.0019669,0.43438,0,0,0,0,0,2.99079e-05,1.12778e-05,1.12156e-05,0.000851901,0.0359903,0.0359967,0.0100088,0.0451969,0.0451985,0.0594279,8.85141e-11,8.85119e-11,6.5977e-10,1.3163e-06,1.31638e-06,5e-08,0,0,0,0,0,0,0,0
22885000,0.982534,-0.00750566,-0.0112126,0.185594,0.0308722,-0.0320127,-1.3783,0.038964,-0.0194839,-2.11693,-1.35147e-05,-5.90856e-05,1.18261e-06,-6.17026e-05,-6.68629e-06,-0.00130338,0.204241,0.0019669,0.43438,0,0,0,0,0,2.57701e-05,1.13462e-05,1.1289e-05,0.000736648,0.0399986,0.0400064,0.0100736,0.0514468,0.0514493,0.0595738,8.8614e-11,8.86117e-11,6.5985e-10,1.3163e-06,1.31639e-06,5e-08,0,0,0,0,0,0,0,0
22985000,0.982664,-0.00743752,-0.0115797,0.184885,0.0322222,-0.0354984,-1.38262,0.0475663,-0.0293882,-2.26911,-1.3362e-05,-5.89861e-05,1.19389e-06,-4.09754e-05,-2.81098e-05,-0.00129745,0.204241,0.0019669,0.43438,0,0,0,0,0,2.26231e-05,1.13938e-05,1.13367e-05,0.000648919,0.0351196,0.0351269,0.00996141,0.0451008,0.0451027,0.0591119,8.82858e-11,8.82836e-11,6.59921e-10,1.17384e-06,1.17392e-06,5e-08,0,0,0,0,0,0,0,0
23085000,0.982719,-0.0074494,-0.0118996,0.184573,0.0359427,-0.0403742,-1.37993,0.0509593,-0.0332114,-2.40841,-1.33618e-05,-5.89858e-05,1.19334e-06,-4.09144e-05,-2.81499e-05,-0.00129705,0.204241,0.0019669,0.43438,0,0,0,0,0,2.06909e-05,1.1478e-05,1.1421e-05,0.000595829,0.0389967,0.0390055,0.0101138,0.0512322,0.051235,0.060146,8.83857e-11,8.83834e-11,6.59995e-10,1.17384e-06,1.17392e-06,5.0002e-08,0,0,0,0,0,0,0,0
23185000,0.982708,-0.00740739,-0.0120888,0.184619,0.0404909,-0.0401367,-1.38323,0.0619863,-0.0431294,-2.55568,-1.32359e-05,-5.88912e-05,1.18657e-06,-2.87776e-05,-3.98123e-05,-0.00129269,0.204241,0.0019669,0.43438,0,0,0,0,0,1.85969e-05,1.15197e-05,1.14654e-05,0.000537201,0.034333,0.0343416,0.0100021,0.0449644,0.0449665,0.0596757,8.79306e-11,8.79286e-11,6.6005e-10,1.0463e-06,1.04637e-06,5.0001e-08,0,0,0,0,0,0,0,0
23285000,0.982755,-0.00788154,-0.0122182,0.184341,0.0442768,-0.0447856,-1.37916,0.0661555,-0.0474195,-2.69992,-1.32346e-05,-5.88897e-05,1.19153e-06,-2.84741e-05,-4.00499e-05,-0.00129051,0.204241,0.0019669,0.43438,0,0,0,0,0,1.69003e-05,1.16111e-05,1.15638e-05,0.000489117,0.038041,0.0380513,0.0100698,0.0509969,0.0510001,0.059821,8.80304e-11,8.80283e-11,6.60096e-10,1.0463e-06,1.04638e-06,5.0001e-08,0,0,0,0,0,0,0,0
23385000,0.982718,-0.00785181,-0.0123269,0.18453,0.0482045,-0.0435174,-1.38055,0.0770325,-0.0512064,-2.84064,-1.30772e-05,-5.88369e-05,1.17361e-06,-2.94237e-05,-7.0292e-05,-0.00128907,0.204241,0.0019669,0.43438,0,0,0,0,0,1.54789e-05,1.16506e-05,1.16059e-05,0.000448988,0.0335294,0.0335384,0.00996047,0.0448102,0.0448125,0.0593566,8.74576e-11,8.74558e-11,6.60129e-10,9.33688e-07,9.33755e-07,5.0001e-08,0,0,0,0,0,0,0,0
23485000,0.982766,-0.00794445,-0.012595,0.184255,0.0515878,-0.0448911,-1.38221,0.0819828,-0.0556584,-2.98435,-1.30757e-05,-5.88357e-05,1.1864e-06,-2.91784e-05,-7.0522e-05,-0.00128707,0.204241,0.0019669,0.43438,0,0,0,0,0,1.4302e-05,1.17559e-05,1.17124e-05,0.000414971,0.0370451,0.037056,0.0100281,0.0507567,0.0507603,0.0594949,8.75574e-11,8.75555e-11,6.6015e-10,9.33688e-07,9.3376e-07,5e-08,0,0,0,0,0,0,0,0
23585000,0.982791,-0.00819568,-0.0125357,0.184112,0.0515429,-0.0472664,-1.38167,0.0888136,-0.0661592,-3.1302,-1.2984e-05,-5.87352e-05,1.19386e-06,-9.14616e-06,-7.72521e-05,-0.00128421,0.204241,0.0019669,0.43438,0,0,0,0,0,1.32887e-05,1.17948e-05,1.17565e-05,0.000385795,0.0326559,0.0326655,0.00992107,0.0446499,0.0446526,0.0590367,8.68935e-11,8.6892e-11,6.60157e-10,8.3556e-07,8.35619e-07,5e-08,0,0,0,0,0,0,0,0
23685000,0.982798,-0.00882733,-0.0130301,0.184011,0.0492645,-0.0493282,-1.2857,0.0938685,-0.0710545,-3.26819,-1.29831e-05,-5.87345e-05,1.20243e-06,-9.02173e-06,-7.73762e-05,-0.00128313,0.204241,0.0019669,0.43438,0,0,0,0,0,1.26302e-05,1.19151e-05,1.18781e-05,0.000366562,0.0359028,0.0359135,0.0100764,0.0505165,0.0505204,0.0600681,8.69934e-11,8.69917e-11,6.60178e-10,8.35562e-07,8.35625e-07,5.0002e-08,0,0,0,0,0,0,0,0
23785000,0.982787,-0.0106096,-0.0157113,0.183768,0.0449305,-0.0441256,-0.96843,0.104019,-0.0750357,-3.39107,-1.28608e-05,-5.87056e-05,1.22073e-06,-1.24579e-05,-9.62285e-05,-0.00127863,0.204241,0.0019669,0.43438,0,0,0,0,0,1.18475e-05,1.19874e-05,1.19377e-05,0.00034365,0.0314783,0.0314873,0.00996955,0.0444864,0.0444893,0.0596026,8.62668e-11,8.62655e-11,6.60159e-10,7.50898e-07,7.50949e-07,5.0002e-08,0,0,0,0,0,0,0,0
23885000,0.982695,-0.0139561,-0.0198409,0.183636,0.0396273,-0.0433639,-0.537882,0.108214,-0.0793628,-3.46946,-1.28601e-05,-5.87047e-05,1.2208e-06,-1.23108e-05,-9.6342e-05,-0.00127755,0.204241,0.0019669,0.43438,0,0,0,0,0,1.11406e-05,1.21597e-05,1.2091e-05,0.000323461,0.0342998,0.0343109,0.0100403,0.050262,0.0502663,0.0597435,8.63665e-11,8.63651e-11,6.60124e-10,7.50898e-07,7.50954e-07,5.0001e-08,0,0,0,0,0,0,0,0
23985000,0.982629,-0.0162211,-0.0223228,0.18352,0.041354,-0.040221,-0.153715,0.116988,-0.081363,-3.53791,-1.27546e-05,-5.86747e-05,1.2121e-06,-1.57577e-05,-0.000112544,-0.00125402,0.204241,0.0019669,0.43438,0,0,0,0,0,1.05084e-05,1.22569e-05,1.21794e-05,0.000305575,0.0300565,0.030067,0.00993645,0.0443129,0.0443161,0.0592848,8.55769e-11,8.55758e-11,6.60071e-10,6.77556e-07,6.77603e-07,5.0001e-08,0,0,0,0,0,0,0,0
24085000,0.982656,-0.0158627,-0.0213974,0.183514,0.0468928,-0.0476554,0.0906041,0.121344,-0.0857146,-3.54131,-1.27543e-05,-5.86736e-05,1.19778e-06,-1.5611e-05,-0.000112625,-0.00125325,0.204241,0.0019669,0.43438,0,0,0,0,0,9.94501e-06,1.23783e-05,1.23125e-05,0.00028967,0.032731,0.032744,0.0100087,0.0499884,0.0499932,0.0594256,8.56767e-11,8.56753e-11,6.59999e-10,6.77556e-07,6.77608e-07,5e-08,0,0,0,0,0,0,0,0
24185000,0.982774,-0.0130776,-0.0177378,0.183491,0.0579637,-0.0523583,0.0829724,0.129487,-0.0904768,-3.55762,-1.26945e-05,-5.86346e-05,1.20364e-06,-1.3833e-05,-0.000119736,-0.00123432,0.204241,0.0019669,0.43438,0,0,0,0,0,9.45795e-06,1.24236e-05,1.23782e-05,0.000275416,0.028877,0.0288885,0.00990621,0.0441273,0.044131,0.0589738,8.48608e-11,8.48598e-11,6.59908e-10,6.14499e-07,6.14544e-07,5e-08,0,0,0,0,0,0,0,0
24285000,0.98287,-0.0106382,-0.0142582,0.183438,0.0609121,-0.0555528,0.0577785,0.135475,-0.0959269,-3.55383,-1.26937e-05,-5.86339e-05,1.20892e-06,-1.37236e-05,-0.000119837,-0.00123339,0.204241,0.0019669,0.43438,0,0,0,0,0,9.01174e-06,1.2542e-05,1.25132e-05,0.000262544,0.031472,0.0314851,0.00997815,0.049711,0.0497162,0.0591147,8.49605e-11,8.49592e-11,6.59797e-10,6.145e-07,6.14549e-07,5e-08,0,0,0,0,0,0,0,0
24385000,0.982934,-0.00972201,-0.0131727,0.183229,0.055342,-0.0490851,0.0742245,0.143306,-0.0965253,-3.55007,-1.26163e-05,-5.8651e-05,1.22995e-06,-2.01097e-05,-0.00013443,-0.00123229,0.204241,0.0019669,0.43438,0,0,0,0,0,8.70479e-06,1.26281e-05,1.26029e-05,0.00025377,0.027774,0.0277845,0.00996025,0.0439347,0.0439387,0.059543,8.41854e-11,8.41844e-11,6.59723e-10,5.61494e-07,5.61536e-07,5.0002e-08,0,0,0,0,0,0,0,0
24485000,0.982974,-0.00994215,-0.013238,0.183,0.0495536,-0.0445423,0.0723706,0.148533,-0.101195,-3.5422,-1.26157e-05,-5.86522e-05,1.26937e-06,-2.02261e-05,-0.000134435,-0.00123244,0.204241,0.0019669,0.43438,0,0,0,0,0,8.33443e-06,1.2789e-05,1.2765e-05,0.00024285,0.0301663,0.0301779,0.0100334,0.0494234,0.049429,0.0596885,8.4285e-11,8.42838e-11,6.59573e-10,5.61495e-07,5.61541e-07,5.0001e-08,0,0,0,0,0,0,0,0
24585000,0.982933,-0.0106432,-0.0133437,0.183173,0.0473781,-0.0391087,0.0677436,0.15372,-0.0982439,-3.53651,-1.2546e-05,-5.86941e-05,1.26702e-06,-2.872e-05,-0.000150054,-0.00123132,0.204241,0.0019669,0.43438,0,0,0,0,0,8.00794e-06,1.28893e-05,1.28686e-05,0.000232863,0.0266506,0.0266599,0.00993155,0.0437335,0.0437378,0.0592369,8.35671e-11,8.35661e-11,6.594e-10,5.17207e-07,5.17249e-07,5.0001e-08,0,0,0,0,0,0,0,0
24685000,0.982917,-0.0111581,-0.0131754,0.18324,0.0439568,-0.0376721,0.0668915,0.158337,-0.102018,-3.52972,-1.25461e-05,-5.8694e-05,1.26473e-06,-2.87135e-05,-0.000150055,-0.00123131,0.204241,0.0019669,0.43438,0,0,0,0,0,7.69941e-06,1.30595e-05,1.30429e-05,0.000223722,0.0288616,0.0288718,0.0100051,0.0491225,0.0491283,0.0593828,8.36667e-11,8.36655e-11,6.59202e-10,5.17208e-07,5.17253e-07,5.0001e-08,0,0,0,0,0,0,0,0
24785000,0.982942,-0.0113068,-0.0125392,0.183139,0.0414789,-0.0346022,0.0591983,0.161737,-0.0985226,-3.52724,-1.24916e-05,-5.87065e-05,1.27177e-06,-3.18186e-05,-0.00016319,-0.00123042,0.204241,0.0019669,0.43438,0,0,0,0,0,7.40531e-06,1.3162e-05,1.31501e-05,0.000215331,0.0255242,0.0255323,0.00990383,0.043521,0.0435254,0.0589327,8.30213e-11,8.30202e-11,6.58978e-10,4.80476e-07,4.8052e-07,5e-08,0,0,0,0,0,0,0,0
24885000,0.982945,-0.0111497,-0.0120307,0.183169,0.0385107,-0.0373011,0.0488873,0.165758,-0.102124,-3.52408,-1.24907e-05,-5.87061e-05,1.28632e-06,-3.17427e-05,-0.000163285,-0.00122962,0.204241,0.0019669,0.43438,0,0,0,0,0,7.14729e-06,1.33417e-05,1.33319e-05,0.000207581,0.0275717,0.0275804,0.00997744,0.0488059,0.0488117,0.0590791,8.31209e-11,8.31195e-11,6.58728e-10,4.80478e-07,4.80524e-07,5e-08,0,0,0,0,0,0,0,0
24985000,0.982926,-0.0109545,-0.0117977,0.183294,0.0312576,-0.0319002,0.0414268,0.167,-0.0939907,-3.52159,-1.24183e-05,-5.87392e-05,1.28748e-06,-3.73741e-05,-0.000181679,-0.00122916,0.204241,0.0019669,0.43438,0,0,0,0,0,6.97506e-06,1.34531e-05,1.34433e-05,0.000202276,0.0244138,0.0244206,0.00996205,0.0432954,0.0432998,0.0595135,8.25574e-11,8.25562e-11,6.58548e-10,4.50228e-07,4.50272e-07,5.0002e-08,0,0,0,0,0,0,0,0
25085000,0.982924,-0.0112926,-0.0118556,0.183282,0.0270851,-0.0306368,0.0383195,0.169844,-0.0971628,-3.5234,-1.24166e-05,-5.87371e-05,1.28127e-06,-3.71016e-05,-0.000181905,-0.00122712,0.204241,0.0019669,0.43438,0,0,0,0,0,6.73987e-06,1.36464e-05,1.36378e-05,0.000195518,0.0263021,0.0263096,0.0100369,0.0484721,0.0484778,0.0596649,8.26569e-11,8.26555e-11,6.5825e-10,4.50229e-07,4.50277e-07,5.0002e-08,0,0,0,0,0,0,0,0
25185000,0.982875,-0.0115409,-0.011705,0.183539,0.0238885,-0.0245288,0.0383684,0.171787,-0.0902849,-3.52111,-1.23853e-05,-5.87793e-05,1.25997e-06,-4.40872e-05,-0.00019268,-0.00122591,0.204241,0.0019669,0.43438,0,0,0,0,0,6.53653e-06,1.37635e-05,1.37565e-05,0.000189227,0.0233202,0.0233262,0.00993654,0.0430553,0.0430596,0.059215,8.21781e-11,8.21768e-11,6.57922e-10,4.25459e-07,4.25505e-07,5.0001e-08,0,0,0,0,0,0,0,0
25285000,0.982828,-0.0116898,-0.0110628,0.183822,0.0178437,-0.0252485,0.0331512,0.173839,-0.092752,-3.51854,-1.23859e-05,-5.87779e-05,1.216e-06,-4.39802e-05,-0.000192703,-0.00122558,0.204241,0.0019669,0.43438,0,0,0,0,0,6.34358e-06,1.39643e-05,1.39607e-05,0.000183381,0.0250692,0.0250757,0.0100116,0.0481203,0.0481258,0.059367,8.22776e-11,8.2276e-11,6.57565e-10,4.25461e-07,4.25509e-07,5.0001e-08,0,0,0,0,0,0,0,0
25385000,0.982829,-0.0118471,-0.0108767,0.183819,0.0110014,-0.0181285,0.0314619,0.171094,-0.0827726,-3.51939,-1.23238e-05,-5.88017e-05,1.218e-06,-4.67951e-05,-0.000208551,-0.00122348,0.204241,0.0019669,0.43438,0,0,0,0,0,6.15608e-06,1.40868e-05,1.40842e-05,0.000177934,0.0222661,0.0222713,0.00991235,0.0428001,0.0428043,0.0589236,8.18837e-11,8.18821e-11,6.57176e-10,4.05304e-07,4.05352e-07,5e-08,0,0,0,0,0,0,0,0
25485000,0.98282,-0.0118916,-0.0105773,0.183881,0.00473808,-0.0167661,0.0305592,0.171819,-0.0845137,-3.51805,-1.23236e-05,-5.88006e-05,1.20099e-06,-4.66947e-05,-0.000208618,-0.00122288,0.204241,0.0019669,0.43438,0,0,0,0,0,5.98123e-06,1.42997e-05,1.42982e-05,0.000172848,0.0238851,0.0238908,0.00998743,0.0477513,0.0477565,0.0590763,8.19831e-11,8.19813e-11,6.56757e-10,4.05305e-07,4.05356e-07,5e-08,0,0,0,0,0,0,0,0
25585000,0.982806,-0.0121277,-0.0103993,0.18395,0.00115598,-0.0144848,0.0323439,0.169555,-0.0784747,-3.51641,-1.23169e-05,-5.88179e-05,1.17839e-06,-4.8721e-05,-0.000214704,-0.00122222,0.204241,0.0019669,0.43438,0,0,0,0,0,5.81705e-06,1.44269e-05,1.44264e-05,0.000168088,0.0212548,0.0212593,0.00988914,0.0425303,0.0425342,0.0586393,8.1671e-11,8.16692e-11,6.56304e-10,3.89006e-07,3.89057e-07,5e-08,0,0,0,0,0,0,0,0
25685000,0.982818,-0.0116076,-0.010098,0.183937,-0.000274164,-0.013654,0.0214661,0.169596,-0.0799149,-3.5165,-1.23157e-05,-5.8817e-05,1.18728e-06,-4.86035e-05,-0.000214824,-0.00122122,0.204241,0.0019669,0.43438,0,0,0,0,0,5.70688e-06,1.46504e-05,1.46486e-05,0.000164871,0.0227655,0.0227702,0.0100485,0.0473666,0.0473714,0.0596696,8.17705e-11,8.17686e-11,6.55968e-10,3.8901e-07,3.89062e-07,5.0002e-08,0,0,0,0,0,0,0,0
25785000,0.982835,-0.0114154,-0.00940447,0.18389,-0.00994226,-0.00693241,0.0202378,0.163947,-0.072421,-3.51937,-1.22886e-05,-5.8828e-05,1.18785e-06,-4.85599e-05,-0.000223491,-0.00121917,0.204241,0.0019669,0.43438,0,0,0,0,0,5.55736e-06,1.47795e-05,1.47788e-05,0.000160626,0.0203036,0.0203075,0.00994948,0.0422467,0.0422503,0.0592258,8.15361e-11,8.15342e-11,6.55455e-10,3.75934e-07,3.75986e-07,5.0001e-08,0,0,0,0,0,0,0,0
25885000,0.982804,-0.0114787,-0.00944969,0.184051,-0.016941,-0.00457704,0.0226353,0.162537,-0.0729717,-3.51816,-1.22895e-05,-5.8826e-05,1.11925e-06,-4.84444e-05,-0.00022352,-0.00121883,0.204241,0.0019669,0.43438,0,0,0,0,0,5.41865e-06,1.50138e-05,1.50128e-05,0.000156636,0.021706,0.0217102,0.0100254,0.0469682,0.0469726,0.0593841,8.16354e-11,8.16333e-11,6.5491e-10,3.75936e-07,3.75989e-07,5.0001e-08,0,0,0,0,0,0,0,0
25985000,0.982797,-0.011612,-0.00962216,0.184073,-0.0248218,9.23048e-05,0.0158553,0.152402,-0.0660169,-3.51843,-1.22652e-05,-5.88081e-05,1.10419e-06,-4.39236e-05,-0.000231303,-0.00121756,0.204241,0.0019669,0.43438,0,0,0,0,0,5.28868e-06,1.51484e-05,1.51465e-05,0.000152879,0.0194083,0.0194117,0.00992702,0.0419509,0.0419542,0.0589464,8.14713e-11,8.14691e-11,6.54327e-10,3.6552e-07,3.65574e-07,5.0001e-08,0,0,0,0,0,0,0,0
26085000,0.982829,-0.0113158,-0.00957649,0.183925,-0.0301852,0.000870812,0.0142184,0.149628,-0.0659586,-3.51884,-1.22638e-05,-5.88082e-05,1.14357e-06,-4.38725e-05,-0.000231392,-0.00121688,0.204241,0.0019669,0.43438,0,0,0,0,0,5.16409e-06,1.53923e-05,1.53891e-05,0.000149347,0.0207244,0.0207281,0.0100018,0.0465588,0.0465627,0.0590997,8.15706e-11,8.15682e-11,6.53708e-10,3.65522e-07,3.65577e-07,5e-08,0,0,0,0,0,0,0,0
26185000,0.982824,-0.0112931,-0.0101021,0.183924,-0.035796,0.0044418,0.00977287,0.140966,-0.0619364,-3.5222,-1.22622e-05,-5.88052e-05,1.17045e-06,-4.16772e-05,-0.000234318,-0.00121506,0.204241,0.0019669,0.43438,0,0,0,0,0,5.05309e-06,1.55288e-05,1.5523e-05,0.000146007,0.0185764,0.0185793,0.00990418,0.0416447,0.0416477,0.0586678,8.14694e-11,8.1467e-11,6.5305e-10,3.5731e-07,3.57364e-07,5e-08,0,0,0,0,0,0,0,0
26285000,0.982822,-0.0113612,-0.0104151,0.183913,-0.0375331,0.00574464,0.00380734,0.137284,-0.0614615,-3.52333,-1.22621e-05,-5.88038e-05,1.13568e-06,-4.15661e-05,-0.000234399,-0.00121441,0.204241,0.0019669,0.43438,0,0,0,0,0,4.97296e-06,1.57834e-05,1.57763e-05,0.00014381,0.0198184,0.0198213,0.0100643,0.0461412,0.0461447,0.0597049,8.15688e-11,8.15663e-11,6.52559e-10,3.57314e-07,3.57368e-07,5.0002e-08,0,0,0,0,0,0,0,0
26385000,0.982853,-0.0108519,-0.0103912,0.183778,-0.0429695,0.0104166,0.00689702,0.124995,-0.0563044,-3.52337,-1.22488e-05,-5.87829e-05,1.11409e-06,-3.68137e-05,-0.000238881,-0.00121426,0.204241,0.0019669,0.43438,0,0,0,0,0,4.85994e-06,1.59176e-05,1.59083e-05,0.000140809,0.0178084,0.0178105,0.00996542,0.0413305,0.0413332,0.0592657,8.15217e-11,8.15191e-11,6.51834e-10,3.50908e-07,3.50962e-07,5.0002e-08,0,0,0,0,0,0,0,0
26485000,0.982861,-0.0106073,-0.0102812,0.183753,-0.0464017,0.0134014,0.0159905,0.120529,-0.055135,-3.52227,-1.22492e-05,-5.87824e-05,1.09026e-06,-3.67942e-05,-0.000238883,-0.00121425,0.204241,0.0019669,0.43438,0,0,0,0,0,4.75857e-06,1.61802e-05,1.61701e-05,0.000137968,0.0189741,0.0189761,0.0100407,0.0457184,0.0457214,0.0594242,8.16209e-11,8.16181e-11,6.51071e-10,3.50911e-07,3.50964e-07,5.0001e-08,0,0,0,0,0,0,0,0
26585000,0.982848,-0.0101153,-0.0105554,0.183837,-0.0469455,0.0186541,0.0163559,0.111904,-0.0508827,-3.52256,-1.22392e-05,-5.87733e-05,1.05561e-06,-3.494e-05,-0.000241393,-0.00121265,0.204241,0.0019669,0.43438,0,0,0,0,0,4.66732e-06,1.63136e-05,1.63005e-05,0.000135274,0.0170994,0.0171006,0.00994233,0.0410105,0.0410128,0.0589906,8.16171e-11,8.16144e-11,6.50267e-10,3.45964e-07,3.46016e-07,5.0001e-08,0,0,0,0,0,0,0,0
26685000,0.982841,-0.00999544,-0.0102648,0.183896,-0.0489712,0.023406,0.0154923,0.107094,-0.0487789,-3.52108,-1.22402e-05,-5.87719e-05,9.93074e-07,-3.48919e-05,-0.000241405,-0.0012126,0.204241,0.0019669,0.43438,0,0,0,0,0,4.57717e-06,1.65846e-05,1.65719e-05,0.00013273,0.0182152,0.0182161,0.0100172,0.0452936,0.0452962,0.059149,8.17162e-11,8.17134e-11,6.49424e-10,3.45966e-07,3.46018e-07,5e-08,0,0,0,0,0,0,0,0
26785000,0.982862,-0.00983321,-0.0097568,0.18382,-0.0543074,0.0247524,0.0141411,0.0959522,-0.0463284,-3.52379,-1.22255e-05,-5.87514e-05,9.68442e-07,-3.09705e-05,-0.000243279,-0.00121068,0.204241,0.0019669,0.43438,0,0,0,0,0,4.48877e-06,1.67114e-05,1.66994e-05,0.000130322,0.0164648,0.0164654,0.00991948,0.0406874,0.0406893,0.0587207,8.17458e-11,8.17431e-11,6.48537e-10,3.42204e-07,3.42253e-07,5e-08,0,0,0,0,0,0,0,0
26885000,0.982891,-0.00923174,-0.00984586,0.183691,-0.0601664,0.02732,0.00977473,0.0901923,-0.0437293,-3.52309,-1.22244e-05,-5.87523e-05,1.01873e-06,-3.09747e-05,-0.000243302,-0.00121049,0.204241,0.0019669,0.43438,0,0,0,0,0,4.40862e-06,1.69927e-05,1.69785e-05,0.000128037,0.0175359,0.0175365,0.0099941,0.0448707,0.0448728,0.0588791,8.18449e-11,8.18421e-11,6.47611e-10,3.42206e-07,3.42254e-07,5e-08,0,0,0,0,0,0,0,0
26985000,0.982885,-0.00874856,-0.0103346,0.183723,-0.0659871,0.031168,0.00780453,0.0788657,-0.0400748,-3.52758,-1.22002e-05,-5.87321e-05,9.88699e-07,-2.78054e-05,-0.000245951,-0.00120809,0.204241,0.0019669,0.43438,0,0,0,0,0,4.35911e-06,1.71161e-05,1.70988e-05,0.000126598,0.0158996,0.0158999,0.00998011,0.0403644,0.040366,0.0593227,8.1897e-11,8.18944e-11,6.4691e-10,3.3939e-07,3.39434e-07,5.0002e-08,0,0,0,0,0,0,0,0
27085000,0.982885,-0.00857843,-0.0106675,0.183712,-0.0682911,0.0382355,0.0116367,0.0720778,-0.0365868,-3.53097,-1.21984e-05,-5.873e-05,9.7532e-07,-2.75956e-05,-0.000246174,-0.0012065,0.204241,0.0019669,0.43438,0,0,0,0,0,4.28679e-06,1.74065e-05,1.73875e-05,0.000124516,0.0169251,0.0169249,0.0100554,0.0444534,0.044455,0.0594856,8.1996e-11,8.19933e-11,6.45909e-10,3.39392e-07,3.39436e-07,5.0001e-08,0,0,0,0,0,0,0,0
27185000,0.982891,-0.00864484,-0.0105763,0.183678,-0.0732143,0.0414971,0.0128894,0.0625859,-0.0328775,-3.53346,-1.21712e-05,-5.87143e-05,9.6371e-07,-2.56721e-05,-0.000248117,-0.00120504,0.204241,0.0019669,0.43438,0,0,0,0,0,4.21713e-06,1.75195e-05,1.75005e-05,0.00012254,0.0153919,0.0153914,0.00995679,0.0400443,0.0400455,0.0590545,8.20584e-11,8.20561e-11,6.44861e-10,3.37312e-07,3.3735e-07,5.0001e-08,0,0,0,0,0,0,0,0
27285000,0.982899,-0.00881183,-0.0114981,0.183577,-0.0798938,0.0473005,0.115736,0.05497,-0.0284512,-3.5316,-1.21699e-05,-5.87133e-05,9.65735e-07,-2.55469e-05,-0.000248258,-0.00120404,0.204241,0.0019669,0.43438,0,0,0,0,0,4.14929e-06,1.78199e-05,1.77979e-05,0.000120664,0.0163049,0.0163043,0.0100317,0.0440434,0.0440446,0.0592171,8.21573e-11,8.2155e-11,6.43773e-10,3.37315e-07,3.37351e-07,5.0001e-08,0,0,0,0,0,0,0,0
27385000,0.982858,-0.0101697,-0.0139733,0.18355,-0.083366,0.0522104,0.431605,0.0470233,-0.0232465,-3.51336,-1.21324e-05,-5.86804e-05,9.66051e-07,-2.34566e-05,-0.000250901,-0.0011991,0.204241,0.0019669,0.43438,0,0,0,0,0,4.08893e-06,1.79365e-05,1.79082e-05,0.000118868,0.0146316,0.0146308,0.00993236,0.039723,0.0397239,0.0587853,8.22214e-11,8.22195e-11,6.42634e-10,3.35786e-07,3.35817e-07,5e-08,0,0,0,0,0,0,0,0
27485000,0.982804,-0.0116112,-0.0159451,0.183598,-0.0863859,0.0577208,0.750679,0.03849,-0.0177318,-3.45574,-1.21321e-05,-5.86779e-05,9.01037e-07,-2.33099e-05,-0.000251058,-0.00119816,0.204241,0.0019669,0.43438,0,0,0,0,0,4.03106e-06,1.82488e-05,1.82156e-05,0.000117165,0.0153314,0.0153302,0.0100067,0.043612,0.0436129,0.0589474,8.23203e-11,8.23184e-11,6.41457e-10,3.35788e-07,3.35817e-07,5e-08,0,0,0,0,0,0,0,0
27585000,0.982825,-0.0116152,-0.0149571,0.183567,-0.0795653,0.0587175,0.855308,0.0314072,-0.0154845,-3.39495,-1.20764e-05,-5.8642e-05,8.86199e-07,-2.04974e-05,-0.000253853,-0.00118298,0.204241,0.0019669,0.43438,0,0,0,0,0,3.99519e-06,1.83757e-05,1.83466e-05,0.000116174,0.0139499,0.0139481,0.00999228,0.0393851,0.0393857,0.0593946,8.23906e-11,8.23892e-11,6.40564e-10,3.34618e-07,3.34641e-07,5.0002e-08,0,0,0,0,0,0,0,0
27685000,0.982893,-0.0104683,-0.0120647,0.183483,-0.0759941,0.0545478,0.762342,0.0236665,-0.00975773,-3.31682,-1.20744e-05,-5.8641e-05,9.0717e-07,-2.03458e-05,-0.000254036,-0.0011817,0.204241,0.0019669,0.43438,0,0,0,0,0,3.93877e-06,1.868e-05,1.86588e-05,0.000114641,0.0149339,0.0149321,0.0100671,0.0431814,0.0431819,0.0595609,8.24895e-11,8.2488e-11,6.39307e-10,3.34621e-07,3.34641e-07,5.0002e-08,0,0,0,0,0,0,0,0
27785000,0.982928,-0.00913445,-0.0104794,0.183466,-0.0740758,0.049951,0.749749,0.0187596,-0.00904204,-3.24302,-1.20356e-05,-5.86231e-05,9.43197e-07,-1.97483e-05,-0.000254309,-0.00118283,0.204241,0.0019669,0.43438,0,0,0,0,0,3.88925e-06,1.87913e-05,1.87721e-05,0.000113171,0.0137308,0.0137293,0.0099666,0.0390551,0.0390555,0.0591255,8.25399e-11,8.25392e-11,6.37997e-10,3.33768e-07,3.33781e-07,5.0001e-08,0,0,0,0,0,0,0,0
27885000,0.982925,-0.0087477,-0.0105573,0.183496,-0.0805873,0.0556657,0.791409,0.011038,-0.0038109,-3.16836,-1.2034e-05,-5.8622e-05,9.48066e-07,-1.96183e-05,-0.000254467,-0.00118177,0.204241,0.0019669,0.43438,0,0,0,0,0,3.84346e-06,1.9113e-05,1.90923e-05,0.000111769,0.0146046,0.0146028,0.0100413,0.0427809,0.042781,0.059291,8.26386e-11,8.2638e-11,6.36649e-10,3.33771e-07,3.33781e-07,5.0001e-08,0,0,0,0,0,0,0,0
27985000,0.982924,-0.00920327,-0.0109404,0.183459,-0.0803952,0.0560478,0.77874,0.00682248,-0.00354813,-3.09797,-1.19698e-05,-5.85851e-05,9.53314e-07,-1.7896e-05,-0.000256363,-0.00117708,0.204241,0.0019669,0.43438,0,0,0,0,0,3.7974e-06,1.92125e-05,1.91914e-05,0.000110433,0.013474,0.0134722,0.00994161,0.0387443,0.0387444,0.05886,8.26588e-11,8.26593e-11,6.35246e-10,3.33142e-07,3.33145e-07,5e-08,0,0,0,0,0,0,0,0
28085000,0.982945,-0.00953636,-0.0109465,0.183327,-0.0839011,0.0560233,0.784973,-0.00135339,0.00209105,-3.02022,-1.19682e-05,-5.85868e-05,1.03943e-06,-1.79106e-05,-0.000256372,-0.00117696,0.204241,0.0019669,0.43438,0,0,0,0,0,3.75359e-06,1.95408e-05,1.95201e-05,0.000109166,0.014374,0.0143723,0.0100156,0.0424058,0.0424057,0.0590246,8.27575e-11,8.2758e-11,6.33805e-10,3.33145e-07,3.33144e-07,5e-08,0,0,0,0,0,0,0,0
28185000,0.982948,-0.00903554,-0.0112464,0.183317,-0.0832708,0.0511408,0.790807,-0.00704884,0.00131445,-2.946,-1.18976e-05,-5.85561e-05,1.04254e-06,-1.62359e-05,-0.000258545,-0.00117443,0.204241,0.0019669,0.43438,0,0,0,0,0,3.71265e-06,1.96175e-05,1.95947e-05,0.000107957,0.0132918,0.0132905,0.00991604,0.0384538,0.0384536,0.0585979,8.27321e-11,8.27337e-11,6.32309e-10,3.32648e-07,3.32638e-07,5e-08,0,0,0,0,0,0,0,0
28285000,0.982968,-0.00852369,-0.011538,0.183219,-0.0883206,0.0536467,0.791373,-0.0155852,0.00660052,-2.86935,-1.18952e-05,-5.85565e-05,1.10707e-06,-1.6145e-05,-0.000258676,-0.00117352,0.204241,0.0019669,0.43438,0,0,0,0,0,3.69114e-06,1.99537e-05,1.99287e-05,0.000107337,0.0141984,0.014197,0.0100747,0.0420598,0.0420594,0.0596376,8.2831e-11,8.28328e-11,6.31185e-10,3.32653e-07,3.3264e-07,5.0002e-08,0,0,0,0,0,0,0,0
28385000,0.982956,-0.00856215,-0.0121714,0.183238,-0.0881812,0.0554364,0.79238,-0.0194335,0.00863466,-2.79655,-1.18197e-05,-5.84967e-05,1.18376e-06,-1.35962e-05,-0.000261594,-0.00117084,0.204241,0.0019669,0.43438,0,0,0,0,0,3.65835e-06,2.00048e-05,1.99777e-05,0.000106225,0.0131753,0.0131741,0.00997399,0.0381863,0.0381859,0.0592025,8.2747e-11,8.275e-11,6.29605e-10,3.32205e-07,3.32184e-07,5.0001e-08,0,0,0,0,0,0,0,0
28485000,0.982953,-0.00888574,-0.0126731,0.183205,-0.0894677,0.057758,0.793499,-0.0282848,0.0142706,-2.7219,-1.18174e-05,-5.8495e-05,1.18553e-06,-1.33989e-05,-0.000261844,-0.00116921,0.204241,0.0019669,0.43438,0,0,0,0,0,3.62207e-06,2.03474e-05,2.0319e-05,0.000105174,0.0140873,0.0140859,0.0100482,0.0417466,0.041746,0.0593699,8.28456e-11,8.28487e-11,6.27987e-10,3.32209e-07,3.32184e-07,5.0001e-08,0,0,0,0,0,0,0,0
28585000,0.982987,-0.00898251,-0.0126536,0.183019,-0.0826345,0.0523702,0.790836,-0.0308891,0.0112113,-2.64635,-1.17004e-05,-5.84466e-05,1.24598e-06,-1.12912e-05,-0.000265794,-0.0011675,0.204241,0.0019669,0.43438,0,0,0,0,0,3.58366e-06,2.03662e-05,2.0338e-05,0.000104176,0.0131143,0.0131131,0.00994752,0.0379449,0.0379443,0.058939,8.26894e-11,8.2694e-11,6.26312e-10,3.3174e-07,3.31706e-07,5.0001e-08,0,0,0,0,0,0,0,0
28685000,0.982983,-0.00878077,-0.0120444,0.18309,-0.0823097,0.0522731,0.791671,-0.0391251,0.0164706,-2.57129,-1.16984e-05,-5.84448e-05,1.23772e-06,-1.11103e-05,-0.000266025,-0.00116602,0.204241,0.0019669,0.43438,0,0,0,0,0,3.55385e-06,2.07113e-05,2.06845e-05,0.000103224,0.0140368,0.0140356,0.0100202,0.0414688,0.041468,0.0590998,8.2788e-11,8.27926e-11,6.24597e-10,3.31743e-07,3.31705e-07,5e-08,0,0,0,0,0,0,0,0
28785000,0.983004,-0.00816145,-0.0118646,0.183021,-0.0777518,0.0513937,0.790257,-0.0410242,0.0176993,-2.49908,-1.16101e-05,-5.83665e-05,1.3243e-06,-7.64126e-06,-0.000269644,-0.00116248,0.204241,0.0019669,0.43438,0,0,0,0,0,3.52387e-06,2.06951e-05,2.06679e-05,0.000102317,0.0130984,0.0130974,0.00992009,0.0377314,0.0377308,0.0586729,8.25463e-11,8.25525e-11,6.22828e-10,3.31189e-07,3.31142e-07,5e-08,0,0,0,0,0,0,0,0
28885000,0.983031,-0.00798417,-0.011604,0.182899,-0.0816041,0.052234,0.78956,-0.0489657,0.0228721,-2.42295,-1.16077e-05,-5.83667e-05,1.38235e-06,-7.53542e-06,-0.000269796,-0.00116146,0.204241,0.0019669,0.43438,0,0,0,0,0,3.50873e-06,2.10462e-05,2.10193e-05,0.000101935,0.0140362,0.0140353,0.0100785,0.0412281,0.0412272,0.0597164,8.26452e-11,8.26514e-11,6.21501e-10,3.31194e-07,3.31144e-07,5.0002e-08,0,0,0,0,0,0,0,0
28985000,0.983018,-0.00777781,-0.0118401,0.182961,-0.0770193,0.0481341,0.788678,-0.047912,0.0216162,-2.35176,-1.14827e-05,-5.82817e-05,1.41663e-06,-4.05766e-06,-0.000274853,-0.00115771,0.204241,0.0019669,0.43438,0,0,0,0,0,3.48467e-06,2.09925e-05,2.09648e-05,0.000101101,0.0131256,0.0131251,0.00997706,0.0375476,0.0375469,0.0592807,8.23057e-11,8.23143e-11,6.19647e-10,3.30501e-07,3.30442e-07,5.0002e-08,0,0,0,0,0,0,0,0
29085000,0.983019,-0.00766575,-0.0118843,0.182958,-0.0797999,0.0494145,0.788383,-0.055815,0.0264658,-2.27487,-1.14813e-05,-5.82813e-05,1.43526e-06,-3.97365e-06,-0.000274966,-0.00115702,0.204241,0.0019669,0.43438,0,0,0,0,0,3.4589e-06,2.13483e-05,2.13203e-05,0.000100313,0.0140787,0.0140783,0.0100501,0.0410255,0.0410246,0.059444,8.24038e-11,8.24133e-11,6.17753e-10,3.30505e-07,3.30441e-07,5.0001e-08,0,0,0,0,0,0,0,0
29185000,0.983046,-0.00763213,-0.0121245,0.1828,-0.075254,0.046774,0.782604,-0.0531088,0.0255297,-2.2064,-1.13503e-05,-5.81687e-05,1.5306e-06,8.4374e-07,-0.000280442,-0.0011522,0.204241,0.0019669,0.43438,0,0,0,0,0,3.43127e-06,2.12528e-05,2.12246e-05,9.95646e-05,0.0131937,0.0131937,0.00994924,0.0373944,0.0373937,0.0590125,8.19566e-11,8.19687e-11,6.15806e-10,3.29629e-07,3.29557e-07,5.0001e-08,0,0,0,0,0,0,0,0
29285000,0.98303,-0.00787892,-0.0121609,0.182874,-0.0767137,0.0517461,0.785006,-0.0606688,0.0304991,-2.12948,-1.13484e-05,-5.8169e-05,1.58223e-06,9.09802e-07,-0.000280537,-0.00115169,0.204241,0.0019669,0.43438,0,0,0,0,0,3.41209e-06,2.16117e-05,2.15838e-05,9.88472e-05,0.0141614,0.0141613,0.0100219,0.0408622,0.0408613,0.0591744,8.20547e-11,8.20677e-11,6.13818e-10,3.29633e-07,3.29556e-07,5e-08,0,0,0,0,0,0,0,0
29385000,0.983039,-0.00834137,-0.0116757,0.182833,-0.0720082,0.049996,0.787211,-0.0585919,0.0313222,-2.05435,-1.12347e-05,-5.80731e-05,1.65452e-06,4.80468e-06,-0.000285254,-0.00114988,0.204241,0.0019669,0.43438,0,0,0,0,0,3.3901e-06,2.14699e-05,2.14448e-05,9.81681e-05,0.0132833,0.0132835,0.00992158,0.0372721,0.0372715,0.0587469,8.14915e-11,8.15068e-11,6.11777e-10,3.2854e-07,3.28456e-07,5e-08,0,0,0,0,0,0,0,0
29485000,0.983051,-0.00839229,-0.0115424,0.182774,-0.0740846,0.049845,0.788475,-0.0658521,0.0363375,-1.97761,-1.12314e-05,-5.80754e-05,1.78812e-06,4.84682e-06,-0.000285348,-0.00114915,0.204241,0.0019669,0.43438,0,0,0,0,0,3.37075e-06,2.18311e-05,2.18063e-05,9.75224e-05,0.0142698,0.0142702,0.0099937,0.0407369,0.0407361,0.0589075,8.159e-11,8.16052e-11,6.09697e-10,3.28545e-07,3.28456e-07,5e-08,0,0,0,0,0,0,0,0
29585000,0.983068,-0.00831821,-0.0115551,0.182688,-0.0692272,0.0471338,0.790295,-0.062973,0.0355556,-1.89955,-1.1097e-05,-5.79794e-05,1.87904e-06,8.72132e-06,-0.000290815,-0.00114895,0.204241,0.0019669,0.43438,0,0,0,0,0,3.36485e-06,2.16447e-05,2.162e-05,9.73432e-05,0.0134004,0.013401,0.00997739,0.0371803,0.0371797,0.0593518,8.09052e-11,8.09223e-11,6.08123e-10,3.27213e-07,3.27119e-07,5.0002e-08,0,0,0,0,0,0,0,0
29685000,0.983093,-0.00838674,-0.0113491,0.182564,-0.073354,0.0452746,0.786084,-0.0700749,0.0402122,-1.82475,-1.1093e-05,-5.79807e-05,1.99599e-06,8.84523e-06,-0.000291016,-0.00114752,0.204241,0.0019669,0.43438,0,0,0,0,0,3.34431e-06,2.20074e-05,2.19832e-05,9.67578e-05,0.0144118,0.0144129,0.0100502,0.0406492,0.0406486,0.0595159,8.10037e-11,8.10206e-11,6.05962e-10,3.27217e-07,3.27119e-07,5.0001e-08,0,0,0,0,0,0,0,0
29785000,0.983101,-0.00825849,-0.0118834,0.182492,-0.0687648,0.037401,0.782412,-0.0650965,0.0377426,-1.75259,-1.09556e-05,-5.78612e-05,2.1297e-06,1.39271e-05,-0.000296653,-0.00114453,0.204241,0.0019669,0.43438,0,0,0,0,0,3.32723e-06,2.17738e-05,2.17482e-05,9.61968e-05,0.0135462,0.0135477,0.00994912,0.0371186,0.0371181,0.0590838,8.01914e-11,8.021e-11,6.03748e-10,3.25625e-07,3.25521e-07,5.0001e-08,0,0,0,0,0,0,0,0
29885000,0.983106,-0.00776056,-0.0122752,0.182462,-0.0687259,0.0370148,0.778739,-0.0718681,0.0414244,-1.68056,-1.09503e-05,-5.78612e-05,2.24018e-06,1.41703e-05,-0.000296996,-0.00114241,0.204241,0.0019669,0.43438,0,0,0,0,0,3.31195e-06,2.21388e-05,2.21111e-05,9.56647e-05,0.0145756,0.0145774,0.0100215,0.0405983,0.040598,0.0592464,8.02895e-11,8.03089e-11,6.01496e-10,3.2563e-07,3.25521e-07,5.0001e-08,0,0,0,0,0,0,0,0
29985000,0.983103,-0.00788696,-0.012351,0.182466,-0.0632587,0.0320737,0.775707,-0.0672122,0.0372114,-1.61094,-1.07888e-05,-5.77622e-05,2.28938e-06,1.84138e-05,-0.000303944,-0.00113845,0.204241,0.0019669,0.43438,0,0,0,0,0,3.2967e-06,2.18546e-05,2.18276e-05,9.51588e-05,0.0137019,0.0137038,0.00992013,0.0370856,0.0370855,0.058813,7.93477e-11,7.93697e-11,5.9919e-10,3.23771e-07,3.23657e-07,5e-08,0,0,0,0,0,0,0,0
30085000,0.983103,-0.00804522,-0.0124954,0.182448,-0.0630623,0.0317828,0.773728,-0.0735247,0.0404305,-1.53708,-1.07892e-05,-5.77593e-05,2.19848e-06,1.8543e-05,-0.000304102,-0.00113713,0.204241,0.0019669,0.43438,0,0,0,0,0,3.27752e-06,2.22185e-05,2.21914e-05,9.46845e-05,0.0147487,0.014751,0.00999215,0.0405812,0.0405812,0.0589742,7.94458e-11,7.94685e-11,5.96849e-10,3.23776e-07,3.23658e-07,5e-08,0,0,0,0,0,0,0,0
30185000,0.98308,-0.00803445,-0.0125153,0.182571,-0.0565065,0.0282705,0.773639,-0.0668405,0.0391634,-1.46519,-1.07043e-05,-5.76211e-05,2.12766e-06,2.43028e-05,-0.000307657,-0.0011346,0.204241,0.0019669,0.43438,0,0,0,0,0,3.27871e-06,2.18855e-05,2.18591e-05,9.46391e-05,0.013861,0.0138634,0.00997593,0.0370791,0.0370792,0.05942,7.83774e-11,7.84022e-11,5.95082e-10,3.21655e-07,3.21534e-07,5.0002e-08,0,0,0,0,0,0,0,0
30285000,0.983069,-0.00807132,-0.0125183,0.18263,-0.0554512,0.0272422,0.773885,-0.072383,0.0419541,-1.39287,-1.07012e-05,-5.76202e-05,2.1674e-06,2.44914e-05,-0.000307916,-0.0011328,0.204241,0.0019669,0.43438,0,0,0,0,0,3.26753e-06,2.22481e-05,2.22218e-05,9.42027e-05,0.0149216,0.0149244,0.0100486,0.0405946,0.040595,0.0595846,7.84754e-11,7.8501e-11,5.92664e-10,3.2166e-07,3.21535e-07,5.0002e-08,0,0,0,0,0,0,0,0
30385000,0.98306,-0.00806098,-0.0124533,0.182684,-0.0474537,0.0214886,0.77148,-0.0641301,0.039535,-1.32491,-1.05835e-05,-5.74617e-05,2.34281e-06,3.15525e-05,-0.000312947,-0.00112854,0.204241,0.0019669,0.43438,0,0,0,0,0,3.26041e-06,2.18676e-05,2.18424e-05,9.37847e-05,0.0140199,0.0140227,0.00994666,0.0370961,0.0370966,0.0591466,7.72847e-11,7.73125e-11,5.90195e-10,3.19291e-07,3.19162e-07,5.0001e-08,0,0,0,0,0,0,0,0
30485000,0.983089,-0.00808392,-0.0125954,0.182516,-0.0498491,0.020529,0.77245,-0.0689497,0.0416825,-1.25313,-1.05785e-05,-5.74624e-05,2.4645e-06,3.17552e-05,-0.000313239,-0.00112659,0.204241,0.0019669,0.43438,0,0,0,0,0,3.24492e-06,2.22286e-05,2.22031e-05,9.33977e-05,0.0150955,0.0150988,0.0100192,0.0406348,0.0406355,0.0593098,7.73828e-11,7.74113e-11,5.87692e-10,3.19296e-07,3.19164e-07,5.0001e-08,0,0,0,0,0,0,0,0
30585000,0.983106,-0.00839633,-0.0128909,0.182392,-0.0446043,0.0178099,0.772087,-0.0618373,0.0385534,-1.1814,-1.0464e-05,-5.73324e-05,2.60708e-06,3.74881e-05,-0.000318079,-0.00112397,0.204241,0.0019669,0.43438,0,0,0,0,0,3.23213e-06,2.18039e-05,2.17789e-05,9.30277e-05,0.0141741,0.0141772,0.00991807,0.0371336,0.0371343,0.058876,7.6077e-11,7.61073e-11,5.8514e-10,3.16696e-07,3.16562e-07,5e-08,0,0,0,0,0,0,0,0
30685000,0.983124,-0.00877634,-0.0131297,0.182258,-0.0426827,0.0153288,0.770983,-0.0662609,0.0402526,-1.11033,-1.04607e-05,-5.73315e-05,2.65054e-06,3.77032e-05,-0.000318369,-0.00112179,0.204241,0.0019669,0.43438,0,0,0,0,0,3.21716e-06,2.21622e-05,2.21373e-05,9.26808e-05,0.0152671,0.0152707,0.00999012,0.0406977,0.0406988,0.0590379,7.61751e-11,7.62061e-11,5.82555e-10,3.16702e-07,3.16564e-07,5e-08,0,0,0,0,0,0,0,0
30785000,0.983152,-0.00848439,-0.0128537,0.182139,-0.0350602,0.0102288,0.769542,-0.0591437,0.0399945,-1.04039,-1.04502e-05,-5.72023e-05,2.67341e-06,4.33229e-05,-0.00031875,-0.00111851,0.204241,0.0019669,0.43438,0,0,0,0,0,3.20206e-06,2.16939e-05,2.16702e-05,9.23544e-05,0.0143249,0.0143283,0.0098895,0.0371884,0.0371894,0.0586083,7.47632e-11,7.47956e-11,5.79923e-10,3.13895e-07,3.13757e-07,5e-08,0,0,0,0,0,0,0,0
30885000,0.983144,-0.00785584,-0.012718,0.182221,-0.0345264,0.0059004,0.767197,-0.0625498,0.0408533,-0.968073,-1.0449e-05,-5.72008e-05,2.65522e-06,4.34705e-05,-0.000318939,-0.00111693,0.204241,0.0019669,0.43438,0,0,0,0,0,3.20732e-06,2.20482e-05,2.20236e-05,9.24317e-05,0.0154336,0.0154375,0.010046,0.0407797,0.0407813,0.0596451,7.48618e-11,7.48946e-11,5.77951e-10,3.13902e-07,3.13762e-07,5.0002e-08,0,0,0,0,0,0,0,0
30985000,0.983145,-0.00802524,-0.0126778,0.182212,-0.0270492,0.00113125,0.768658,-0.0526991,0.0350265,-0.898982,-1.033e-05,-5.70697e-05,2.68004e-06,4.91713e-05,-0.000324096,-0.00111372,0.204241,0.0019669,0.43438,0,0,0,0,0,3.1975e-06,2.15412e-05,2.15179e-05,9.21323e-05,0.0144631,0.0144668,0.00994435,0.0372574,0.0372587,0.059207,7.33541e-11,7.33879e-11,5.75249e-10,3.10915e-07,3.10775e-07,5.0001e-08,0,0,0,0,0,0,0,0
31085000,0.983107,-0.00817448,-0.0127877,0.182402,-0.0251413,-0.001926,0.767649,-0.0552617,0.0349207,-0.824911,-1.03297e-05,-5.70685e-05,2.65195e-06,4.9258e-05,-0.000324201,-0.00111275,0.204241,0.0019669,0.43438,0,0,0,0,0,3.19405e-06,2.18914e-05,2.18681e-05,9.18436e-05,0.0155816,0.0155857,0.0100169,0.0408762,0.0408781,0.0593709,7.34523e-11,7.34866e-11,5.72517e-10,3.10922e-07,3.10779e-07,5.0001e-08,0,0,0,0,0,0,0,0
31185000,0.983121,-0.0083109,-0.0129389,0.182307,-0.0206282,-0.00522775,0.769143,-0.0470488,0.0313564,-0.755062,-1.02821e-05,-5.69603e-05,2.83642e-06,5.41195e-05,-0.000326138,-0.00111015,0.204241,0.0019669,0.43438,0,0,0,0,0,3.18641e-06,2.13503e-05,2.13276e-05,9.15744e-05,0.0145875,0.0145912,0.00991598,0.0373369,0.0373385,0.0589371,7.18622e-11,7.18973e-11,5.6974e-10,3.07791e-07,3.07649e-07,5.0001e-08,0,0,0,0,0,0,0,0
31285000,0.98314,-0.00857917,-0.0130199,0.182188,-0.0173758,-0.00873823,0.773041,-0.0489022,0.0307003,-0.683433,-1.02779e-05,-5.69612e-05,2.94799e-06,5.42947e-05,-0.000326382,-0.0011082,0.204241,0.0019669,0.43438,0,0,0,0,0,3.17675e-06,2.16955e-05,2.16731e-05,9.13224e-05,0.0157059,0.0157101,0.00998727,0.0409825,0.0409847,0.0590942,7.19604e-11,7.19959e-11,5.66931e-10,3.07797e-07,3.07653e-07,5e-08,0,0,0,0,0,0,0,0
31385000,0.983153,-0.00835699,-0.0128284,0.182144,-0.0115176,-0.0143558,0.77237,-0.0405074,0.026691,-0.610581,-1.0247e-05,-5.68746e-05,2.89666e-06,5.79772e-05,-0.000327755,-0.0011057,0.204241,0.0019669,0.43438,0,0,0,0,0,3.1656e-06,2.11244e-05,2.11028e-05,9.10876e-05,0.014692,0.0146958,0.00988704,0.0374231,0.037425,0.0586647,7.03032e-11,7.0339e-11,5.64082e-10,3.04561e-07,3.04419e-07,5e-08,0,0,0,0,0,0,0,0
31485000,0.983136,-0.00810704,-0.0131398,0.182222,-0.0111881,-0.0188785,0.769209,-0.0416907,0.0249892,-0.535437,-1.02465e-05,-5.68741e-05,2.89436e-06,5.80331e-05,-0.000327824,-0.00110503,0.204241,0.0019669,0.43438,0,0,0,0,0,3.17406e-06,2.14648e-05,2.14419e-05,9.12409e-05,0.0158298,0.015834,0.010044,0.0410952,0.0410977,0.059704,7.04019e-11,7.0438e-11,5.61952e-10,3.04568e-07,3.04425e-07,5.0002e-08,0,0,0,0,0,0,0,0
31585000,0.983161,-0.0079162,-0.0136173,0.182062,-0.00682425,-0.0195261,0.772822,-0.0311573,0.0225195,-0.464013,-1.02442e-05,-5.67387e-05,3.02175e-06,6.40091e-05,-0.000327894,-0.00110231,0.204241,0.0019669,0.43438,0,0,0,0,0,3.1644e-06,2.08694e-05,2.08455e-05,9.10282e-05,0.0147842,0.0147878,0.00994271,0.0375136,0.0375156,0.059266,6.8689e-11,6.87249e-11,5.59042e-10,3.01252e-07,3.01111e-07,5.0002e-08,0,0,0,0,0,0,0,0
31685000,0.983186,-0.00791582,-0.0140926,0.181889,-0.00843944,-0.0218787,0.769143,-0.0319343,0.0203735,-0.394517,-1.02389e-05,-5.674e-05,3.16966e-06,6.42345e-05,-0.0003282,-0.00109956,0.204241,0.0019669,0.43438,0,0,0,0,0,3.15557e-06,2.12041e-05,2.11788e-05,9.08267e-05,0.0159246,0.0159286,0.0100147,0.04121,0.0412128,0.0594254,6.87873e-11,6.88235e-11,5.56102e-10,3.01259e-07,3.01117e-07,5.0001e-08,0,0,0,0,0,0,0,0
31785000,0.9832,-0.00808007,-0.0147615,0.181757,0.000418667,-0.023228,0.768992,-0.0208952,0.0208396,-0.323074,-1.03106e-05,-5.65768e-05,3.29856e-06,7.14e-05,-0.000325132,-0.00109701,0.204241,0.0019669,0.43438,0,0,0,0,0,3.14777e-06,2.05889e-05,2.05628e-05,9.06355e-05,0.0148621,0.0148656,0.00991411,0.0376051,0.0376074,0.0589919,6.70346e-11,6.70704e-11,5.53127e-10,2.97902e-07,2.97763e-07,5.0001e-08,0,0,0,0,0,0,0,0
31885000,0.98321,-0.00785506,-0.0145635,0.181728,0.00453225,-0.0267658,0.767714,-0.0206183,0.0182757,-0.253823,-1.03068e-05,-5.65771e-05,3.38908e-06,7.16137e-05,-0.000325402,-0.00109431,0.204241,0.0019669,0.43438,0,0,0,0,0,3.14273e-06,2.09154e-05,2.08896e-05,9.04549e-05,0.0160017,0.0160056,0.00998572,0.0413247,0.0413276,0.05915,6.71329e-11,6.71691e-11,5.50123e-10,2.97909e-07,2.97769e-07,5e-08,0,0,0,0,0,0,0,0
31985000,0.983201,-0.00803523,-0.0141422,0.181798,0.0123106,-0.0259118,0.764372,-0.00931705,0.0174405,-0.187431,-1.03615e-05,-5.64457e-05,3.36282e-06,7.73671e-05,-0.000323324,-0.00108993,0.204241,0.0019669,0.43438,0,0,0,0,0,3.13818e-06,2.0282e-05,2.02587e-05,9.02843e-05,0.0149199,0.0149234,0.00988587,0.0376956,0.037698,0.0587209,6.53538e-11,6.53892e-11,5.47087e-10,2.94542e-07,2.94406e-07,5e-08,0,0,0,0,0,0,0,0
32085000,0.983219,-0.00841754,-0.0137727,0.181716,0.0128301,-0.0305126,0.766756,-0.00803751,0.0146813,-0.116528,-1.03598e-05,-5.64452e-05,3.38782e-06,7.75211e-05,-0.000323504,-0.0010879,0.204241,0.0019669,0.43438,0,0,0,0,0,3.13047e-06,2.06012e-05,2.05799e-05,9.01265e-05,0.0160555,0.0160592,0.00995731,0.0414356,0.0414387,0.0588778,6.54521e-11,6.54879e-11,5.44023e-10,2.94549e-07,2.94413e-07,5e-08,0,0,0,0,0,0,0,0
32185000,0.983211,-0.00857977,-0.0140497,0.181731,0.0171378,-0.031689,0.766797,0.00230265,0.0158187,-0.0473825,-1.04817e-05,-5.63305e-05,3.38299e-06,8.25398e-05,-0.00031857,-0.00108429,0.204241,0.0019669,0.43438,0,0,0,0,0,3.13852e-06,1.99592e-05,1.99382e-05,9.03481e-05,0.0149509,0.014954,0.00994136,0.0377822,0.0377847,0.0593199,6.3661e-11,6.36956e-11,5.41727e-10,2.91204e-07,2.91072e-07,5.0002e-08,0,0,0,0,0,0,0,0
32285000,0.983227,-0.00850308,-0.0143064,0.181626,0.0193081,-0.0361914,0.765312,0.00414237,0.0123896,0.0216534,-1.04781e-05,-5.6331e-05,3.47752e-06,8.27412e-05,-0.000318811,-0.00108156,0.204241,0.0019669,0.43438,0,0,0,0,0,3.13245e-06,2.02732e-05,2.02512e-05,9.02052e-05,0.0160901,0.0160935,0.0100136,0.0415394,0.0415426,0.0594804,6.37593e-11,6.37943e-11,5.38612e-10,2.91211e-07,2.91079e-07,5.0001e-08,0,0,0,0,0,0,0,0
32385000,0.983209,-0.00851057,-0.0144189,0.181714,0.0255728,-0.0352413,0.763975,0.0144705,0.0123321,0.0944001,-1.05786e-05,-5.62429e-05,3.4543e-06,8.65647e-05,-0.000314767,-0.00107893,0.204241,0.0019669,0.43438,0,0,0,0,0,3.13005e-06,1.96248e-05,1.96033e-05,9.00672e-05,0.0149719,0.0149748,0.00991338,0.037863,0.0378656,0.0590474,6.19677e-11,6.20013e-11,5.3547e-10,2.87913e-07,2.87786e-07,5.0001e-08,0,0,0,0,0,0,0,0
32485000,0.983225,-0.0114152,-0.0123544,0.181619,0.0528188,-0.102795,-0.108627,0.0188618,0.00363739,0.102934,-1.05787e-05,-5.62411e-05,3.40938e-06,8.6594e-05,-0.000314792,-0.00107851,0.204241,0.0019669,0.43438,0,0,0,0,0,3.12123e-06,1.99257e-05,1.99163e-05,8.99448e-05,0.0179005,0.0179025,0.00978728,0.0417272,0.0417304,0.0591979,6.20664e-11,6.20995e-11,5.32303e-10,0,0,0,0,0,0,0,0,0,0,0
32585000,0.983237,-0.0113268,-0.0123064,0.181563,0.0518041,-0.101385,-0.110019,0.0297178,0.00307106,0.0850367,-1.08487e-05,-5.61571e-05,3.53597e-06,8.6594e-05,-0.000314792,-0.00107851,0.204241,0.0019669,0.43438,0,0,0,0,0,3.11747e-06,1.91248e-05,1.91155e-05,8.98219e-05,0.0170847,0.0170867,0.00941992,0.0380571,0.0380597,0.0587286,6.00353e-11,6.00638e-11,5.29106e-10,0,0,0,0,0,0,0,0,0,0,0
32685000,0.983242,-0.0113153,-0.0121731,0.181547,0.0486592,-0.108072,-0.111818,0.0347891,-0.00740841,0.0702748,-1.08483e-05,-5.61565e-05,3.53231e-06,8.6594e-05,-0.000314792,-0.00107851,0.204241,0.0019669,0.43438,0,0,0,0,0,3.11286e-06,1.94217e-05,1.94122e-05,8.9709e-05,0.0189467,0.0189496,0.00922381,0.0420603,0.0420637,0.0588025,6.01341e-11,6.0162e-11,5.25891e-10,0,0,0,0,0,0,0,0,0,0,0
32785000,0.983246,-0.0110909,-0.0122405,0.181536,0.045928,-0.103372,-0.112439,0.0431784,-0.0060933,0.0553965,-1.11609e-05,-5.60739e-05,3.65087e-06,8.6594e-05,-0.000314792,-0.00107851,0.204241,0.0019669,0.43438,0,0,0,0,0,3.12362e-06,1.85024e-05,1.84924e-05,8.99692e-05,0.0180226,0.0180256,0.00896819,0.0383261,0.0383288,0.059161,5.79818e-11,5.80048e-11,5.23486e-10,0,0,0,0,0,0,0,0,0,0,0
32885000,0.983266,-0.0110659,-0.0123052,0.181425,0.0467131,-0.111134,-0.113759,0.0478627,-0.0168393,0.0417332,-1.11596e-05,-5.6075e-05,3.71043e-06,8.6594e-05,-0.000314792,-0.00107851,0.204241,0.0019669,0.43438,0,0,0,0,0,3.11768e-06,1.87891e-05,1.87785e-05,8.98693e-05,0.0199774,0.0199815,0.00878846,0.042437,0.0424405,0.0591668,5.80806e-11,5.8103e-11,5.2023e-10,2.87917e-07,2.8779e-07,5.0003e-08,0,0,0,0,0,0,0,0
32985000,0.983278,-0.0108957,-0.0122563,0.181372,0.04318,-0.106527,-0.112749,0.0542468,-0.017267,0.0291095,-1.14404e-05,-5.60235e-05,3.85832e-06,8.66154e-05,-0.000315303,-0.00107855,0.204241,0.0019669,0.43438,0,0,0,0,0,3.11512e-06,1.77668e-05,1.7756e-05,8.97698e-05,0.0189539,0.018958,0.00849325,0.0386251,0.0386279,0.0586129,5.58511e-11,5.58683e-11,5.16949e-10,2.87923e-07,2.87795e-07,5.00129e-08,0,0,0,0,0,0,0,0
33085000,0.983281,-0.0108638,-0.0122757,0.181355,0.0403805,-0.111603,-0.110522,0.0584544,-0.0281332,0.0205835,-1.14406e-05,-5.60238e-05,3.8588e-06,8.66148e-05,-0.000315302,-0.00107855,0.204241,0.0019669,0.43438,0,0,0,0,0,3.11134e-06,1.80416e-05,1.80304e-05,8.96789e-05,0.021066,0.0210714,0.00834809,0.042845,0.0428488,0.0585598,5.59499e-11,5.59666e-11,5.13653e-10,2.87933e-07,2.87805e-07,5.00229e-08,0,0,0,0,0,0,0,0
33185000,0.98329,-0.0106579,-0.0121837,0.181325,0.0356167,-0.107442,-0.108933,0.0631492,-0.0275099,0.0144552,-1.1721e-05,-5.597e-05,3.82844e-06,8.65839e-05,-0.000318029,-0.0010788,0.204241,0.0019669,0.43438,0,0,0,0,0,3.10583e-06,1.69405e-05,1.6929e-05,8.95929e-05,0.0199604,0.0199654,0.00810197,0.0389448,0.0389477,0.0579862,5.36941e-11,5.37059e-11,5.10333e-10,2.87771e-07,2.87644e-07,5.00304e-08,0,0,0,0,0,0,0,0
33285000,0.983313,-0.0107306,-0.012196,0.181194,0.0334693,-0.110788,-0.108762,0.0665402,-0.0384273,0.00594749,-1.1718e-05,-5.59738e-05,3.98977e-06,8.65815e-05,-0.000318026,-0.00107881,0.204241,0.0019669,0.43438,0,0,0,0,0,3.10209e-06,1.72027e-05,1.71911e-05,8.95115e-05,0.022213,0.0222194,0.00799267,0.0432768,0.0432807,0.0578862,5.37929e-11,5.38042e-11,5.07001e-10,2.87781e-07,2.87654e-07,5.00403e-08,0,0,0,0,0,0,0,0
33385000,0.983328,-0.010485,-0.0122385,0.181126,0.0280479,-0.099495,-0.106415,0.0682241,-0.0314859,-0.00247595,-1.2094e-05,-5.58967e-05,4.05926e-06,8.65815e-05,-0.000318026,-0.0010791,0.204241,0.0019669,0.43438,0,0,0,0,0,3.0978e-06,1.60521e-05,1.604e-05,8.94331e-05,0.0207421,0.0207482,0.00779095,0.0392783,0.0392813,0.0573029,5.1563e-11,5.15697e-11,5.03647e-10,0,0,5.00418e-08,0,0,0,0,0,0,0,0
33485000,0.983332,-0.0104714,-0.0121957,0.181109,0.0241899,-0.103161,-0.106343,0.0707925,-0.041588,-0.0132182,-1.20937e-05,-5.58971e-05,4.07735e-06,8.65815e-05,-0.000318026,-0.0010791,0.204241,0.0019669,0.43438,0,0,0,0,0,3.10764e-06,1.63014e-05,1.62892e-05,8.9728e-05,0.0227946,0.0228019,0.00777878,0.0437151,0.0437192,0.057997,5.1662e-11,5.16686e-11,5.01148e-10,0,0,5.00515e-08,0,0,0,0,0,0,0,0
33585000,0.98336,-0.0101936,-0.0121512,0.180975,0.0195428,-0.0959523,-0.102601,0.071783,-0.0358574,-0.0190369,-1.2398e-05,-5.5832e-05,4.2218e-06,8.65815e-05,-0.000318026,-0.00107974,0.204241,0.0019669,0.43438,0,0,0,0,0,3.10293e-06,1.51288e-05,1.51163e-05,8.96573e-05,0.0211351,0.0211416,0.00761453,0.0396112,0.0396144,0.0573959,4.95011e-11,4.95034e-11,4.97767e-10,0,0,5.00437e-08,0,0,0,0,0,0,0,0
33685000,0.983369,-0.0101881,-0.0121428,0.180925,0.0157785,-0.0996772,-0.104209,0.0735864,-0.0456789,-0.0275244,-1.23971e-05,-5.58332e-05,4.27311e-06,8.65815e-05,-0.000318026,-0.00107977,0.204241,0.0019669,0.43438,0,0,0,0,0,3.09984e-06,1.53653e-05,1.53526e-05,8.95899e-05,0.0231765,0.0231843,0.00757007,0.044136,0.0441404,0.0572334,4.95997e-11,4.96019e-11,4.94377e-10,0,0,5.00524e-08,0,0,0,0,0,0,0,0
33785000,0.983382,-0.00998351,-0.0121287,0.18087,0.0106958,-0.0919465,-0.0984413,0.0757249,-0.0390438,-0.0335136,-1.2684e-05,-5.57354e-05,4.24986e-06,8.65815e-05,-0.000318026,-0.0010805,0.204241,0.0019669,0.43438,0,0,0,0,0,3.09434e-06,1.41961e-05,1.41833e-05,8.95262e-05,0.0213673,0.0213741,0.00744202,0.0399267,0.03993,0.05664,4.75413e-11,4.75397e-11,4.9097e-10,0,0,5.00318e-08,0,0,0,0,0,0,0,0
33885000,0.983398,-0.0100227,-0.0120886,0.180784,0.0073539,-0.0927636,-0.0980454,0.0765721,-0.0483249,-0.04079,-1.26816e-05,-5.57381e-05,4.37129e-06,8.65815e-05,-0.000318026,-0.00108058,0.204241,0.0019669,0.43438,0,0,0,0,0,3.09173e-06,1.442e-05,1.44072e-05,8.94633e-05,0.0233712,0.0233793,0.00742673,0.0445217,0.0445261,0.0564606,4.76399e-11,4.76383e-11,4.87552e-10,0,0,5.00388e-08,0,0,0,0,0,0,0,0
33985000,0.983391,-0.00976427,-0.012215,0.180827,0.00436887,-0.0821334,-0.0944102,0.0775873,-0.0391037,-0.0439964,-1.29837e-05,-5.56127e-05,4.3224e-06,8.65815e-05,-0.000318026,-0.00108152,0.204241,0.0019669,0.43438,0,0,0,0,0,3.08916e-06,1.32767e-05,1.32635e-05,8.94018e-05,0.021448,0.0214551,0.00733065,0.0402126,0.040216,0.0558821,4.57087e-11,4.57038e-11,4.84123e-10,0,0,5.0005e-08,0,0,0,0,0,0,0,0
34085000,0.983396,-0.00970041,-0.0122211,0.180802,0.000946584,-0.0864354,-0.0935005,0.0778966,-0.0475635,-0.050699,-1.29836e-05,-5.56131e-05,4.32917e-06,8.65815e-05,-0.000318026,-0.00108163,0.204241,0.0019669,0.43438,0,0,0,0,0,3.09894e-06,1.34888e-05,1.34752e-05,8.97129e-05,0.0234031,0.0234112,0.00739854,0.0448594,0.0448639,0.0564913,4.58077e-11,4.58028e-11,4.81572e-10,0,0,5.00108e-08,0,0,0,0,0,0,0,0
34185000,0.983397,-0.00952656,-0.0122516,0.180804,-0.00318908,-0.0765384,-0.0911656,0.0793654,-0.0392871,-0.0524824,-1.32351e-05,-5.55008e-05,4.38262e-06,8.65815e-05,-0.000318026,-0.0010824,0.204241,0.0019669,0.43438,0,0,0,0,0,3.09736e-06,1.23879e-05,1.23742e-05,8.96541e-05,0.0213911,0.021398,0.0073285,0.04046,0.0404634,0.0559176,4.40183e-11,4.40105e-11,4.78126e-10,0,0,5.00037e-08,0,0,0,0,0,0,0,0
34285000,0.983401,-0.00941821,-0.0123144,0.180784,-0.00317593,-0.0798237,-0.0901349,0.0790765,-0.0471461,-0.0597502,-1.32338e-05,-5.55022e-05,4.44813e-06,8.65815e-05,-0.000318026,-0.0010825,0.204241,0.0019669,0.43438,0,0,0,0,0,3.09597e-06,1.25888e-05,1.25747e-05,8.95975e-05,0.0232866,0.0232945,0.00736495,0.0451399,0.0451445,0.0557375,4.41168e-11,4.41092e-11,4.74673e-10,0,0,5.0004e-08,0,0,0,0,0,0,0,0
34385000,0.983424,-0.00920375,-0.0123159,0.180667,-0.00651938,-0.0690607,-0.0851312,0.0787784,-0.0387096,-0.0629224,-1.34669e-05,-5.5408e-05,4.46594e-06,8.65815e-05,-0.000318026,-0.00108397,0.204241,0.0019669,0.43438,0,0,0,0,0,3.08973e-06,1.15431e-05,1.15288e-05,8.95465e-05,0.0212078,0.0212145,0.00731924,0.0406631,0.0406665,0.0551903,4.24759e-11,4.24659e-11,4.71213e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
34485000,0.983428,-0.00928746,-0.0122482,0.180646,-0.00942477,-0.0725596,-0.0836502,0.0779808,-0.0458588,-0.066431,-1.34654e-05,-5.54096e-05,4.53459e-06,8.65815e-05,-0.000318026,-0.00108433,0.204241,0.0019669,0.43438,0,0,0,0,0,3.08843e-06,1.17333e-05,1.17191e-05,8.94924e-05,0.0230373,0.0230449,0.00737817,0.045358,0.0453626,0.0550248,4.25744e-11,4.25646e-11,4.67748e-10,0,0,5e-08,0,0,0,0,0,0,0,0
34585000,0.983434,-0.00909251,-0.0120647,0.180637,-0.0104566,-0.0616945,0.66225,0.0778848,-0.0386066,-0.041322,-1.36507e-05,-5.53191e-05,4.52608e-06,8.65815e-05,-0.000318026,-0.00108569,0.204241,0.0019669,0.43438,0,0,0,0,0,3.08535e-06,1.07508e-05,1.0737e-05,8.9441e-05,0.0197499,0.0197557,0.00735173,0.0407868,0.0407902,0.0545078,4.10824e-11,4.10708e-11,4.64277e-10,0,0,5e-08,0,0,0,0,0,0,0,0
34685000,0.98344,-0.00907846,-0.0117801,0.180621,-0.0126764,-0.0588799,1.65291,0.0767357,-0.0446321,0.0715211,-1.3651e-05,-5.53188e-05,4.51429e-06,8.65815e-05,-0.000318026,-0.00108543,0.204241,0.0019669,0.43438,0,0,0,0,0,3.08248e-06,1.0931e-05,1.09179e-05,8.93906e-05,0.0198555,0.0198614,0.00742868,0.0452981,0.0453025,0.0543631,4.11809e-11,4.11695e-11,4.60804e-10,0,0,5e-08,0,0,0,0,0,0,0,0
34785000,0.983451,-0.00892438,-0.0115466,0.180588,-0.0135731,-0.0481166,2.61941,0.0770266,-0.0375206,0.233589,-1.37972e-05,-5.52336e-05,4.5445e-06,8.65815e-05,-0.000318026,-0.00105945,0.204241,0.0019669,0.43438,0,0,0,0,0,3.09197e-06,1.01263e-05,1.01137e-05,8.97092e-05,0.016854,0.0168585,0.00746905,0.0406905,0.0406938,0.0546143,3.99757e-11,3.9963e-11,4.5822e-10,0,0,5.0002e-08,0,0,0,0,0,0,0,0
34885000,0.983457,-0.00890904,-0.0112634,0.180574,-0.0157331,-0.045287,3.60498,0.0756091,-0.0421646,0.523439,-1.37979e-05,-5.52325e-05,4.53031e-06,8.65815e-05,-0.000318026,-0.00105721,0.204241,0.0019669,0.43438,0,0,0,0,0,3.08911e-06,1.02993e-05,1.02872e-05,8.96592e-05,0.0169623,0.0169668,0.0075637,0.0449043,0.0449085,0.0544924,4.00741e-11,4.00617e-11,4.54741e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
185000,0.978841,-0.00940342,-0.0138305,0.203939,0.000868247,-0.000432975,-0.0109878,5.51235e-05,-7.42197e-06,-0.0416697,6.93025e-11,1.77536e-08,-7.39915e-07,0,0,-2.00585e-09,0.202638,0.0100117,0.433627,0,0,0,0,0,0.000152606,0.00247499,0.00247397,0.00360127,0.253406,0.253405,0.562563,0.126411,0.126411,1.00079,1e-06,1e-06,9.99741e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
285000,0.978553,-0.00947781,-0.014151,0.205289,0.00243718,-0.00221013,-0.0263667,0.000169923,-0.000108556,-0.0412749,3.70594e-10,4.49321e-08,-1.87023e-06,0,0,-1.03405e-08,0.202638,0.0100117,0.433627,0,0,0,0,0,0.000103023,0.00252502,0.00252383,0.00242603,0.273201,0.273198,0.562506,0.132789,0.132789,0.576885,1e-06,9.99999e-07,9.97806e-07,0,0,4.00001e-06,0,0,0,0,0,0,0,0
385000,0.980078,-0.00953093,-0.014351,0.197863,0.00528301,-0.00302875,-0.0395382,0.000420773,-0.000253337,-0.0244114,-1.2655e-08,-4.95636e-07,2.04904e-05,0,0,-2.11522e-07,0.202638,0.0100117,0.433627,0,0,0,0,0,7.33058e-05,0.00262318,0.00262185,0.00172175,0.304531,0.304525,0.560114,0.0939538,0.0939537,0.375592,9.99998e-07,9.99992e-07,9.90493e-07,0,0,3.99998e-06,0,0,0,0,0,0,0,0
485000,0.980935,-0.00968888,-0.0148482,0.193528,0.00982759,-0.00667245,-0.0568121,0.00132566,-0.000773921,-0.0284138,8.40272e-07,-2.27633e-07,4.49953e-05,0,0,-1.46461e-08,0.202638,0.0100117,0.433627,0,0,0,0,0,5.86412e-05,0.00277274,0.00277138,0.00137375,0.36556,0.365583,0.55387,0.108527,0.108527,0.287379,9.9998e-07,9.9999e-07,9.75648e-07,0,0,3.99978e-06,0,0,0,0,0,0,0,0
585000,0.981446,-0.00977015,-0.0151262,0.190892,0.0122716,-0.00999272,-0.0751501,0.00195456,-0.00126521,-0.0361339,1.44985e-06,-1.14137e-07,6.58791e-05,0,0,2.76911e-07,0.202638,0.0100117,0.433627,0,0,0,0,0,5.04182e-05,0.00293483,0.00293343,0.00118328,0.411898,0.411963,0.542812,0.0893709,0.0893724,0.242024,9.99709e-07,9.99741e-07,9.52151e-07,0,0,3.99919e-06,0,0,0,0,0,0,0,0
685000,0.98176,-0.00984672,-0.0155383,0.189235,0.0181755,-0.0126958,-0.079765,0.00359858,-0.00241693,-0.0326454,1.91935e-06,-3.60837e-08,8.1523e-05,0,0,-1.6953e-06,0.202638,0.0100117,0.433627,0,0,0,0,0,4.55862e-05,0.00318361,0.00318212,0.00107557,0.516237,0.516375,0.525907,0.114589,0.114595,0.217499,9.99679e-07,9.9974e-07,9.18799e-07,0,0,3.99786e-06,0,0,0,0,0,0,0,0
785000,0.982023,-0.00979184,-0.0157123,0.187852,0.0211215,-0.0120094,-0.0884533,0.00392279,-0.00256314,-0.0373845,1.92224e-06,-2.49904e-07,9.53332e-05,0,0,-2.81548e-06,0.202638,0.0100117,0.433627,0,0,0,0,0,4.26141e-05,0.00330368,0.00330223,0.00101621,0.540694,0.540881,0.503501,0.0990934,0.099101,0.204568,9.97017e-07,9.9711e-07,8.76387e-07,0,0,3.99536e-06,0,0,0,0,0,0,0,0
885000,0.982175,-0.00985493,-0.0160794,0.18702,0.0257555,-0.0127343,-0.104574,0.0062643,-0.00383762,-0.0502246,2.07931e-06,-2.35812e-07,0.000100917,0,0,-1.89113e-06,0.202638,0.0100117,0.433627,0,0,0,0,0,4.08464e-05,0.00364557,0.00364398,0.000984803,0.686233,0.686533,0.475831,0.136933,0.136953,0.198089,9.96976e-07,9.9711e-07,8.255e-07,0,0,3.99118e-06,0,0,0,0,0,0,0,0
985000,0.982188,-0.00959921,-0.0161461,0.186961,0.02548,-0.0099564,-0.116428,0.00557201,-0.00313179,-0.0592959,6.32374e-07,-1.17085e-06,9.28885e-05,0,0,-2.97392e-06,0.202638,0.0100117,0.433627,0,0,0,0,0,4.1334e-05,0.00358837,0.00358701,0.00101512,0.6426,0.642879,0.453924,0.113733,0.113749,0.20526,9.85886e-07,9.86042e-07,7.82931e-07,0,0,3.9866e-06,0,0,0,0,0,0,0,0
1085000,0.982436,-0.00970805,-0.0163541,0.185627,0.0357421,-0.01283,-0.134558,0.00863414,-0.00421267,-0.0779928,1.01005e-06,-1.16987e-06,0.000106839,0,0,-3.55292e-07,0.202638,0.0100117,0.433627,0,0,0,0,0,4.04985e-05,0.0040074,0.00400593,0.00100677,0.81804,0.818449,0.420557,0.162616,0.16265,0.20383,9.85839e-07,9.86042e-07,7.22502e-07,0,0,3.97832e-06,0,0,0,0,0,0,0,0
1185000,0.982629,-0.009376,-0.016215,0.184634,0.0341162,-0.0111947,-0.131011,0.00696648,-0.00308594,-0.0734422,-1.02631e-06,-3.25723e-06,0.000114034,0,0,-9.55569e-06,0.202638,0.0100117,0.433627,0,0,0,0,0,3.94925e-05,0.00372784,0.0037268,0.00100169,0.689881,0.690177,0.386375,0.124916,0.124936,0.203012,9.59002e-07,9.59225e-07,6.60384e-07,0,0,3.96732e-06,0,0,0,0,0,0,0,0
1285000,0.982973,-0.00927524,-0.0164925,0.182774,0.0441505,-0.0121445,-0.137145,0.0109828,-0.00429794,-0.0780983,-4.23974e-07,-3.26396e-06,0.00013553,0,0,-1.4817e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.87924e-05,0.00420002,0.00419884,0.000995752,0.881426,0.881843,0.352464,0.180129,0.180169,0.20185,9.58956e-07,9.59225e-07,5.98372e-07,0,0,3.95328e-06,0,0,0,0,0,0,0,0
1385000,0.983132,-0.008886,-0.0160825,0.181974,0.0404405,-0.00909161,-0.134727,0.00811338,-0.00281806,-0.0751603,-3.64446e-06,-6.91576e-06,0.000136827,0,0,-2.58496e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.75589e-05,0.00375983,0.00375912,0.000986837,0.695614,0.695872,0.320036,0.129617,0.129636,0.19999,9.12921e-07,9.13193e-07,5.38299e-07,0,0,3.93598e-06,0,0,0,0,0,0,0,0
1485000,0.983095,-0.0088203,-0.0162462,0.182163,0.0463285,-0.00987824,-0.145946,0.0124459,-0.00369679,-0.0873605,-4.0155e-06,-6.86295e-06,0.0001227,0,0,-2.73295e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.67972e-05,0.00426027,0.00425947,0.000975217,0.892242,0.892591,0.290236,0.186625,0.186662,0.197531,9.12881e-07,9.13192e-07,4.82087e-07,0,0,3.91565e-06,0,0,0,0,0,0,0,0
1585000,0.983156,-0.00852408,-0.0158428,0.181882,0.0383209,-0.00647075,-0.156394,0.00843818,-0.00230591,-0.0982294,-8.01557e-06,-1.19154e-05,0.000117654,0,0,-3.08256e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.70866e-05,0.00373087,0.00373046,0.00100483,0.683993,0.684191,0.271814,0.129353,0.129368,0.204446,8.48387e-07,8.48674e-07,4.42698e-07,0,0,3.8983e-06,0,0,0,0,0,0,0,0
1685000,0.983175,-0.00856868,-0.0160557,0.181756,0.0459118,-0.00579941,-0.161627,0.01267,-0.00286207,-0.103522,-8.14487e-06,-1.18421e-05,0.000111392,0,0,-3.92121e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.62215e-05,0.0042377,0.00423721,0.000985324,0.88178,0.882053,0.24718,0.185645,0.185675,0.200424,8.48354e-07,8.48672e-07,3.94316e-07,0,0,3.87226e-06,0,0,0,0,0,0,0,0
1785000,0.983132,-0.00867435,-0.0163034,0.181963,0.0555627,-0.00685987,-0.162493,0.0178072,-0.00352641,-0.106041,-8.41812e-06,-1.17243e-05,9.9083e-05,0,0,-5.10542e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.53543e-05,0.00478693,0.00478637,0.000963023,1.12358,1.12394,0.225522,0.266166,0.266219,0.195911,8.48322e-07,8.4867e-07,3.50677e-07,0,0,3.84276e-06,0,0,0,0,0,0,0,0
1885000,0.983223,-0.00822356,-0.0156554,0.181548,0.0444571,-0.000592779,-0.163824,0.0124994,-0.00185756,-0.110734,-1.23773e-05,-1.77845e-05,9.80573e-05,0,0,-6.19125e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.38433e-05,0.00414405,0.00414376,0.000939012,0.865069,0.86529,0.206866,0.181237,0.181259,0.191243,7.6811e-07,7.68426e-07,3.11829e-07,0,0,3.81008e-06,0,0,0,0,0,0,0,0
1985000,0.983209,-0.00827243,-0.0159687,0.181593,0.0516589,-0.000150602,-0.162415,0.0173435,-0.00197594,-0.110064,-1.24897e-05,-1.76231e-05,9.07375e-05,0,0,-7.895e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.30014e-05,0.0046766,0.00467622,0.000913761,1.10486,1.10515,0.190844,0.259702,0.259743,0.186408,7.68086e-07,7.68423e-07,2.77412e-07,0,0,3.77375e-06,0,0,0,0,0,0,0,0
2085000,0.983085,-0.0080177,-0.0153531,0.182331,0.0400863,0.00272938,-0.160921,0.0117972,-0.000773254,-0.107788,-1.64074e-05,-2.42102e-05,7.48744e-05,0,0,-9.92268e-05,0.202638,0.0100117,0.433627,0,0,0,0,0,3.15277e-05,0.00397017,0.00397,0.000887914,0.846357,0.846533,0.177296,0.175672,0.175689,0.181667,6.76422e-07,6.76719e-07,2.47083e-07,0,0,3.73406e-06,0,0,0,0,0,0,0,0
2185000,0.983045,-0.00791925,-0.015637,0.182524,0.0462677,0.00365563,-0.162106,0.0161309,-0.000426748,-0.112203,-1.65492e-05,-2.40676e-05,6.70191e-05,0,0,-0.00011296,0.202638,0.0100117,0.433627,0,0,0,0,0,3.07387e-05,0.00446904,0.00446877,0.000861871,1.08032,1.08056,0.165843,0.251794,0.251825,0.176978,6.76404e-07,6.76716e-07,2.20423e-07,0,0,3.69044e-06,0,0,0,0,0,0,0,0
2285000,0.983156,-0.00775274,-0.0150158,0.181988,0.0334751,0.00590942,-0.159621,0.0105654,0.000237655,-0.112107,-1.93269e-05,-3.08856e-05,6.93558e-05,0,0,-0.000132862,0.202638,0.0100117,0.433627,0,0,0,0,0,3.04075e-05,0.00371161,0.0037115,0.000869302,0.820419,0.820563,0.160805,0.169793,0.169806,0.180305,5.79017e-07,5.79282e-07,2.02495e-07,0,0,3.65504e-06,0,0,0,0,0,0,0,0
2385000,0.983107,-0.00773992,-0.015143,0.182238,0.039117,0.00607187,-0.159176,0.014234,0.000782537,-0.110632,-1.94236e-05,-3.06887e-05,6.2405e-05,0,0,-0.000155101,0.202638,0.0100117,0.433627,0,0,0,0,0,2.95754e-05,0.00416361,0.00416342,0.000841812,1.04527,1.04546,0.152442,0.243269,0.243294,0.175641,5.79003e-07,5.79279e-07,1.81259e-07,0,0,3.6043e-06,0,0,0,0,0,0,0,0
2485000,0.983168,-0.00751173,-0.0145513,0.181969,0.0262096,0.0072234,-0.160029,0.00904123,0.000883335,-0.113847,-2.14427e-05,-3.7042e-05,6.28858e-05,0,0,-0.000172069,0.202638,0.0100117,0.433627,0,0,0,0,0,2.81842e-05,0.00338153,0.00338144,0.000815043,0.785707,0.785825,0.145526,0.163732,0.163743,0.171323,4.82463e-07,4.82694e-07,1.62602e-07,0,0,3.54969e-06,0,0,0,0,0,0,0,0
2585000,0.983141,-0.00755847,-0.0146404,0.182106,0.0279928,0.00703042,-0.162066,0.0117504,0.00160901,-0.117764,-2.15444e-05,-3.68926e-05,5.68248e-05,0,0,-0.000189262,0.202638,0.0100117,0.433627,0,0,0,0,0,2.73786e-05,0.00377859,0.00377844,0.000789206,0.996275,0.99643,0.139793,0.234148,0.234168,0.167263,4.82453e-07,4.82691e-07,1.46239e-07,0,0,3.49054e-06,0,0,0,0,0,0,0,0
2685000,0.983141,-0.0075548,-0.0141109,0.182145,0.0181386,0.00780726,-0.160763,0.00717528,0.00127966,-0.116894,-2.27916e-05,-4.20966e-05,5.3742e-05,0,0,-0.000215429,0.202638,0.0100117,0.433627,0,0,0,0,0,2.60799e-05,0.00300716,0.00300712,0.000763975,0.740963,0.74106,0.135018,0.15744,0.157449,0.163468,3.92671e-07,3.92867e-07,1.31771e-07,0,0,3.4267e-06,0,0,0,0,0,0,0,0
2785000,0.983064,-0.0074292,-0.0142258,0.182557,0.0221739,0.00904533,-0.157374,0.00933035,0.00209587,-0.113416,-2.29146e-05,-4.18692e-05,4.59254e-05,0,0,-0.000246785,0.202638,0.0100117,0.433627,0,0,0,0,0,2.53537e-05,0.00334674,0.00334664,0.000740125,0.934192,0.934331,0.131148,0.22428,0.224297,0.160041,3.92663e-07,3.92865e-07,1.19101e-07,0,0,3.35874e-06,0,0,0,0,0,0,0,0
2885000,0.983114,-0.00745083,-0.0138355,0.182319,0.0150901,0.00669869,-0.158078,0.00567455,0.00148558,-0.114763,-2.34682e-05,-4.59847e-05,4.52535e-05,0,0,-0.000270622,0.202638,0.0100117,0.433627,0,0,0,0,0,2.49634e-05,0.00262038,0.00262036,0.000741635,0.688444,0.688526,0.131224,0.150907,0.150914,0.163371,3.13687e-07,3.13849e-07,1.10539e-07,0,0,3.30487e-06,0,0,0,0,0,0,0,0
2985000,0.983131,-0.00741151,-0.0138904,0.182223,0.0167206,0.00690476,-0.159849,0.00737651,0.00216274,-0.118475,-2.34647e-05,-4.58907e-05,4.40775e-05,0,0,-0.000291111,0.202638,0.0100117,0.433627,0,0,0,0,0,2.42739e-05,0.00290465,0.00290459,0.000718297,0.862372,0.862482,0.128447,0.213726,0.21374,0.160307,3.13681e-07,3.13847e-07,1.00329e-07,0,0,3.22898e-06,0,0,0,0,0,0,0,0
3085000,0.98304,-0.00741737,-0.0136439,0.182733,0.0130057,0.00386812,-0.162536,0.00453635,0.00134382,-0.122684,-2.38321e-05,-4.89729e-05,3.89465e-05,0,0,-0.000312485,0.202638,0.0100117,0.433627,0,0,0,0,0,2.32561e-05,0.00224826,0.00224825,0.000695793,0.63168,0.631747,0.126084,0.144218,0.144224,0.157497,2.47275e-07,2.47408e-07,9.12337e-08,0,0,3.14845e-06,0,0,0,0,0,0,0,0
3185000,0.982874,-0.00738681,-0.0137364,0.183619,0.0152254,0.00327908,-0.163058,0.00597394,0.00163628,-0.127431,-2.4043e-05,-4.88035e-05,2.91299e-05,0,0,-0.00033342,0.202638,0.0100117,0.433627,0,0,0,0,0,2.26577e-05,0.00248254,0.00248251,0.000674636,0.785632,0.785722,0.124122,0.202747,0.202758,0.155012,2.47271e-07,2.47406e-07,8.32046e-08,0,0,3.06418e-06,0,0,0,0,0,0,0,0
3285000,0.982851,-0.00736268,-0.0134088,0.183766,0.0103407,0.00258927,-0.165772,0.00372943,0.000954691,-0.135155,-2.4378e-05,-5.11351e-05,2.66985e-05,0,0,-0.000350311,0.202638,0.0100117,0.433627,0,0,0,0,0,2.17337e-05,0.00190856,0.00190857,0.000654314,0.573705,0.573761,0.122373,0.137514,0.137519,0.152738,1.93311e-07,1.93417e-07,7.60182e-08,0,0,2.9757e-06,0,0,0,0,0,0,0,0
3385000,0.982751,-0.00714424,-0.0134289,0.184306,0.010519,0.00422486,-0.163751,0.00475779,0.00128052,-0.132982,-2.44864e-05,-5.09677e-05,2.08254e-05,0,0,-0.000387648,0.202638,0.0100117,0.433627,0,0,0,0,0,2.11824e-05,0.00209968,0.00209966,0.000635185,0.709132,0.709209,0.120849,0.19167,0.19168,0.150738,1.93307e-07,1.93416e-07,6.96428e-08,0,0,2.8841e-06,0,0,0,0,0,0,0,0
3485000,0.982649,-0.00709366,-0.0131982,0.184869,0.00889291,0.00609927,-0.161637,0.0030114,0.000937874,-0.1329,-2.47425e-05,-5.25965e-05,1.49305e-05,0,0,-0.000421103,0.202638,0.0100117,0.433627,0,0,0,0,0,2.03845e-05,0.00160977,0.00160978,0.000616823,0.518186,0.51824,0.119398,0.130942,0.130946,0.148899,1.505e-07,1.50584e-07,6.39102e-08,0,0,2.78901e-06,0,0,0,0,0,0,0,0
3585000,0.982628,-0.00698251,-0.0131097,0.184993,0.0103458,0.00648998,-0.166648,0.00402298,0.00156436,-0.140437,-2.47805e-05,-5.2534e-05,1.29106e-05,0,0,-0.000439421,0.202638,0.0100117,0.433627,0,0,0,0,0,2.04245e-05,0.00176478,0.00176477,0.000616452,0.636215,0.636287,0.120837,0.180844,0.180852,0.152908,1.50497e-07,1.50584e-07,6.00165e-08,0,0,2.71569e-06,0,0,0,0,0,0,0,0
3685000,0.982705,-0.00699966,-0.0129486,0.184592,0.00658903,0.00575718,-0.162462,0.00261733,0.00112367,-0.138638,-2.46408e-05,-5.39675e-05,1.57582e-05,0,0,-0.000477905,0.202638,0.0100117,0.433627,0,0,0,0,0,1.97129e-05,0.00135338,0.0013534,0.000598902,0.466244,0.466289,0.119389,0.124621,0.124625,0.151282,1.17056e-07,1.17123e-07,5.52728e-08,0,0,2.61595e-06,0,0,0,0,0,0,0,0
3785000,0.982647,-0.006904,-0.0130362,0.184896,0.00592338,0.00996651,-0.163408,0.00326792,0.00199106,-0.143479,-2.47032e-05,-5.389e-05,1.28186e-05,0,0,-0.000501903,0.202638,0.0100117,0.433627,0,0,0,0,0,1.9243e-05,0.00147878,0.00147878,0.000582353,0.568452,0.568515,0.117949,0.170479,0.170486,0.149836,1.17054e-07,1.17122e-07,5.10248e-08,0,0,2.51485e-06,0,0,0,0,0,0,0,0
3885000,0.98267,-0.00683416,-0.0130709,0.184777,0.00516049,0.0116424,-0.160778,0.00394857,0.00313111,-0.144464,-2.46699e-05,-5.38575e-05,1.37836e-05,0,0,-0.000533829,0.202638,0.0100117,0.433627,0,0,0,0,0,1.88056e-05,0.00161003,0.00161002,0.000566545,0.686588,0.686669,0.116418,0.232144,0.232157,0.148463,1.17051e-07,1.17121e-07,4.71879e-08,0,0,2.41218e-06,0,0,0,0,0,0,0,0
3985000,0.98255,-0.00689917,-0.0129353,0.18542,0.00460053,0.0103244,-0.159848,0.00238671,0.00250175,-0.143678,-2.44195e-05,-5.48728e-05,8.96882e-06,0,0,-0.000570883,0.202638,0.0100117,0.433627,0,0,0,0,0,1.82076e-05,0.00123844,0.00123846,0.000551386,0.507349,0.507401,0.11477,0.160717,0.160723,0.14714,9.1169e-08,9.12237e-08,4.37022e-08,0,0,2.30852e-06,0,0,0,0,0,0,0,0
4085000,0.982479,-0.00681247,-0.0128538,0.185806,0.00555607,0.0109645,-0.148375,0.00303767,0.00359074,-0.132664,-2.44807e-05,-5.47656e-05,6.17474e-06,0,0,-0.000628546,0.202638,0.0100117,0.433627,0,0,0,0,0,1.78047e-05,0.00134446,0.00134448,0.000537064,0.609211,0.609277,0.113058,0.216895,0.216907,0.145924,9.11673e-08,9.12229e-08,4.05606e-08,0,0,2.20521e-06,0,0,0,0,0,0,0,0
4185000,0.982505,-0.00699703,-0.0127009,0.185669,0.00350826,0.00851795,-0.149861,0.00192613,0.0026474,-0.138879,-2.39786e-05,-5.56418e-05,6.69986e-06,0,0,-0.000647312,0.202638,0.0100117,0.433627,0,0,0,0,0,1.76862e-05,0.00103832,0.00103836,0.0005363,0.452514,0.452554,0.113955,0.151625,0.15163,0.150231,7.12199e-08,7.12634e-08,3.83863e-08,0,0,2.12804e-06,0,0,0,0,0,0,0,0
4285000,0.982554,-0.00702798,-0.0127381,0.185409,0.00557583,0.0102732,-0.152042,0.00246048,0.00357415,-0.144611,-2.3937e-05,-5.56538e-05,8.45885e-06,0,0,-0.000667468,0.202638,0.0100117,0.433627,0,0,0,0,0,1.72952e-05,0.00112411,0.00112416,0.000522646,0.540567,0.54062,0.111966,0.202812,0.202822,0.149009,7.12185e-08,7.12628e-08,3.57281e-08,0,0,2.02579e-06,0,0,0,0,0,0,0,0
4385000,0.98262,-0.00703146,-0.0126871,0.18506,0.0052979,0.00682746,-0.14321,0.00180453,0.00251225,-0.13493,-2.34199e-05,-5.63566e-05,1.03488e-05,0,0,-0.000719743,0.202638,0.0100117,0.433627,0,0,0,0,0,1.67927e-05,0.000872513,0.000872557,0.000509571,0.404257,0.40429,0.109833,0.14322,0.143225,0.147766,5.58608e-08,5.58959e-08,3.32966e-08,0,0,1.92468e-06,0,0,0,0,0,0,0,0
4485000,0.982615,-0.00705969,-0.0126298,0.18509,0.00599404,0.0100838,-0.139739,0.00245417,0.0034134,-0.13346,-2.3428e-05,-5.63346e-05,1.01363e-05,0,0,-0.000753017,0.202638,0.0100117,0.433627,0,0,0,0,0,1.64295e-05,0.000942164,0.000942213,0.000497157,0.480287,0.480331,0.107623,0.189915,0.189923,0.146568,5.58597e-08,5.58953e-08,3.1087e-08,0,0,1.82588e-06,0,0,0,0,0,0,0,0
4585000,0.982551,-0.00712435,-0.0125922,0.18543,0.00510526,0.00675104,-0.139207,0.00175346,0.00249379,-0.136185,-2.30717e-05,-5.69125e-05,7.97427e-06,0,0,-0.000777221,0.202638,0.0100117,0.433627,0,0,0,0,0,1.59999e-05,0.000735391,0.000735439,0.000485236,0.361667,0.361694,0.105285,0.135484,0.135488,0.145327,4.402e-08,4.40482e-08,2.90589e-08,0,0,1.72915e-06,0,0,0,0,0,0,0,0
4685000,0.982616,-0.00706606,-0.0125378,0.18509,0.00454048,0.00769862,-0.130651,0.00234947,0.00329643,-0.13007,-2.30387e-05,-5.69234e-05,9.62468e-06,0,0,-0.000818364,0.202638,0.0100117,0.433627,0,0,0,0,0,1.56505e-05,0.00079215,0.000792201,0.000473929,0.427409,0.427443,0.102887,0.178147,0.178153,0.14411,4.4019e-08,4.40477e-08,2.72085e-08,0,0,1.63549e-06,0,0,0,0,0,0,0,0
4785000,0.982571,-0.00699,-0.0125341,0.185333,-0.0022568,0.00666383,-0.129234,0.00132177,0.00238916,-0.131434,-2.27123e-05,-5.74183e-05,8.22831e-06,0,0,-0.000842828,0.202638,0.0100117,0.433627,0,0,0,0,0,1.52666e-05,0.00062198,0.000622023,0.000463041,0.324175,0.324195,0.100386,0.128372,0.128375,0.142838,3.48659e-08,3.48887e-08,2.55045e-08,0,0,1.54461e-06,0,0,0,0,0,0,0,0
4885000,0.982603,-0.00691809,-0.0125527,0.185162,-0.00178037,0.00522459,-0.12566,0.00114402,0.00297867,-0.131721,-2.269e-05,-5.74323e-05,9.37093e-06,0,0,-0.000868061,0.202638,0.0100117,0.433627,0,0,0,0,0,1.52745e-05,0.000668429,0.000668473,0.000462279,0.381299,0.381321,0.100272,0.16743,0.167435,0.146773,3.48654e-08,3.48884e-08,2.432e-08,0,0,1.47848e-06,0,0,0,0,0,0,0,0
4985000,0.982591,-0.00692983,-0.0125071,0.185232,-0.00130465,0.00495874,-0.118811,0.000547132,0.00206801,-0.127591,-2.23722e-05,-5.76909e-05,8.57058e-06,0,0,-0.000900987,0.202638,0.0100117,0.433627,0,0,0,0,0,1.48999e-05,0.000528035,0.000528074,0.000451893,0.291225,0.291241,0.0975883,0.121842,0.121845,0.145353,2.77622e-08,2.77806e-08,2.28479e-08,0,0,1.39337e-06,0,0,0,0,0,0,0,0
5085000,0.982545,-0.00678326,-0.0124343,0.185483,-0.00105275,0.00587384,-0.114515,0.000466707,0.0025821,-0.123616,-2.24084e-05,-5.76629e-05,7.27677e-06,0,0,-0.000931934,0.202638,0.0100117,0.433627,0,0,0,0,0,1.46074e-05,0.000566216,0.000566257,0.000441981,0.341084,0.341104,0.0948952,0.157679,0.157683,0.143942,2.77616e-08,2.77802e-08,2.14957e-08,0,0,1.31214e-06,0,0,0,0,0,0,0,0
5185000,0.98254,-0.00667415,-0.0124522,0.185516,-0.00386265,0.00730925,-0.111415,7.72151e-05,0.00196115,-0.121274,-2.21069e-05,-5.78173e-05,7.17336e-06,0,0,-0.000958524,0.202638,0.0100117,0.433627,0,0,0,0,0,1.42814e-05,0.000450014,0.000450046,0.000432439,0.262485,0.262499,0.0921592,0.11585,0.115853,0.142469,2.22245e-08,2.22393e-08,2.02437e-08,0,0,1.23441e-06,0,0,0,0,0,0,0,0
5285000,0.98255,-0.00655786,-0.0124251,0.185469,-0.00354388,0.00907426,-0.10083,-0.000263663,0.00279573,-0.114835,-2.21058e-05,-5.7822e-05,7.51649e-06,0,0,-0.00099114,0.202638,0.0100117,0.433627,0,0,0,0,0,1.40062e-05,0.000481545,0.000481579,0.000423284,0.305862,0.30588,0.0893984,0.148812,0.148816,0.140936,2.2224e-08,2.2239e-08,1.90878e-08,0,0,1.16025e-06,0,0,0,0,0,0,0,0
5385000,0.982538,-0.00650638,-0.0124238,0.185535,-0.00612794,0.0102174,-0.096358,-0.000472084,0.0022774,-0.109637,-2.17705e-05,-5.78808e-05,6.83227e-06,0,0,-0.00101944,0.202638,0.0100117,0.433627,0,0,0,0,0,1.36983e-05,0.000385019,0.000385046,0.000414515,0.237038,0.237051,0.0866669,0.110341,0.110343,0.139413,1.78866e-08,1.78986e-08,1.80167e-08,0,0,1.0901e-06,0,0,0,0,0,0,0,0
5485000,0.982523,-0.00650521,-0.012487,0.18561,-0.00604964,0.0137961,-0.0932747,-0.00110967,0.00346287,-0.11003,-2.17883e-05,-5.78694e-05,6.23746e-06,0,0,-0.00103637,0.202638,0.0100117,0.433627,0,0,0,0,0,1.36934e-05,0.000411178,0.000411209,0.000413838,0.275185,0.275202,0.0860569,0.140729,0.140732,0.142825,1.78863e-08,1.78985e-08,1.72666e-08,0,0,1.03995e-06,0,0,0,0,0,0,0,0
5585000,0.98234,-0.00657583,-0.0125313,0.186567,-0.00619599,0.0151818,-0.0854829,-0.00101811,0.00302182,-0.102377,-2.13447e-05,-5.78843e-05,5.82415e-06,0,0,-0.00106601,0.203458,0.00195935,0.434775,0,0,0,0,0,0.000100415,0.000331079,0.000330821,0.00281792,0.214652,0.214664,0.0832893,0.105274,0.105276,0.14115,1.44716e-08,1.44814e-08,1.63274e-08,0,0,9.76209e-07,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,0,0
5685000,0.982199,-0.00652648,-0.0124261,0.187316,-0.00651164,0.0181302,-0.0855902,-0.00170806,0.00461957,-0.101788,-2.13483e-05,-5.78854e-05,5.84093e-06,0,0,-0.00108188,0.203458,0.00195935,0.434775,0,0,0,0,0,6.60773e-05,0.000331334,0.000331195,0.00185567,0.216501,0.216514,0.0805424,0.132493,0.132496,0.139431,1.44717e-08,1.44815e-08,1.63271e-08,0,0,9.15974e-07,0,0,0,0,0,0,0,0
5785000,0.982413,-0.00640013,-0.0123886,0.1862,-0.00591057,0.0181195,-0.0798164,-0.00141873,0.00395751,-0.0957693,-2.08011e-05,-5.7903e-05,5.91456e-06,0,0,-0.00110626,0.203458,0.00195935,0.434775,0,0,0,0,0,4.92548e-05,0.000331906,0.000331818,0.00138392,0.152571,0.152579,0.077864,0.0990735,0.099075,0.137732,1.18706e-08,1.18785e-08,1.63241e-08,0,0,8.59437e-07,0,0,0,0,0,0,0,0
5885000,0.982402,-0.00632628,-0.0124417,0.186255,-0.00415994,0.019772,-0.076465,-0.00190114,0.00589289,-0.0971815,-2.08035e-05,-5.79038e-05,5.9245e-06,0,0,-0.00111689,0.203458,0.00195935,0.434775,0,0,0,0,0,3.93197e-05,0.000333303,0.000333245,0.00110408,0.160638,0.160646,0.0752266,0.121141,0.121143,0.135998,1.18707e-08,1.18786e-08,1.632e-08,0,0,8.0618e-07,0,0,0,0,0,0,0,0
5985000,0.9823,-0.00625662,-0.0125537,0.186789,-0.00404305,0.0218179,-0.0699316,-0.00229247,0.00796544,-0.0913963,-2.08115e-05,-5.79032e-05,5.82404e-06,0,0,-0.00113839,0.203458,0.00195935,0.434775,0,0,0,0,0,3.27361e-05,0.00033531,0.00033527,0.000919162,0.172,0.172009,0.0726689,0.146644,0.146648,0.134292,1.18708e-08,1.18787e-08,1.6313e-08,0,0,7.56335e-07,0,0,0,0,0,0,0,0
6085000,0.982195,-0.00625391,-0.0124948,0.187342,-0.00451049,0.0206956,-0.066755,-0.00183403,0.00692233,-0.0896196,-2.02359e-05,-5.79553e-05,5.6057e-06,0,0,-0.00115211,0.203458,0.00195935,0.434775,0,0,0,0,0,2.80192e-05,0.000334536,0.000334514,0.000788165,0.137152,0.137157,0.070164,0.110293,0.110295,0.132559,9.97724e-09,9.98377e-09,1.63012e-08,0,0,7.09504e-07,0,0,0,0,0,0,0,0
6185000,0.982166,-0.00626533,-0.0124473,0.187499,-0.00582251,0.023359,-0.0654273,-0.00230843,0.00915326,-0.0890573,-2.02397e-05,-5.79548e-05,5.55718e-06,0,0,-0.00116355,0.203458,0.00195935,0.434775,0,0,0,0,0,2.53673e-05,0.000336897,0.000336886,0.000713329,0.153492,0.153497,0.0693673,0.131933,0.131935,0.135284,9.97733e-09,9.98386e-09,1.62902e-08,0,0,6.76296e-07,0,0,0,0,0,0,0,0
6285000,0.982159,-0.00625824,-0.0124736,0.187535,-0.00718598,0.0229563,-0.0665107,-0.00207861,0.00796552,-0.0927924,-1.96535e-05,-5.80284e-05,5.52379e-06,0,0,-0.00116794,0.203458,0.00195935,0.434775,0,0,0,0,0,2.25427e-05,0.000331794,0.00033179,0.000633414,0.133584,0.133587,0.0669313,0.101783,0.101784,0.133449,8.60211e-09,8.60764e-09,1.62707e-08,0,0,6.34523e-07,0,0,0,0,0,0,0,0
6385000,0.982218,-0.00619865,-0.0124073,0.18723,-0.00663287,0.0256733,-0.0658936,-0.00281642,0.0103895,-0.0941696,-1.96513e-05,-5.80317e-05,5.68461e-06,0,0,-0.0011757,0.203458,0.00195935,0.434775,0,0,0,0,0,2.03119e-05,0.000334074,0.000334078,0.000570542,0.153967,0.153969,0.0645874,0.121505,0.121507,0.131654,8.60219e-09,8.60773e-09,1.62464e-08,0,0,5.95568e-07,0,0,0,0,0,0,0,0
6485000,0.982216,-0.00620271,-0.0124079,0.187243,-0.00856955,0.0217852,-0.0622713,-0.00252661,0.00887621,-0.0911027,-1.90659e-05,-5.80933e-05,5.56492e-06,0,0,-0.00118948,0.203458,0.00195935,0.434775,0,0,0,0,0,1.8497e-05,0.000322066,0.000322073,0.000519967,0.14106,0.14106,0.0623103,0.0960425,0.0960435,0.12985,7.60413e-09,7.60894e-09,1.62156e-08,0,0,5.59088e-07,0,0,0,0,0,0,0,0
6585000,0.98219,-0.00615147,-0.012362,0.187381,-0.00980829,0.0241826,-0.0635904,-0.00343154,0.0111309,-0.0929662,-1.90713e-05,-5.80892e-05,5.36482e-06,0,0,-0.00119587,0.203458,0.00195935,0.434775,0,0,0,0,0,1.7021e-05,0.000323971,0.000323984,0.000478548,0.164546,0.164545,0.0601026,0.115303,0.115304,0.128042,7.60421e-09,7.60903e-09,1.61786e-08,0,0,5.2495e-07,0,0,0,0,0,0,0,0
6685000,0.982166,-0.0061415,-0.0123443,0.187509,-0.0125312,0.0239216,-0.0651687,-0.00330922,0.0094983,-0.0928704,-1.85228e-05,-5.81186e-05,5.10721e-06,0,0,-0.00120511,0.203458,0.00195935,0.434775,0,0,0,0,0,1.57919e-05,0.00030325,0.000303263,0.000444166,0.153064,0.153063,0.0579869,0.092863,0.0928636,0.12628,6.89392e-09,6.89822e-09,1.61342e-08,0,0,4.93163e-07,0,0,0,0,0,0,0,0
6785000,0.982155,-0.00616767,-0.0122772,0.187571,-0.0119646,0.0264957,-0.0620577,-0.00458971,0.0119864,-0.0922432,-1.85269e-05,-5.81149e-05,4.95723e-06,0,0,-0.00121454,0.203458,0.00195935,0.434775,0,0,0,0,0,1.50546e-05,0.000304623,0.000304639,0.000423399,0.178366,0.178364,0.0572474,0.112603,0.112604,0.128568,6.894e-09,6.89831e-09,1.60963e-08,0,0,4.70725e-07,0,0,0,0,0,0,0,0
6885000,0.982148,-0.00609531,-0.0122122,0.187617,-0.0108719,0.0223544,-0.0588591,-0.00401913,0.00997255,-0.0911462,-1.80196e-05,-5.811e-05,4.76473e-06,0,0,-0.00122399,0.203458,0.00195935,0.434775,0,0,0,0,0,1.41447e-05,0.000275024,0.000275037,0.000398027,0.163938,0.163935,0.0552251,0.0916392,0.0916395,0.126744,6.41212e-09,6.41608e-09,1.60383e-08,0,0,4.42523e-07,0,0,0,0,0,0,0,0
6985000,0.982162,-0.0060405,-0.0121725,0.187546,-0.0122216,0.0241256,-0.0553072,-0.00523423,0.0122966,-0.088494,-1.80194e-05,-5.81087e-05,4.77531e-06,0,0,-0.00123474,0.203458,0.00195935,0.434775,0,0,0,0,0,1.33816e-05,0.000275845,0.00027586,0.000376426,0.189758,0.189754,0.0532738,0.112268,0.112268,0.124928,6.41219e-09,6.41615e-09,1.5972e-08,0,0,4.16161e-07,0,0,0,0,0,0,0,0
7085000,0.982142,-0.00607565,-0.0121052,0.187655,-0.0114295,0.024777,-0.0553161,-0.00444916,0.010205,-0.0895366,-1.75937e-05,-5.80897e-05,4.62317e-06,0,0,-0.00124043,0.203458,0.00195935,0.434775,0,0,0,0,0,1.2732e-05,0.000239407,0.000239418,0.000357925,0.17001,0.170007,0.0514099,0.091521,0.091521,0.123166,6.10998e-09,6.11372e-09,1.58969e-08,0,0,3.91627e-07,0,0,0,0,0,0,0,0
7185000,0.982126,-0.00600667,-0.0121691,0.187732,-0.0128656,0.0272412,-0.0539849,-0.00572026,0.0128632,-0.0913707,-1.7599e-05,-5.80836e-05,4.36874e-06,0,0,-0.00124504,0.203458,0.00195935,0.434775,0,0,0,0,0,1.21728e-05,0.000239796,0.000239808,0.000342021,0.19496,0.194957,0.0496138,0.112973,0.112973,0.121415,6.11003e-09,6.11378e-09,1.58127e-08,0,0,3.68696e-07,0,0,0,0,0,0,0,0
7285000,0.982135,-0.00613942,-0.0122136,0.187682,-0.0104868,0.0253697,-0.0501402,-0.00472637,0.0104895,-0.0869795,-1.72547e-05,-5.80628e-05,4.32694e-06,0,0,-0.00125657,0.203458,0.00195935,0.434775,0,0,0,0,0,1.16812e-05,0.000200322,0.000200328,0.0003283,0.169302,0.1693,0.0478994,0.0916353,0.0916351,0.119718,5.93999e-09,5.94361e-09,1.57191e-08,0,0,3.47351e-07,0,0,0,0,0,0,0,0
7385000,0.982156,-0.00606356,-0.0121973,0.187577,-0.0128326,0.0284024,-0.0470497,-0.00588271,0.0132711,-0.0837193,-1.72524e-05,-5.80606e-05,4.34987e-06,0,0,-0.00126613,0.203458,0.00195935,0.434775,0,0,0,0,0,1.12612e-05,0.00020049,0.000200499,0.000316433,0.192265,0.192263,0.0462494,0.113487,0.113487,0.118035,5.94004e-09,5.94367e-09,1.56158e-08,0,0,3.27395e-07,0,0,0,0,0,0,0,0
7485000,0.98218,-0.00618158,-0.0122674,0.187439,-0.00856096,0.0257964,-0.0428099,-0.00463527,0.010697,-0.0802051,-1.69924e-05,-5.80535e-05,4.63534e-06,0,0,-0.00127528,0.203458,0.00195935,0.434775,0,0,0,0,0,1.10529e-05,0.000162214,0.000162216,0.00031052,0.162051,0.16205,0.0456369,0.0913129,0.0913126,0.119893,5.8568e-09,5.86037e-09,1.55317e-08,0,0,3.13292e-07,0,0,0,0,0,0,0,0
7585000,0.982202,-0.00626445,-0.0122312,0.187322,-0.00818922,0.027969,-0.038743,-0.00549452,0.0133449,-0.074173,-1.6986e-05,-5.80525e-05,4.78345e-06,0,0,-0.00128655,0.203458,0.00195935,0.434775,0,0,0,0,0,1.07333e-05,0.000162406,0.000162411,0.000301348,0.182291,0.18229,0.044076,0.112987,0.112987,0.118181,5.85683e-09,5.86042e-09,1.54109e-08,0,0,2.95587e-07,0,0,0,0,0,0,0,0
7685000,0.982208,-0.00643907,-0.0123211,0.187281,-0.00664475,0.0256738,-0.0371757,-0.00413007,0.0106538,-0.0677852,-1.68223e-05,-5.80472e-05,4.70282e-06,0,0,-0.0012977,0.203458,0.00195935,0.434775,0,0,0,0,0,1.04496e-05,0.000128599,0.0001286,0.000293405,0.150026,0.150026,0.042588,0.090218,0.0902178,0.116524,5.82277e-09,5.82634e-09,1.52803e-08,0,0,2.79093e-07,0,0,0,0,0,0,0,0
7785000,0.982207,-0.00632381,-0.0123231,0.187288,-0.00534957,0.0270097,-0.038844,-0.00474513,0.0132264,-0.0718125,-1.6825e-05,-5.80453e-05,4.594e-06,0,0,-0.00129739,0.203458,0.00195935,0.434775,0,0,0,0,0,1.02138e-05,0.000129034,0.000129036,0.000286521,0.167295,0.167295,0.0411581,0.111169,0.111169,0.114887,5.8228e-09,5.82638e-09,1.51396e-08,0,0,2.63661e-07,0,0,0,0,0,0,0,0
7885000,0.982195,-0.00648293,-0.0124143,0.187339,-0.00513499,0.0251264,-0.0385064,-0.00352995,0.0104175,-0.0745318,-1.67355e-05,-5.80486e-05,4.55048e-06,0,0,-0.00129859,0.203458,0.00195935,0.434775,0,0,0,0,0,1.00126e-05,0.00010136,0.000101359,0.000280547,0.135288,0.135289,0.0397835,0.0883202,0.08832,0.11327,5.81198e-09,5.81557e-09,1.49886e-08,0,0,2.49219e-07,0,0,0,0,0,0,0,0
7985000,0.982201,-0.00642023,-0.0123263,0.187317,-0.00511938,0.0265124,-0.0345919,-0.00408575,0.0129595,-0.0708954,-1.67289e-05,-5.80476e-05,4.69025e-06,0,0,-0.00130609,0.203458,0.00195935,0.434775,0,0,0,0,0,9.84417e-06,0.000102201,0.000102202,0.000275396,0.149665,0.149666,0.0384746,0.108137,0.108137,0.111707,5.81199e-09,5.8156e-09,1.48282e-08,0,0,2.35751e-07,0,0,0,0,0,0,0,0
8085000,0.982186,-0.00630072,-0.0123213,0.187401,-0.00437373,0.0299161,-0.034862,-0.00452438,0.0157644,-0.0732883,-1.674e-05,-5.80371e-05,4.17976e-06,0,0,-0.00130732,0.203458,0.00195935,0.434775,0,0,0,0,0,9.81359e-06,0.000103334,0.000103335,0.000274391,0.164806,0.164807,0.0379855,0.131919,0.131919,0.113318,5.81202e-09,5.81565e-09,1.47016e-08,0,0,2.26232e-07,0,0,0,0,0,0,0,0
8185000,0.982176,-0.00647493,-0.0122587,0.187454,-0.00258131,0.0293109,-0.0313237,-0.00321609,0.0129227,-0.0687527,-1.67017e-05,-5.80323e-05,3.92053e-06,0,0,-0.00131518,0.203458,0.00195935,0.434775,0,0,0,0,0,9.68069e-06,8.22481e-05,8.22483e-05,0.000270475,0.131698,0.131699,0.0367508,0.104211,0.104211,0.111741,5.80978e-09,5.81343e-09,1.45245e-08,0,0,2.14243e-07,0,0,0,0,0,0,0,0
8285000,0.982187,-0.00645188,-0.0122426,0.187397,-0.000493042,0.0321683,-0.0287394,-0.00338684,0.0159803,-0.067394,-1.67028e-05,-5.80272e-05,3.77744e-06,0,0,-0.00131927,0.203458,0.00195935,0.434775,0,0,0,0,0,9.56398e-06,8.38894e-05,8.38912e-05,0.000267121,0.14415,0.144152,0.0355655,0.126132,0.126132,0.110188,5.80978e-09,5.81346e-09,1.4338e-08,0,0,2.03009e-07,0,0,0,0,0,0,0,0
8385000,0.982187,-0.00652159,-0.0122391,0.187392,-0.00202607,0.0279964,-0.0270389,-0.00230212,0.0131089,-0.0638553,-1.66885e-05,-5.80265e-05,3.78839e-06,0,0,-0.00132516,0.203458,0.00195935,0.434775,0,0,0,0,0,9.47099e-06,6.85819e-05,6.85822e-05,0.000264248,0.114851,0.114852,0.0344357,0.0997551,0.0997551,0.108687,5.80962e-09,5.81332e-09,1.41431e-08,0,0,1.92515e-07,0,0,0,0,0,0,0,0
8485000,0.982213,-0.00641901,-0.0122347,0.187262,-0.00257656,0.0311145,-0.0275645,-0.0025064,0.0160218,-0.0678959,-1.66772e-05,-5.80375e-05,4.31512e-06,0,0,-0.00132382,0.203458,0.00195935,0.434775,0,0,0,0,0,9.39595e-06,7.07874e-05,7.07888e-05,0.000261796,0.125144,0.125144,0.033351,0.11976,0.119761,0.10721,5.80961e-09,5.81334e-09,1.39397e-08,0,0,1.82673e-07,0,0,0,0,0,0,0,0
8585000,0.982224,-0.00646883,-0.0123359,0.187196,-0.00108381,0.0278371,-0.022386,-0.0018366,0.0132013,-0.0627184,-1.66778e-05,-5.80314e-05,4.22613e-06,0,0,-0.00133068,0.203458,0.00195935,0.434775,0,0,0,0,0,9.32321e-06,6.02188e-05,6.02186e-05,0.000259723,0.099941,0.0999411,0.0323172,0.0950892,0.0950892,0.105782,5.80959e-09,5.81334e-09,1.3729e-08,0,0,1.7347e-07,0,0,0,0,0,0,0,0
8685000,0.982252,-0.00649989,-0.0124213,0.187039,-0.00128858,0.0290586,-0.023603,-0.00199347,0.016032,-0.0644285,-1.66721e-05,-5.80357e-05,4.4638e-06,0,0,-0.00133107,0.203458,0.00195935,0.434775,0,0,0,0,0,9.2623e-06,6.3009e-05,6.30102e-05,0.000257965,0.108593,0.108593,0.0313243,0.113253,0.113253,0.104376,5.80957e-09,5.81336e-09,1.35107e-08,0,0,1.6483e-07,0,0,0,0,0,0,0,0
8785000,0.982251,-0.00654077,-0.0123788,0.18705,6.83366e-05,0.0258323,-0.0225732,-0.00145042,0.0131038,-0.0610511,-1.66775e-05,-5.80272e-05,4.19566e-06,0,0,-0.001336,0.203458,0.00195935,0.434775,0,0,0,0,0,9.32349e-06,5.61272e-05,5.6128e-05,0.000259545,0.0873984,0.0873978,0.0309526,0.0904513,0.0904513,0.105741,5.80957e-09,5.81338e-09,1.33424e-08,0,0,1.58701e-07,0,0,0,0,0,0,0,0
8885000,0.982284,-0.00658961,-0.0123728,0.186873,0.000269124,0.0282764,-0.0192493,-0.00140881,0.0158357,-0.0554383,-1.66615e-05,-5.80311e-05,4.67637e-06,0,0,-0.0013424,0.203458,0.00195935,0.434775,0,0,0,0,0,9.28294e-06,5.95004e-05,5.95034e-05,0.000258258,0.0948601,0.094859,0.0300173,0.106932,0.106932,0.104332,5.80954e-09,5.81339e-09,1.31126e-08,0,0,1.50971e-07,0,0,0,0,0,0,0,0
8985000,0.98232,-0.0065801,-0.0122933,0.186688,-0.000446041,0.026706,-0.0173191,-0.00103163,0.0130667,-0.0571187,-1.66352e-05,-5.80496e-05,5.43655e-06,0,0,-0.00134234,0.203458,0.00195935,0.434775,0,0,0,0,0,9.25239e-06,5.53907e-05,5.53939e-05,0.000257173,0.0772323,0.0772309,0.0291253,0.0860075,0.0860075,0.102972,5.8094e-09,5.81328e-09,1.28776e-08,0,0,1.4373e-07,0,0,0,0,0,0,0,0
9085000,0.98237,-0.00659063,-0.0123614,0.186421,-0.000188343,0.0300673,-0.0186961,-0.0010684,0.0158575,-0.0568419,-1.66154e-05,-5.80635e-05,6.24396e-06,0,0,-0.00134385,0.203458,0.00195935,0.434775,0,0,0,0,0,9.22163e-06,5.93355e-05,5.93402e-05,0.000256256,0.0839439,0.0839421,0.0282685,0.101001,0.101001,0.101633,5.80937e-09,5.81328e-09,1.26374e-08,0,0,1.36919e-07,0,0,0,0,0,0,0,0
9185000,0.982402,-0.00664263,-0.0123952,0.186249,0.00291022,0.0266519,-0.0168399,-0.000632009,0.0133667,-0.0567013,-1.65665e-05,-5.80872e-05,6.94419e-06,0,0,-0.00134526,0.203458,0.00195935,0.434775,0,0,0,0,0,9.20034e-06,5.72595e-05,5.72641e-05,0.000255463,0.0694371,0.069435,0.027445,0.081866,0.0818658,0.100317,5.80805e-09,5.81199e-09,1.23925e-08,0,0,1.30511e-07,0,0,0,0,0,0,0,0
9285000,0.982424,-0.00649151,-0.0122187,0.186148,0.00493718,0.0287878,-0.0151595,-0.000178883,0.016119,-0.054016,-1.65562e-05,-5.80899e-05,7.26487e-06,0,0,-0.00134851,0.203458,0.00195935,0.434775,0,0,0,0,0,9.18234e-06,6.1755e-05,6.17619e-05,0.000254791,0.0757316,0.075729,0.0266596,0.0955929,0.0955925,0.0990459,5.80802e-09,5.812e-09,1.21443e-08,0,0,1.245e-07,0,0,0,0,0,0,0,0
9385000,0.982414,-0.00645132,-0.0122423,0.186202,0.0048386,0.0261755,-0.0136044,0.000287653,0.013543,-0.0537789,-1.65033e-05,-5.81068e-05,6.78623e-06,0,0,-0.00134983,0.203458,0.00195935,0.434775,0,0,0,0,0,9.27231e-06,6.11251e-05,6.11313e-05,0.000257223,0.0638524,0.0638495,0.0263729,0.0780988,0.0780985,0.100269,5.80298e-09,5.80697e-09,1.19562e-08,0,0,1.20229e-07,0,0,0,0,0,0,0,0
9485000,0.982441,-0.00648066,-0.0123143,0.186056,0.00427216,0.0265,-0.0113537,0.000715806,0.0161557,-0.0498506,-1.64939e-05,-5.81071e-05,7.02915e-06,0,0,-0.00135363,0.203458,0.00195935,0.434775,0,0,0,0,0,9.25331e-06,6.615e-05,6.6158e-05,0.000256692,0.0700494,0.0700456,0.0256323,0.0907856,0.0907851,0.0989985,5.80295e-09,5.80697e-09,1.17031e-08,0,0,1.14823e-07,0,0,0,0,0,0,0,0
9585000,0.982408,-0.0065691,-0.0122729,0.186227,0.00331598,0.0225956,-0.0119134,0.000743174,0.0134143,-0.0527595,-1.64105e-05,-5.81434e-05,6.32386e-06,0,0,-0.00135242,0.203458,0.00195935,0.434775,0,0,0,0,0,9.24459e-06,6.64883e-05,6.64971e-05,0.000256193,0.0603382,0.0603342,0.0249201,0.074755,0.0747546,0.0977504,5.78975e-09,5.79379e-09,1.14478e-08,0,0,1.09726e-07,0,0,0,0,0,0,0,0
9685000,0.982416,-0.00656179,-0.0122257,0.186186,0.00291523,0.0240005,-0.00872306,0.00114029,0.0158482,-0.0503219,-1.64141e-05,-5.81352e-05,6.05017e-06,0,0,-0.00135496,0.203458,0.00195935,0.434775,0,0,0,0,0,9.22704e-06,7.20112e-05,7.20225e-05,0.000255741,0.0666882,0.0666832,0.0242401,0.0866289,0.086628,0.0965441,5.78972e-09,5.79379e-09,1.11916e-08,0,0,1.04936e-07,0,0,0,0,0,0,0,0
9785000,0.982396,-0.00659563,-0.012157,0.186297,0.0036443,0.0227153,-0.00924631,0.00108792,0.0132186,-0.0506496,-1.6291e-05,-5.81896e-05,5.10068e-06,0,0,-0.00135553,0.203458,0.00195935,0.434775,0,0,0,0,0,9.20895e-06,7.29066e-05,7.29184e-05,0.000255298,0.0587195,0.0587148,0.023586,0.0718682,0.0718675,0.0953584,5.76214e-09,5.76619e-09,1.09346e-08,0,0,1.00415e-07,0,0,0,0,0,0,0,0
9885000,0.982412,-0.00655767,-0.012099,0.186217,0.00556856,0.0230774,-0.00761221,0.00151855,0.0153924,-0.0507896,-1.62827e-05,-5.81953e-05,5.43643e-06,0,0,-0.00135597,0.203458,0.00195935,0.434775,0,0,0,0,0,9.20087e-06,7.88911e-05,7.89053e-05,0.000254855,0.0654518,0.0654461,0.0229614,0.0831518,0.0831506,0.0942121,5.7621e-09,5.76619e-09,1.06778e-08,0,0,9.61611e-08,0,0,0,0,0,0,0,0
9985000,0.982379,-0.00660567,-0.0121505,0.186387,0.00641266,0.0199482,-0.00652218,0.00152812,0.0127575,-0.0518007,-1.61155e-05,-5.82822e-05,4.56291e-06,0,0,-0.00135592,0.203458,0.00195935,0.434775,0,0,0,0,0,9.18995e-06,7.99562e-05,7.99698e-05,0.000254396,0.0588023,0.0587968,0.02236,0.0694601,0.0694592,0.0930853,5.7121e-09,5.71614e-09,1.04213e-08,0,0,9.21424e-08,0,0,0,0,0,0,0,0
10085000,0.982367,-0.00654496,-0.0123065,0.186443,0.00516124,0.0182599,-0.00534162,0.00212643,0.0146277,-0.050187,-1.61277e-05,-5.82686e-05,3.95119e-06,0,0,-0.00135745,0.203458,0.00195935,0.434775,0,0,0,0,0,9.28245e-06,8.63557e-05,8.63698e-05,0.000256936,0.0660952,0.0660882,0.0221478,0.080367,0.0803655,0.094161,5.7121e-09,5.71617e-09,1.02296e-08,0,0,8.92778e-08,0,0,0,0,0,0,0,0
10185000,0.982321,-0.00650551,-0.0122225,0.186694,0.00274993,0.019596,-0.00364431,0.00250058,0.016538,-0.0501842,-1.61547e-05,-5.82455e-05,2.74753e-06,0,0,-0.00135791,0.203458,0.00195935,0.434775,0,0,0,0,0,9.27148e-06,9.30386e-05,9.30556e-05,0.00025642,0.0742536,0.0742452,0.0215797,0.0930481,0.0930459,0.0930386,5.71207e-09,5.71617e-09,9.97516e-09,0,0,8.56431e-08,0,0,0,0,0,0,0,0
10285000,0.982351,-0.00660355,-0.0121208,0.186537,0.0022741,0.0172801,-0.00475442,0.00199996,0.0136119,-0.0501279,-1.59186e-05,-5.83864e-05,3.22987e-06,0,0,-0.00135814,0.203458,0.00195935,0.434775,0,0,0,0,0,9.25434e-06,9.3943e-05,9.39602e-05,0.000255881,0.068365,0.0683571,0.0210369,0.078272,0.0782702,0.0919529,5.63034e-09,5.63435e-09,9.72296e-09,0,0,8.22152e-08,0,0,0,0,0,0,0,0
10385000,0.982375,-0.00660237,-0.0120182,0.186419,0.0069531,0.00288639,-0.00293252,0.000764022,6.91822e-05,-0.0485443,-1.59096e-05,-5.8391e-05,3.56275e-06,0,0,-0.00135918,0.203458,0.00195935,0.434775,0,0,0,0,0,9.23716e-06,0.000100972,0.000100993,0.000255296,0.0348985,0.0348985,0.0374559,0.12528,0.12528,0.0851462,5.6303e-09,5.63435e-09,9.47293e-09,0,0,7.91359e-08,0,0,0,0,0,0,0,0
10485000,0.982357,-0.00650283,-0.0119655,0.18652,0.00697386,0.00323354,-0.00183703,0.00145266,0.000372235,-0.0441115,-1.59239e-05,-5.83716e-05,2.76456e-06,0,0,-0.0013622,0.203458,0.00195935,0.434775,0,0,0,0,0,9.21533e-06,0.000108283,0.000108306,0.000254665,0.0361205,0.0361204,0.0375589,0.126259,0.126259,0.0794979,5.63027e-09,5.63435e-09,9.22552e-09,0,0,7.6535e-08,0,0,0,0,0,0,0,0
10585000,0.982376,-0.00644019,-0.0118923,0.186427,0.00532214,0.00325481,-0.00050772,0.00108861,-0.00317399,-0.0433366,-1.59386e-05,-5.85614e-05,3.33243e-06,0,0,-0.0013625,0.203458,0.00195935,0.434775,0,0,0,0,0,9.20221e-06,0.000115242,0.000115267,0.000253984,0.0333337,0.0333333,0.0352689,0.0848766,0.0848766,0.0751591,5.60278e-09,5.60686e-09,8.98153e-09,0,0,7.43078e-08,0,0,0,0,0,0,0,0
10685000,0.982386,-0.00638705,-0.0119235,0.186373,0.00549718,0.00193789,-0.000363454,0.00162251,-0.002919,-0.0425342,-1.59418e-05,-5.85574e-05,3.16009e-06,0,0,-0.00136303,0.203458,0.00195935,0.434775,0,0,0,0,0,9.28258e-06,0.000123074,0.000123101,0.000256262,0.0361852,0.0361843,0.0353122,0.0866481,0.0866481,0.0734122,5.60278e-09,5.60689e-09,8.80085e-09,0,0,7.28423e-08,0,0,0,0,0,0,0,0
10785000,0.982389,-0.00640039,-0.0120135,0.186349,0.00600021,0.00113392,0.000536427,0.0015024,-0.00252141,-0.0397345,-1.57771e-05,-5.87398e-05,2.9387e-06,0,0,-0.00136465,0.203458,0.00195935,0.434775,0,0,0,0,0,9.25453e-06,0.000128461,0.000128488,0.000255472,0.0347389,0.0347378,0.0331836,0.0658033,0.0658033,0.0707771,5.49808e-09,5.50209e-09,8.56299e-09,0,0,7.11064e-08,0,0,0,0,0,0,0,0
10885000,0.982417,-0.00636907,-0.0120574,0.186202,0.00617936,0.00213903,0.000759117,0.00211361,-0.00241444,-0.0392346,-1.57586e-05,-5.87546e-05,3.74265e-06,0,0,-0.00136478,0.203458,0.00195935,0.434775,0,0,0,0,0,9.23494e-06,0.000136681,0.000136711,0.000254614,0.0392907,0.039289,0.0330581,0.0682749,0.0682748,0.0692415,5.49806e-09,5.5021e-09,8.32896e-09,0,0,6.95923e-08,0,0,0,0,0,0,0,0
10985000,0.982426,-0.00636836,-0.0121468,0.186147,0.0042401,0.00792654,0.00277735,0.00184352,-0.00157113,-0.0365117,-1.57641e-05,-5.89188e-05,3.58897e-06,0,0,-0.00136583,0.203458,0.00195935,0.434775,0,0,0,0,0,9.19974e-06,0.000138759,0.000138786,0.000253722,0.0383542,0.0383528,0.0310438,0.0554735,0.0554735,0.067676,5.27808e-09,5.28189e-09,8.09928e-09,0,0,6.82606e-08,0,0,0,0,0,0,0,0
11085000,0.982378,-0.00648731,-0.0121263,0.1864,0.00469469,0.0112365,0.00467954,0.00226313,-0.000674048,-0.0339174,-1.57853e-05,-5.88984e-05,2.58951e-06,0,0,-0.00136709,0.203458,0.00195935,0.434775,0,0,0,0,0,9.17485e-06,0.000147147,0.000147178,0.00025276,0.0445529,0.0445511,0.0307768,0.0586911,0.0586909,0.0671759,5.27806e-09,5.28191e-09,7.87391e-09,0,0,6.70927e-08,0,0,0,0,0,0,0,0
11185000,0.982373,-0.00655648,-0.0120911,0.186423,0.00454585,0.0127269,0.00792501,0.00274055,-0.000189417,-0.0293297,-1.53861e-05,-5.88817e-05,2.00635e-06,0,0,-0.00136868,0.203458,0.00195935,0.434775,0,0,0,0,0,9.13257e-06,0.00014442,0.00014445,0.000251766,0.0432227,0.043221,0.028873,0.0496993,0.0496992,0.0662102,4.92804e-09,4.93154e-09,7.6532e-09,0,0,6.6061e-08,0,0,0,0,0,0,0,0
11285000,0.982359,-0.00655439,-0.0121216,0.186496,0.00332692,0.0132663,0.00901048,0.00309129,0.00116625,-0.0295709,-1.53938e-05,-5.88766e-05,1.6887e-06,0,0,-0.00136824,0.203458,0.00195935,0.434775,0,0,0,0,0,9.10168e-06,0.000152696,0.000152728,0.000250705,0.0508623,0.0508597,0.0284838,0.0537318,0.0537316,0.0663425,4.92803e-09,4.93156e-09,7.43716e-09,0,0,6.51545e-08,0,0,0,0,0,0,0,0
11385000,0.982358,-0.00653932,-0.0120816,0.186504,0.001938,0.0130202,0.00811902,0.0024837,0.00113376,-0.031451,-1.49797e-05,-5.92227e-05,1.51785e-06,0,0,-0.00136704,0.203458,0.00195935,0.434775,0,0,0,0,0,9.16621e-06,0.000144536,0.000144561,0.000252507,0.048285,0.0482828,0.0268443,0.046623,0.0466227,0.0667863,4.46483e-09,4.46791e-09,7.27805e-09,0,0,6.45453e-08,0,0,0,0,0,0,0,0
11485000,0.982382,-0.00644696,-0.0120552,0.186382,0.000104855,0.0132178,0.00980938,0.00253846,0.00246716,-0.0283071,-1.49761e-05,-5.92238e-05,1.64154e-06,0,0,-0.00136793,0.203458,0.00195935,0.434775,0,0,0,0,0,9.12131e-06,0.000152413,0.000152441,0.000251333,0.0570129,0.0570097,0.0263775,0.051498,0.0514976,0.0672924,4.46483e-09,4.46793e-09,7.07041e-09,0,0,6.38184e-08,0,0,0,0,0,0,0,0
11585000,0.98238,-0.00662519,-0.0120116,0.18639,0.00173464,0.0118426,0.0103248,0.00217201,0.00196057,-0.0270141,-1.44588e-05,-5.94745e-05,1.47562e-06,0,0,-0.00136867,0.203458,0.00195935,0.434775,0,0,0,0,0,9.07583e-06,0.000139342,0.000139364,0.000250111,0.0525736,0.0525712,0.0247216,0.0452097,0.0452094,0.0667581,3.93147e-09,3.93407e-09,6.86771e-09,0,0,6.3175e-08,0,0,0,0,0,0,0,0
11685000,0.982389,-0.0065821,-0.0119552,0.186348,0.00170877,0.0149332,0.0120835,0.0023527,0.00329663,-0.0268237,-1.44573e-05,-5.94765e-05,1.55425e-06,0,0,-0.0013683,0.203458,0.00195935,0.434775,0,0,0,0,0,9.03421e-06,0.00014659,0.000146614,0.000248842,0.0619253,0.0619226,0.0241907,0.0508812,0.0508807,0.0674377,3.93147e-09,3.93409e-09,6.67009e-09,0,0,6.26106e-08,0,0,0,0,0,0,0,0
11785000,0.982415,-0.00681891,-0.011896,0.186206,0.000346436,0.0129996,0.0129017,0.00183889,0.00125808,-0.0241231,-1.34781e-05,-5.99659e-05,2.18128e-06,0,0,-0.00136874,0.203458,0.00195935,0.434775,0,0,0,0,0,8.9883e-06,0.00013011,0.000130127,0.00024752,0.0555157,0.0555139,0.0226672,0.0447873,0.044787,0.0669261,3.38191e-09,3.38404e-09,6.47715e-09,0,0,6.21106e-08,0,0,0,0,0,0,0,0
11885000,0.982408,-0.00689815,-0.0117913,0.186248,0.00263096,0.0138044,0.0119586,0.00191585,0.00255368,-0.0228224,-1.34862e-05,-5.9959e-05,1.81058e-06,0,0,-0.00136879,0.203458,0.00195935,0.434775,0,0,0,0,0,8.94015e-06,0.000136589,0.00013661,0.000246174,0.0651009,0.0650988,0.022103,0.0511431,0.0511426,0.0676471,3.38192e-09,3.38407e-09,6.28964e-09,0,0,6.16726e-08,0,0,0,0,0,0,0,0
11985000,0.982425,-0.00705336,-0.011862,0.186148,0.00432563,0.0138555,0.0110989,0.00279642,0.0011472,-0.0253822,-1.30539e-05,-5.98606e-05,1.93092e-06,0,0,-0.00136793,0.203458,0.00195935,0.434775,0,0,0,0,0,8.98371e-06,0.000118496,0.00011851,0.000247588,0.0569705,0.0569692,0.0208992,0.0448999,0.0448996,0.0682603,2.86124e-09,2.86296e-09,6.15213e-09,0,0,6.13781e-08,0,0,0,0,0,0,0,0
12085000,0.982409,-0.00697065,-0.0119136,0.186231,0.00560668,0.0140327,0.0137143,0.00330128,0.00250278,-0.018659,-1.30588e-05,-5.98541e-05,1.6791e-06,0,0,-0.0013695,0.203458,0.00195935,0.434775,0,0,0,0,0,8.93884e-06,0.000124166,0.000124181,0.000246134,0.0663911,0.0663894,0.0203342,0.0517887,0.0517882,0.0689619,2.86126e-09,2.86299e-09,5.97334e-09,0,0,6.10273e-08,0,0,0,0,0,0,0,0
12185000,0.982404,-0.00690449,-0.01187,0.186264,0.00520268,0.0126124,0.013074,0.00254901,0.00292487,-0.0170384,-1.30213e-05,-6.01355e-05,1.11182e-06,0,0,-0.00136967,0.203458,0.00195935,0.434775,0,0,0,0,0,8.87402e-06,0.000106055,0.000106063,0.000244653,0.0570901,0.0570889,0.0190854,0.0452533,0.045253,0.0683418,2.39797e-09,2.39933e-09,5.79923e-09,0,0,6.07138e-08,0,0,0,0,0,0,0,0
12285000,0.982392,-0.00695586,-0.0118547,0.186324,0.00252793,0.0116177,0.0115123,0.00294601,0.00412962,-0.0164374,-1.30277e-05,-6.013e-05,8.13544e-07,0,0,-0.00136954,0.203458,0.00195935,0.434775,0,0,0,0,0,8.82313e-06,0.000110947,0.000110957,0.000243142,0.0661335,0.0661315,0.0185332,0.052516,0.0525155,0.0689474,2.398e-09,2.39936e-09,5.63039e-09,0,0,6.04406e-08,0,0,0,0,0,0,0,0
12385000,0.982404,-0.00706742,-0.011776,0.186263,0.00146008,0.008536,0.0120194,0.00237299,0.00284769,-0.0193394,-1.26661e-05,-6.03812e-05,6.40439e-07,0,0,-0.0013687,0.203458,0.00195935,0.434775,0,0,0,0,0,8.75702e-06,9.38807e-05,9.38856e-05,0.000241606,0.0561678,0.0561663,0.0174223,0.0456694,0.0456692,0.0682581,2.0029e-09,2.00393e-09,5.46615e-09,0,0,6.01936e-08,0,0,0,0,0,0,0,0
12485000,0.982384,-0.00706924,-0.0117802,0.18637,0.00156012,0.009514,0.0159134,0.00253175,0.0037329,-0.0173053,-1.26705e-05,-6.03771e-05,4.3093e-07,0,0,-0.00136886,0.203458,0.00195935,0.434775,0,0,0,0,0,8.71054e-06,9.80678e-05,9.80737e-05,0.000240039,0.0646285,0.0646268,0.0169,0.0531605,0.0531601,0.0687426,2.00292e-09,2.00398e-09,5.30702e-09,0,0,5.99793e-08,0,0,0,0,0,0,0,0
12585000,0.982362,-0.0072202,-0.0117421,0.186481,0.00471344,0.00347131,0.0175973,0.00368044,0.000972831,-0.016019,-1.20004e-05,-6.0363e-05,1.26099e-07,0,0,-0.00136879,0.203458,0.00195935,0.434775,0,0,0,0,0,8.65588e-06,8.26413e-05,8.26429e-05,0.000238447,0.0545264,0.0545251,0.015921,0.0460549,0.0460546,0.0679878,1.67553e-09,1.67632e-09,5.15238e-09,0,0,5.97811e-08,0,0,0,0,0,0,0,0
12685000,0.982367,-0.00719653,-0.0117531,0.186456,0.00464829,0.0017136,0.0177659,0.00409314,0.00123158,-0.0130871,-1.20027e-05,-6.03607e-05,1.46683e-08,0,0,-0.00136903,0.203458,0.00195935,0.434775,0,0,0,0,0,8.69193e-06,8.62173e-05,8.62192e-05,0.000239462,0.0624221,0.0624203,0.0156029,0.0536576,0.0536572,0.0695318,1.67558e-09,1.67638e-09,5.03954e-09,0,0,5.96544e-08,0,0,0,0,0,0,0,0
12785000,0.982428,-0.00742121,-0.0116434,0.186133,0.00602966,-0.00124889,0.0189569,0.00430057,-0.00209042,-0.0115405,-1.13378e-05,-6.03737e-05,9.52522e-07,0,0,-0.00136885,0.203458,0.00195935,0.434775,0,0,0,0,0,8.62519e-06,7.26049e-05,7.26041e-05,0.00023781,0.0525021,0.052501,0.0147378,0.0463659,0.0463657,0.0686938,1.40834e-09,1.40892e-09,4.89295e-09,0,0,5.94863e-08,0,0,0,0,0,0,0,0
12885000,0.982471,-0.00740835,-0.0115736,0.185906,0.00557862,-0.00267166,0.0198158,0.00491897,-0.00228648,-0.00820342,-1.13273e-05,-6.03829e-05,1.4526e-06,0,0,-0.00136904,0.203458,0.00195935,0.434775,0,0,0,0,0,8.56047e-06,7.56614e-05,7.56615e-05,0.000236152,0.0597869,0.0597855,0.014304,0.0539914,0.053991,0.0689337,1.40837e-09,1.40897e-09,4.75108e-09,0,0,5.93457e-08,0,0,0,0,0,0,0,0
12985000,0.982514,-0.00741433,-0.0115529,0.18568,0.00421322,-0.00105074,0.0202071,0.00375224,-0.00173705,-0.00669357,-1.14603e-05,-6.05316e-05,1.88556e-06,0,0,-0.00136893,0.203458,0.00195935,0.434775,0,0,0,0,0,8.48975e-06,6.38344e-05,6.38312e-05,0.000234478,0.0502674,0.0502665,0.0135532,0.0465901,0.0465899,0.0680531,1.19195e-09,1.19237e-09,4.61341e-09,0,0,5.92018e-08,0,0,0,0,0,0,0,0
13085000,0.982533,-0.00742675,-0.0114722,0.185584,0.00500842,-0.000967515,0.0186491,0.00420973,-0.00179257,-0.00669647,-1.14477e-05,-6.05431e-05,2.49068e-06,0,0,-0.00136852,0.203458,0.00195935,0.434775,0,0,0,0,0,8.43784e-06,6.64571e-05,6.64549e-05,0.000232776,0.0569778,0.0569768,0.0131697,0.054173,0.0541728,0.0681684,1.19199e-09,1.19243e-09,4.48007e-09,0,0,5.90857e-08,0,0,0,0,0,0,0,0
13185000,0.982547,-0.00744864,-0.0114236,0.185514,0.00137026,-0.00276407,0.01779,0.00128284,-0.00299587,-0.00572048,-1.13816e-05,-6.08634e-05,2.83739e-06,0,0,-0.00136835,0.203458,0.00195935,0.434775,0,0,0,0,0,8.37826e-06,5.62622e-05,5.62571e-05,0.000231074,0.0479753,0.0479746,0.0125231,0.0467277,0.0467275,0.0672603,1.01701e-09,1.01732e-09,4.35092e-09,0,0,5.89564e-08,0,0,0,0,0,0,0,0
13285000,0.982553,-0.00746423,-0.0114018,0.185481,0.000198799,-0.00373558,0.0160572,0.00129338,-0.00330556,-0.00505426,-1.1382e-05,-6.08632e-05,2.81867e-06,0,0,-0.00136819,0.203458,0.00195935,0.434775,0,0,0,0,0,8.40403e-06,5.85254e-05,5.85207e-05,0.000231827,0.0541458,0.0541448,0.0123273,0.054224,0.0542238,0.0684345,1.01707e-09,1.01739e-09,4.25683e-09,0,0,5.88846e-08,0,0,0,0,0,0,0,0
13385000,0.982548,-0.00741744,-0.0115138,0.185507,-0.000366005,-0.00241553,0.0151558,0.0010385,-0.00244655,-0.00512329,-1.14917e-05,-6.08343e-05,2.57699e-06,0,0,-0.00136796,0.203458,0.00195935,0.434775,0,0,0,0,0,8.33691e-06,4.97695e-05,4.97617e-05,0.000230085,0.0457023,0.0457017,0.0117663,0.046787,0.0467869,0.067481,8.75342e-10,8.75557e-10,4.13472e-09,0,0,5.87596e-08,0,0,0,0,0,0,0,0
13485000,0.982549,-0.00739244,-0.0114694,0.185503,0.000112184,-0.000682876,0.015952,0.00102395,-0.00255395,-0.00631495,-1.14914e-05,-6.08348e-05,2.59195e-06,0,0,-0.00136756,0.203458,0.00195935,0.434775,0,0,0,0,0,8.27609e-06,5.1734e-05,5.17268e-05,0.000228335,0.0513566,0.0513561,0.0114857,0.0541658,0.0541656,0.0674114,8.7539e-10,8.75617e-10,4.01652e-09,0,0,5.86722e-08,0,0,0,0,0,0,0,0
13585000,0.982526,-0.00740349,-0.011556,0.18562,0.0041803,-0.00115316,0.017368,0.00395581,-0.00210575,-0.00809498,-1.14001e-05,-6.04941e-05,2.36269e-06,0,0,-0.00136705,0.203458,0.00195935,0.434775,0,0,0,0,0,8.21724e-06,4.42212e-05,4.42123e-05,0.000226583,0.0434777,0.0434773,0.0110093,0.0467784,0.0467783,0.0664575,7.60128e-10,7.60276e-10,3.90212e-09,0,0,5.85473e-08,0,0,0,0,0,0,0,0
13685000,0.982561,-0.00734316,-0.0114661,0.185439,0.00343543,-0.00269477,0.0169959,0.00432886,-0.00229946,-0.00564141,-1.13939e-05,-6.04994e-05,2.65574e-06,0,0,-0.00136711,0.203458,0.00195935,0.434775,0,0,0,0,0,8.1479e-06,4.59387e-05,4.59304e-05,0.000224844,0.0486938,0.0486932,0.0107792,0.054019,0.0540188,0.0663207,7.60179e-10,7.60338e-10,3.79141e-09,0,0,5.8468e-08,0,0,0,0,0,0,0,0
13785000,0.982549,-0.00730264,-0.0115863,0.185499,0.0102761,0.000303245,0.0171573,0.00798023,-0.000224326,-0.00602324,-1.14683e-05,-6.00633e-05,2.41055e-06,0,0,-0.00136673,0.203458,0.00195935,0.434775,0,0,0,0,0,8.08374e-06,3.94832e-05,3.94734e-05,0.000223102,0.0413855,0.0413853,0.0103778,0.0467125,0.0467124,0.0653775,6.65865e-10,6.65959e-10,3.68427e-09,0,0,5.83374e-08,0,0,0,0,0,0,0,0
13885000,0.98258,-0.00722862,-0.0115516,0.185339,0.0112432,0.00117311,0.0184337,0.00902804,-0.00012371,-0.00363787,-1.1457e-05,-6.00732e-05,2.94882e-06,0,0,-0.00136676,0.203458,0.00195935,0.434775,0,0,0,0,0,8.02293e-06,4.09961e-05,4.09864e-05,0.000221361,0.0461889,0.0461887,0.0101954,0.0538051,0.053805,0.0651907,6.65919e-10,6.66023e-10,3.58061e-09,0,0,5.82626e-08,0,0,0,0,0,0,0,0
13985000,0.982594,-0.00728767,-0.0113164,0.185279,0.0115597,0.00210248,0.0174635,0.00706891,-0.00156986,-0.00327774,-1.13734e-05,-6.03508e-05,3.30266e-06,0,0,-0.00136653,0.203458,0.00195935,0.434775,0,0,0,0,0,8.0449e-06,3.54316e-05,3.54216e-05,0.000221868,0.0394167,0.039417,0.00996042,0.0466,0.0465999,0.0653169,5.88184e-10,5.8824e-10,3.50501e-09,0,0,5.81413e-08,0,0,0,0,0,0,0,0
14085000,0.982534,-0.00727986,-0.0112487,0.185599,0.00875627,-0.00230022,0.0193418,0.00817373,-0.0016006,-0.00471228,-1.13949e-05,-6.03319e-05,2.27379e-06,0,0,-0.00136619,0.203458,0.00195935,0.434775,0,0,0,0,0,7.98345e-06,3.67737e-05,3.67643e-05,0.000220104,0.0438513,0.0438511,0.00981993,0.0535389,0.0535388,0.0650883,5.88242e-10,5.88306e-10,3.40713e-09,0,0,5.80682e-08,0,0,0,0,0,0,0,0
14185000,0.982495,-0.0072673,-0.011192,0.185811,0.00671554,-0.00102542,0.0183484,0.00767645,-0.001143,-0.00691233,-1.14697e-05,-6.03377e-05,1.6042e-06,0,0,-0.0013654,0.203458,0.00195935,0.434775,0,0,0,0,0,7.92105e-06,3.19611e-05,3.1951e-05,0.000218348,0.0375681,0.037568,0.00953698,0.0464496,0.0464496,0.0641634,5.23671e-10,5.23695e-10,3.31242e-09,0,0,5.79106e-08,0,0,0,0,0,0,0,0
14285000,0.982492,-0.00719466,-0.0111799,0.185831,0.00764412,-0.00159218,0.0172242,0.00826083,-0.00133331,-0.00317873,-1.14696e-05,-6.03376e-05,1.60184e-06,0,0,-0.00136567,0.203458,0.00195935,0.434775,0,0,0,0,0,7.86162e-06,3.31607e-05,3.31505e-05,0.000216599,0.041699,0.0416989,0.00943732,0.0532334,0.0532333,0.0639136,5.23731e-10,5.23764e-10,3.22081e-09,0,0,5.78365e-08,0,0,0,0,0,0,0,0
14385000,0.9825,-0.00727409,-0.011132,0.185785,0.00860828,-0.0042727,0.017282,0.00797527,-0.00253974,0.000386501,-1.13879e-05,-6.04e-05,1.85234e-06,0,0,-0.00136577,0.203458,0.00195935,0.434775,0,0,0,0,0,7.80195e-06,2.89785e-05,2.89679e-05,0.000214853,0.0358666,0.0358665,0.00920448,0.0462685,0.0462685,0.0630176,4.69641e-10,4.69643e-10,3.13207e-09,0,0,5.76592e-08,0,0,0,0,0,0,0,0
14485000,0.982475,-0.00737905,-0.0110956,0.185916,0.006541,-0.00414824,0.0210741,0.00865567,-0.00297017,0.00269828,-1.14e-05,-6.03893e-05,1.27164e-06,0,0,-0.00136588,0.203458,0.00195935,0.434775,0,0,0,0,0,7.73717e-06,3.00577e-05,3.00479e-05,0.000213129,0.0396882,0.039688,0.00914182,0.0528986,0.0528986,0.0627591,4.69704e-10,4.69714e-10,3.04632e-09,0,0,5.75817e-08,0,0,0,0,0,0,0,0
14585000,0.982463,-0.00745025,-0.0109614,0.185984,0.00516354,-0.00393615,0.0197354,0.00558502,-0.00367724,0.000582037,-1.14425e-05,-6.06217e-05,1.1049e-06,0,0,-0.00136526,0.203458,0.00195935,0.434775,0,0,0,0,0,7.75221e-06,2.641e-05,2.63999e-05,0.000213492,0.0342699,0.0342699,0.00903711,0.0460642,0.0460641,0.062882,4.24066e-10,4.24049e-10,2.98381e-09,0,0,5.74039e-08,0,0,0,0,0,0,0,0
14685000,0.982484,-0.00742662,-0.0110153,0.185873,0.00443654,-0.00406599,0.0195111,0.00605742,-0.00405932,0.00109254,-1.14382e-05,-6.06256e-05,1.31776e-06,0,0,-0.00136502,0.203458,0.00195935,0.434775,0,0,0,0,0,7.68784e-06,2.73881e-05,2.73777e-05,0.000211758,0.0378471,0.0378471,0.00900644,0.0525434,0.0525433,0.0626171,4.24132e-10,4.24121e-10,2.90285e-09,0,0,5.73221e-08,0,0,0,0,0,0,0,0
14785000,0.982523,-0.0074363,-0.011003,0.185667,0.00612978,0.0017268,0.0192478,0.00497149,0.000855876,0.00303924,-1.17957e-05,-6.05699e-05,1.73796e-06,0,0,-0.00136521,0.203458,0.00195935,0.434775,0,0,0,0,0,7.62039e-06,2.41901e-05,2.41795e-05,0.000210035,0.0328033,0.0328035,0.00885185,0.0458415,0.0458414,0.0617784,3.8528e-10,3.8525e-10,2.82442e-09,0,0,5.70954e-08,0,0,0,0,0,0,0,0
14885000,0.982561,-0.00736643,-0.0109267,0.185471,0.0047289,-0.000437415,0.0228422,0.00550307,0.000923821,0.00400495,-1.17863e-05,-6.05784e-05,2.19713e-06,0,0,-0.00136497,0.203458,0.00195935,0.434775,0,0,0,0,0,7.55635e-06,2.50812e-05,2.50708e-05,0.000208329,0.036138,0.0361381,0.00885113,0.0521741,0.0521741,0.0615247,3.85347e-10,3.85325e-10,2.74863e-09,0,0,5.7006e-08,0,0,0,0,0,0,0,0
14985000,0.982568,-0.00749384,-0.0108234,0.185439,0.00425314,-0.00183183,0.0256349,0.00444014,-0.000524721,0.00541783,-1.17284e-05,-6.06869e-05,2.41416e-06,0,0,-0.00136426,0.203458,0.00195935,0.434775,0,0,0,0,0,7.49826e-06,2.22655e-05,2.22549e-05,0.000206625,0.0314258,0.0314259,0.00872912,0.0456049,0.0456049,0.0607329,3.52035e-10,3.51987e-10,2.6752e-09,0,0,5.67501e-08,0,0,0,0,0,0,0,0
15085000,0.982568,-0.00743863,-0.0109076,0.185434,0.0042095,-0.00121389,0.0295324,0.0048743,-0.000710392,0.00788977,-1.17292e-05,-6.0686e-05,2.37085e-06,0,0,-0.00136421,0.203458,0.00195935,0.434775,0,0,0,0,0,7.43719e-06,2.30836e-05,2.3072e-05,0.000204945,0.0345542,0.0345545,0.00875482,0.0517946,0.0517946,0.0604977,3.52109e-10,3.52059e-10,2.60423e-09,0,0,5.66511e-08,0,0,0,0,0,0,0,0
15185000,0.982564,-0.00756807,-0.0109678,0.185445,0.00295161,-0.002225,0.0299425,0.00393041,-0.000659958,0.00848918,-1.17633e-05,-6.07348e-05,2.26708e-06,0,0,-0.00136356,0.203458,0.00195935,0.434775,0,0,0,0,0,7.37533e-06,2.05939e-05,2.05816e-05,0.000203276,0.0301615,0.0301617,0.00866014,0.0453578,0.0453578,0.059754,3.23324e-10,3.23255e-10,2.53546e-09,0,0,5.63634e-08,0,0,0,0,0,0,0,0
15285000,0.982584,-0.00767068,-0.0109967,0.185335,0.00279093,-0.00301207,0.029777,0.00423772,-0.000876242,0.00837272,-1.17563e-05,-6.07427e-05,2.65206e-06,0,0,-0.00136297,0.203458,0.00195935,0.434775,0,0,0,0,0,7.38641e-06,2.13484e-05,2.13359e-05,0.000203514,0.0331157,0.033116,0.00878135,0.0514111,0.0514112,0.060443,3.23406e-10,3.23334e-10,2.48538e-09,0,0,5.62833e-08,0,0,0,0,0,0,0,0
15385000,0.982553,-0.00774479,-0.0110156,0.185493,0.00388828,-0.00062891,0.0294587,0.0034667,-0.000573198,0.00765081,-1.1807e-05,-6.07708e-05,2.36235e-06,0,0,-0.00136189,0.203458,0.00195935,0.434775,0,0,0,0,0,7.33088e-06,1.91348e-05,1.91218e-05,0.000201839,0.0290033,0.0290037,0.00870676,0.0451041,0.0451041,0.0597264,2.98337e-10,2.9825e-10,2.42041e-09,0,0,5.59621e-08,0,0,0,0,0,0,0,0
15485000,0.982551,-0.00778621,-0.0109757,0.185507,0.00289084,-0.00310432,0.0294993,0.00379556,-0.000723415,0.00858653,-1.18054e-05,-6.07727e-05,2.45471e-06,0,0,-0.0013615,0.203458,0.00195935,0.434775,0,0,0,0,0,7.27566e-06,1.98339e-05,1.98208e-05,0.000200187,0.031793,0.0317934,0.00877516,0.0510273,0.0510274,0.0595392,2.98414e-10,2.98325e-10,2.35758e-09,0,0,5.58401e-08,0,0,0,0,0,0,0,0
15585000,0.982552,-0.00786264,-0.0109685,0.185499,0.00612597,-0.00532971,0.0291018,0.00567826,-0.00419101,0.00759392,-1.15763e-05,-6.0749e-05,2.68688e-06,0,0,-0.00136041,0.203458,0.00195935,0.434775,0,0,0,0,0,7.22218e-06,1.78562e-05,1.78427e-05,0.000198546,0.0279337,0.0279341,0.00871907,0.0448465,0.0448466,0.058872,2.76419e-10,2.7632e-10,2.2967e-09,0,0,5.54832e-08,0,0,0,0,0,0,0,0
15685000,0.982582,-0.00783096,-0.0109596,0.185342,0.00781993,-0.0085919,0.0295079,0.00636429,-0.0048897,0.00874069,-1.15705e-05,-6.07552e-05,2.99628e-06,0,0,-0.00136001,0.203458,0.00195935,0.434775,0,0,0,0,0,7.16051e-06,1.85076e-05,1.84937e-05,0.00019693,0.0305745,0.0305749,0.00880377,0.0506455,0.0506457,0.0587134,2.76498e-10,2.76397e-10,2.23776e-09,0,0,5.53451e-08,0,0,0,0,0,0,0,0
15785000,0.982618,-0.00785935,-0.0108717,0.185152,0.00521887,-0.00883379,0.0288952,0.00506582,-0.00397044,0.00995316,-1.16693e-05,-6.08097e-05,3.45287e-06,0,0,-0.00135917,0.203458,0.00195935,0.434775,0,0,0,0,0,7.10035e-06,1.67327e-05,1.6719e-05,0.000195332,0.0269469,0.0269472,0.00876214,0.0445873,0.0445874,0.0580945,2.5707e-10,2.56963e-10,2.18068e-09,0,0,5.4951e-08,0,0,0,0,0,0,0,0
15885000,0.98259,-0.00790708,-0.0109185,0.185299,0.00384406,-0.00695127,0.0300838,0.00545061,-0.00476189,0.0101069,-1.16755e-05,-6.08035e-05,3.14026e-06,0,0,-0.00135857,0.203458,0.00195935,0.434775,0,0,0,0,0,7.10931e-06,1.73427e-05,1.73285e-05,0.000195493,0.0294517,0.0294522,0.00893004,0.0502679,0.0502681,0.0588291,2.57154e-10,2.57047e-10,2.13911e-09,0,0,5.48387e-08,0,0,0,0,0,0,0,0
15985000,0.982597,-0.00773663,-0.0108805,0.185268,0.00258364,-0.0055533,0.0266217,0.0044529,-0.00377369,0.00790911,-1.17555e-05,-6.08223e-05,3.06946e-06,0,0,-0.00135655,0.203458,0.00195935,0.434775,0,0,0,0,0,7.04716e-06,1.5743e-05,1.57282e-05,0.000193904,0.0260367,0.0260371,0.00889757,0.0443282,0.0443283,0.0582395,2.39882e-10,2.39771e-10,2.08512e-09,0,0,5.44075e-08,0,0,0,0,0,0,0,0
16085000,0.982601,-0.00770252,-0.010869,0.185249,0.00104946,-0.00684468,0.025202,0.00456951,-0.00441128,0.00946573,-1.17611e-05,-6.08168e-05,2.78297e-06,0,0,-0.00135633,0.203458,0.00195935,0.434775,0,0,0,0,0,6.9816e-06,1.63157e-05,1.63006e-05,0.000192335,0.0284292,0.0284296,0.00900821,0.0498968,0.049897,0.0581513,2.39963e-10,2.39851e-10,2.03284e-09,0,0,5.42369e-08,0,0,0,0,0,0,0,0
16185000,0.98259,-0.00763025,-0.0107998,0.185314,-0.00213035,-0.00521652,0.0241063,0.00254975,-0.0034618,0.00635544,-1.18616e-05,-6.08692e-05,2.45859e-06,0,0,-0.00135464,0.203458,0.00195935,0.434775,0,0,0,0,0,6.9214e-06,1.48665e-05,1.48513e-05,0.00019078,0.0251965,0.0251968,0.00898336,0.0440708,0.0440709,0.057607,2.24507e-10,2.24393e-10,1.98218e-09,0,0,5.37674e-08,0,0,0,0,0,0,0,0
16285000,0.982588,-0.00768414,-0.010731,0.185331,-0.00175851,-0.00681566,0.0236737,0.00233651,-0.00407741,0.00776514,-1.186e-05,-6.08709e-05,2.5471e-06,0,0,-0.0013544,0.203458,0.00195935,0.434775,0,0,0,0,0,6.87008e-06,1.54064e-05,1.53914e-05,0.000189235,0.0274785,0.0274789,0.0091029,0.0495327,0.0495329,0.0575572,2.24589e-10,2.24475e-10,1.93311e-09,0,0,5.3577e-08,0,0,0,0,0,0,0,0
16385000,0.9826,-0.0076408,-0.0107165,0.185266,0.000200093,-0.00611674,0.0242903,0.00318851,-0.0032756,0.00768354,-1.18846e-05,-6.08004e-05,2.82767e-06,0,0,-0.00135339,0.203458,0.00195935,0.434775,0,0,0,0,0,6.81798e-06,1.40884e-05,1.40734e-05,0.000187709,0.0244166,0.0244169,0.00908272,0.0438161,0.0438163,0.0570553,2.10683e-10,2.10569e-10,1.88555e-09,0,0,5.30695e-08,0,0,0,0,0,0,0,0
16485000,0.982599,-0.00774536,-0.0107,0.185269,0.00259175,-0.00773317,0.0261664,0.00332312,-0.00403335,0.0111158,-1.18866e-05,-6.07983e-05,2.71723e-06,0,0,-0.00135362,0.203458,0.00195935,0.434775,0,0,0,0,0,6.76144e-06,1.45995e-05,1.45846e-05,0.000186206,0.0265966,0.0265971,0.00920874,0.0491765,0.0491767,0.0570435,2.10765e-10,2.10652e-10,1.83947e-09,0,0,5.28582e-08,0,0,0,0,0,0,0,0
16585000,0.982599,-0.00774129,-0.0107096,0.185272,0.00672359,-0.00857831,0.029609,0.00299941,-0.00330525,0.0118373,-1.19542e-05,-6.07965e-05,2.6656e-06,0,0,-0.00135284,0.203458,0.00195935,0.434775,0,0,0,0,0,6.76387e-06,1.33961e-05,1.33811e-05,0.000186305,0.0236879,0.0236885,0.00925778,0.0435649,0.0435651,0.0573924,1.98191e-10,1.98078e-10,1.80583e-09,0,0,5.23708e-08,0,0,0,0,0,0,0,0
16685000,0.982612,-0.00780256,-0.0106442,0.1852,0.00794088,-0.0125166,0.0299078,0.00373283,-0.00433935,0.013249,-1.19506e-05,-6.08001e-05,2.85479e-06,0,0,-0.00135242,0.203458,0.00195935,0.434775,0,0,0,0,0,6.71036e-06,1.3881e-05,1.38662e-05,0.00018481,0.0257808,0.0257814,0.00938911,0.0488285,0.0488287,0.0574179,1.98274e-10,1.98162e-10,1.76218e-09,0,0,5.21417e-08,0,0,0,0,0,0,0,0
16785000,0.982634,-0.00767315,-0.0105525,0.185093,0.00956769,-0.0125917,0.0286709,0.00313563,-0.00352441,0.012407,-1.20518e-05,-6.08224e-05,2.97681e-06,0,0,-0.00135087,0.203458,0.00195935,0.434775,0,0,0,0,0,6.6528e-06,1.27769e-05,1.27622e-05,0.000183338,0.0230248,0.0230255,0.00936937,0.0433182,0.0433183,0.0569781,1.8684e-10,1.86728e-10,1.71986e-09,0,0,5.15619e-08,0,0,0,0,0,0,0,0
16885000,0.982677,-0.00764536,-0.0106454,0.184864,0.00837476,-0.012859,0.0299418,0.00402866,-0.00478066,0.0116157,-1.20446e-05,-6.08296e-05,3.35743e-06,0,0,-0.00134978,0.203458,0.00195935,0.434775,0,0,0,0,0,6.59467e-06,1.32391e-05,1.32237e-05,0.000181885,0.0250342,0.0250349,0.00950289,0.0484908,0.048491,0.0570393,1.86924e-10,1.86814e-10,1.67883e-09,0,0,5.1311e-08,0,0,0,0,0,0,0,0
16985000,0.982678,-0.00767889,-0.0106568,0.184853,0.00811294,-0.0132338,0.030068,0.00361066,-0.00392959,0.0106372,-1.21185e-05,-6.07914e-05,3.44444e-06,0,0,-0.00134845,0.203458,0.00195935,0.434775,0,0,0,0,0,6.54407e-06,1.22223e-05,1.22072e-05,0.000180439,0.022407,0.0224075,0.00947987,0.0430766,0.0430767,0.0566272,1.76478e-10,1.7637e-10,1.639e-09,0,0,5.06961e-08,0,0,0,0,0,0,0,0
17085000,0.982672,-0.00778453,-0.0105893,0.184885,0.00902732,-0.0159451,0.0302698,0.0044732,-0.00540434,0.0105004,-1.21206e-05,-6.07896e-05,3.35041e-06,0,0,-0.00134751,0.203458,0.00195935,0.434775,0,0,0,0,0,6.49256e-06,1.26627e-05,1.26479e-05,0.000179017,0.0243458,0.0243464,0.00961367,0.048163,0.0481633,0.0567214,1.76563e-10,1.76456e-10,1.60041e-09,0,0,5.04233e-08,0,0,0,0,0,0,0,0
17185000,0.98263,-0.0078637,-0.0105036,0.185111,0.00859074,-0.0199211,0.0314322,0.00297284,-0.00840549,0.0132046,-1.21109e-05,-6.08393e-05,2.98425e-06,0,0,-0.00134694,0.203458,0.00195935,0.434775,0,0,0,0,0,6.50024e-06,1.17221e-05,1.17078e-05,0.000179072,0.0218379,0.0218384,0.0096574,0.0428408,0.0428409,0.0571474,1.66982e-10,1.66876e-10,1.57223e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
17285000,0.982603,-0.00782164,-0.0104991,0.185258,0.0090231,-0.0207427,0.030956,0.00383807,-0.0104072,0.0137834,-1.2118e-05,-6.08326e-05,2.62943e-06,0,0,-0.00134619,0.203458,0.00195935,0.434775,0,0,0,0,0,6.45016e-06,1.21435e-05,1.21289e-05,0.000177661,0.0237119,0.0237125,0.00979124,0.0478463,0.0478465,0.0572754,1.67068e-10,1.66964e-10,1.53563e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
17385000,0.982644,-0.00777791,-0.0104707,0.18504,0.00581229,-0.0219917,0.030953,0.00508108,-0.00765642,0.014361,-1.22666e-05,-6.07367e-05,2.90991e-06,0,0,-0.00134492,0.203458,0.00195935,0.434775,0,0,0,0,0,6.39264e-06,1.12699e-05,1.12557e-05,0.000176272,0.0213139,0.0213142,0.00975742,0.0426117,0.0426119,0.0569054,1.58239e-10,1.58136e-10,1.50007e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
17485000,0.982635,-0.00778213,-0.0105233,0.185085,0.00350966,-0.0231917,0.0304478,0.00548012,-0.0098874,0.0149038,-1.22694e-05,-6.07342e-05,2.77994e-06,0,0,-0.00134413,0.203458,0.00195935,0.434775,0,0,0,0,0,6.34283e-06,1.1674e-05,1.16593e-05,0.000174898,0.0231274,0.0231277,0.00988861,0.0475408,0.047541,0.0570608,1.58326e-10,1.58224e-10,1.46561e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
17585000,0.982638,-0.00776008,-0.0104598,0.185074,0.00119875,-0.0199052,0.0294591,0.00251408,-0.00811492,0.0130625,-1.24392e-05,-6.07977e-05,2.78947e-06,0,0,-0.00134228,0.203458,0.00195935,0.434775,0,0,0,0,0,6.29327e-06,1.08598e-05,1.08453e-05,0.000173538,0.0208294,0.0208296,0.00984839,0.0423896,0.0423897,0.0567114,1.50164e-10,1.50064e-10,1.43212e-09,0,0,5e-08,0,0,0,0,0,0,0,0
17685000,0.982667,-0.00786134,-0.0103791,0.18492,0.000231721,-0.0209194,0.0307571,0.00260635,-0.0101783,0.0154416,-1.24381e-05,-6.07987e-05,2.84711e-06,0,0,-0.00134207,0.203458,0.00195935,0.434775,0,0,0,0,0,6.23671e-06,1.12471e-05,1.12331e-05,0.000172207,0.0225854,0.0225857,0.00997596,0.0472466,0.0472468,0.0568905,1.50252e-10,1.50152e-10,1.39965e-09,0,0,5e-08,0,0,0,0,0,0,0,0
17785000,0.982713,-0.00786612,-0.0103329,0.184681,0.00212826,-0.0196755,0.0305323,0.00323302,-0.00923477,0.0190631,-1.25456e-05,-6.07183e-05,2.95288e-06,0,0,-0.00134206,0.203458,0.00195935,0.434775,0,0,0,0,0,6.17628e-06,1.04852e-05,1.04715e-05,0.000170894,0.0203801,0.0203804,0.00992883,0.0421746,0.0421748,0.0565575,1.42682e-10,1.42584e-10,1.36809e-09,0,0,5e-08,0,0,0,0,0,0,0,0
17885000,0.982722,-0.00782035,-0.0104395,0.184629,0.0044084,-0.022483,0.0300247,0.00361553,-0.0113605,0.0241015,-1.25444e-05,-6.07192e-05,3.00169e-06,0,0,-0.00134271,0.203458,0.00195935,0.434775,0,0,0,0,0,6.17549e-06,1.08585e-05,1.0844e-05,0.000170924,0.0220898,0.0220902,0.0101282,0.0469639,0.0469641,0.0575736,1.42773e-10,1.42676e-10,1.34505e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
17985000,0.982732,-0.00771869,-0.0104186,0.184581,0.00359474,-0.017746,0.029745,0.00301684,-0.00639336,0.0242174,-1.27909e-05,-6.06536e-05,2.97936e-06,0,0,-0.00134177,0.203458,0.00195935,0.434775,0,0,0,0,0,6.12455e-06,1.0143e-05,1.01287e-05,0.000169616,0.0199657,0.019966,0.0100729,0.0419673,0.0419674,0.0572439,1.35729e-10,1.35633e-10,1.31506e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18085000,0.982735,-0.00781145,-0.0103812,0.184565,0.00382686,-0.0189327,0.0294072,0.00346191,-0.0082561,0.023672,-1.27907e-05,-6.0654e-05,3.00446e-06,0,0,-0.00134059,0.203458,0.00195935,0.434775,0,0,0,0,0,6.07796e-06,1.05018e-05,1.04876e-05,0.000168324,0.0216258,0.0216262,0.0101928,0.0466929,0.0466931,0.0574654,1.35817e-10,1.35723e-10,1.28597e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18185000,0.982777,-0.00782793,-0.0104115,0.184337,0.00338476,-0.0175269,0.030105,0.00383552,-0.00694635,0.0219986,-1.28695e-05,-6.06095e-05,3.43296e-06,0,0,-0.0013387,0.203458,0.00195935,0.434775,0,0,0,0,0,6.02902e-06,9.82788e-06,9.81384e-06,0.000167048,0.0195756,0.0195759,0.0101301,0.0417674,0.0417675,0.057145,1.29247e-10,1.29155e-10,1.25767e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18285000,0.982778,-0.00787179,-0.0103846,0.184331,0.00421654,-0.0189288,0.0294063,0.00415644,-0.0087546,0.0210946,-1.28688e-05,-6.06103e-05,3.48498e-06,0,0,-0.00133735,0.203458,0.00195935,0.434775,0,0,0,0,0,5.98483e-06,1.01738e-05,1.01598e-05,0.000165785,0.0211929,0.0211932,0.0102438,0.0464324,0.0464326,0.0573742,1.29336e-10,1.29246e-10,1.23019e-09,0,0,5e-08,0,0,0,0,0,0,0,0
18385000,0.982761,-0.00779468,-0.0103839,0.184425,0.00422517,-0.0177422,0.029184,0.00541409,-0.0073954,0.020713,-1.29434e-05,-6.05268e-05,3.37959e-06,0,0,-0.00133608,0.203458,0.00195935,0.434775,0,0,0,0,0,5.94303e-06,9.53679e-06,9.52286e-06,0.000164536,0.0192152,0.0192155,0.0101739,0.0415748,0.0415749,0.0570598,1.23194e-10,1.23106e-10,1.20348e-09,0,0,5e-08,0,0,0,0,0,0,0,0
18485000,0.98277,-0.00783682,-0.0103965,0.184374,0.00710053,-0.018125,0.028894,0.00606394,-0.00919619,0.0233882,-1.29404e-05,-6.05296e-05,3.53312e-06,0,0,-0.00133603,0.203458,0.00195935,0.434775,0,0,0,0,0,5.94449e-06,9.87094e-06,9.85683e-06,0.000164546,0.0207937,0.0207942,0.0103635,0.0461834,0.0461836,0.0581362,1.23287e-10,1.23199e-10,1.18398e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
18585000,0.982749,-0.00767702,-0.0102923,0.184497,0.00619929,-0.0172238,0.0285636,0.00511675,-0.0078228,0.0250506,-1.30452e-05,-6.05336e-05,3.42644e-06,0,0,-0.00133519,0.203458,0.00195935,0.434775,0,0,0,0,0,5.90483e-06,9.26684e-06,9.25291e-06,0.00016331,0.0188811,0.0188816,0.0102855,0.0413899,0.0413901,0.0578157,1.17532e-10,1.17447e-10,1.15856e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
18685000,0.982766,-0.00766759,-0.0102416,0.184412,0.0058235,-0.0169337,0.0271027,0.0057237,-0.00953098,0.0245221,-1.30436e-05,-6.05353e-05,3.5253e-06,0,0,-0.00133404,0.203458,0.00195935,0.434775,0,0,0,0,0,5.85863e-06,9.58932e-06,9.57542e-06,0.000162097,0.020423,0.0204235,0.0103896,0.0459452,0.0459454,0.0580673,1.17622e-10,1.17539e-10,1.13385e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18785000,0.982771,-0.00760246,-0.0101386,0.184391,0.00470891,-0.0163077,0.0264372,0.00571567,-0.00814937,0.02123,-1.31246e-05,-6.05044e-05,3.55908e-06,0,0,-0.00133109,0.203458,0.00195935,0.434775,0,0,0,0,0,5.81488e-06,9.01498e-06,9.00154e-06,0.000160898,0.0185674,0.0185678,0.010305,0.0412125,0.0412126,0.0577474,1.12222e-10,1.12141e-10,1.10983e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
18885000,0.982769,-0.00756605,-0.0101521,0.184406,0.00378118,-0.0166837,0.0249813,0.00611418,-0.00985808,0.0182775,-1.31271e-05,-6.05024e-05,3.45661e-06,0,0,-0.00132909,0.203458,0.00195935,0.434775,0,0,0,0,0,5.7704e-06,9.32707e-06,9.31336e-06,0.000159715,0.0200737,0.0200741,0.0104034,0.0457172,0.0457174,0.0580021,1.12313e-10,1.12234e-10,1.08647e-09,0,0,5e-08,0,0,0,0,0,0,0,0
18985000,0.98275,-0.00754817,-0.0102036,0.1845,0.00247472,-0.0162719,0.025485,0.00517587,-0.00841016,0.0210879,-1.32158e-05,-6.04971e-05,3.44931e-06,0,0,-0.00132866,0.203458,0.00195935,0.434775,0,0,0,0,0,5.73392e-06,8.78044e-06,8.76668e-06,0.000158541,0.0182742,0.0182745,0.0103128,0.0410422,0.0410423,0.0576807,1.07237e-10,1.07161e-10,1.06375e-09,0,0,5e-08,0,0,0,0,0,0,0,0
19085000,0.982758,-0.0076313,-0.0102124,0.184457,0.000498986,-0.0170723,0.0260142,0.00536667,-0.010039,0.0173198,-1.3214e-05,-6.0499e-05,3.56909e-06,0,0,-0.00132641,0.203458,0.00195935,0.434775,0,0,0,0,0,5.69314e-06,9.08246e-06,9.06873e-06,0.000157386,0.0197451,0.0197454,0.0104057,0.0454994,0.0454996,0.0579356,1.07329e-10,1.07254e-10,1.04166e-09,0,0,5e-08,0,0,0,0,0,0,0,0
19185000,0.982738,-0.00752401,-0.0103459,0.184562,-0.000790137,-0.01647,0.0260426,0.0045199,-0.0086444,0.0173802,-1.33021e-05,-6.04768e-05,3.34096e-06,0,0,-0.00132541,0.203458,0.00195935,0.434775,0,0,0,0,0,5.69272e-06,8.5609e-06,8.54654e-06,0.000157379,0.0179961,0.0179964,0.0103927,0.0408789,0.040879,0.058453,1.02556e-10,1.02483e-10,1.02549e-09,0,0,5.0002e-08,0,0,0,0,0,0,0,0
19285000,0.982739,-0.00747246,-0.0102976,0.184559,-0.00187321,-0.0171355,0.0264054,0.00442226,-0.0103266,0.0174812,-1.33036e-05,-6.04755e-05,3.27402e-06,0,0,-0.00132451,0.203458,0.00195935,0.434775,0,0,0,0,0,5.64981e-06,8.85325e-06,8.83886e-06,0.000156241,0.0194387,0.0194389,0.0104819,0.0452909,0.0452911,0.0587133,1.02648e-10,1.02576e-10,1.00442e-09,0,0,5.0001e-08,0,0,0,0,0,0,0,0
19385000,0.98274,-0.00756348,-0.0101867,0.184558,-0.00188399,-0.0134334,0.028066,0.00378078,-0.00776835,0.0162587,-1.34134e-05,-6.04361e-05,3.16584e-06,0,0,-0.00132269,0.203458,0.00195935,0.434775,0,0,0,0,0,5.60624e-06,8.35307e-06,8.33953e-06,0.000155119,0.0177335,0.0177338,0.0103797,0.0407221,0.0407222,0.0583747,9.81493e-11,9.808e-11,9.83924e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
19485000,0.982701,-0.00762305,-0.010089,0.184769,-0.00279744,-0.0141383,0.0273638,0.00351206,-0.00914509,0.0160372,-1.34181e-05,-6.04319e-05,2.93812e-06,0,0,-0.00132158,0.203458,0.00195935,0.434775,0,0,0,0,0,5.5727e-06,8.63625e-06,8.62311e-06,0.000154001,0.0191487,0.019149,0.0104639,0.0450912,0.0450913,0.058631,9.82416e-11,9.81735e-11,9.63974e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
19585000,0.982682,-0.00753983,-0.0101908,0.184866,-0.00498769,-0.0158447,0.0287848,0.00377249,-0.00883943,0.0161804,-1.34398e-05,-6.03845e-05,2.87632e-06,0,0,-0.00132024,0.203458,0.00195935,0.434775,0,0,0,0,0,5.53722e-06,8.15739e-06,8.14389e-06,0.000152899,0.0174879,0.0174881,0.0103567,0.0405716,0.0405718,0.0582817,9.40003e-11,9.39347e-11,9.44541e-10,0,0,5e-08,0,0,0,0,0,0,0,0
19685000,0.982698,-0.00756738,-0.0102046,0.18478,-0.0063508,-0.0153389,0.0280331,0.00324067,-0.0104026,0.0160513,-1.34373e-05,-6.0387e-05,3.01735e-06,0,0,-0.00131914,0.203458,0.00195935,0.434775,0,0,0,0,0,5.4974e-06,8.43244e-06,8.41885e-06,0.000151817,0.0188762,0.0188764,0.0104363,0.0449002,0.0449004,0.0585321,9.40929e-11,9.40285e-11,9.25636e-10,0,0,5e-08,0,0,0,0,0,0,0,0
19785000,0.982688,-0.00763414,-0.010194,0.18483,-0.00722471,-0.0132915,0.0268374,0.00525273,-0.00889415,0.0130568,-1.348e-05,-6.02949e-05,2.9265e-06,0,0,-0.00131669,0.203458,0.00195935,0.434775,0,0,0,0,0,5.49713e-06,7.97216e-06,7.95895e-06,0.000151802,0.0172577,0.0172579,0.0104123,0.0404274,0.0404276,0.0590411,9.00928e-11,9.00304e-11,9.11803e-10,0,0,5.0002e-08,0,0,0,0,0,0,0,0
19885000,0.982668,-0.00765004,-0.0102832,0.184928,-0.00699105,-0.0133903,0.0265972,0.00449053,-0.010185,0.0118991,-1.34838e-05,-6.02916e-05,2.74744e-06,0,0,-0.00131531,0.203458,0.00195935,0.434775,0,0,0,0,0,5.45962e-06,8.23936e-06,8.22577e-06,0.000150731,0.0186196,0.0186198,0.0104892,0.0447178,0.044718,0.0592918,9.01858e-11,9.01245e-11,8.93755e-10,0,0,5.0002e-08,0,0,0,0,0,0,0,0
19985000,0.982691,-0.00766718,-0.0104052,0.184803,-0.00741723,-0.0128516,0.0240394,0.00464149,-0.00785877,0.0082414,-1.35554e-05,-6.02181e-05,2.81504e-06,0,0,-0.00131227,0.203458,0.00195935,0.434775,0,0,0,0,0,5.41621e-06,7.79694e-06,7.7832e-06,0.000149678,0.0170397,0.0170398,0.0103743,0.0402894,0.0402895,0.0589199,8.64073e-11,8.63483e-11,8.76165e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
20085000,0.982703,-0.00768044,-0.0104147,0.184736,-0.00696038,-0.0159765,0.0241243,0.00389909,-0.00932668,0.0114385,-1.35556e-05,-6.02178e-05,2.79969e-06,0,0,-0.00131254,0.203458,0.00195935,0.434775,0,0,0,0,0,5.37478e-06,8.05614e-06,8.04232e-06,0.00014864,0.0183789,0.018379,0.0104475,0.0445435,0.0445436,0.0591622,8.65007e-11,8.64427e-11,8.59043e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
20185000,0.982689,-0.0076714,-0.0105118,0.184808,-0.00608668,-0.0134883,0.0249158,0.00490907,-0.00801048,0.0110124,-1.361e-05,-6.01558e-05,2.61025e-06,-5.29974e-11,5.64413e-11,-0.00131117,0.203458,0.00195935,0.434775,0,0,0,0,0,5.33663e-06,7.62973e-06,7.61576e-06,0.00014761,0.0170868,0.017087,0.0103308,0.0401572,0.0401574,0.0587843,8.29306e-11,8.28746e-11,8.42353e-10,4.00001e-06,4.00001e-06,5e-08,0,0,0,0,0,0,0,0
20285000,0.982703,-0.00767085,-0.0105396,0.18473,-0.00922076,-0.014433,0.0252311,0.00417621,-0.00933079,0.0117335,-1.36113e-05,-6.01547e-05,2.55069e-06,3.52332e-09,-3.74905e-09,-0.00131051,0.203458,0.00195935,0.434775,0,0,0,0,0,5.29443e-06,7.88164e-06,7.86751e-06,0.0001466,0.019441,0.0194417,0.0104013,0.0443857,0.0443858,0.0590177,8.30243e-11,8.29693e-11,8.26102e-10,4.00002e-06,4.00002e-06,5e-08,0,0,0,0,0,0,0,0
20385000,0.982699,-0.00760821,-0.0105269,0.184755,-0.010069,-0.01263,0.0242305,0.00506825,-0.00799294,0.0111595,-1.36513e-05,-6.00959e-05,2.7024e-06,-3.88873e-06,-3.10428e-06,-0.00130867,0.203458,0.00195935,0.434775,0,0,0,0,0,5.26413e-06,7.47206e-06,7.45806e-06,0.00014559,0.0194579,0.0194593,0.0102843,0.0400464,0.0400465,0.058634,7.96621e-11,7.9609e-11,8.10255e-10,3.97862e-06,3.97862e-06,5e-08,0,0,0,0,0,0,0,0
20485000,0.982718,-0.00762779,-0.0104971,0.184653,-0.0144545,-0.0141697,0.0248559,0.003818,-0.00930845,0.0108242,-1.36528e-05,-6.00946e-05,2.63541e-06,-3.87099e-06,-3.12253e-06,-0.00130764,0.203458,0.00195935,0.434775,0,0,0,0,0,5.25597e-06,7.71693e-06,7.70295e-06,0.000145576,0.0232545,0.0232569,0.0104413,0.0443218,0.044322,0.0597373,7.97576e-11,7.97052e-11,7.98661e-10,3.97863e-06,3.97863e-06,5.0002e-08,0,0,0,0,0,0,0,0
20585000,0.982754,-0.00758552,-0.0104973,0.184464,-0.0139188,-0.0139205,0.0244757,0.00477727,-0.00801774,0.00917312,-1.3681e-05,-6.00259e-05,2.91534e-06,-1.47034e-05,-7.79515e-06,-0.0013057,0.203458,0.00195935,0.434775,0,0,0,0,0,5.21782e-06,7.33629e-06,7.32242e-06,0.000144586,0.0239058,0.023909,0.0103224,0.0400269,0.040027,0.0593367,7.6659e-11,7.66084e-11,7.83508e-10,3.89655e-06,3.89655e-06,5.0001e-08,0,0,0,0,0,0,0,0
20685000,0.982748,-0.0075179,-0.01049,0.184498,-0.0159908,-0.0134202,0.0254401,0.00332959,-0.00934413,0.00958323,-1.36852e-05,-6.00221e-05,2.7088e-06,-1.46782e-05,-7.82235e-06,-0.00130494,0.203458,0.00195935,0.434775,0,0,0,0,0,5.17906e-06,7.57484e-06,7.56081e-06,0.000143612,0.0289187,0.0289235,0.0103909,0.0444797,0.0444799,0.0595582,7.67533e-11,7.67036e-11,7.68744e-10,3.89656e-06,3.89656e-06,5.0001e-08,0,0,0,0,0,0,0,0
20785000,0.982773,-0.00704411,-0.0104252,0.184389,-0.0171202,-0.00970259,0.0130932,0.0026452,-0.0079356,0.00817562,-1.37206e-05,-5.99752e-05,2.78379e-06,-2.92946e-05,-1.40703e-05,-0.00130326,0.203458,0.00195935,0.434775,0,0,0,0,0,5.14054e-06,7.24456e-06,7.22998e-06,0.00014265,0.0293852,0.0293907,0.0102722,0.0401886,0.0401888,0.0591529,7.40179e-11,7.39698e-11,7.54342e-10,3.73251e-06,3.73252e-06,5.0001e-08,0,0,0,0,0,0,0,0
20885000,0.982836,0.00181178,-0.00675237,0.184347,-0.0234009,0.00152382,-0.100369,0.000551581,-0.00831487,0.00261793,-1.37206e-05,-5.99751e-05,2.78904e-06,-2.92402e-05,-1.41223e-05,-0.00130252,0.203458,0.00195935,0.434775,0,0,0,0,0,5.1042e-06,7.46836e-06,7.45952e-06,0.000141711,0.0354105,0.0354175,0.0103378,0.0449611,0.0449615,0.0593597,7.41119e-11,7.40655e-11,7.40297e-10,3.73252e-06,3.73253e-06,5e-08,0,0,0,0,0,0,0,0
20985000,0.982838,0.00556368,-0.00302306,0.184361,-0.0323192,0.0200383,-0.24161,0.000171631,-0.00633788,-0.0108402,-1.37128e-05,-5.9924e-05,2.74991e-06,-5.02151e-05,-4.20299e-06,-0.00130547,0.203458,0.00195935,0.434775,0,0,0,0,0,5.07062e-06,7.20186e-06,7.20409e-06,0.000140769,0.0349553,0.0349608,0.0102165,0.0405908,0.0405912,0.0589506,7.18148e-11,7.17708e-11,7.26601e-10,3.48862e-06,3.48863e-06,5e-08,0,0,0,0,0,0,0,0
21085000,0.982779,0.00413235,-0.00326332,0.184712,-0.0456296,0.035827,-0.35929,-0.00372227,-0.00349066,-0.0401706,-1.37139e-05,-5.9923e-05,2.69529e-06,-5.02347e-05,-4.18573e-06,-0.0013057,0.203458,0.00195935,0.434775,0,0,0,0,0,5.08733e-06,7.43238e-06,7.43157e-06,0.000140728,0.0414854,0.0414908,0.0103677,0.0457975,0.0457982,0.0600418,7.19107e-11,7.18675e-11,7.16579e-10,3.48863e-06,3.48864e-06,5.0002e-08,0,0,0,0,0,0,0,0
21185000,0.982725,0.00136924,-0.00484624,0.185004,-0.0462009,0.0393833,-0.484309,-0.00272448,-0.00321003,-0.0739986,-1.3623e-05,-5.98635e-05,2.75052e-06,-8.40561e-05,4.91774e-05,-0.00131332,0.203458,0.00195935,0.434775,0,0,0,0,0,5.07141e-06,7.25921e-06,7.25314e-06,0.000139777,0.0394079,0.0394122,0.0102453,0.041216,0.0412165,0.0596169,7.00906e-11,7.00506e-11,7.0346e-10,3.18767e-06,3.1877e-06,5.0002e-08,0,0,0,0,0,0,0,0
21285000,0.982676,-0.000850243,-0.00621809,0.185224,-0.0459965,0.0422641,-0.614355,-0.00736392,0.000887622,-0.130116,-1.3627e-05,-5.986e-05,2.56053e-06,-8.40208e-05,4.91376e-05,-0.0013129,0.203458,0.00195935,0.434775,0,0,0,0,0,5.04487e-06,7.49032e-06,7.48108e-06,0.000138847,0.0460583,0.0460632,0.010308,0.0468728,0.0468736,0.0598117,7.01851e-11,7.01465e-11,6.90665e-10,3.18767e-06,3.1877e-06,5.0001e-08,0,0,0,0,0,0,0,0
21385000,0.982631,-0.00231522,-0.00687507,0.185428,-0.0391078,0.0391149,-0.738633,-0.0056691,0.00453198,-0.191837,-1.36e-05,-5.97986e-05,2.4867e-06,-0.000114489,6.41172e-05,-0.00131879,0.203458,0.00195935,0.434775,0,0,0,0,0,5.0213e-06,7.40475e-06,7.39466e-06,0.000137926,0.0422894,0.042294,0.0101871,0.041974,0.0419746,0.0593844,6.8833e-11,6.87974e-11,6.78178e-10,2.86151e-06,2.86156e-06,5.0001e-08,0,0,0,0,0,0,0,0
21485000,0.982605,-0.00316467,-0.00731601,0.185537,-0.0341407,0.0357176,-0.874034,-0.00940316,0.00830944,-0.276428,-1.35981e-05,-5.97999e-05,2.57744e-06,-0.000114295,6.39831e-05,-0.00131736,0.203458,0.00195935,0.434775,0,0,0,0,0,4.99746e-06,7.63427e-06,7.62375e-06,0.000137018,0.0487422,0.0487478,0.0102493,0.0480309,0.048032,0.0595708,6.89278e-11,6.88936e-11,6.65996e-10,2.86152e-06,2.86156e-06,5e-08,0,0,0,0,0,0,0,0
21585000,0.982607,-0.00359563,-0.00730122,0.185522,-0.0253891,0.032578,-0.997287,-0.00808103,0.0104472,-0.36179,-1.35722e-05,-5.97723e-05,2.63808e-06,-0.000122428,5.78368e-05,-0.00132508,0.203458,0.00195935,0.434775,0,0,0,0,0,4.96672e-06,7.62882e-06,7.61883e-06,0.000136129,0.0435709,0.0435759,0.0101296,0.0427612,0.0427619,0.059142,6.79795e-11,6.79476e-11,6.54106e-10,2.53938e-06,2.53943e-06,5e-08,0,0,0,0,0,0,0,0
21685000,0.982597,-0.00394967,-0.00715241,0.185572,-0.0223987,0.0283485,-1.13068,-0.0104655,0.0135409,-0.475907,-1.35692e-05,-5.97741e-05,2.77906e-06,-0.000122017,5.75712e-05,-0.00132232,0.203458,0.00195935,0.434775,0,0,0,0,0,4.94174e-06,7.85877e-06,7.84956e-06,0.000135247,0.0496147,0.049621,0.0101912,0.0491258,0.049127,0.0593206,6.80745e-11,6.8044e-11,6.42501e-10,2.53938e-06,2.53944e-06,5e-08,0,0,0,0,0,0,0,0
21785000,0.982613,-0.00431215,-0.00725534,0.185474,-0.0126423,0.0244942,-1.25841,-0.0030983,0.0127791,-0.588856,-1.3506e-05,-5.97252e-05,2.98254e-06,-0.000147535,5.02352e-05,-0.00132903,0.203458,0.00195935,0.434775,0,0,0,0,0,4.94174e-06,7.9217e-06,7.91266e-06,0.000135218,0.0435061,0.0435114,0.010159,0.0434919,0.0434928,0.059771,6.74437e-11,6.74146e-11,6.33999e-10,2.24122e-06,2.24128e-06,5.0002e-08,0,0,0,0,0,0,0,0
21885000,0.982607,-0.00460443,-0.00737152,0.185497,-0.00901883,0.0201373,-1.37956,-0.00420478,0.0150562,-0.728379,-1.35091e-05,-5.97215e-05,2.81995e-06,-0.000147221,4.99985e-05,-0.00132648,0.203458,0.00195935,0.434775,0,0,0,0,0,4.90705e-06,8.15556e-06,8.14659e-06,0.000134356,0.0490301,0.0490365,0.0102211,0.0500569,0.0500584,0.0599476,6.75389e-11,6.75111e-11,6.2287e-10,2.24122e-06,2.24128e-06,5.0001e-08,0,0,0,0,0,0,0,0
21985000,0.982623,-0.00528914,-0.00766641,0.185379,-0.00779929,0.0169844,-1.36757,-0.000178892,0.0125949,-0.863528,-1.34463e-05,-5.96927e-05,2.87342e-06,-0.000132551,2.57446e-05,-0.001331,0.203458,0.00195935,0.434775,0,0,0,0,0,4.87185e-06,8.27191e-06,8.26319e-06,0.000133505,0.0424307,0.0424361,0.0101016,0.0441086,0.0441096,0.059505,6.71375e-11,6.71112e-11,6.12004e-10,1.97704e-06,1.97711e-06,5.0001e-08,0,0,0,0,0,0,0,0
22085000,0.982616,-0.00603391,-0.00845715,0.185359,-0.00467532,0.0133698,-1.34826,-0.00086957,0.0140713,-1.00534,-1.3443e-05,-5.96947e-05,3.02662e-06,-0.000132186,2.55344e-05,-0.00132869,0.203458,0.00195935,0.434775,0,0,0,0,0,4.84483e-06,8.51185e-06,8.50208e-06,0.000132654,0.0473863,0.0473928,0.0101632,0.0507579,0.0507595,0.0596747,6.72334e-11,6.72075e-11,6.01391e-10,1.97704e-06,1.97712e-06,5.0001e-08,0,0,0,0,0,0,0,0
22185000,0.982632,-0.00647854,-0.00875477,0.185244,0.00133503,0.0100641,-1.36317,0.00572812,0.0101434,-1.1466,-1.33643e-05,-5.96548e-05,3.14493e-06,-0.000125836,4.40457e-06,-0.00132644,0.203458,0.00195935,0.434775,0,0,0,0,0,4.81218e-06,8.66894e-06,8.65901e-06,0.000131821,0.0407381,0.0407437,0.0100449,0.0445825,0.0445837,0.0592273,6.69981e-11,6.69725e-11,5.91021e-10,1.7477e-06,1.74778e-06,5e-08,0,0,0,0,0,0,0,0
22285000,0.98262,-0.00720593,-0.00899444,0.185268,0.00730874,0.00497824,-1.36118,0.00614179,0.0109362,-1.28912,-1.33656e-05,-5.96523e-05,3.05717e-06,-0.000125526,4.18874e-06,-0.00132426,0.203458,0.00195935,0.434775,0,0,0,0,0,4.78119e-06,8.91238e-06,8.9031e-06,0.000130997,0.0451729,0.0451797,0.0101065,0.0512351,0.0512369,0.0593908,6.70942e-11,6.7069e-11,5.80896e-10,1.7477e-06,1.74778e-06,5e-08,0,0,0,0,0,0,0,0
22385000,0.982754,-0.00758158,-0.00918538,0.184534,0.00918722,-0.00392521,-1.36307,0.0115677,0.00180938,-1.43346,-1.32829e-05,-5.96124e-05,2.99725e-06,-9.91456e-05,-1.74772e-06,-0.00132035,0.204284,0.00196732,0.43436,0,0,0,0,0,7.97548e-05,9.24725e-06,9.17893e-06,0.00227958,0.038721,0.0387268,0.0100764,0.0449112,0.0449126,0.0598323,6.69672e-11,6.6942e-11,5.75969e-10,1.5522e-06,1.55229e-06,5.0002e-08,0,0,0,0,0,0,0,0
22485000,0.982448,-0.00774155,-0.00962932,0.186129,0.013706,-0.0104026,-1.36781,0.0126943,0.00107957,-1.57477,-1.32825e-05,-5.96117e-05,3.00014e-06,-9.88998e-05,-1.90791e-06,-0.00131867,0.204284,0.00196732,0.43436,0,0,0,0,0,5.62001e-05,9.25976e-06,9.20122e-06,0.00160596,0.0428419,0.0428487,0.0101371,0.0514763,0.0514782,0.0599948,6.70671e-11,6.70419e-11,5.76066e-10,1.5522e-06,1.55229e-06,5.0002e-08,0,0,0,0,0,0,0,0
22585000,0.982551,-0.00760369,-0.0102135,0.185556,0.0223618,-0.0166368,-1.36755,0.0244845,-0.00657335,-1.71762,-1.31924e-05,-5.95686e-05,3.0061e-06,-0.000104965,-1.29283e-05,-0.00131591,0.204284,0.00196732,0.43436,0,0,0,0,0,4.34454e-05,9.29969e-06,9.23536e-06,0.00123962,0.0370466,0.0370525,0.0100196,0.0450825,0.045084,0.0595374,6.69935e-11,6.69683e-11,5.76159e-10,1.37959e-06,1.37968e-06,5.0001e-08,0,0,0,0,0,0,0,0
22685000,0.982495,-0.00753692,-0.0104117,0.185843,0.0246769,-0.0214839,-1.371,0.026828,-0.00852594,-1.86148,-1.31917e-05,-5.95674e-05,3.00952e-06,-0.00010461,-1.31628e-05,-0.00131348,0.204284,0.00196732,0.43436,0,0,0,0,0,3.54211e-05,9.34421e-06,9.28557e-06,0.00100941,0.041062,0.041069,0.0100823,0.0514917,0.0514939,0.0596941,6.70935e-11,6.70682e-11,5.76251e-10,1.37959e-06,1.37969e-06,5.0001e-08,0,0,0,0,0,0,0,0
22785000,0.982446,-0.00748589,-0.0108012,0.186082,0.0279745,-0.0273817,-1.3751,0.0356089,-0.0174513,-2.00942,-1.3083e-05,-5.95005e-05,3.01451e-06,-8.71829e-05,-3.24348e-05,-0.00130887,0.204284,0.00196732,0.43436,0,0,0,0,0,2.98075e-05,9.39308e-06,9.33475e-06,0.000851441,0.0357671,0.0357733,0.0099684,0.0451146,0.0451163,0.0592393,6.69986e-11,6.69733e-11,5.76337e-10,1.22419e-06,1.22428e-06,5e-08,0,0,0,0,0,0,0,0
22885000,0.982605,-0.00767805,-0.0111284,0.185214,0.031124,-0.0321496,-1.37695,0.0385233,-0.0203476,-2.15369,-1.30821e-05,-5.94995e-05,3.02591e-06,-8.68643e-05,-3.26768e-05,-0.00130653,0.204284,0.00196732,0.43436,0,0,0,0,0,2.56877e-05,9.4569e-06,9.40222e-06,0.000736311,0.0396462,0.0396537,0.0100331,0.0513835,0.051386,0.0593911,6.70985e-11,6.70732e-11,5.7642e-10,1.22419e-06,1.22429e-06,5e-08,0,0,0,0,0,0,0,0
22985000,0.982736,-0.00761514,-0.0114969,0.184498,0.0326747,-0.0356575,-1.38128,0.047143,-0.0300626,-2.30588,-1.29644e-05,-5.94221e-05,3.04262e-06,-6.76067e-05,-5.22439e-05,-0.00130061,0.204284,0.00196732,0.43436,0,0,0,0,0,2.2554e-05,9.50678e-06,9.45209e-06,0.000648658,0.0346994,0.0347063,0.00992272,0.0450563,0.0450582,0.0589397,6.69425e-11,6.69173e-11,5.76496e-10,1.08552e-06,1.08561e-06,5e-08,0,0,0,0,0,0,0,0
23085000,0.982793,-0.00762942,-0.0118151,0.184177,0.036458,-0.0405781,-1.37859,0.0505838,-0.0339036,-2.44517,-1.29642e-05,-5.94218e-05,3.04269e-06,-6.7543e-05,-5.22852e-05,-0.00130017,0.204284,0.00196732,0.43436,0,0,0,0,0,2.06291e-05,9.58335e-06,9.52864e-06,0.000595602,0.0384139,0.0384222,0.0100752,0.0512013,0.0512041,0.0599736,6.70425e-11,6.70172e-11,5.76575e-10,1.08552e-06,1.08562e-06,5.0002e-08,0,0,0,0,0,0,0,0
23185000,0.982783,-0.00759195,-0.0120053,0.184215,0.0412109,-0.0403987,-1.38191,0.061635,-0.0436812,-2.59247,-1.28672e-05,-5.93484e-05,3.04094e-06,-5.66157e-05,-6.25834e-05,-0.00129578,0.204284,0.00196732,0.43436,0,0,0,0,0,1.85434e-05,9.6291e-06,9.57689e-06,0.00053701,0.0337205,0.0337285,0.00996598,0.0449426,0.0449447,0.0595128,6.6813e-11,6.67879e-11,5.76639e-10,9.63027e-07,9.63112e-07,5.0001e-08,0,0,0,0,0,0,0,0
23285000,0.982832,-0.00806825,-0.0121326,0.183929,0.0450782,-0.0451126,-1.37785,0.0658791,-0.0479996,-2.73672,-1.28662e-05,-5.93472e-05,3.04769e-06,-5.63239e-05,-6.28096e-05,-0.00129359,0.204284,0.00196732,0.43436,0,0,0,0,0,1.68534e-05,9.71024e-06,9.665e-06,0.000488947,0.0372475,0.0372571,0.0100352,0.0509775,0.0509806,0.0596622,6.69129e-11,6.68878e-11,5.76697e-10,9.63028e-07,9.63118e-07,5.0001e-08,0,0,0,0,0,0,0,0
23385000,0.982797,-0.00804523,-0.0122411,0.18411,0.0491658,-0.0440277,-1.37927,0.0767793,-0.0516793,-2.87749,-1.27445e-05,-5.93058e-05,3.03358e-06,-5.77201e-05,-9.14896e-05,-0.00129207,0.204284,0.00196732,0.43436,0,0,0,0,0,1.54373e-05,9.7545e-06,9.71178e-06,0.000448831,0.032754,0.0327624,0.0099291,0.0447968,0.0447992,0.0592063,6.66147e-11,6.65899e-11,5.76745e-10,8.55923e-07,8.56002e-07,5.0001e-08,0,0,0,0,0,0,0,0
23485000,0.982845,-0.00813989,-0.0125072,0.183827,0.0526419,-0.0454988,-1.38094,0.0818295,-0.0561862,-3.02121,-1.27434e-05,-5.93048e-05,3.04676e-06,-5.74855e-05,-9.17093e-05,-0.00129005,0.204284,0.00196732,0.43436,0,0,0,0,0,1.42646e-05,9.84685e-06,9.80517e-06,0.000414821,0.0360821,0.0360922,0.00999905,0.0507312,0.0507347,0.0593481,6.67146e-11,6.66897e-11,5.76784e-10,8.55924e-07,8.56007e-07,5e-08,0,0,0,0,0,0,0,0
23585000,0.982872,-0.00839425,-0.0124491,0.183676,0.0527932,-0.0479208,-1.38041,0.0886801,-0.0665895,-3.1671,-1.26716e-05,-5.92264e-05,3.05633e-06,-3.834e-05,-9.79129e-05,-0.00128714,0.204284,0.00196732,0.43436,0,0,0,0,0,1.32547e-05,9.89006e-06,9.85353e-06,0.000385646,0.0317589,0.0317678,0.0098957,0.044633,0.0446356,0.0588977,6.63624e-11,6.63379e-11,5.76812e-10,7.6319e-07,7.63261e-07,5e-08,0,0,0,0,0,0,0,0
23685000,0.982881,-0.0090279,-0.0129411,0.183567,0.0506256,-0.0500456,-1.28445,0.0938645,-0.0715534,-3.30508,-1.26709e-05,-5.92259e-05,3.06481e-06,-3.82244e-05,-9.80282e-05,-0.00128605,0.204284,0.00196732,0.43436,0,0,0,0,0,1.25978e-05,9.99469e-06,9.95917e-06,0.000366404,0.0348293,0.0348392,0.010053,0.0504721,0.0504759,0.0599281,6.64623e-11,6.64378e-11,5.76851e-10,7.63193e-07,7.63267e-07,5.0002e-08,0,0,0,0,0,0,0,0
23785000,0.98287,-0.010816,-0.0156194,0.183316,0.0463738,-0.044875,-0.967204,0.104005,-0.0754629,-3.42799,-1.25751e-05,-5.92024e-05,3.08284e-06,-4.1589e-05,-0.0001162,-0.00128151,0.204284,0.00196732,0.43436,0,0,0,0,0,1.18173e-05,1.00694e-05,1.00206e-05,0.000343487,0.0305325,0.0305409,0.009949,0.0444568,0.0444597,0.0594701,6.60718e-11,6.60476e-11,5.76859e-10,6.83486e-07,6.83549e-07,5.0002e-08,0,0,0,0,0,0,0,0
23885000,0.982779,-0.0141661,-0.0197454,0.183178,0.041215,-0.0440499,-0.536667,0.108351,-0.0798612,-3.5064,-1.25745e-05,-5.92017e-05,3.08374e-06,-4.14459e-05,-0.00011631,-0.0012804,0.204284,0.00196732,0.43436,0,0,0,0,0,1.1112e-05,1.02234e-05,1.01554e-05,0.000323289,0.0332136,0.0332238,0.0100214,0.0501921,0.0501962,0.059614,6.61716e-11,6.61473e-11,5.76855e-10,6.83487e-07,6.83555e-07,5.0001e-08,0,0,0,0,0,0,0,0
23985000,0.982714,-0.0164348,-0.0222222,0.183054,0.0429585,-0.0408754,-0.152504,0.117088,-0.0817828,-3.57481,-1.2491e-05,-5.91776e-05,3.0766e-06,-4.48364e-05,-0.000132085,-0.00125699,0.204284,0.00196732,0.43436,0,0,0,0,0,1.04814e-05,1.03157e-05,1.02393e-05,0.000305392,0.0291182,0.0291279,0.00992007,0.0442654,0.0442686,0.0591623,6.57422e-11,6.57183e-11,5.76838e-10,6.14712e-07,6.14772e-07,5.0001e-08,0,0,0,0,0,0,0,0
24085000,0.982743,-0.0160773,-0.021295,0.18304,0.048608,-0.0483465,0.091806,0.121609,-0.0862001,-3.57824,-1.24907e-05,-5.91767e-05,3.06457e-06,-4.46946e-05,-0.000132161,-0.00125617,0.204284,0.00196732,0.43436,0,0,0,0,0,9.91957e-06,1.04154e-05,1.03509e-05,0.000289476,0.0316546,0.0316666,0.00999484,0.0498902,0.0498948,0.059306,6.5842e-11,6.5818e-11,5.76806e-10,6.14714e-07,6.14777e-07,5e-08,0,0,0,0,0,0,0,0
24185000,0.982863,-0.0132914,-0.0176329,0.183008,0.0596137,-0.0531238,0.0841572,0.129695,-0.0908798,-3.59454,-1.24422e-05,-5.91453e-05,3.06704e-06,-4.28882e-05,-0.000139323,-0.0012373,0.204284,0.00196732,0.43436,0,0,0,0,0,9.43412e-06,1.04498e-05,1.04057e-05,0.000275207,0.0279389,0.0279496,0.00989669,0.0440592,0.0440627,0.0588609,6.53947e-11,6.5371e-11,5.7676e-10,5.55692e-07,5.55749e-07,5e-08,0,0,0,0,0,0,0,0
24285000,0.982961,-0.0108518,-0.0141523,0.182947,0.0626373,-0.0564765,0.0589526,0.135852,-0.0964141,-3.59078,-1.24416e-05,-5.91448e-05,3.07209e-06,-4.27813e-05,-0.000139424,-0.00123634,0.204284,0.00196732,0.43436,0,0,0,0,0,8.98921e-06,1.0544e-05,1.05162e-05,0.000262319,0.0303952,0.0304072,0.00997273,0.049582,0.0495871,0.059005,6.54945e-11,6.54707e-11,5.76698e-10,5.55694e-07,5.55754e-07,5e-08,0,0,0,0,0,0,0,0
24385000,0.983026,-0.00993814,-0.0130641,0.18273,0.0569377,-0.0501547,0.0753723,0.143599,-0.0969754,-3.58704,-1.23792e-05,-5.91563e-05,3.09105e-06,-4.85365e-05,-0.000154058,-0.00123518,0.204284,0.00196732,0.43436,0,0,0,0,0,8.68236e-06,1.06174e-05,1.05934e-05,0.000253521,0.0268493,0.0268589,0.00995877,0.0438443,0.0438482,0.0594366,6.50682e-11,6.50448e-11,5.76665e-10,5.05937e-07,5.0599e-07,5.0002e-08,0,0,0,0,0,0,0,0
24485000,0.983067,-0.0101598,-0.0131272,0.182494,0.0512199,-0.0457647,0.0735029,0.148988,-0.10176,-3.57921,-1.23786e-05,-5.91572e-05,3.1252e-06,-4.8637e-05,-0.000154075,-0.00123528,0.204284,0.00196732,0.43436,0,0,0,0,0,8.31261e-06,1.07515e-05,1.07287e-05,0.000242582,0.0291186,0.0291292,0.0100363,0.0492642,0.0492696,0.0595856,6.51679e-11,6.51444e-11,5.76574e-10,5.05939e-07,5.05996e-07,5.0001e-08,0,0,0,0,0,0,0,0
24585000,0.983027,-0.0108637,-0.0132287,0.18266,0.0488477,-0.0404742,0.0688348,0.15406,-0.0987676,-3.57358,-1.23217e-05,-5.91884e-05,3.12245e-06,-5.64231e-05,-0.000169925,-0.00123409,0.204284,0.00196732,0.43436,0,0,0,0,0,7.98653e-06,1.08368e-05,1.08176e-05,0.000232575,0.0257595,0.0257681,0.00993889,0.0436209,0.043625,0.0591406,6.47727e-11,6.47495e-11,5.76465e-10,4.64187e-07,4.64239e-07,5.0001e-08,0,0,0,0,0,0,0,0
24685000,0.983012,-0.01138,-0.0130581,0.18272,0.045477,-0.0392013,0.0679682,0.158825,-0.102686,-3.56682,-1.23217e-05,-5.91883e-05,3.12017e-06,-5.64107e-05,-0.000169931,-0.00123403,0.204284,0.00196732,0.43436,0,0,0,0,0,7.67831e-06,1.09777e-05,1.09625e-05,0.000223412,0.027862,0.0278714,0.010017,0.0489356,0.0489412,0.0592907,6.48724e-11,6.48491e-11,5.76337e-10,4.64189e-07,4.64244e-07,5.0001e-08,0,0,0,0,0,0,0,0
24785000,0.983039,-0.0115306,-0.0124191,0.182612,0.0428539,-0.0362014,0.0602403,0.16213,-0.0991174,-3.5644,-1.22763e-05,-5.91968e-05,3.12726e-06,-5.91337e-05,-0.000183488,-0.00123308,0.204284,0.00196732,0.43436,0,0,0,0,0,7.38448e-06,1.10629e-05,1.10525e-05,0.000214999,0.024681,0.0246884,0.00992011,0.0433877,0.0433919,0.058847,6.45178e-11,6.44947e-11,5.76188e-10,4.29357e-07,4.29409e-07,5e-08,0,0,0,0,0,0,0,0
24885000,0.983043,-0.0113745,-0.0119085,0.182635,0.0399183,-0.0390744,0.0499173,0.166291,-0.102887,-3.56127,-1.22755e-05,-5.91965e-05,3.13989e-06,-5.90595e-05,-0.000183582,-0.00123225,0.204284,0.00196732,0.43436,0,0,0,0,0,7.12654e-06,1.12107e-05,1.12024e-05,0.000207226,0.0266335,0.0266415,0.00999854,0.0485949,0.0486005,0.058998,6.46175e-11,6.45943e-11,5.76021e-10,4.2936e-07,4.29414e-07,5e-08,0,0,0,0,0,0,0,0
24985000,0.983026,-0.0111819,-0.0116724,0.182752,0.032492,-0.0337716,0.0424305,0.167421,-0.0946959,-3.55881,-1.22157e-05,-5.92216e-05,3.14124e-06,-6.42948e-05,-0.000202367,-0.00123173,0.204284,0.00196732,0.43436,0,0,0,0,0,6.95357e-06,1.13027e-05,1.12946e-05,0.000201889,0.0236272,0.0236335,0.00998708,0.0431437,0.0431479,0.0594366,6.43097e-11,6.42869e-11,5.75907e-10,4.00464e-07,4.00515e-07,5.0002e-08,0,0,0,0,0,0,0,0
25085000,0.983025,-0.0115212,-0.0117279,0.182733,0.0283448,-0.0326835,0.0393103,0.170389,-0.0980629,-3.56064,-1.22144e-05,-5.92199e-05,3.13587e-06,-6.40438e-05,-0.000202577,-0.00122967,0.204284,0.00196732,0.43436,0,0,0,0,0,6.71827e-06,1.14616e-05,1.14547e-05,0.000195104,0.0254337,0.0254406,0.0100668,0.0482415,0.048247,0.0595935,6.44094e-11,6.43865e-11,5.75702e-10,4.00467e-07,4.0052e-07,5.0002e-08,0,0,0,0,0,0,0,0
25185000,0.982978,-0.0117705,-0.0115731,0.182982,0.024927,-0.0265671,0.0393177,0.17219,-0.0910699,-3.55842,-1.21867e-05,-5.92526e-05,3.116e-06,-7.07457e-05,-0.000213948,-0.00122839,0.204284,0.00196732,0.43436,0,0,0,0,0,6.51466e-06,1.15574e-05,1.15521e-05,0.000188787,0.0225959,0.0226014,0.00997025,0.0428882,0.0428924,0.0591501,6.4151e-11,6.41283e-11,5.75475e-10,3.76603e-07,3.76655e-07,5.0001e-08,0,0,0,0,0,0,0,0
25285000,0.982932,-0.0119203,-0.0109287,0.183257,0.0188882,-0.0274631,0.0340868,0.174346,-0.093749,-3.55588,-1.21872e-05,-5.92514e-05,3.07712e-06,-7.06423e-05,-0.000213968,-0.00122802,0.204284,0.00196732,0.43436,0,0,0,0,0,6.32138e-06,1.17213e-05,1.17195e-05,0.000182913,0.0242744,0.0242804,0.0100502,0.0478748,0.0478801,0.0593082,6.42507e-11,6.42279e-11,5.75225e-10,3.76606e-07,3.7666e-07,5.0001e-08,0,0,0,0,0,0,0,0
25385000,0.982934,-0.0120792,-0.0107391,0.183248,0.0118948,-0.0203666,0.0323576,0.171499,-0.0836726,-3.55679,-1.21351e-05,-5.927e-05,3.07757e-06,-7.33679e-05,-0.000230298,-0.00122587,0.204284,0.00196732,0.43436,0,0,0,0,0,6.13349e-06,1.18206e-05,1.18199e-05,0.000177438,0.0216052,0.02161,0.00995439,0.042621,0.042625,0.0588713,6.40425e-11,6.40199e-11,5.74951e-10,3.56996e-07,3.57049e-07,5e-08,0,0,0,0,0,0,0,0
25485000,0.982926,-0.0121248,-0.0104376,0.183303,0.00562891,-0.0191813,0.0314405,0.172313,-0.0856456,-3.55547,-1.21349e-05,-5.92692e-05,3.06207e-06,-7.32723e-05,-0.000230361,-0.00122523,0.204284,0.00196732,0.43436,0,0,0,0,0,5.95819e-06,1.19943e-05,1.19947e-05,0.000172322,0.0231639,0.0231692,0.0100342,0.0474955,0.0475005,0.0590305,6.41421e-11,6.41194e-11,5.74653e-10,3.56999e-07,3.57054e-07,5e-08,0,0,0,0,0,0,0,0
25585000,0.982914,-0.01236,-0.0102561,0.183365,0.00187223,-0.0167842,0.0331905,0.169932,-0.0794216,-3.55389,-1.21268e-05,-5.92828e-05,3.04142e-06,-7.52948e-05,-0.000237018,-0.00122452,0.204284,0.00196732,0.43436,0,0,0,0,0,5.79348e-06,1.20967e-05,1.20983e-05,0.000167531,0.0206563,0.0206606,0.00993897,0.0423424,0.0423462,0.0585998,6.39829e-11,6.39604e-11,5.7433e-10,3.40965e-07,3.4102e-07,5e-08,0,0,0,0,0,0,0,0
25685000,0.982927,-0.011841,-0.009953,0.183344,0.000425134,-0.0161384,0.0223061,0.170044,-0.0811005,-3.55399,-1.21259e-05,-5.92822e-05,3.04856e-06,-7.51871e-05,-0.00023713,-0.0012235,0.204284,0.00196732,0.43436,0,0,0,0,0,5.68209e-06,1.22787e-05,1.2279e-05,0.000164273,0.0221147,0.0221192,0.0101032,0.0471048,0.0471094,0.0596362,6.40826e-11,6.406e-11,5.74095e-10,3.40971e-07,3.41026e-07,5.0002e-08,0,0,0,0,0,0,0,0
25785000,0.982946,-0.0116481,-0.00925596,0.183291,-0.0093859,-0.00932842,0.0210416,0.164296,-0.073443,-3.55692,-1.21017e-05,-5.92912e-05,3.04758e-06,-7.52702e-05,-0.000246261,-0.0012214,0.204284,0.00196732,0.43436,0,0,0,0,0,5.53198e-06,1.23818e-05,1.23833e-05,0.000159996,0.0197638,0.0197675,0.0100068,0.0420532,0.0420567,0.0591987,6.39706e-11,6.39481e-11,5.73726e-10,3.27942e-07,3.27997e-07,5.0001e-08,0,0,0,0,0,0,0,0
25885000,0.982916,-0.0117126,-0.00929914,0.183444,-0.0164077,-0.00714351,0.0234234,0.16294,-0.0742411,-3.55574,-1.21026e-05,-5.92895e-05,2.98666e-06,-7.51607e-05,-0.000246286,-0.00122102,0.204284,0.00196732,0.43436,0,0,0,0,0,5.39253e-06,1.25725e-05,1.25737e-05,0.000155973,0.0211214,0.0211256,0.0100872,0.0467043,0.0467085,0.0593648,6.40701e-11,6.40476e-11,5.73331e-10,3.27945e-07,3.28002e-07,5.0001e-08,0,0,0,0,0,0,0,0
25985000,0.98291,-0.0118451,-0.00946947,0.18346,-0.0243624,-0.00235343,0.0166084,0.152758,-0.0670931,-3.55607,-1.2081e-05,-5.92755e-05,2.97171e-06,-7.07558e-05,-0.000254458,-0.0012197,0.204284,0.00196732,0.43436,0,0,0,0,0,5.26176e-06,1.26802e-05,1.26806e-05,0.000152183,0.0189226,0.0189259,0.009991,0.0417547,0.0417579,0.0589331,6.40011e-11,6.39788e-11,5.72907e-10,3.17418e-07,3.17474e-07,5.0001e-08,0,0,0,0,0,0,0,0
26085000,0.982943,-0.0115499,-0.00942197,0.183305,-0.0297601,-0.00174711,0.0149582,0.150027,-0.0672876,-3.55651,-1.20798e-05,-5.92756e-05,3.00492e-06,-7.07073e-05,-0.000254545,-0.00121898,0.204284,0.00196732,0.43436,0,0,0,0,0,5.13636e-06,1.28782e-05,1.28774e-05,0.000148616,0.0201993,0.020203,0.01007,0.0462961,0.0462999,0.0590945,6.41006e-11,6.40782e-11,5.72455e-10,3.17422e-07,3.17478e-07,5e-08,0,0,0,0,0,0,0,0
26185000,0.98294,-0.0115245,-0.00994349,0.183298,-0.0355138,0.00199798,0.0104829,0.141267,-0.0630342,-3.55991,-1.20767e-05,-5.92738e-05,3.02669e-06,-6.87633e-05,-0.000257645,-0.00121712,0.204284,0.00196732,0.43436,0,0,0,0,0,5.02442e-06,1.29874e-05,1.29842e-05,0.000145241,0.0181389,0.0181419,0.00997408,0.0414484,0.0414513,0.0586683,6.40708e-11,6.40485e-11,5.71974e-10,3.08982e-07,3.09038e-07,5e-08,0,0,0,0,0,0,0,0
26285000,0.982939,-0.011594,-0.0102544,0.183281,-0.0372955,0.00312647,0.00451018,0.13761,-0.0628119,-3.56106,-1.20767e-05,-5.92726e-05,2.99503e-06,-6.86618e-05,-0.000257718,-0.00121645,0.204284,0.00196732,0.43436,0,0,0,0,0,4.94274e-06,1.3194e-05,1.31897e-05,0.000142997,0.0193455,0.0193485,0.0101387,0.0458826,0.045886,0.0597141,6.41704e-11,6.4148e-11,5.7162e-10,3.08988e-07,3.09044e-07,5.0002e-08,0,0,0,0,0,0,0,0
26385000,0.982971,-0.0110817,-0.010229,0.183139,-0.0427979,0.00796384,0.0075736,0.125281,-0.0574301,-3.56114,-1.20649e-05,-5.92562e-05,2.97483e-06,-6.3999e-05,-0.000262314,-0.00121625,0.204284,0.00196732,0.43436,0,0,0,0,0,4.82884e-06,1.33011e-05,1.32946e-05,0.000139959,0.017413,0.0174151,0.010041,0.0411363,0.0411388,0.0592804,6.41744e-11,6.41521e-11,5.71086e-10,3.02279e-07,3.02335e-07,5.0002e-08,0,0,0,0,0,0,0,0
26485000,0.982981,-0.0108383,-0.0101171,0.183108,-0.0462765,0.0107869,0.0166541,0.12083,-0.0565139,-3.56007,-1.20652e-05,-5.92557e-05,2.95248e-06,-6.39766e-05,-0.000262318,-0.0012162,0.204284,0.00196732,0.43436,0,0,0,0,0,4.72648e-06,1.35136e-05,1.35065e-05,0.000137081,0.0185472,0.0185494,0.0101199,0.045466,0.045469,0.0594477,6.42739e-11,6.42515e-11,5.70524e-10,3.02283e-07,3.02339e-07,5.0001e-08,0,0,0,0,0,0,0,0
26585000,0.982969,-0.0103419,-0.0103871,0.183186,-0.0469466,0.0162117,0.016988,0.112121,-0.052029,-3.56041,-1.20566e-05,-5.9249e-05,2.91897e-06,-6.24549e-05,-0.000264673,-0.00121456,0.204284,0.00196732,0.43436,0,0,0,0,0,4.63413e-06,1.36204e-05,1.36105e-05,0.000134349,0.0167398,0.0167411,0.0100222,0.0408199,0.0408222,0.059019,6.43055e-11,6.42833e-11,5.69928e-10,2.96992e-07,2.97046e-07,5.0001e-08,0,0,0,0,0,0,0,0
26685000,0.982964,-0.0102231,-0.0100946,0.183239,-0.0490283,0.0207991,0.0161103,0.107307,-0.0501775,-3.55896,-1.20575e-05,-5.92478e-05,2.86238e-06,-6.24075e-05,-0.000264684,-0.00121447,0.204284,0.00196732,0.43436,0,0,0,0,0,4.54291e-06,1.38395e-05,1.38299e-05,0.000131766,0.0178254,0.0178265,0.0101005,0.0450489,0.0450515,0.0591864,6.44049e-11,6.43826e-11,5.69304e-10,2.96996e-07,2.9705e-07,5e-08,0,0,0,0,0,0,0,0
26785000,0.982985,-0.0100543,-0.00958317,0.183157,-0.054462,0.0223467,0.0147337,0.0961118,-0.0474756,-3.56172,-1.20458e-05,-5.92318e-05,2.83767e-06,-5.87158e-05,-0.00026615,-0.00121251,0.204284,0.00196732,0.43436,0,0,0,0,0,4.45346e-06,1.39409e-05,1.39321e-05,0.000129319,0.0161333,0.016134,0.010003,0.0405017,0.0405036,0.0587625,6.4458e-11,6.4436e-11,5.68645e-10,2.92872e-07,2.92924e-07,5e-08,0,0,0,0,0,0,0,0
26885000,0.983016,-0.00945408,-0.0096706,0.183024,-0.0603901,0.0247583,0.0103582,0.0903326,-0.0451249,-3.56105,-1.20448e-05,-5.92325e-05,2.87958e-06,-5.87154e-05,-0.000266177,-0.00121228,0.204284,0.00196732,0.43436,0,0,0,0,0,4.37213e-06,1.41682e-05,1.41575e-05,0.000126995,0.0171748,0.0171755,0.0100806,0.0446346,0.0446368,0.0589298,6.45574e-11,6.45353e-11,5.67956e-10,2.92876e-07,2.92927e-07,5e-08,0,0,0,0,0,0,0,0
26985000,0.98301,-0.00896551,-0.0101555,0.183049,-0.0663049,0.0287798,0.00836775,0.0789579,-0.0412439,-3.56557,-1.20258e-05,-5.92168e-05,2.85001e-06,-5.58636e-05,-0.000268394,-0.00120986,0.204284,0.00196732,0.43436,0,0,0,0,0,4.32071e-06,1.42681e-05,1.42544e-05,0.000125503,0.0155887,0.0155891,0.0100671,0.0401844,0.040186,0.059379,6.46255e-11,6.46037e-11,5.67438e-10,2.89704e-07,2.89752e-07,5.0002e-08,0,0,0,0,0,0,0,0
27085000,0.983011,-0.00879661,-0.0104861,0.183033,-0.0686799,0.0356962,0.0121825,0.072134,-0.0380013,-3.56899,-1.20244e-05,-5.92152e-05,2.83495e-06,-5.56789e-05,-0.000268592,-0.00120825,0.204284,0.00196732,0.43436,0,0,0,0,0,4.24712e-06,1.45028e-05,1.44875e-05,0.00012338,0.0165852,0.0165852,0.010145,0.0442261,0.0442279,0.0595509,6.47249e-11,6.47031e-11,5.66691e-10,2.89708e-07,2.89756e-07,5.0001e-08,0,0,0,0,0,0,0,0
27185000,0.983019,-0.00885664,-0.0103906,0.182995,-0.0736983,0.0391312,0.0134167,0.0625973,-0.0340678,-3.57152,-1.20035e-05,-5.92029e-05,2.82156e-06,-5.40777e-05,-0.000269987,-0.00120674,0.204284,0.00196732,0.43436,0,0,0,0,0,4.1762e-06,1.4595e-05,1.45798e-05,0.000121362,0.0150953,0.015095,0.0100458,0.0398701,0.0398713,0.0591233,6.48005e-11,6.4779e-11,5.65906e-10,2.87297e-07,2.87342e-07,5.0001e-08,0,0,0,0,0,0,0,0
27285000,0.983027,-0.00902531,-0.0113101,0.182889,-0.0804315,0.0448393,0.116251,0.0549291,-0.0298832,-3.56969,-1.20025e-05,-5.92021e-05,2.81998e-06,-5.39661e-05,-0.000270114,-0.00120573,0.204284,0.00196732,0.43436,0,0,0,0,0,4.10702e-06,1.48379e-05,1.48199e-05,0.000119444,0.0159877,0.0159872,0.0101222,0.0438248,0.0438261,0.0592946,6.48997e-11,6.48783e-11,5.65091e-10,2.87302e-07,2.87345e-07,5.0001e-08,0,0,0,0,0,0,0,0
27385000,0.982988,-0.0103787,-0.013776,0.182859,-0.0839443,0.0500432,0.432084,0.0469192,-0.0244654,-3.55152,-1.19735e-05,-5.91769e-05,2.81266e-06,-5.27383e-05,-0.000272094,-0.00120076,0.204284,0.00196732,0.43436,0,0,0,0,0,4.04509e-06,1.49351e-05,1.49112e-05,0.000117606,0.0143782,0.0143775,0.0100193,0.039555,0.0395559,0.0588655,6.49772e-11,6.49562e-11,5.64235e-10,2.85477e-07,2.85516e-07,5e-08,0,0,0,0,0,0,0,0
27485000,0.982934,-0.0118226,-0.0157444,0.182902,-0.0869621,0.0555558,0.751146,0.0383278,-0.0191663,-3.49392,-1.19734e-05,-5.91749e-05,2.75195e-06,-5.26092e-05,-0.000272232,-0.0011998,0.204284,0.00196732,0.43436,0,0,0,0,0,3.98563e-06,1.51883e-05,1.516e-05,0.000115861,0.0150773,0.0150763,0.0100932,0.0434042,0.0434051,0.0590355,6.50765e-11,6.50555e-11,5.6335e-10,2.85482e-07,2.85519e-07,5e-08,0,0,0,0,0,0,0,0
27585000,0.982956,-0.0118161,-0.0147479,0.182868,-0.080238,0.0567522,0.855688,0.0312006,-0.0166737,-3.43324,-1.19303e-05,-5.91476e-05,2.71978e-06,-5.05819e-05,-0.00027386,-0.00118466,0.204284,0.00196732,0.43436,0,0,0,0,0,3.9478e-06,1.52908e-05,1.52665e-05,0.000114812,0.0137316,0.0137299,0.0100775,0.0392248,0.0392255,0.0594872,6.5158e-11,6.51375e-11,5.62683e-10,2.84033e-07,2.84065e-07,5.0002e-08,0,0,0,0,0,0,0,0
27685000,0.983025,-0.010668,-0.011854,0.18278,-0.0768183,0.0523916,0.762714,0.0233842,-0.0111521,-3.35515,-1.19287e-05,-5.91468e-05,2.73381e-06,-5.04486e-05,-0.000274024,-0.00118337,0.204284,0.00196732,0.43436,0,0,0,0,0,3.89029e-06,1.55346e-05,1.55179e-05,0.000113235,0.0146794,0.0146777,0.0101546,0.0429843,0.0429849,0.0596611,6.52572e-11,6.52367e-11,5.61736e-10,2.84037e-07,2.84068e-07,5.0002e-08,0,0,0,0,0,0,0,0
27785000,0.98306,-0.00932519,-0.0102641,0.182759,-0.075015,0.0479237,0.750133,0.0184526,-0.0102233,-3.28136,-1.18991e-05,-5.91324e-05,2.76426e-06,-5.03125e-05,-0.000273405,-0.00118445,0.204284,0.00196732,0.43436,0,0,0,0,0,3.83946e-06,1.56263e-05,1.56115e-05,0.000111722,0.0134964,0.0134948,0.0100527,0.0389019,0.0389023,0.0592269,6.53272e-11,6.53073e-11,5.60747e-10,2.82964e-07,2.82989e-07,5.0001e-08,0,0,0,0,0,0,0,0
27885000,0.983058,-0.00893935,-0.01034,0.182786,-0.0816284,0.0535257,0.791785,0.0106311,-0.00519984,-3.20673,-1.18979e-05,-5.91316e-05,2.76383e-06,-5.01981e-05,-0.000273545,-0.00118338,0.204284,0.00196732,0.43436,0,0,0,0,0,3.79218e-06,1.58858e-05,1.58697e-05,0.000110277,0.0143423,0.0143405,0.0101284,0.0425918,0.0425921,0.0593996,6.54263e-11,6.54065e-11,5.59727e-10,2.82969e-07,2.82992e-07,5.0001e-08,0,0,0,0,0,0,0,0
27985000,0.983057,-0.00938487,-0.0107145,0.182746,-0.0815621,0.0540573,0.779094,0.00638833,-0.00471807,-3.13639,-1.18487e-05,-5.91022e-05,2.76009e-06,-4.92325e-05,-0.000274154,-0.00117866,0.204284,0.00196732,0.43436,0,0,0,0,0,3.74463e-06,1.59708e-05,1.59544e-05,0.000108897,0.0132278,0.0132261,0.0100268,0.0385964,0.0385965,0.0589692,6.54782e-11,6.54592e-11,5.58665e-10,2.82184e-07,2.82201e-07,5e-08,0,0,0,0,0,0,0,0
28085000,0.983079,-0.00971888,-0.0107181,0.182613,-0.0852013,0.0539041,0.785328,-0.00191157,0.000715123,-3.05866,-1.18473e-05,-5.91036e-05,2.83146e-06,-4.92397e-05,-0.000274167,-0.00117853,0.204284,0.00196732,0.43436,0,0,0,0,0,3.69935e-06,1.62356e-05,1.62197e-05,0.000107585,0.0140926,0.0140909,0.0101017,0.0422223,0.0422222,0.0591407,6.55773e-11,6.55584e-11,5.57573e-10,2.82189e-07,2.82203e-07,5e-08,0,0,0,0,0,0,0,0
28185000,0.983083,-0.00920746,-0.0110121,0.1826,-0.0846723,0.0491819,0.791155,-0.00760657,0.000153068,-2.98447,-1.17931e-05,-5.90785e-05,2.82771e-06,-4.80889e-05,-0.000275026,-0.00117597,0.204284,0.00196732,0.43436,0,0,0,0,0,3.6569e-06,1.63048e-05,1.62868e-05,0.000106332,0.0130255,0.0130241,0.00999996,0.0383091,0.038309,0.058714,6.56014e-11,6.55835e-11,5.56436e-10,2.81614e-07,2.81622e-07,5e-08,0,0,0,0,0,0,0,0
28285000,0.983103,-0.00869654,-0.0113016,0.182499,-0.0898653,0.051566,0.791724,-0.0162914,0.00523746,-2.90783,-1.17911e-05,-5.90789e-05,2.88009e-06,-4.80077e-05,-0.000275143,-0.00117506,0.204284,0.00196732,0.43436,0,0,0,0,0,3.63312e-06,1.65762e-05,1.65563e-05,0.00010565,0.013892,0.0138905,0.0101602,0.0418787,0.0418784,0.0597637,6.57007e-11,6.56829e-11,5.55589e-10,2.8162e-07,2.81626e-07,5.0002e-08,0,0,0,0,0,0,0,0
28385000,0.983092,-0.0087259,-0.0119249,0.182518,-0.0898497,0.053495,0.792727,-0.0201488,0.00746234,-2.83506,-1.17329e-05,-5.90308e-05,2.94108e-06,-4.64826e-05,-0.000276838,-0.00117235,0.204284,0.00196732,0.43436,0,0,0,0,0,3.59866e-06,1.66278e-05,1.6606e-05,0.000104493,0.0128817,0.0128803,0.010057,0.0380423,0.038042,0.0593279,6.56888e-11,6.5672e-11,5.54386e-10,2.81183e-07,2.81183e-07,5.0001e-08,0,0,0,0,0,0,0,0
28485000,0.983089,-0.00905038,-0.0124237,0.182482,-0.0912941,0.0556954,0.79384,-0.029177,0.0128989,-2.76043,-1.17311e-05,-5.90294e-05,2.93622e-06,-4.63122e-05,-0.000277057,-0.00117072,0.204284,0.00196732,0.43436,0,0,0,0,0,3.56082e-06,1.69046e-05,1.68816e-05,0.000103398,0.013749,0.0137474,0.0101316,0.0415643,0.0415638,0.0595013,6.57878e-11,6.57711e-11,5.53154e-10,2.81188e-07,2.81185e-07,5.0001e-08,0,0,0,0,0,0,0,0
28585000,0.983123,-0.0091317,-0.0123953,0.182295,-0.0845872,0.0505013,0.791181,-0.0317764,0.0100696,-2.68491,-1.16406e-05,-5.89894e-05,2.9833e-06,-4.49545e-05,-0.000279081,-0.00116896,0.204284,0.00196732,0.43436,0,0,0,0,0,3.52098e-06,1.69332e-05,1.69105e-05,0.000102355,0.0127875,0.012786,0.0100284,0.0377986,0.0377982,0.0590692,6.57311e-11,6.57156e-11,5.51875e-10,2.80826e-07,2.80816e-07,5.0001e-08,0,0,0,0,0,0,0,0
28685000,0.98312,-0.00892989,-0.0117836,0.182364,-0.0844371,0.0502898,0.792011,-0.0402184,0.015137,-2.60987,-1.16391e-05,-5.89879e-05,2.96897e-06,-4.47984e-05,-0.000279283,-0.00116747,0.204284,0.00196732,0.43436,0,0,0,0,0,3.48963e-06,1.72118e-05,1.71905e-05,0.000101358,0.0136602,0.0136586,0.0101012,0.0412814,0.0412807,0.0592354,6.58301e-11,6.58147e-11,5.50566e-10,2.80831e-07,2.80818e-07,5e-08,0,0,0,0,0,0,0,0
28785000,0.98314,-0.00830017,-0.0115932,0.182295,-0.080009,0.0495528,0.79059,-0.0421044,0.0165511,-2.53769,-1.15707e-05,-5.89239e-05,3.03673e-06,-4.24706e-05,-0.000281578,-0.00116392,0.204284,0.00196732,0.43436,0,0,0,0,0,3.45811e-06,1.72159e-05,1.71943e-05,0.000100407,0.0127341,0.0127327,0.00999835,0.0375798,0.0375792,0.0588068,6.57199e-11,6.57058e-11,5.49213e-10,2.80489e-07,2.80469e-07,5e-08,0,0,0,0,0,0,0,0
28885000,0.983168,-0.0081231,-0.01133,0.182172,-0.0840488,0.0502895,0.789899,-0.0502826,0.021535,-2.46157,-1.15687e-05,-5.89241e-05,3.0823e-06,-4.23766e-05,-0.000281713,-0.00116289,0.204284,0.00196732,0.43436,0,0,0,0,0,3.44071e-06,1.74999e-05,1.74785e-05,9.99611e-05,0.0136165,0.0136152,0.0101576,0.0410313,0.0410304,0.0598592,6.58191e-11,6.58051e-11,5.48203e-10,2.80495e-07,2.80473e-07,5.0002e-08,0,0,0,0,0,0,0,0
28985000,0.983156,-0.00790241,-0.0115541,0.182234,-0.0796118,0.0463818,0.789013,-0.0492147,0.0204919,-2.39039,-1.14714e-05,-5.88538e-05,3.1037e-06,-4.00905e-05,-0.000284925,-0.00115912,0.204284,0.00196732,0.43436,0,0,0,0,0,3.41495e-06,1.74781e-05,1.74559e-05,9.90829e-05,0.0127199,0.0127189,0.0100532,0.0373872,0.0373864,0.0594214,6.56474e-11,6.56348e-11,5.46783e-10,2.80125e-07,2.80096e-07,5.0002e-08,0,0,0,0,0,0,0,0
29085000,0.983157,-0.00779065,-0.0115956,0.18223,-0.0825951,0.0475658,0.788722,-0.057389,0.0251618,-2.31352,-1.14703e-05,-5.88534e-05,3.11286e-06,-4.00183e-05,-0.000285022,-0.00115842,0.204284,0.00196732,0.43436,0,0,0,0,0,3.3876e-06,1.77664e-05,1.77439e-05,9.82502e-05,0.0136125,0.0136115,0.0101259,0.0408151,0.0408142,0.0595889,6.5746e-11,6.57342e-11,5.4533e-10,2.8013e-07,2.80098e-07,5.0001e-08,0,0,0,0,0,0,0,0
29185000,0.983183,-0.00774304,-0.0118213,0.182074,-0.0782209,0.0451128,0.782937,-0.0546694,0.0244314,-2.24508,-1.13678e-05,-5.87605e-05,3.18674e-06,-3.66964e-05,-0.000288652,-0.00115359,0.204284,0.00196732,0.43436,0,0,0,0,0,3.35848e-06,1.77151e-05,1.76924e-05,9.74569e-05,0.0127436,0.0127429,0.010022,0.0372218,0.037221,0.0591547,6.55054e-11,6.54957e-11,5.43833e-10,2.79692e-07,2.79653e-07,5.0001e-08,0,0,0,0,0,0,0,0
29285000,0.983167,-0.00798996,-0.0118546,0.182148,-0.0798943,0.0499959,0.785343,-0.0625386,0.0292303,-2.16817,-1.13664e-05,-5.87608e-05,3.22471e-06,-3.66382e-05,-0.000288734,-0.00115307,0.204284,0.00196732,0.43436,0,0,0,0,0,3.33761e-06,1.80065e-05,1.79841e-05,9.66954e-05,0.0136458,0.013645,0.0100941,0.0406338,0.0406329,0.0593203,6.5604e-11,6.5595e-11,5.42305e-10,2.79697e-07,2.79655e-07,5e-08,0,0,0,0,0,0,0,0
29385000,0.983177,-0.00843987,-0.0113575,0.182108,-0.075311,0.0484219,0.787556,-0.0604037,0.0302469,-2.09305,-1.12772e-05,-5.86797e-05,3.28072e-06,-3.39223e-05,-0.000291922,-0.00115123,0.204284,0.00196732,0.43436,0,0,0,0,0,3.3141e-06,1.79221e-05,1.79022e-05,9.59725e-05,0.0127884,0.0127878,0.00999061,0.037084,0.0370832,0.0588897,6.5289e-11,6.52816e-11,5.40733e-10,2.79157e-07,2.79109e-07,5e-08,0,0,0,0,0,0,0,0
29485000,0.983188,-0.00849073,-0.0112213,0.182052,-0.0776237,0.04819,0.788827,-0.0680073,0.0351005,-2.01631,-1.12744e-05,-5.86816e-05,3.3903e-06,-3.38767e-05,-0.00029201,-0.0011505,0.204284,0.00196732,0.43436,0,0,0,0,0,3.29318e-06,1.82159e-05,1.81963e-05,9.52831e-05,0.0137044,0.0137039,0.0100619,0.0404866,0.0404856,0.0590534,6.53879e-11,6.53805e-11,5.3913e-10,2.79163e-07,2.79111e-07,5e-08,0,0,0,0,0,0,0,0
29585000,0.983205,-0.00840268,-0.0112233,0.181966,-0.0728787,0.0456831,0.790666,-0.0650496,0.0345276,-1.93824,-1.1168e-05,-5.8599e-05,3.4662e-06,-3.10693e-05,-0.000295765,-0.00115025,0.204284,0.00196732,0.43436,0,0,0,0,0,3.28492e-06,1.81e-05,1.80805e-05,9.50402e-05,0.01286,0.0128598,0.0100434,0.0369735,0.0369728,0.0594985,6.49935e-11,6.49879e-11,5.3792e-10,2.78496e-07,2.7844e-07,5.0002e-08,0,0,0,0,0,0,0,0
29685000,0.983229,-0.00847091,-0.0110142,0.181845,-0.0772643,0.0437554,0.78646,-0.072532,0.0390362,-1.86345,-1.11647e-05,-5.86001e-05,3.56e-06,-3.09549e-05,-0.000295944,-0.00114882,0.204284,0.00196732,0.43436,0,0,0,0,0,3.26292e-06,1.83957e-05,1.83767e-05,9.44115e-05,0.0137954,0.0137954,0.0101153,0.0403733,0.0403724,0.0596651,6.50924e-11,6.50868e-11,5.36251e-10,2.78502e-07,2.78443e-07,5.0001e-08,0,0,0,0,0,0,0,0
29785000,0.983237,-0.00832929,-0.0115361,0.181775,-0.0728123,0.0360813,0.782794,-0.0674718,0.0367697,-1.7913,-1.10552e-05,-5.84976e-05,3.66866e-06,-2.71572e-05,-0.000299857,-0.00114581,0.204284,0.00196732,0.43436,0,0,0,0,0,3.24427e-06,1.82463e-05,1.82259e-05,9.38077e-05,0.0129598,0.0129602,0.010011,0.0368903,0.0368896,0.059229,6.46139e-11,6.46099e-11,5.34539e-10,2.77685e-07,2.77621e-07,5.0001e-08,0,0,0,0,0,0,0,0
29885000,0.983241,-0.00783095,-0.0119245,0.181749,-0.0730551,0.0356345,0.779122,-0.0746708,0.0403198,-1.71929,-1.10512e-05,-5.8498e-05,3.75563e-06,-2.69723e-05,-0.000300126,-0.00114369,0.204284,0.00196732,0.43436,0,0,0,0,0,3.22737e-06,1.8545e-05,1.85227e-05,9.32334e-05,0.013909,0.0139095,0.0100822,0.0402935,0.0402928,0.0593937,6.47126e-11,6.4709e-11,5.32796e-10,2.77691e-07,2.77624e-07,5.0001e-08,0,0,0,0,0,0,0,0
29985000,0.983239,-0.00794104,-0.0119906,0.181756,-0.0676796,0.0309378,0.776089,-0.0698908,0.0363368,-1.64968,-1.09217e-05,-5.84103e-05,3.78808e-06,-2.36627e-05,-0.000305129,-0.00113971,0.204284,0.00196732,0.43436,0,0,0,0,0,3.21062e-06,1.83586e-05,1.83367e-05,9.26856e-05,0.0130719,0.0130727,0.00997763,0.0368336,0.036833,0.058956,6.41473e-11,6.4146e-11,5.31007e-10,2.76712e-07,2.7664e-07,5e-08,0,0,0,0,0,0,0,0
30085000,0.983239,-0.00809906,-0.0121314,0.181737,-0.0677717,0.0305952,0.77411,-0.0766629,0.0394403,-1.57583,-1.09224e-05,-5.84078e-05,3.69717e-06,-2.35573e-05,-0.000305264,-0.0011384,0.204284,0.00196732,0.43436,0,0,0,0,0,3.19008e-06,1.86572e-05,1.86353e-05,9.21698e-05,0.0140348,0.0140357,0.0100484,0.040245,0.0402445,0.0591187,6.42459e-11,6.42452e-11,5.2919e-10,2.76718e-07,2.76644e-07,5e-08,0,0,0,0,0,0,0,0
30185000,0.983217,-0.00808061,-0.0121402,0.181858,-0.0612936,0.0272049,0.774024,-0.0698294,0.0383142,-1.50396,-1.08534e-05,-5.8287e-05,3.62678e-06,-1.90635e-05,-0.000307776,-0.00113584,0.204284,0.00196732,0.43436,0,0,0,0,0,3.18886e-06,1.84349e-05,1.84134e-05,9.20614e-05,0.013191,0.0131921,0.0100298,0.0368014,0.0368011,0.0595641,6.35942e-11,6.35955e-11,5.27822e-10,2.7557e-07,2.75493e-07,5.0002e-08,0,0,0,0,0,0,0,0
30285000,0.983205,-0.00811686,-0.0121397,0.181919,-0.0605426,0.0261304,0.774272,-0.0758701,0.0409973,-1.43164,-1.08511e-05,-5.82863e-05,3.65058e-06,-1.8901e-05,-0.000307999,-0.00113404,0.204284,0.00196732,0.43436,0,0,0,0,0,3.17614e-06,1.87334e-05,1.87121e-05,9.15846e-05,0.0141649,0.0141662,0.0101011,0.0402253,0.040225,0.0597298,6.36928e-11,6.36947e-11,5.25942e-10,2.75577e-07,2.75496e-07,5.0002e-08,0,0,0,0,0,0,0,0
30385000,0.983195,-0.00809661,-0.012062,0.181978,-0.0526485,0.0205227,0.771869,-0.0674681,0.0387348,-1.3637,-1.07545e-05,-5.81476e-05,3.79424e-06,-1.32394e-05,-0.000311742,-0.00112978,0.204284,0.00196732,0.43436,0,0,0,0,0,3.16742e-06,1.84754e-05,1.8455e-05,9.11266e-05,0.0133141,0.0133156,0.00999587,0.0367918,0.0367917,0.0592868,6.29557e-11,6.29598e-11,5.24018e-10,2.74261e-07,2.74177e-07,5.0001e-08,0,0,0,0,0,0,0,0
30485000,0.983224,-0.00811895,-0.0122005,0.181815,-0.0553648,0.0195293,0.772847,-0.0728277,0.0407856,-1.29192,-1.07504e-05,-5.81482e-05,3.89027e-06,-1.30604e-05,-0.000311995,-0.00112785,0.204284,0.00196732,0.43436,0,0,0,0,0,3.15062e-06,1.87738e-05,1.87531e-05,9.07002e-05,0.0143004,0.0143022,0.0100668,0.0402313,0.0402314,0.0594505,6.30543e-11,6.30589e-11,5.22067e-10,2.74268e-07,2.74181e-07,5.0001e-08,0,0,0,0,0,0,0,0
30585000,0.983239,-0.00842206,-0.0124873,0.181697,-0.050143,0.0169689,0.772491,-0.0654953,0.0378177,-1.22021,-1.06554e-05,-5.80305e-05,4.00604e-06,-8.28661e-06,-0.000315662,-0.00112521,0.204284,0.00196732,0.43436,0,0,0,0,0,3.1365e-06,1.84823e-05,1.84619e-05,9.02913e-05,0.0134374,0.0134391,0.00996252,0.0368022,0.0368023,0.0590116,6.22349e-11,6.22415e-11,5.20073e-10,2.72788e-07,2.727e-07,5e-08,0,0,0,0,0,0,0,0
30685000,0.983257,-0.00880141,-0.012722,0.181567,-0.0485618,0.0144556,0.77139,-0.0704961,0.0394336,-1.14915,-1.0653e-05,-5.80298e-05,4.03224e-06,-8.11043e-06,-0.000315903,-0.00112305,0.204284,0.00196732,0.43436,0,0,0,0,0,3.12027e-06,1.87798e-05,1.87593e-05,8.99064e-05,0.0144387,0.0144407,0.0100329,0.0402602,0.0402606,0.0591734,6.23336e-11,6.23405e-11,5.18053e-10,2.72795e-07,2.72705e-07,5e-08,0,0,0,0,0,0,0,0
30785000,0.983285,-0.00850967,-0.0124409,0.18145,-0.0408793,0.00936385,0.769945,-0.0630761,0.0392263,-1.07923,-1.06417e-05,-5.7911e-05,4.0409e-06,-3.33799e-06,-0.00031617,-0.00111979,0.204284,0.00196732,0.43436,0,0,0,0,0,3.10409e-06,1.8454e-05,1.84346e-05,8.95423e-05,0.013562,0.013564,0.00992923,0.0368301,0.0368305,0.0587387,6.14361e-11,6.14448e-11,5.15992e-10,2.71162e-07,2.71071e-07,5e-08,0,0,0,0,0,0,0,0
30885000,0.983277,-0.00788038,-0.0123019,0.181531,-0.0406949,0.00500233,0.76761,-0.0670851,0.0399978,-1.0069,-1.06409e-05,-5.79096e-05,4.01552e-06,-3.21241e-06,-0.000316332,-0.00111821,0.204284,0.00196732,0.43436,0,0,0,0,0,3.107e-06,1.87493e-05,1.87292e-05,8.95589e-05,0.0145774,0.0145796,0.0100847,0.0403091,0.0403098,0.0597788,6.1535e-11,6.15441e-11,5.14453e-10,2.7117e-07,2.71077e-07,5.0002e-08,0,0,0,0,0,0,0,0
30985000,0.983277,-0.00804027,-0.0122555,0.181525,-0.0331827,0.000400666,0.769072,-0.0569425,0.0343403,-0.937826,-1.05405e-05,-5.77874e-05,4.02621e-06,1.73023e-06,-0.000320351,-0.00111499,0.204284,0.00196732,0.43436,0,0,0,0,0,3.09596e-06,1.83926e-05,1.83735e-05,8.92234e-05,0.0136801,0.0136823,0.00997998,0.0368733,0.0368739,0.0593353,6.05645e-11,6.0575e-11,5.12333e-10,2.69395e-07,2.69301e-07,5.0001e-08,0,0,0,0,0,0,0,0
31085000,0.983239,-0.00818885,-0.0123615,0.181716,-0.0316315,-0.00268426,0.768071,-0.060139,0.0341603,-0.863755,-1.05406e-05,-5.77862e-05,3.98963e-06,1.80328e-06,-0.000320441,-0.00111403,0.204284,0.00196732,0.43436,0,0,0,0,0,3.09104e-06,1.8686e-05,1.86669e-05,8.88997e-05,0.0147047,0.0147071,0.0100507,0.040374,0.0403749,0.0594982,6.06631e-11,6.06741e-11,5.10187e-10,2.69402e-07,2.69307e-07,5.0001e-08,0,0,0,0,0,0,0,0
31185000,0.983252,-0.00832274,-0.0125108,0.181628,-0.0269805,-0.00591836,0.76957,-0.0515396,0.0306831,-0.793916,-1.04973e-05,-5.76811e-05,4.14217e-06,6.20666e-06,-0.000322011,-0.00111143,0.204284,0.00196732,0.43436,0,0,0,0,0,3.08217e-06,1.83011e-05,1.82824e-05,8.8596e-05,0.0137902,0.0137924,0.00994682,0.0369285,0.0369294,0.0590589,5.96269e-11,5.96392e-11,5.08003e-10,2.67504e-07,2.67409e-07,5.0001e-08,0,0,0,0,0,0,0,0
31285000,0.98327,-0.00859023,-0.0125879,0.181515,-0.0240884,-0.00945397,0.773476,-0.0540502,0.0299579,-0.722284,-1.04939e-05,-5.76817e-05,4.22889e-06,6.36324e-06,-0.000322223,-0.0011095,0.204284,0.00196732,0.43436,0,0,0,0,0,3.07138e-06,1.85917e-05,1.85733e-05,8.83103e-05,0.0148157,0.0148183,0.0100162,0.0404512,0.0404524,0.0592146,5.97255e-11,5.97382e-11,5.05791e-10,2.67511e-07,2.67414e-07,5e-08,0,0,0,0,0,0,0,0
31385000,0.983282,-0.00836635,-0.012398,0.181472,-0.0180248,-0.0150107,0.772804,-0.045199,0.0260324,-0.649449,-1.04641e-05,-5.75927e-05,4.17172e-06,9.88169e-06,-0.00032338,-0.001107,0.204284,0.00196732,0.43436,0,0,0,0,0,3.05928e-06,1.81808e-05,1.81631e-05,8.80423e-05,0.0138867,0.013889,0.00991313,0.0369926,0.0369937,0.0587797,5.86325e-11,5.86462e-11,5.03545e-10,2.65512e-07,2.65416e-07,5e-08,0,0,0,0,0,0,0,0
31485000,0.983266,-0.00811594,-0.0127059,0.18155,-0.0180637,-0.0195551,0.769659,-0.0470531,0.0242643,-0.574289,-1.04639e-05,-5.75922e-05,4.16095e-06,9.92989e-06,-0.000323439,-0.00110634,0.204284,0.00196732,0.43436,0,0,0,0,0,3.06545e-06,1.8469e-05,1.84499e-05,8.81382e-05,0.0149306,0.0149331,0.0100686,0.0405376,0.0405391,0.0598206,5.87315e-11,5.87454e-11,5.01868e-10,2.6552e-07,2.65423e-07,5.0002e-08,0,0,0,0,0,0,0,0
31585000,0.98329,-0.00792751,-0.013182,0.181396,-0.0135164,-0.0202148,0.773278,-0.036078,0.0218162,-0.502873,-1.04572e-05,-5.74617e-05,4.26294e-06,1.53677e-05,-0.0003236,-0.00110363,0.204284,0.00196732,0.43436,0,0,0,0,0,3.05482e-06,1.80363e-05,1.80162e-05,8.7894e-05,0.013976,0.0139782,0.00996458,0.0370635,0.0370647,0.059377,5.7588e-11,5.76027e-11,4.99569e-10,2.63434e-07,2.63339e-07,5.0002e-08,0,0,0,0,0,0,0,0
31685000,0.983314,-0.00792659,-0.0136535,0.181229,-0.0155041,-0.0225868,0.769613,-0.0375473,0.0196022,-0.433373,-1.04528e-05,-5.74628e-05,4.38177e-06,1.55706e-05,-0.000323867,-0.00110092,0.204284,0.00196732,0.43436,0,0,0,0,0,3.04498e-06,1.8321e-05,1.82997e-05,8.76621e-05,0.0150239,0.0150263,0.0100346,0.0406298,0.0406315,0.0595342,5.76867e-11,5.77016e-11,4.97242e-10,2.63442e-07,2.63346e-07,5.0001e-08,0,0,0,0,0,0,0,0
31785000,0.983327,-0.00809981,-0.0143205,0.181103,-0.00644066,-0.0240741,0.769467,-0.0260308,0.0199943,-0.361938,-1.05075e-05,-5.73076e-05,4.48561e-06,2.20546e-05,-0.000321506,-0.00109839,0.204284,0.00196732,0.43436,0,0,0,0,0,3.03623e-06,1.78693e-05,1.7847e-05,8.74414e-05,0.0140558,0.014058,0.00993128,0.0371382,0.0371397,0.0590951,5.65028e-11,5.65182e-11,4.94885e-10,2.61294e-07,2.612e-07,5.0001e-08,0,0,0,0,0,0,0,0
31885000,0.983336,-0.00787391,-0.0141188,0.181079,-0.00270284,-0.0276474,0.768199,-0.0264631,0.0173454,-0.292682,-1.05044e-05,-5.73078e-05,4.55398e-06,2.2245e-05,-0.000321742,-0.00109572,0.204284,0.00196732,0.43436,0,0,0,0,0,3.0302e-06,1.81484e-05,1.81264e-05,8.72324e-05,0.0151049,0.0151073,0.0100008,0.0407254,0.0407273,0.0592507,5.66014e-11,5.66172e-11,4.92501e-10,2.61302e-07,2.61207e-07,5e-08,0,0,0,0,0,0,0,0
31985000,0.983327,-0.00805983,-0.013699,0.18115,0.0053475,-0.0268698,0.764854,-0.0146201,0.0164935,-0.226311,-1.05456e-05,-5.71775e-05,4.51824e-06,2.76665e-05,-0.000320181,-0.0010914,0.204284,0.00196732,0.43436,0,0,0,0,0,3.02476e-06,1.76775e-05,1.76578e-05,8.70343e-05,0.0141209,0.014123,0.00989846,0.037215,0.0372165,0.0588162,5.53856e-11,5.54015e-11,4.90089e-10,2.59112e-07,2.5902e-07,5e-08,0,0,0,0,0,0,0,0
32085000,0.983343,-0.00844136,-0.0133254,0.181071,0.00549286,-0.0315068,0.767254,-0.0140587,0.0136374,-0.155399,-1.05443e-05,-5.71769e-05,4.529e-06,2.78019e-05,-0.000320337,-0.00108938,0.204284,0.00196732,0.43436,0,0,0,0,0,3.01627e-06,1.79518e-05,1.79339e-05,8.68499e-05,0.0151685,0.0151708,0.00996778,0.0408213,0.0408233,0.0589703,5.54842e-11,5.55004e-11,4.87652e-10,2.5912e-07,2.59027e-07,5e-08,0,0,0,0,0,0,0,0
32185000,0.983335,-0.00861457,-0.0136069,0.181087,0.0101527,-0.0328331,0.767299,-0.00309774,0.0146971,-0.0862616,-1.06423e-05,-5.70595e-05,4.51556e-06,3.26846e-05,-0.000316417,-0.00108583,0.204284,0.00196732,0.43436,0,0,0,0,0,3.0224e-06,1.747e-05,1.74522e-05,8.70189e-05,0.0141644,0.0141663,0.00994975,0.037291,0.0372926,0.0594097,5.42459e-11,5.4262e-11,4.85828e-10,2.5691e-07,2.56821e-07,5.0002e-08,0,0,0,0,0,0,0,0
32285000,0.983351,-0.00853755,-0.0138598,0.180986,0.0119488,-0.0373843,0.76583,-0.00197889,0.0111523,-0.0172141,-1.06394e-05,-5.70599e-05,4.58852e-06,3.28651e-05,-0.000316627,-0.00108314,0.204284,0.00196732,0.43436,0,0,0,0,0,3.01552e-06,1.77414e-05,1.77227e-05,8.68512e-05,0.0152175,0.0152195,0.0100198,0.0409142,0.0409162,0.059567,5.43445e-11,5.4361e-11,4.83344e-10,2.56918e-07,2.56829e-07,5.0001e-08,0,0,0,0,0,0,0,0
32385000,0.983333,-0.0085533,-0.0139792,0.181076,0.0186095,-0.0365249,0.764495,0.00901143,0.0110791,0.0555225,-1.07205e-05,-5.69638e-05,4.55738e-06,3.6807e-05,-0.000313398,-0.00108055,0.204284,0.00196732,0.43436,0,0,0,0,0,3.01229e-06,1.72496e-05,1.72312e-05,8.66895e-05,0.014201,0.0142028,0.00991731,0.0373645,0.0373662,0.0591287,5.30916e-11,5.31078e-11,4.80834e-10,2.54706e-07,2.54621e-07,5.0001e-08,0,0,0,0,0,0,0,0
32485000,0.983348,-0.0114564,-0.0119091,0.180982,0.0446693,-0.104362,-0.108101,0.0126265,0.00223724,0.0640683,-1.07207e-05,-5.69622e-05,4.50651e-06,3.68309e-05,-0.000313419,-0.00108013,0.204284,0.00196732,0.43436,0,0,0,0,0,3.00307e-06,1.75105e-05,1.75033e-05,8.65445e-05,0.0168291,0.0168296,0.0097965,0.0410846,0.0410867,0.0592765,5.31905e-11,5.32064e-11,4.78302e-10,0,0,0,0,0,0,0,0,0,0,0
32585000,0.983358,-0.0113888,-0.0118735,0.180931,0.0442818,-0.103307,-0.109485,0.0242629,0.00145237,0.0461586,-1.09461e-05,-5.6866e-05,4.60931e-06,3.68309e-05,-0.000313419,-0.00108013,0.204284,0.00196732,0.43436,0,0,0,0,0,2.99865e-06,1.68936e-05,1.68864e-05,8.64002e-05,0.0160722,0.0160728,0.00943194,0.0375432,0.0375449,0.0588031,5.1752e-11,5.17652e-11,4.75743e-10,0,0,0,0,0,0,0,0,0,0,0
32685000,0.983363,-0.0113772,-0.0117368,0.180915,0.0407911,-0.110081,-0.111265,0.0285636,-0.0092236,0.0314137,-1.09459e-05,-5.68653e-05,4.59679e-06,3.68309e-05,-0.000313419,-0.00108013,0.204284,0.00196732,0.43436,0,0,0,0,0,2.99341e-06,1.71531e-05,1.71459e-05,8.62667e-05,0.0177469,0.017748,0.00923906,0.0413856,0.0413878,0.0588756,5.1851e-11,5.18638e-11,4.73165e-10,0,0,0,0,0,0,0,0,0,0,0
32785000,0.983366,-0.0111758,-0.0118184,0.180906,0.0387653,-0.105812,-0.111873,0.0377837,-0.00814189,0.0165387,-1.12103e-05,-5.67693e-05,4.6962e-06,3.68309e-05,-0.000313419,-0.00108013,0.204284,0.00196732,0.43436,0,0,0,0,0,3.00241e-06,1.64359e-05,1.6428e-05,8.64793e-05,0.0169106,0.0169119,0.0089866,0.0377893,0.0377911,0.059233,5.03079e-11,5.03177e-11,4.7124e-10,0,0,0,0,0,0,0,0,0,0,0
32885000,0.983385,-0.0111511,-0.0118798,0.180798,0.039234,-0.113707,-0.113175,0.0417363,-0.0191388,0.00289907,-1.12092e-05,-5.67701e-05,4.74182e-06,3.68309e-05,-0.000313419,-0.00108013,0.204284,0.00196732,0.43436,0,0,0,0,0,2.99598e-06,1.66882e-05,1.66799e-05,8.63605e-05,0.0186747,0.0186766,0.00881031,0.041728,0.0417303,0.0592384,5.04069e-11,5.04164e-11,4.68623e-10,2.54711e-07,2.54625e-07,5.0003e-08,0,0,0,0,0,0,0,0
32985000,0.983396,-0.0109995,-0.0118475,0.180749,0.0364774,-0.109443,-0.112153,0.0489922,-0.0196935,-0.00972228,-1.14499e-05,-5.67001e-05,4.86756e-06,3.68216e-05,-0.000313872,-0.00108016,0.204284,0.00196732,0.43436,0,0,0,0,0,2.99291e-06,1.58799e-05,1.58711e-05,8.62437e-05,0.0177647,0.0177667,0.00851794,0.038065,0.0380669,0.0586821,4.87872e-11,4.87934e-11,4.65982e-10,2.54717e-07,2.54631e-07,5.00129e-08,0,0,0,0,0,0,0,0
33085000,0.9834,-0.0109681,-0.0118638,0.180731,0.0334007,-0.114679,-0.109902,0.0525173,-0.0308595,-0.0182185,-1.14502e-05,-5.67002e-05,4.86221e-06,3.68211e-05,-0.000313871,-0.00108017,0.204284,0.00196732,0.43436,0,0,0,0,0,2.98863e-06,1.61236e-05,1.61145e-05,8.61362e-05,0.0196769,0.0196798,0.00837635,0.0421039,0.0421063,0.0586296,4.88861e-11,4.88921e-11,4.63325e-10,2.54727e-07,2.54641e-07,5.00229e-08,0,0,0,0,0,0,0,0
33185000,0.983409,-0.0107786,-0.0117884,0.180699,0.0294344,-0.110828,-0.108299,0.0580855,-0.0303051,-0.0243402,-1.16944e-05,-5.66282e-05,4.83009e-06,3.66213e-05,-0.000316308,-0.00108041,0.204284,0.00196732,0.43436,0,0,0,0,0,2.98283e-06,1.52408e-05,1.52314e-05,8.60348e-05,0.0187062,0.018709,0.00813306,0.0383641,0.0383661,0.0580545,4.72244e-11,4.72271e-11,4.60646e-10,2.54602e-07,2.54516e-07,5.00304e-08,0,0,0,0,0,0,0,0
33285000,0.983431,-0.0108518,-0.0117977,0.180571,0.0270476,-0.114366,-0.108104,0.0608495,-0.0415712,-0.032812,-1.16918e-05,-5.66313e-05,4.97021e-06,3.66193e-05,-0.000316307,-0.00108043,0.204284,0.00196732,0.43436,0,0,0,0,0,2.97868e-06,1.54752e-05,1.54657e-05,8.59388e-05,0.0207535,0.0207574,0.00802748,0.0425086,0.0425112,0.0579559,4.73233e-11,4.73259e-11,4.57952e-10,2.54612e-07,2.54526e-07,5.00403e-08,0,0,0,0,0,0,0,0
33385000,0.983446,-0.0106273,-0.0118556,0.180504,0.0224591,-0.103559,-0.105744,0.0634141,-0.0348014,-0.0412282,-1.20233e-05,-5.65398e-05,5.02812e-06,3.66193e-05,-0.000316307,-0.00108071,0.204284,0.00196732,0.43436,0,0,0,0,0,2.97411e-06,1.45398e-05,1.45297e-05,8.5847e-05,0.0194666,0.0194703,0.00782859,0.038682,0.0386841,0.0573718,4.56563e-11,4.56558e-11,4.55237e-10,0,0,5.00418e-08,0,0,0,0,0,0,0,0
33485000,0.98345,-0.0106145,-0.0118099,0.180485,0.0183889,-0.107453,-0.105649,0.0654136,-0.0453213,-0.0519314,-1.2023e-05,-5.654e-05,5.04086e-06,3.66193e-05,-0.000316307,-0.00108071,0.204284,0.00196732,0.43436,0,0,0,0,0,2.98245e-06,1.47644e-05,1.47542e-05,8.61e-05,0.0213468,0.0213515,0.00782073,0.0429283,0.0429311,0.0580703,4.57555e-11,4.57549e-11,4.53216e-10,0,0,5.00515e-08,0,0,0,0,0,0,0,0
33585000,0.983477,-0.0103497,-0.0117798,0.180352,0.0145162,-0.100504,-0.101888,0.0672396,-0.0395705,-0.057731,-1.22967e-05,-5.64594e-05,5.16805e-06,3.66193e-05,-0.000316307,-0.00108134,0.204284,0.00196732,0.43436,0,0,0,0,0,2.97756e-06,1.37976e-05,1.3787e-05,8.60179e-05,0.019891,0.0198953,0.00765929,0.039006,0.0390082,0.057469,4.41157e-11,4.41123e-11,4.50472e-10,0,0,5.00437e-08,0,0,0,0,0,0,0,0
33685000,0.983487,-0.0103452,-0.0117686,0.180301,0.0105664,-0.104481,-0.103474,0.0685326,-0.0498601,-0.0661834,-1.22959e-05,-5.64603e-05,5.21026e-06,3.66193e-05,-0.000316307,-0.00108138,0.204284,0.00196732,0.43436,0,0,0,0,0,2.97421e-06,1.40123e-05,1.40016e-05,8.59399e-05,0.021772,0.0217772,0.00761885,0.0433411,0.0433441,0.0573098,4.42146e-11,4.42111e-11,4.47717e-10,0,0,5.00524e-08,0,0,0,0,0,0,0,0
33785000,0.983499,-0.0101502,-0.011766,0.180244,0.0061529,-0.0969165,-0.0976914,0.0714237,-0.0431212,-0.0721574,-1.25583e-05,-5.63517e-05,5.1864e-06,3.66193e-05,-0.000316307,-0.0010821,0.204284,0.00196732,0.43436,0,0,0,0,0,2.96865e-06,1.3035e-05,1.3024e-05,8.58668e-05,0.0201765,0.020181,0.00749354,0.0393203,0.0393226,0.0567168,4.26294e-11,4.26234e-11,4.44943e-10,0,0,5.00318e-08,0,0,0,0,0,0,0,0
33885000,0.983515,-0.0101904,-0.0117232,0.180159,0.00265152,-0.0980029,-0.0972728,0.0718109,-0.0529131,-0.0793943,-1.25562e-05,-5.63539e-05,5.29279e-06,3.66193e-05,-0.000316307,-0.00108218,0.204284,0.00196732,0.43436,0,0,0,0,0,2.96583e-06,1.32399e-05,1.32288e-05,8.57955e-05,0.0220337,0.0220393,0.00748235,0.0437295,0.0437327,0.0565415,4.27283e-11,4.27222e-11,4.42157e-10,0,0,5.00388e-08,0,0,0,0,0,0,0,0
33985000,0.983509,-0.00994049,-0.0118585,0.180198,0.00025062,-0.0875232,-0.093623,0.0735091,-0.0435621,-0.0825813,-1.28357e-05,-5.62215e-05,5.24678e-06,3.66193e-05,-0.000316307,-0.00108311,0.204284,0.00196732,0.43436,0,0,0,0,0,2.96313e-06,1.22714e-05,1.22598e-05,8.57268e-05,0.0203261,0.020331,0.00738894,0.0396126,0.039615,0.0559638,4.12195e-11,4.12112e-11,4.39358e-10,0,0,5.0005e-08,0,0,0,0,0,0,0,0
34085000,0.983514,-0.00987785,-0.0118619,0.18017,-0.00332181,-0.09211,-0.0926886,0.0734001,-0.0525751,-0.0892355,-1.28356e-05,-5.62217e-05,5.25057e-06,3.66193e-05,-0.000316307,-0.00108322,0.204284,0.00196732,0.43436,0,0,0,0,0,2.97162e-06,1.24669e-05,1.2455e-05,8.60015e-05,0.0221485,0.0221543,0.00746156,0.0440804,0.0440836,0.0565803,4.13186e-11,4.13104e-11,4.37277e-10,0,0,5.00108e-08,0,0,0,0,0,0,0,0
34185000,0.983516,-0.00970738,-0.0119009,0.180171,-0.00691984,-0.0821847,-0.0903385,0.0755168,-0.0440138,-0.0909958,-1.30729e-05,-5.61014e-05,5.29734e-06,3.66193e-05,-0.000316307,-0.00108398,0.204284,0.00196732,0.43436,0,0,0,0,0,2.96993e-06,1.15223e-05,1.15102e-05,8.59375e-05,0.0203481,0.0203531,0.00739411,0.0398734,0.0398758,0.056008,3.99011e-11,3.98909e-11,4.34456e-10,0,0,5.00037e-08,0,0,0,0,0,0,0,0
34285000,0.983519,-0.00960031,-0.0119611,0.180151,-0.00704253,-0.085766,-0.089289,0.0748492,-0.0524524,-0.0982248,-1.30718e-05,-5.61025e-05,5.3535e-06,3.66193e-05,-0.000316307,-0.00108407,0.204284,0.00196732,0.43436,0,0,0,0,0,2.96842e-06,1.17088e-05,1.16963e-05,8.58765e-05,0.0221248,0.0221305,0.00743478,0.0443831,0.0443864,0.0558336,3.99999e-11,3.99898e-11,4.31626e-10,0,0,5.00041e-08,0,0,0,0,0,0,0,0
34385000,0.983543,-0.00938656,-0.011971,0.180031,-0.00986885,-0.0748689,-0.0842704,0.075178,-0.0436356,-0.101371,-1.32948e-05,-5.59992e-05,5.36789e-06,3.66193e-05,-0.000316307,-0.00108554,0.204284,0.00196732,0.43436,0,0,0,0,0,2.96235e-06,1.08008e-05,1.07881e-05,8.58221e-05,0.0202492,0.0202542,0.00739149,0.0400958,0.0400983,0.0552881,3.86828e-11,3.86712e-11,4.28786e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
34485000,0.983547,-0.0094715,-0.0119006,0.18001,-0.0128984,-0.0786622,-0.0827644,0.074041,-0.0513805,-0.104835,-1.32936e-05,-5.60006e-05,5.4274e-06,3.66193e-05,-0.000316307,-0.00108589,0.204284,0.00196732,0.43436,0,0,0,0,0,2.96101e-06,1.09785e-05,1.09659e-05,8.57657e-05,0.0219732,0.0219789,0.00745464,0.0446306,0.0446339,0.055129,3.87816e-11,3.87701e-11,4.25937e-10,0,0,5e-08,0,0,0,0,0,0,0,0
34585000,0.983553,-0.00927357,-0.0117243,0.179998,-0.0130421,-0.0671889,0.663145,0.0745274,-0.0436142,-0.0797037,-1.34749e-05,-5.59014e-05,5.4176e-06,3.66193e-05,-0.000316307,-0.00108724,0.204284,0.00196732,0.43436,0,0,0,0,0,2.95802e-06,1.01158e-05,1.01035e-05,8.57128e-05,0.0189434,0.0189479,0.00742518,0.0402451,0.0402476,0.0546138,3.75693e-11,3.75565e-11,4.2308e-10,0,0,5e-08,0,0,0,0,0,0,0,0
34685000,0.98356,-0.00926064,-0.0114371,0.179981,-0.0147792,-0.0642053,1.65381,0.0731437,-0.0501807,0.0331661,-1.34752e-05,-5.5901e-05,5.40248e-06,3.66193e-05,-0.000316307,-0.00108697,0.204284,0.00196732,0.43436,0,0,0,0,0,2.95523e-06,1.02851e-05,1.02734e-05,8.56619e-05,0.01905,0.0190545,0.00749931,0.044617,0.0446203,0.0544751,3.7668e-11,3.76555e-11,4.20216e-10,0,0,5e-08,0,0,0,0,0,0,0,0
34785000,0.983569,-0.00910198,-0.0112075,0.179953,-0.0148354,-0.0527349,2.62008,0.0739439,-0.0424845,0.194956,-1.36203e-05,-5.58107e-05,5.41699e-06,3.66193e-05,-0.000316307,-0.00106101,0.204284,0.00196732,0.43436,0,0,0,0,0,2.9637e-06,9.57218e-06,9.56083e-06,8.59506e-05,0.0162508,0.0162544,0.00753572,0.0401801,0.0401826,0.0547303,3.66803e-11,3.66668e-11,4.18086e-10,0,0,5.0002e-08,0,0,0,0,0,0,0,0
34885000,0.983575,-0.00908769,-0.0109215,0.179939,-0.016516,-0.0497357,3.60563,0.0724213,-0.0475812,0.484785,-1.3621e-05,-5.58096e-05,5.39671e-06,3.66193e-05,-0.000316307,-0.00105876,0.204284,0.00196732,0.43436,0,0,0,0,0,2.961e-06,9.7355e-06,9.72468e-06,8.5902e-05,0.0163598,0.0163633,0.00762762,0.0442776,0.0442807,0.0546132,3.67789e-11,3.67657e-11,4.15211e-10,0,0,5.0001e-08,0,0,0,0,0,0,0,0
1 Timestamp state[0] state[1] state[2] state[3] state[4] state[5] state[6] state[7] state[8] state[9] state[10] state[11] state[12] state[13] state[14] state[15] state[16] state[17] state[18] state[19] state[20] state[21] state[22] state[23] variance[0] variance[1] variance[2] variance[3] variance[4] variance[5] variance[6] variance[7] variance[8] variance[9] variance[10] variance[11] variance[12] variance[13] variance[14] variance[15] variance[16] variance[17] variance[18] variance[19] variance[20] variance[21] variance[22] variance[23]
2 15000 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
3 85000 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
4 185000 1 0.978841 0 -0.00940342 0 -0.0138305 0 0.203939 0 0.000868247 0 -0.000432975 0 -0.0109878 0 5.51235e-05 0 -7.42197e-06 0 -0.0416697 0 6.93025e-11 0 1.77536e-08 0 -7.39915e-07 0 0 0 -2.00585e-09 0 0.202638 0 0.0100117 0 0.433627 0 0 0 0 0 0 0.000152606 0 0.00247499 0 0.00247397 0 0.00360127 0 0.253406 0 0.253405 0 0.562563 0 0.126411 0 0.126411 0 1.00079 0 1e-06 0 1e-06 0 9.99741e-07 0 0 0 4.00001e-06 0 0 0 0 0 0 0 0
5 285000 1 0.978553 0 -0.00947781 0 -0.014151 0 0.205289 0 0.00243718 0 -0.00221013 0 -0.0263667 0 0.000169923 0 -0.000108556 0 -0.0412749 0 3.70594e-10 0 4.49321e-08 0 -1.87023e-06 0 0 0 -1.03405e-08 0 0.202638 0 0.0100117 0 0.433627 0 0 0 0 0 0 0.000103023 0 0.00252502 0 0.00252383 0 0.00242603 0 0.273201 0 0.273198 0 0.562506 0 0.132789 0 0.132789 0 0.576885 0 1e-06 0 9.99999e-07 0 9.97806e-07 0 0 0 4.00001e-06 0 0 0 0 0 0 0 0
6 385000 0.982011 0.980078 -0.00768853 -0.00953093 -0.0134662 -0.014351 0.188184 0.197863 0.000443332 0.00528301 0.000261826 -0.00302875 -0.00515777 -0.0395382 4.48561e-06 0.000420773 3.93582e-06 -0.000253337 -7.479e-05 -0.0244114 0 -1.2655e-08 0 -4.95636e-07 0 2.04904e-05 0 0 0 -2.11522e-07 0.203397 0.202638 0.00195875 0.0100117 0.43452 0.433627 0 0 0 0 0 0.000177748 7.33058e-05 0.0024727 0.00262318 0.00247219 0.00262185 0.00482432 0.00172175 25.0004 0.304531 25.0004 0.304525 0.562573 0.560114 0.259374 0.0939538 0.259374 0.0939537 4.00051 0.375592 1e-06 9.99998e-07 1e-06 9.99992e-07 1e-06 9.90493e-07 0 0 4e-06 3.99998e-06 0 0 0 0 0 0 0 0
7 485000 0.982383 0.980935 -0.0077361 -0.00968888 -0.0138297 -0.0148482 0.186204 0.193528 0.00147596 0.00982759 0.000493386 -0.00667245 -0.0226201 -0.0568121 0.000128083 0.00132566 3.81988e-05 -0.000773921 0.012004 -0.0284138 2.01269e-08 8.40272e-07 3.33849e-11 -2.27633e-07 8.41725e-07 4.49953e-05 0 0 5.50648e-08 -1.46461e-08 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 0.00011506 5.86412e-05 0.0024946 0.00277274 0.00249436 0.00277138 0.00311143 0.00137375 25.009 0.36556 25.009 0.365583 0.56266 0.55387 0.609397 0.108527 0.609397 0.108527 0.802449 0.287379 1e-06 9.9998e-07 1e-06 9.9999e-07 9.99318e-07 9.75648e-07 0 0 4.00001e-06 3.99978e-06 0 0 0 0 0 0 0 0
8 585000 0.982395 0.981446 -0.00775776 -0.00977015 -0.0140474 -0.0151262 0.186127 0.190892 0.000124163 0.0122716 0.000407154 -0.00999272 -0.0407871 -0.0751501 4.57057e-05 0.00195456 1.49825e-05 -0.00126521 0.00559437 -0.0361339 2.23668e-08 1.44985e-06 -1.4794e-10 -1.14137e-07 9.35397e-07 6.58791e-05 0 0 1.69579e-07 2.76911e-07 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 7.46438e-05 5.04182e-05 0.0025641 0.00293483 0.00256402 0.00293343 0.00200975 0.00118328 7.81334 0.411898 7.81334 0.411963 0.561469 0.542812 0.228164 0.0893709 0.228164 0.0893724 0.451638 0.242024 9.99997e-07 9.99709e-07 1e-06 9.99741e-07 9.94889e-07 9.52151e-07 0 0 4e-06 3.99919e-06 0 0 0 0 0 0 0 0
9 685000 0.982306 0.98176 -0.00778766 -0.00984672 -0.014415 -0.0155383 0.186564 0.189235 0.00269711 0.0181755 0.00147583 -0.0126958 -0.0490401 -0.079765 0.000225835 0.00359858 0.000114014 -0.00241693 0.0168583 -0.0326454 -1.70626e-08 1.91935e-06 -3.19376e-10 -3.60837e-08 -6.75191e-07 8.1523e-05 0 0 -3.88272e-07 -1.6953e-06 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 5.66967e-05 4.55862e-05 0.00268405 0.00318361 0.00268402 0.00318212 0.00151998 0.00107557 7.85185 0.516237 7.85185 0.516375 0.557235 0.525907 0.486041 0.114589 0.486041 0.114595 0.322026 0.217499 9.9999e-07 9.99679e-07 1e-06 9.9974e-07 9.84024e-07 9.18799e-07 0 0 3.99989e-06 3.99786e-06 0 0 0 0 0 0 0 0
10 785000 0.98226 0.982023 -0.0077893 -0.00979184 -0.0146418 -0.0157123 0.186787 0.187852 0.00367557 0.0211215 0.00336477 -0.0120094 -0.0598107 -0.0884533 0.00012 0.00392279 8.49913e-05 -0.00256314 0.0131552 -0.0373845 -4.88069e-08 1.92224e-06 -4.55154e-09 -2.49904e-07 -1.999e-06 9.53332e-05 0 0 -6.61606e-07 -2.81548e-06 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 4.72199e-05 4.26141e-05 0.00284792 0.00330368 0.00284792 0.00330223 0.00126121 0.00101621 2.59845 0.540694 2.59845 0.540881 0.548781 0.503501 0.195719 0.0990934 0.195719 0.099101 0.259034 0.204568 9.99924e-07 9.97017e-07 9.99946e-07 9.9711e-07 9.65217e-07 8.76387e-07 0 0 3.99951e-06 3.99536e-06 0 0 0 0 0 0 0 0
11 885000 0.982158 0.982175 -0.00783508 -0.00985493 -0.0149921 -0.0160794 0.187296 0.18702 0.00529847 0.0257555 0.00620103 -0.0127343 -0.0766202 -0.104574 0.000534645 0.0062643 0.000532679 -0.00383762 -0.000215845 -0.0502246 -1.88752e-07 2.07931e-06 -8.08544e-09 -2.35812e-07 -7.49367e-06 0.000100917 0 0 9.87764e-08 -1.89113e-06 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 4.19196e-05 4.08464e-05 0.0030677 0.00364557 0.00306771 0.00364398 0.00111513 0.000984803 2.66006 0.686233 2.66007 0.686533 0.534815 0.475831 0.329467 0.136933 0.329467 0.136953 0.225286 0.198089 9.99906e-07 9.96976e-07 9.99946e-07 9.9711e-07 9.36864e-07 8.255e-07 0 0 3.99856e-06 3.99118e-06 0 0 0 0 0 0 0 0
12 985000 0.981971 0.982188 -0.0077787 -0.00959921 -0.0152895 -0.0161461 0.188252 0.186961 0.00814651 0.02548 0.00897846 -0.0099564 -0.0901035 -0.116428 0.00121988 0.00557201 0.00123072 -0.00313179 -0.00832347 -0.0592959 -4.98634e-07 6.32374e-07 -1.27859e-08 -1.17085e-06 -1.95553e-05 9.28885e-05 0 0 -1.56181e-07 -2.97392e-06 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 4.08581e-05 4.1334e-05 0.0033375 0.00358837 0.00333748 0.00358701 0.0010841 0.00101512 2.74789 0.6426 2.74791 0.642879 0.521629 0.453924 0.517251 0.113733 0.517252 0.113749 0.218362 0.20526 9.99888e-07 9.85886e-07 9.99946e-07 9.86042e-07 9.09096e-07 7.82931e-07 0 0 3.99721e-06 3.9866e-06 0 0 0 0 0 0 0 0
13 1085000 0.982058 0.982436 -0.00788834 -0.00970805 -0.0154754 -0.0163541 0.187778 0.185627 0.0140069 0.0357421 0.00747436 -0.01283 -0.109258 -0.134558 0.00131404 0.00863414 0.00114157 -0.00421267 -0.0271122 -0.0779928 -2.97538e-07 1.01005e-06 -6.23305e-08 -1.16987e-06 -1.26407e-05 0.000106839 0 0 2.02264e-06 -3.55292e-07 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.91193e-05 4.04985e-05 0.00362883 0.0040074 0.0036288 0.00400593 0.00103395 0.00100677 1.28867 0.81804 1.28869 0.818449 0.497697 0.420557 0.244169 0.162616 0.244169 0.16265 0.207776 0.20383 9.99213e-07 9.85839e-07 9.99301e-07 9.86042e-07 8.64086e-07 7.22502e-07 0 0 3.99418e-06 3.97832e-06 0 0 0 0 0 0 0 0
14 1185000 0.982103 0.982629 -0.00785134 -0.009376 -0.0157472 -0.016215 0.187519 0.184634 0.0199119 0.0341162 0.00773154 -0.0111947 -0.109438 -0.131011 0.00297966 0.00696648 0.00189164 -0.00308594 -0.0224504 -0.0734422 -1.89472e-07 -1.02631e-06 -4.93037e-08 -3.25723e-06 -8.44625e-06 0.000114034 0 0 -3.17847e-06 -9.55569e-06 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.83111e-05 3.94925e-05 0.00399723 0.00372784 0.00399715 0.0037268 0.00100838 0.00100169 1.41188 0.689881 1.41193 0.690177 0.469194 0.386375 0.351603 0.124916 0.351605 0.124936 0.202802 0.203012 9.99176e-07 9.59002e-07 9.99301e-07 9.59225e-07 8.11655e-07 6.60384e-07 0 0 3.98936e-06 3.96732e-06 0 0 0 0 0 0 0 0
15 1285000 0.982352 0.982973 -0.00777499 -0.00927524 -0.0159835 -0.0164925 0.186195 0.182774 0.0247828 0.0441505 0.00742468 -0.0121445 -0.118105 -0.137145 0.00313056 0.0109828 0.00131659 -0.00429794 -0.0274475 -0.0780983 4.47778e-07 -4.23974e-07 -3.26863e-07 -3.26396e-06 1.34511e-05 0.00013553 0 0 -5.99233e-06 -1.4817e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.79059e-05 3.87924e-05 0.00431959 0.00420002 0.00431945 0.00419884 0.000995537 0.000995752 0.887165 0.881426 0.887222 0.881843 0.437027 0.352464 0.196916 0.180129 0.196917 0.180169 0.200584 0.20185 9.95592e-07 9.58956e-07 9.95759e-07 9.59225e-07 7.53272e-07 5.98372e-07 0 0 3.98218e-06 3.95328e-06 0 0 0 0 0 0 0 0
16 1385000 0.982423 0.983132 -0.0077567 -0.008886 -0.0161987 -0.0160825 0.185803 0.181974 0.0335764 0.0404405 0.00818402 -0.00909161 -0.117743 -0.134727 0.00607413 0.00811338 0.00212754 -0.00281806 -0.0250334 -0.0751603 5.75184e-07 -3.64446e-06 -2.97805e-07 -6.91576e-06 1.81008e-05 0.000136827 0 0 -1.31876e-05 -2.58496e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.77201e-05 3.75589e-05 0.00478197 0.00375983 0.00478175 0.00375912 0.000988194 0.000986837 1.05544 0.695614 1.05554 0.695872 0.402817 0.320036 0.273467 0.129617 0.273471 0.129636 0.199431 0.19999 9.95546e-07 9.12921e-07 9.95759e-07 9.13193e-07 6.91415e-07 5.38299e-07 0 0 3.97225e-06 3.93598e-06 0 0 0 0 0 0 0 0
17 1485000 0.982344 0.983095 -0.00774028 -0.0088203 -0.0162312 -0.0162462 0.186216 0.182163 0.0328954 0.0463285 0.00736377 -0.00987824 -0.131166 -0.145946 0.00539622 0.0124459 0.0016211 -0.00369679 -0.0377946 -0.0873605 2.88776e-07 -4.0155e-06 -1.43042e-06 -6.86295e-06 9.67851e-06 0.0001227 0 0 -1.3221e-05 -2.73295e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.75599e-05 3.67972e-05 0.0050284 0.00426027 0.00502812 0.00425947 0.000982458 0.000975217 0.820131 0.892242 0.82023 0.892591 0.368572 0.290236 0.171213 0.186625 0.171216 0.186662 0.198527 0.197531 9.82897e-07 9.12881e-07 9.83154e-07 9.13192e-07 6.29097e-07 4.82087e-07 0 0 3.95945e-06 3.91565e-06 0 0 0 0 0 0 0 0
18 1585000 0.982341 0.983156 -0.00783321 -0.00852408 -0.0165968 -0.0158428 0.186197 0.181882 0.0407489 0.0383209 0.00831374 -0.00647075 -0.142896 -0.156394 0.00907188 0.00843818 0.00237274 -0.00230591 -0.048738 -0.0982294 2.84346e-07 -8.01557e-06 -1.419e-06 -1.19154e-05 9.46092e-06 0.000117654 0 0 -1.50659e-05 -3.08256e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.92088e-05 3.70866e-05 0.0055717 0.00373087 0.00557131 0.00373046 0.00102157 0.00100483 1.03987 0.683993 1.04002 0.684191 0.345437 0.271814 0.237963 0.129353 0.237971 0.129368 0.207551 0.204446 9.82862e-07 8.48387e-07 9.83154e-07 8.48674e-07 5.83132e-07 4.42698e-07 0 0 3.94785e-06 3.8983e-06 0 0 0 0 0 0 0 0
19 1685000 0.982369 0.983175 -0.00794259 -0.00856868 -0.0164903 -0.0160557 0.186056 0.181756 0.0398606 0.0459118 0.00805451 -0.00579941 -0.149392 -0.161627 0.00741854 0.01267 0.00180772 -0.00286207 -0.0545571 -0.103522 9.14125e-09 -8.14487e-06 -4.13421e-06 -1.18421e-05 1.18544e-05 0.000111392 0 0 -2.08158e-05 -3.92121e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.882e-05 3.62215e-05 0.00556111 0.0042377 0.00556075 0.00423721 0.00101071 0.000985324 0.88674 0.88178 0.886892 0.882053 0.313728 0.24718 0.159531 0.185645 0.159536 0.185675 0.205396 0.200424 9.50462e-07 8.48354e-07 9.5079e-07 8.48672e-07 5.24054e-07 3.94316e-07 0 0 3.92954e-06 3.87226e-06 0 0 0 0 0 0 0 0
20 1785000 0.982334 0.983132 -0.00808799 -0.00867435 -0.0167811 -0.0163034 0.186205 0.181963 0.0501565 0.0555627 0.00835837 -0.00685987 -0.150958 -0.162493 0.0119658 0.0178072 0.00262719 -0.00352641 -0.0574105 -0.106041 -9.86644e-08 -8.41812e-06 -4.07221e-06 -1.17243e-05 7.51234e-06 9.9083e-05 0 0 -2.95762e-05 -5.10542e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.85692e-05 3.53543e-05 0.00615771 0.00478693 0.0061572 0.00478637 0.000996183 0.000963023 1.15403 1.12358 1.15426 1.12394 0.284485 0.225522 0.227071 0.266166 0.227085 0.266219 0.202407 0.195911 9.5042e-07 8.48322e-07 9.50789e-07 8.4867e-07 4.68638e-07 3.50677e-07 0 0 3.90791e-06 3.84276e-06 0 0 0 0 0 0 0 0
21 1885000 0.982456 0.983223 -0.00803278 -0.00822356 -0.0163404 -0.0156554 0.185603 0.181548 0.0442965 0.0444571 0.00911068 -0.000592779 -0.152972 -0.163824 0.00912952 0.0124994 0.00192647 -0.00185756 -0.0623763 -0.110734 -6.89113e-07 -1.23773e-05 -9.08826e-06 -1.77845e-05 1.6594e-05 9.80573e-05 0 0 -3.75606e-05 -6.19125e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.77135e-05 3.38433e-05 0.00570546 0.00414405 0.00570506 0.00414376 0.000978666 0.000939012 0.975295 0.865069 0.975496 0.86529 0.258346 0.206866 0.156401 0.181237 0.15641 0.181259 0.198874 0.191243 8.88242e-07 7.6811e-07 8.88626e-07 7.68426e-07 4.1791e-07 3.11829e-07 0 0 3.88319e-06 3.81008e-06 0 0 0 0 0 0 0 0
22 1985000 0.982484 0.983209 -0.00813573 -0.00827243 -0.0167089 -0.0159687 0.185416 0.181593 0.0528511 0.0516589 0.010163 -0.000150602 -0.151646 -0.162415 0.0140118 0.0173435 0.00284661 -0.00197594 -0.0616876 -0.110064 -6.17211e-07 -1.24897e-05 -8.97091e-06 -1.76231e-05 1.83519e-05 9.07375e-05 0 0 -5.10329e-05 -7.895e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.72857e-05 3.30014e-05 0.006313 0.0046766 0.00631243 0.00467622 0.000958273 0.000913761 1.27231 1.10486 1.2726 1.10515 0.235187 0.190844 0.228684 0.259702 0.228705 0.259743 0.194764 0.186408 8.88209e-07 7.68086e-07 8.88624e-07 7.68423e-07 3.71907e-07 2.77412e-07 0 0 3.85509e-06 3.77375e-06 0 0 0 0 0 0 0 0
23 2085000 0.982403 0.983085 -0.00820968 -0.0080177 -0.01606 -0.0153531 0.185902 0.182331 0.0428688 0.0400863 0.00778176 0.00272938 -0.150045 -0.160921 0.00976408 0.0117972 0.00192821 -0.000773254 -0.0592128 -0.107788 -2.06802e-06 -1.64074e-05 -1.59782e-05 -2.42102e-05 9.9021e-06 7.48744e-05 0 0 -6.74532e-05 -9.92268e-05 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.60425e-05 3.15277e-05 0.00539436 0.00397017 0.00539404 0.00397 0.00093585 0.000887914 1.01533 0.846357 1.01554 0.846533 0.215118 0.177296 0.156223 0.175672 0.156234 0.175689 0.190412 0.181667 7.97339e-07 6.76422e-07 7.97744e-07 6.76719e-07 3.30791e-07 2.47083e-07 0 0 3.82386e-06 3.73406e-06 0 0 0 0 0 0 0 0
24 2185000 0.982422 0.983045 -0.00817963 -0.00791925 -0.0163991 -0.015637 0.185773 0.182524 0.0506113 0.0462677 0.00855272 0.00365563 -0.151868 -0.162106 0.0144505 0.0161309 0.00280604 -0.000426748 -0.0637389 -0.112203 -2.02821e-06 -1.65492e-05 -1.58815e-05 -2.40676e-05 1.05455e-05 6.70191e-05 0 0 -7.8001e-05 -0.00011296 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.54832e-05 3.07387e-05 0.00596901 0.00446904 0.0059685 0.00446877 0.000911938 0.000861871 1.31425 1.08032 1.31455 1.08056 0.197789 0.165843 0.232007 0.251794 0.232031 0.251825 0.185808 0.176978 7.97317e-07 6.76404e-07 7.97741e-07 6.76716e-07 2.94224e-07 2.20423e-07 0 0 3.78909e-06 3.69044e-06 0 0 0 0 0 0 0 0
25 2285000 0.982579 0.983156 -0.00825584 -0.00775274 -0.0156295 -0.0150158 0.185004 0.181988 0.0370421 0.0334751 0.00635088 0.00590942 -0.149355 -0.159621 0.00930094 0.0105654 0.00176835 0.000237655 -0.0631027 -0.112107 -3.25685e-06 -1.93269e-05 -2.36858e-05 -3.08856e-05 2.01746e-05 6.93558e-05 0 0 -9.45543e-05 -0.000132862 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.53177e-05 3.04075e-05 0.00477762 0.00371161 0.00477742 0.0037115 0.000924776 0.000869302 0.983703 0.820419 0.983879 0.820563 0.188685 0.160805 0.154751 0.169793 0.154762 0.169806 0.189826 0.180305 6.92092e-07 5.79017e-07 6.92484e-07 5.79282e-07 2.69513e-07 2.02495e-07 0 0 3.76058e-06 3.65504e-06 0 0 0 0 0 0 0 0
26 2385000 0.982599 0.983107 -0.00831892 -0.00773992 -0.0158091 -0.015143 0.184876 0.182238 0.0441957 0.039117 0.00574252 0.00607187 -0.14923 -0.159176 0.0133974 0.014234 0.0023617 0.000782537 -0.061494 -0.110632 -3.20528e-06 -1.94236e-05 -2.35383e-05 -3.06887e-05 2.07612e-05 6.2405e-05 0 0 -0.000112632 -0.000155101 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.45463e-05 2.95754e-05 0.00529153 0.00416361 0.00529121 0.00416342 0.000897407 0.000841812 1.26229 1.04527 1.26254 1.04546 0.175646 0.152442 0.230156 0.243269 0.230178 0.243294 0.184795 0.175641 6.92077e-07 5.79003e-07 6.92481e-07 5.79279e-07 2.40119e-07 1.81259e-07 0 0 3.71943e-06 3.6043e-06 0 0 0 0 0 0 0 0
27 2485000 0.982738 0.983168 -0.00824021 -0.00751173 -0.0150709 -0.0145513 0.184202 0.181969 0.029843 0.0262096 0.00381465 0.0072234 -0.150946 -0.160029 0.00819469 0.00904123 0.00135768 0.000883335 -0.0648707 -0.113847 -4.52457e-06 -2.14427e-05 -3.07403e-05 -3.7042e-05 2.91336e-05 6.28858e-05 0 0 -0.000125966 -0.000172069 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.29155e-05 2.81842e-05 0.00408311 0.00338153 0.00408302 0.00338144 0.000870016 0.000815043 0.904773 0.785707 0.904906 0.785825 0.164702 0.145526 0.15059 0.163732 0.150598 0.163743 0.179987 0.171323 5.8904e-07 4.82463e-07 5.89405e-07 4.82694e-07 2.14294e-07 1.62602e-07 0 0 3.67475e-06 3.54969e-06 0 0 0 0 0 0 0 0
28 2585000 0.982779 0.983141 -0.00836863 -0.00755847 -0.015207 -0.0146404 0.18397 0.182106 0.0330184 0.0279928 0.00233121 0.00703042 -0.153877 -0.162066 0.0113339 0.0117504 0.00170753 0.00160901 -0.0690052 -0.117764 -4.49709e-06 -2.15444e-05 -3.06456e-05 -3.68926e-05 2.91162e-05 5.68248e-05 0 0 -0.000139435 -0.000189262 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.20634e-05 2.73786e-05 0.0045291 0.00377859 0.00452894 0.00377844 0.00084311 0.000789206 1.15084 0.996275 1.15101 0.99643 0.155525 0.139793 0.222218 0.234148 0.222236 0.234168 0.175338 0.167263 5.8903e-07 4.82453e-07 5.89402e-07 4.82691e-07 1.91636e-07 1.46239e-07 0 0 3.62596e-06 3.49054e-06 0 0 0 0 0 0 0 0
29 2685000 0.982848 0.983141 -0.00842845 -0.0075548 -0.0145921 -0.0141109 0.183649 0.182145 0.0221951 0.0181386 0.00155523 0.00780726 -0.153268 -0.160763 0.00671124 0.00717528 0.000897824 0.00127966 -0.0681768 -0.116894 -5.79852e-06 -2.27916e-05 -3.6275e-05 -4.20966e-05 3.16622e-05 5.3742e-05 0 0 -0.000161179 -0.000215429 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 3.04881e-05 2.60799e-05 0.00345947 0.00300716 0.00345949 0.00300712 0.00081633 0.000763975 0.809423 0.740963 0.809516 0.74106 0.147823 0.135018 0.144404 0.15744 0.14441 0.157449 0.170893 0.163468 4.97368e-07 3.92671e-07 4.97698e-07 3.92867e-07 1.71663e-07 1.31771e-07 0 0 3.57283e-06 3.4267e-06 0 0 0 0 0 0 0 0
30 2785000 0.982827 0.983064 -0.00838477 -0.0074292 -0.0147521 -0.0142258 0.183749 0.182557 0.0276101 0.0221739 0.00122579 0.00904533 -0.150508 -0.157374 0.00933737 0.00933035 0.00104206 0.00209587 -0.0646975 -0.113416 -5.81706e-06 -2.29146e-05 -3.60867e-05 -4.18692e-05 2.79547e-05 4.59254e-05 0 0 -0.000187643 -0.000246785 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.96653e-05 2.53537e-05 0.00384307 0.00334674 0.00384301 0.00334664 0.000790827 0.000740125 1.02279 0.934192 1.02292 0.934331 0.141516 0.131148 0.210532 0.22428 0.210546 0.224297 0.166798 0.160041 4.97361e-07 3.92663e-07 4.97696e-07 3.92865e-07 1.54221e-07 1.19101e-07 0 0 3.51578e-06 3.35874e-06 0 0 0 0 0 0 0 0
31 2885000 0.982922 0.983114 -0.00839969 -0.00745083 -0.0143121 -0.0138355 0.183273 0.182319 0.0198522 0.0150901 -0.00141653 0.00669869 -0.15202 -0.158078 0.0055695 0.00567455 0.000478032 0.00148558 -0.065987 -0.114763 -7.03735e-06 -2.34682e-05 -4.04489e-05 -4.59847e-05 3.08365e-05 4.52535e-05 0 0 -0.000207848 -0.000270622 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.92205e-05 2.49634e-05 0.00295316 0.00262038 0.00295323 0.00262036 0.000794074 0.000741635 0.718518 0.688444 0.718584 0.688526 0.139979 0.131224 0.137333 0.150907 0.137338 0.150914 0.169975 0.163371 4.19026e-07 3.13687e-07 4.19319e-07 3.13849e-07 1.42494e-07 1.10539e-07 0 0 3.47018e-06 3.30487e-06 0 0 0 0 0 0 0 0
32 2985000 0.982996 0.983131 -0.00843865 -0.00741151 -0.0144084 -0.0138904 0.182864 0.182223 0.0228485 0.0167206 -0.00293635 0.00690476 -0.155032 -0.159849 0.00781168 0.00737651 0.000278074 0.00216274 -0.0702069 -0.118475 -6.94962e-06 -2.34647e-05 -4.03976e-05 -4.58907e-05 3.36889e-05 4.40775e-05 0 0 -0.000224422 -0.000291111 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.84018e-05 2.42739e-05 0.00328368 0.00290465 0.00328371 0.00290459 0.000768599 0.000718297 0.903534 0.862372 0.903622 0.862482 0.135476 0.128447 0.197647 0.213726 0.197657 0.21374 0.166181 0.160307 4.19021e-07 3.13681e-07 4.19317e-07 3.13847e-07 1.28549e-07 1.00329e-07 0 0 3.40536e-06 3.22898e-06 0 0 0 0 0 0 0 0
33 3085000 0.982946 0.98304 -0.00848459 -0.00741737 -0.0145901 -0.0136439 0.183117 0.182733 0.0285875 0.0130057 -0.00550112 0.00386812 -0.158893 -0.162536 0.0104242 0.00453635 -0.000190947 0.00134382 -0.0749456 -0.122684 -6.95714e-06 -2.38321e-05 -4.02863e-05 -4.89729e-05 3.13527e-05 3.89465e-05 0 0 -0.000241952 -0.000312485 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.77032e-05 2.32561e-05 0.00363514 0.00224826 0.00363513 0.00224825 0.000744046 0.000695793 1.1235 0.63168 1.12362 0.631747 0.131741 0.126084 0.282762 0.144218 0.282781 0.144224 0.162668 0.157497 4.19016e-07 2.47275e-07 4.19314e-07 2.47408e-07 1.16239e-07 9.12337e-08 0 0 3.3358e-06 3.14845e-06 0 0 0 0 0 0 0 0
34 3185000 0.982823 0.982874 -0.00843186 -0.00738681 -0.0142554 -0.0137364 0.183809 0.183619 0.0221182 0.0152254 -0.00765307 0.00327908 -0.160674 -0.163058 0.00680933 0.00597394 -0.000763218 0.00163628 -0.0803059 -0.127431 -8.53369e-06 -2.4043e-05 -4.35952e-05 -4.88035e-05 2.30248e-05 2.91299e-05 0 0 -0.000259189 -0.00033342 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.64267e-05 2.26577e-05 0.00284016 0.00248254 0.00284023 0.00248251 0.000720579 0.000674636 0.802139 0.785632 0.802201 0.785722 0.128672 0.124122 0.18515 0.202747 0.185158 0.202758 0.159519 0.155012 3.52557e-07 2.47271e-07 3.52818e-07 2.47406e-07 1.05352e-07 8.32046e-08 0 0 3.26217e-06 3.06418e-06 0 0 0 0 0 0 0 0
35 3285000 0.982838 0.982851 -0.00846252 -0.00736268 -0.0142669 -0.0134088 0.183726 0.183766 0.0250887 0.0103407 -0.00862238 0.00258927 -0.164702 -0.165772 0.00920371 0.00372943 -0.0016296 0.000954691 -0.0887593 -0.135155 -8.5049e-06 -2.4378e-05 -4.35361e-05 -5.11351e-05 2.29562e-05 2.66985e-05 0 0 -0.000272964 -0.000350311 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.57412e-05 2.17337e-05 0.00314379 0.00190856 0.00314384 0.00190857 0.000698263 0.000654314 0.994125 0.573705 0.994215 0.573761 0.126109 0.122373 0.262082 0.137514 0.262096 0.137519 0.156631 0.152738 3.52553e-07 1.93311e-07 3.52815e-07 1.93417e-07 9.5736e-08 7.60182e-08 0 0 3.18391e-06 2.9757e-06 0 0 0 0 0 0 0 0
36 3385000 0.982774 0.982751 -0.00816739 -0.00714424 -0.0139452 -0.0134289 0.184104 0.184306 0.0180715 0.010519 -0.00714377 0.00422486 -0.163838 -0.163751 0.0059688 0.00475779 -0.00142476 0.00128052 -0.0871283 -0.132982 -1.0235e-05 -2.44864e-05 -4.61096e-05 -5.09677e-05 1.82849e-05 2.08254e-05 0 0 -0.000306313 -0.000387648 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.4616e-05 2.11824e-05 0.0024836 0.00209968 0.0024837 0.00209966 0.000676979 0.000635185 0.719299 0.709132 0.719352 0.709209 0.123971 0.120849 0.173738 0.19167 0.173744 0.19168 0.154066 0.150738 2.95827e-07 1.93307e-07 2.96053e-07 1.93416e-07 8.71884e-08 6.96428e-08 0 0 3.10184e-06 2.8841e-06 0 0 0 0 0 0 0 0
37 3485000 0.982695 0.982649 -0.00816339 -0.00709366 -0.0139806 -0.0131982 0.184525 0.184869 0.0228884 0.00889291 -0.00568018 0.00609927 -0.162858 -0.161637 0.00812011 0.0030114 -0.00207703 0.000937874 -0.0876651 -0.1329 -1.02676e-05 -2.47425e-05 -4.59447e-05 -5.25965e-05 1.3348e-05 1.49305e-05 0 0 -0.00033625 -0.000421103 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.39918e-05 2.03845e-05 0.00274646 0.00160977 0.00274653 0.00160978 0.000656757 0.000616823 0.889359 0.518186 0.889446 0.51824 0.122129 0.119398 0.243681 0.130942 0.243693 0.130946 0.151722 0.148899 2.95824e-07 1.505e-07 2.96051e-07 1.50584e-07 7.96069e-08 6.39102e-08 0 0 3.01547e-06 2.78901e-06 0 0 0 0 0 0 0 0
38 3585000 0.982699 0.982628 -0.00796598 -0.00698251 -0.0136074 -0.0131097 0.184537 0.184993 0.0182781 0.0103458 -0.00508906 0.00648998 -0.169078 -0.166648 0.00551376 0.00402298 -0.00141354 0.00156436 -0.0958663 -0.140437 -1.18888e-05 -2.47805e-05 -4.81556e-05 -5.2534e-05 1.2233e-05 1.29106e-05 0 0 -0.000352539 -0.000439421 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.36751e-05 2.04245e-05 0.00218659 0.00176478 0.00218671 0.00176477 0.000656709 0.000616452 0.651549 0.636215 0.651602 0.636287 0.123407 0.120837 0.163606 0.180844 0.163612 0.180852 0.155467 0.152908 2.4703e-07 1.50497e-07 2.47224e-07 1.50584e-07 7.44343e-08 6.00165e-08 0 0 2.94807e-06 2.71569e-06 0 0 0 0 0 0 0 0
39 3685000 0.982807 0.982705 -0.0080029 -0.00699966 -0.0136691 -0.0129486 0.183957 0.184592 0.0200469 0.00658903 -0.00584276 0.00575718 -0.166139 -0.162462 0.00757218 0.00261733 -0.00198029 0.00112367 -0.0948425 -0.138638 -1.17373e-05 -2.46408e-05 -4.81215e-05 -5.39675e-05 1.68549e-05 1.57582e-05 0 0 -0.000388329 -0.000477905 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.30767e-05 1.97129e-05 0.00241387 0.00135338 0.00241399 0.0013534 0.000637289 0.000598902 0.80345 0.466244 0.803521 0.466289 0.121857 0.119389 0.22766 0.124621 0.22767 0.124625 0.153422 0.151282 2.47028e-07 1.17056e-07 2.47223e-07 1.17123e-07 6.82226e-08 5.52728e-08 0 0 2.85524e-06 2.61595e-06 0 0 0 0 0 0 0 0
40 3785000 0.982773 0.982647 -0.00783102 -0.006904 -0.0135027 -0.0130362 0.184156 0.184896 0.0139712 0.00592338 -0.00151095 0.00996651 -0.168319 -0.163408 0.00497409 0.00326792 -0.00115701 0.00199106 -0.100561 -0.143479 -1.32045e-05 -2.47032e-05 -5.0065e-05 -5.389e-05 1.45328e-05 1.28186e-05 0 0 -0.000410317 -0.000501903 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.21955e-05 1.9243e-05 0.00192922 0.00147878 0.00192936 0.00147878 0.000618815 0.000582353 0.59437 0.568452 0.594421 0.568515 0.12042 0.117949 0.154645 0.170479 0.15465 0.170486 0.151619 0.149836 2.04919e-07 1.17054e-07 2.05084e-07 1.17122e-07 6.26475e-08 5.10248e-08 0 0 2.7598e-06 2.51485e-06 0 0 0 0 0 0 0 0
41 3885000 0.982817 0.98267 -0.00781719 -0.00683416 -0.0135686 -0.0130709 0.183915 0.184777 0.014566 0.00516049 -0.00151863 0.0116424 -0.166859 -0.160778 0.00653182 0.00394857 -0.00125161 0.00313111 -0.102401 -0.144464 -1.31226e-05 -2.46699e-05 -5.00295e-05 -5.38575e-05 1.64763e-05 1.37836e-05 0 0 -0.000440574 -0.000533829 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.16606e-05 1.88056e-05 0.00212493 0.00161003 0.00212507 0.00161002 0.000601279 0.000566545 0.730692 0.686588 0.73076 0.686669 0.119002 0.116418 0.213657 0.232144 0.213667 0.232157 0.149954 0.148463 2.04918e-07 1.17051e-07 2.05083e-07 1.17121e-07 5.76622e-08 4.71879e-08 0 0 2.66147e-06 2.41218e-06 0 0 0 0 0 0 0 0
42 3985000 0.982709 0.98255 -0.00776702 -0.00689917 -0.0133656 -0.0129353 0.184508 0.18542 0.0126386 0.00460053 -0.000934107 0.0103244 -0.166913 -0.159848 0.00428869 0.00238671 -0.00075271 0.00250175 -0.102402 -0.143678 -1.42236e-05 -2.44195e-05 -5.15936e-05 -5.48728e-05 1.16033e-05 8.96882e-06 0 0 -0.000476228 -0.000570883 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.08853e-05 1.82076e-05 0.00169953 0.00123844 0.00169969 0.00123846 0.000584443 0.000551386 0.54499 0.507349 0.545035 0.507401 0.117541 0.11477 0.146667 0.160717 0.146672 0.160723 0.148396 0.14714 1.68696e-07 9.1169e-08 1.68835e-07 9.12237e-08 5.31532e-08 4.37022e-08 0 0 2.56073e-06 2.30852e-06 0 0 0 0 0 0 0 0
43 4085000 0.982648 0.982479 -0.00773488 -0.00681247 -0.0133148 -0.0128538 0.184838 0.185806 0.0149281 0.00555607 -0.00193326 0.0109645 -0.156318 -0.148375 0.0058387 0.00303767 -0.000893984 0.00359074 -0.0921072 -0.132664 -1.42013e-05 -2.44807e-05 -5.14546e-05 -5.47656e-05 8.91686e-06 6.17474e-06 0 0 -0.000532892 -0.000628546 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.03936e-05 1.78047e-05 0.001867 0.00134446 0.00186717 0.00134448 0.000568587 0.000537064 0.667582 0.609211 0.667639 0.609277 0.116076 0.113058 0.20131 0.216895 0.201318 0.216907 0.147005 0.145924 1.68695e-07 9.11673e-08 1.68834e-07 9.12229e-08 4.91159e-08 4.05606e-08 0 0 2.45891e-06 2.20521e-06 0 0 0 0 0 0 0 0
44 4185000 0.982688 0.982505 -0.00779914 -0.00699703 -0.013085 -0.0127009 0.184642 0.185669 0.0112228 0.00350826 -0.00234072 0.00851795 -0.158786 -0.149861 0.00388818 0.00192613 -0.000617489 0.0026474 -0.0991956 -0.138879 -1.50251e-05 -2.39786e-05 -5.29285e-05 -5.56418e-05 9.81956e-06 6.69986e-06 0 0 -0.000551482 -0.000647312 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 2.01959e-05 1.76862e-05 0.00149113 0.00103832 0.00149132 0.00103836 0.000567924 0.0005363 0.500288 0.452514 0.500321 0.452554 0.117306 0.113955 0.139474 0.151625 0.139477 0.15163 0.151261 0.150231 1.37789e-07 7.12199e-08 1.37904e-07 7.12634e-08 4.63287e-08 3.83863e-08 0 0 2.38192e-06 2.12804e-06 0 0 0 0 0 0 0 0
45 4285000 0.982749 0.982554 -0.00787293 -0.00702798 -0.0131452 -0.0127381 0.184307 0.185409 0.0144245 0.00557583 -0.00203879 0.0102732 -0.16188 -0.152042 0.00525483 0.00246048 -0.000852316 0.00357415 -0.105809 -0.144611 -1.49612e-05 -2.3937e-05 -5.29368e-05 -5.56538e-05 1.21184e-05 8.45885e-06 0 0 -0.000571877 -0.000667468 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.9722e-05 1.72952e-05 0.00163339 0.00112411 0.0016336 0.00112416 0.000552803 0.000522646 0.610603 0.540567 0.610648 0.54062 0.115631 0.111966 0.190207 0.202812 0.190214 0.202822 0.149954 0.149009 1.37788e-07 7.12185e-08 1.37904e-07 7.12628e-08 4.29434e-08 3.57281e-08 0 0 2.27865e-06 2.02579e-06 0 0 0 0 0 0 0 0
46 4385000 0.982828 0.98262 -0.00776176 -0.00703146 -0.013019 -0.0126871 0.1839 0.18506 0.0124399 0.0052979 -0.00346153 0.00682746 -0.153751 -0.14321 0.0037084 0.00180453 -0.00067106 0.00251225 -0.0968809 -0.13493 -1.56467e-05 -2.34199e-05 -5.41978e-05 -5.63566e-05 1.43912e-05 1.03488e-05 0 0 -0.000625187 -0.000719743 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.90621e-05 1.67927e-05 0.00130143 0.000872513 0.00130163 0.000872557 0.000538313 0.000509571 0.459428 0.404257 0.459452 0.40429 0.113817 0.109833 0.132893 0.14322 0.132896 0.143225 0.148671 0.147766 1.11723e-07 5.58608e-08 1.11818e-07 5.58959e-08 3.98559e-08 3.32966e-08 0 0 2.17514e-06 1.92468e-06 0 0 0 0 0 0 0 0
47 4485000 0.982828 0.982615 -0.00782965 -0.00705969 -0.0129824 -0.0126298 0.183897 0.18509 0.0141738 0.00599404 -0.00156243 0.0100838 -0.150891 -0.139739 0.00514105 0.00245417 -0.000881406 0.0034134 -0.096137 -0.13346 -1.56186e-05 -2.3428e-05 -5.41607e-05 -5.63346e-05 1.42337e-05 1.01363e-05 0 0 -0.000659605 -0.000753017 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.86222e-05 1.64295e-05 0.00142141 0.000942164 0.00142162 0.000942213 0.000524607 0.000497157 0.55811 0.480287 0.558147 0.480331 0.111927 0.107623 0.180059 0.189915 0.180064 0.189923 0.147471 0.146568 1.11722e-07 5.58597e-08 1.11818e-07 5.58953e-08 3.70696e-08 3.1087e-08 0 0 2.07269e-06 1.82588e-06 0 0 0 0 0 0 0 0
48 4585000 0.982769 0.982551 -0.00778877 -0.00712435 -0.0128696 -0.0125922 0.184223 0.18543 0.0115738 0.00510526 -0.00301001 0.00675104 -0.150869 -0.139207 0.00355612 0.00175346 -0.000624981 0.00249379 -0.0995391 -0.136185 -1.63456e-05 -2.30717e-05 -5.5275e-05 -5.69125e-05 1.18944e-05 7.97427e-06 0 0 -0.000685041 -0.000777221 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.80533e-05 1.59999e-05 0.00112971 0.000735391 0.00112991 0.000735439 0.000511437 0.000485236 0.421112 0.361667 0.421131 0.361694 0.109892 0.105285 0.126797 0.135484 0.1268 0.135488 0.14626 0.145327 9.00265e-08 4.402e-08 9.01039e-08 4.40482e-08 3.4518e-08 2.90589e-08 0 0 1.97113e-06 1.72915e-06 0 0 0 0 0 0 0 0
49 4685000 0.982839 0.982616 -0.0077651 -0.00706606 -0.0128331 -0.0125378 0.183852 0.18509 0.0119063 0.00454048 -0.00329666 0.00769862 -0.142687 -0.130651 0.00486118 0.00234947 -0.000875816 0.00329643 -0.0940319 -0.13007 -1.62797e-05 -2.30387e-05 -5.52694e-05 -5.69234e-05 1.36933e-05 9.62468e-06 0 0 -0.000728607 -0.000818364 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.76337e-05 1.56505e-05 0.00123023 0.00079215 0.00123044 0.000792201 0.00049899 0.000473929 0.508956 0.427409 0.50898 0.427443 0.10778 0.102887 0.170646 0.178147 0.170651 0.178153 0.145101 0.14411 9.00258e-08 4.4019e-08 9.01034e-08 4.40477e-08 3.22061e-08 2.72085e-08 0 0 1.87163e-06 1.63549e-06 0 0 0 0 0 0 0 0
50 4785000 0.982797 0.982571 -0.00759191 -0.00699 -0.0127674 -0.0125341 0.184091 0.185333 0.00365462 -0.0022568 -0.00250183 0.00666383 -0.141589 -0.129234 0.00310044 0.00132177 -0.000630766 0.00238916 -0.0959576 -0.131434 -1.69028e-05 -2.27123e-05 -5.61862e-05 -5.74183e-05 1.21114e-05 8.22831e-06 0 0 -0.00075503 -0.000842828 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.71256e-05 1.52666e-05 0.000975899 0.00062198 0.00097608 0.000622023 0.000486999 0.000463041 0.385058 0.324175 0.385069 0.324195 0.105532 0.100386 0.121092 0.128372 0.121094 0.128375 0.143905 0.142838 7.21994e-08 3.48659e-08 7.22617e-08 3.48887e-08 3.0081e-08 2.55045e-08 0 0 1.77399e-06 1.54461e-06 0 0 0 0 0 0 0 0
51 4885000 0.982832 0.982603 -0.00754908 -0.00691809 -0.0127995 -0.0125527 0.183903 0.185162 0.00488292 -0.00178037 -0.00505069 0.00522459 -0.138381 -0.12566 0.00356151 0.00114402 -0.0010229 0.00297867 -0.0969377 -0.131721 -1.68643e-05 -2.269e-05 -5.61919e-05 -5.74323e-05 1.32926e-05 9.37093e-06 0 0 -0.000782419 -0.000868061 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.71264e-05 1.52745e-05 0.00105966 0.000668429 0.00105985 0.000668473 0.000486255 0.000462279 0.463103 0.381299 0.463115 0.381321 0.105757 0.100272 0.161839 0.16743 0.161842 0.167435 0.14802 0.146773 7.2199e-08 3.48654e-08 7.22613e-08 3.48884e-08 2.8613e-08 2.432e-08 0 0 1.70227e-06 1.47848e-06 0 0 0 0 0 0 0 0
52 4985000 0.982821 0.982591 -0.00747087 -0.00692983 -0.0127045 -0.0125071 0.183973 0.185232 0.00406715 -0.00130465 -0.00356345 0.00495874 -0.131602 -0.118811 0.00225841 0.000547132 -0.000807549 0.00206801 -0.0932238 -0.127591 -1.73753e-05 -2.23722e-05 -5.67479e-05 -5.76909e-05 1.23131e-05 8.57058e-06 0 0 -0.000818243 -0.000900987 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.66374e-05 1.48999e-05 0.000839767 0.000528035 0.000839931 0.000528074 0.000474824 0.000451893 0.351274 0.291225 0.351282 0.291241 0.103268 0.0975883 0.115726 0.121842 0.115728 0.121845 0.14671 0.145353 5.77202e-08 2.77622e-08 5.77699e-08 2.77806e-08 2.67904e-08 2.28479e-08 0 0 1.60915e-06 1.39337e-06 0 0 0 0 0 0 0 0
53 5085000 0.982772 0.982545 -0.00735108 -0.00678326 -0.0126438 -0.0124343 0.184242 0.185483 0.00500236 -0.00105275 -0.00367886 0.00587384 -0.127284 -0.114515 0.00276879 0.000466707 -0.00121663 0.0025821 -0.0895953 -0.123616 -1.73888e-05 -2.24084e-05 -5.67062e-05 -5.76629e-05 1.0707e-05 7.27677e-06 0 0 -0.000852176 -0.000931934 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.62858e-05 1.46074e-05 0.000909294 0.000566216 0.000909466 0.000566257 0.000463956 0.000441981 0.420474 0.341084 0.420485 0.341104 0.100736 0.0948952 0.153566 0.157679 0.153568 0.157683 0.145416 0.143942 5.77197e-08 2.77616e-08 5.77694e-08 2.77802e-08 2.51274e-08 2.14957e-08 0 0 1.51946e-06 1.31214e-06 0 0 0 0 0 0 0 0
54 5185000 0.982766 0.98254 -0.00721237 -0.00667415 -0.0126904 -0.0124522 0.184279 0.185516 0.00308785 -0.00386265 -0.00159753 0.00730925 -0.124137 -0.111415 0.00318584 7.72151e-05 -0.00149073 0.00196115 -0.0875634 -0.121274 -1.73778e-05 -2.21069e-05 -5.66898e-05 -5.78173e-05 1.04638e-05 7.17336e-06 0 0 -0.000881879 -0.000958524 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.59508e-05 1.42814e-05 0.000981708 0.000450014 0.000981885 0.000450046 0.00045353 0.000432439 0.499458 0.262485 0.499475 0.262499 0.0981216 0.0921592 0.203083 0.11585 0.203087 0.115853 0.144061 0.142469 5.77193e-08 2.22245e-08 5.7769e-08 2.22393e-08 2.35967e-08 2.02437e-08 0 0 1.43286e-06 1.23441e-06 0 0 0 0 0 0 0 0
55 5285000 0.982775 0.98255 -0.00706961 -0.00655786 -0.0126048 -0.0124251 0.184242 0.185469 0.00199042 -0.00354388 0.00018851 0.00907426 -0.113361 -0.10083 0.00194215 -0.000263663 -0.000840493 0.00279573 -0.0813374 -0.114835 -1.7769e-05 -2.21058e-05 -5.70755e-05 -5.7822e-05 1.06596e-05 7.51649e-06 0 0 -0.00091821 -0.00099114 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.55333e-05 1.40062e-05 0.0007782 0.000481545 0.000778346 0.000481579 0.000443478 0.000423284 0.380941 0.305862 0.380953 0.30588 0.0954422 0.0893984 0.145796 0.148812 0.145798 0.148816 0.142645 0.140936 4.60697e-08 2.2224e-08 4.6109e-08 2.2239e-08 2.21787e-08 1.90878e-08 0 0 1.34958e-06 1.16025e-06 0 0 0 0 0 0 0 0
56 5385000 0.98276 0.982538 -0.00697843 -0.00650638 -0.0126149 -0.0124238 0.184324 0.185535 -0.000279016 -0.00612794 0.0022408 0.0102174 -0.108651 -0.096358 0.00207772 -0.000472084 -0.000772074 0.0022774 -0.0762985 -0.109637 -1.77738e-05 -2.17705e-05 -5.70491e-05 -5.78808e-05 9.74502e-06 6.83227e-06 0 0 -0.000949966 -0.00101944 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.52115e-05 1.36983e-05 0.00083807 0.000385019 0.000838223 0.000385046 0.000433923 0.000414515 0.450386 0.237038 0.450402 0.237051 0.0927601 0.0866669 0.19147 0.110341 0.191473 0.110343 0.141237 0.139413 4.60693e-08 1.78866e-08 4.61086e-08 1.78986e-08 2.08787e-08 1.80167e-08 0 0 1.27023e-06 1.0901e-06 0 0 0 0 0 0 0 0
57 5485000 0.982743 0.982523 -0.00697261 -0.00650521 -0.0126441 -0.012487 0.184413 0.18561 -0.000902453 -0.00604964 0.00541753 0.0137961 -0.105568 -0.0932747 0.00104033 -0.00110967 -7.85796e-05 0.00346287 -0.0771071 -0.11003 -1.79882e-05 -2.17883e-05 -5.72695e-05 -5.78694e-05 8.95245e-06 6.23746e-06 0 0 -0.000969272 -0.00103637 0.203316 0.202638 0.00195799 0.0100117 0.434329 0.433627 0 0 0 0 0 1.51269e-05 1.36934e-05 0.000665036 0.000411178 0.000665163 0.000411209 0.000433198 0.000413838 0.344901 0.275185 0.344915 0.275202 0.0923273 0.0860569 0.138496 0.140729 0.138498 0.140732 0.1449 0.142825 3.67647e-08 1.78863e-08 3.67958e-08 1.78985e-08 1.99637e-08 1.72666e-08 0 0 1.21316e-06 1.03995e-06 0 0 0 0 0 0 0 0
58 5585000 0.982741 0.98234 -0.00699505 -0.00657583 -0.0126794 -0.0125313 0.184419 0.186567 -0.0012885 -0.00619599 0.00832179 0.0151818 -0.0973984 -0.0854829 0.00101659 -0.00101811 0.000605647 0.00302182 -0.0694874 -0.102377 -1.79908e-05 -2.13447e-05 -5.72528e-05 -5.78843e-05 8.34106e-06 5.82415e-06 0 0 -0.00100264 -0.00106601 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.48138e-05 0.000100415 0.000714483 0.000331079 0.000714619 0.000330821 0.000424054 0.00281792 0.405748 0.214652 0.405768 0.214664 0.089548 0.0832893 0.180623 0.105274 0.180626 0.105276 0.143333 0.14115 3.67644e-08 1.44716e-08 3.67955e-08 1.44814e-08 1.88304e-08 1.63274e-08 0 0 1.14024e-06 9.76209e-07 0 0.0025 0 0.0025 0 0.0025 0 0.0025 0 0.0025 0 0.0025 0 0
59 5685000 0.982713 0.982199 -0.00698514 -0.00652648 -0.0125569 -0.0124261 0.184579 0.187316 -0.00165948 -0.00651164 0.00999922 0.0181302 -0.0972876 -0.0855902 0.000392444 -0.00170806 0.00105634 0.00461957 -0.0690064 -0.101788 -1.7962e-05 -2.13483e-05 -5.73749e-05 -5.78854e-05 6.70077e-06 5.84093e-06 0 0 -0.00102142 -0.00108188 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.44451e-05 6.60773e-05 0.000568092 0.000331334 0.000568206 0.000331195 0.000415232 0.00185567 0.312177 0.216501 0.312192 0.216514 0.0867608 0.0805424 0.131662 0.132493 0.131664 0.132496 0.14171 0.139431 2.93695e-08 1.44717e-08 2.93941e-08 1.44815e-08 1.77755e-08 1.63271e-08 0 0 1.07091e-06 9.15974e-07 0 0 0 0 0 0 0 0
60 5785000 0.982762 0.982413 -0.00685896 -0.00640013 -0.0125348 -0.0123886 0.184322 0.1862 -0.00150466 -0.00591057 0.011859 0.0181195 -0.0911082 -0.0798164 0.000274827 -0.00141873 0.00212665 0.00395751 -0.0629584 -0.0957693 -1.79404e-05 -2.08011e-05 -5.73892e-05 -5.7903e-05 7.55155e-06 5.91456e-06 0 0 -0.00104932 -0.00110626 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.4153e-05 4.92548e-05 0.00060894 0.000331906 0.000609059 0.000331818 0.000406809 0.00138392 0.36564 0.152571 0.365659 0.152579 0.084019 0.077864 0.170526 0.0990735 0.170529 0.099075 0.140101 0.137732 2.93692e-08 1.18706e-08 2.93938e-08 1.18785e-08 1.68024e-08 1.63241e-08 0 0 1.00551e-06 8.59437e-07 0 0 0 0 0 0 0 0
61 5885000 0.982746 0.982402 -0.00684875 -0.00632628 -0.0125817 -0.0124417 0.184403 0.186255 0.000620451 -0.00415994 0.0111966 0.019772 -0.0875361 -0.076465 0.000152401 -0.00190114 0.00217681 0.00589289 -0.0644408 -0.0971815 -1.76779e-05 -2.08035e-05 -5.75151e-05 -5.79038e-05 7.05841e-06 5.9245e-06 0 0 -0.00106245 -0.00111689 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.38389e-05 3.93197e-05 0.000485511 0.000333303 0.000485608 0.000333245 0.000398653 0.00110408 0.282384 0.160638 0.282397 0.160646 0.0812934 0.0752266 0.125278 0.121141 0.125279 0.121143 0.138444 0.135998 2.35092e-08 1.18707e-08 2.35287e-08 1.18786e-08 1.58946e-08 1.632e-08 0 0 9.43622e-07 8.0618e-07 0 0 0 0 0 0 0 0
62 5985000 0.982698 0.9823 -0.00680083 -0.00625662 -0.0127011 -0.0125537 0.184653 0.186789 0.00129749 -0.00404305 0.012274 0.0218179 -0.0805704 -0.0699316 0.000284545 -0.00229247 0.00332648 0.00796544 -0.058574 -0.0913963 -1.77095e-05 -2.08115e-05 -5.74811e-05 -5.79032e-05 5.39839e-06 5.82404e-06 0 0 -0.00108729 -0.00113839 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.35771e-05 3.27361e-05 0.000519292 0.00033531 0.000519394 0.00033527 0.00039086 0.000919162 0.329247 0.172 0.329263 0.172009 0.0786301 0.0726689 0.161139 0.146644 0.161142 0.146648 0.136806 0.134292 2.35089e-08 1.18708e-08 2.35284e-08 1.18787e-08 1.50546e-08 1.6313e-08 0 0 8.85479e-07 7.56335e-07 0 0 0 0 0 0 0 0
63 6085000 0.982656 0.982195 -0.00686316 -0.00625391 -0.012627 -0.0124948 0.184882 0.187342 0.000399645 -0.00451049 0.0109139 0.0206956 -0.0770647 -0.066755 0.000222145 -0.00183403 0.0028136 0.00692233 -0.056762 -0.0896196 -1.73881e-05 -2.02359e-05 -5.76151e-05 -5.79553e-05 3.03291e-06 5.6057e-06 0 0 -0.0011037 -0.00115211 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.32608e-05 2.80192e-05 0.000415459 0.000334536 0.000415544 0.000334514 0.000383344 0.000788165 0.255618 0.137152 0.255629 0.137157 0.0760005 0.070164 0.119317 0.110293 0.119318 0.110295 0.13513 0.132559 1.88719e-08 9.97724e-09 1.88875e-08 9.98377e-09 1.42692e-08 1.63012e-08 0 0 8.30655e-07 7.09504e-07 0 0 0 0 0 0 0 0
64 6185000 0.982627 0.982166 -0.00689007 -0.00626533 -0.0125859 -0.0124473 0.185036 0.187499 -0.000350469 -0.00582251 0.0124821 0.023359 -0.0755668 -0.0654273 0.000277192 -0.00230843 0.00400324 0.00915326 -0.0563861 -0.0890573 -1.74048e-05 -2.02397e-05 -5.75985e-05 -5.79548e-05 2.20694e-06 5.55718e-06 0 0 -0.00111726 -0.00116355 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.32532e-05 2.53673e-05 0.000443452 0.000336897 0.000443544 0.000336886 0.000382728 0.000713329 0.296872 0.153492 0.296886 0.153497 0.0752292 0.0693673 0.152437 0.131933 0.15244 0.131935 0.138085 0.135284 1.88718e-08 9.97733e-09 1.88874e-08 9.98386e-09 1.37171e-08 1.62902e-08 0 0 7.91674e-07 6.76296e-07 0 0 0 0 0 0 0 0
65 6285000 0.982602 0.982159 -0.00692838 -0.00625824 -0.0125973 -0.0124736 0.185167 0.187535 -0.00204504 -0.00718598 0.0116086 0.0229563 -0.0764529 -0.0665107 6.89575e-05 -0.00207861 0.00324669 0.00796552 -0.0601447 -0.0927924 -1.70111e-05 -1.96535e-05 -5.7768e-05 -5.80284e-05 1.65025e-06 5.52379e-06 0 0 -0.0011235 -0.00116794 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.29903e-05 2.25427e-05 0.000356177 0.000331794 0.000356252 0.00033179 0.000375477 0.000633414 0.231725 0.133584 0.231734 0.133587 0.0726393 0.0669313 0.11377 0.101783 0.113771 0.101784 0.136286 0.133449 1.5202e-08 8.60211e-09 1.52144e-08 8.60764e-09 1.30222e-08 1.62707e-08 0 0 7.42526e-07 6.34523e-07 0 0 0 0 0 0 0 0
66 6385000 0.982625 0.982218 -0.00688028 -0.00619865 -0.0125372 -0.0124073 0.185051 0.18723 -0.000945014 -0.00663287 0.0131115 0.0256733 -0.0755588 -0.0658936 -0.000122388 -0.00281642 0.00447316 0.0103895 -0.0614791 -0.0941696 -1.70012e-05 -1.96513e-05 -5.77779e-05 -5.80317e-05 2.13977e-06 5.68461e-06 0 0 -0.0011334 -0.0011757 0.203316 0.203458 0.00195799 0.00195935 0.434329 0.434775 0 0 0 0 0 1.27608e-05 2.03119e-05 0.000379433 0.000334074 0.000379513 0.000334078 0.00036853 0.000570542 0.26802 0.153967 0.268032 0.153969 0.070135 0.0645874 0.144396 0.121505 0.144398 0.121507 0.134521 0.131654 1.52018e-08 8.60219e-09 1.52142e-08 8.60773e-09 1.23757e-08 1.62464e-08 0 0 6.96595e-07 5.95568e-07 0 0 0 0 0 0 0 0
67 6485000 0.982296 0.982216 -0.00688562 -0.00620271 -0.0125388 -0.0124079 0.186789 0.187243 -0.00313811 -0.00856955 0.00887285 0.0217852 -0.0715144 -0.0622713 -0.000216531 -0.00252661 0.00342089 0.00887621 -0.0582506 -0.0911027 -1.65898e-05 -1.90659e-05 -5.79154e-05 -5.80933e-05 1.80064e-06 5.56492e-06 0 0 -0.00114972 -0.00118948 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.81048e-05 1.8497e-05 0.000302622 0.000322066 0.000302446 0.000322073 0.00246226 0.000519967 0.204394 0.14106 0.2044 0.14106 0.0676886 0.0623103 0.108594 0.0960425 0.108595 0.0960435 0.132734 0.12985 1.22936e-08 7.60413e-09 1.23035e-08 7.60894e-09 1.19163e-08 1.62156e-08 0 0 6.53496e-07 5.59088e-07 0 0 0 0 0 0 0 0
68 6585000 0.98221 0.98219 -0.00684311 -0.00615147 -0.0124982 -0.012362 0.187244 0.187381 -0.00382721 -0.00980829 0.00998736 0.0241826 -0.0725566 -0.0635904 -0.000541158 -0.00343154 0.00431743 0.0111309 -0.0600432 -0.0929662 -1.65904e-05 -1.90713e-05 -5.79156e-05 -5.80892e-05 1.79328e-06 5.36482e-06 0 0 -0.00115795 -0.00119587 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.06068e-05 1.7021e-05 0.000302985 0.000323971 0.000302892 0.000323984 0.00169441 0.000478548 0.206732 0.164546 0.206739 0.164545 0.0653048 0.0601026 0.135731 0.115303 0.135733 0.115304 0.130934 0.128042 1.22937e-08 7.60421e-09 1.23036e-08 7.60903e-09 1.1916e-08 1.61786e-08 0 0 6.13103e-07 5.2495e-07 0 0 0 0 0 0 0 0
69 6685000 0.982156 0.982166 -0.00675043 -0.0061415 -0.0124725 -0.0123443 0.187531 0.187509 -0.00682235 -0.0125312 0.0102012 0.0239216 -0.0737893 -0.0651687 -0.000741562 -0.00330922 0.00337511 0.0094983 -0.0598114 -0.0928704 -1.62067e-05 -1.85228e-05 -5.79859e-05 -5.81186e-05 1.74968e-06 5.10721e-06 0 0 -0.0011692 -0.00120511 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 4.6199e-05 1.57919e-05 0.000303538 0.00030325 0.000303487 0.000303263 0.00129208 0.000444166 0.14726 0.153064 0.147265 0.153063 0.0630121 0.0579869 0.10177 0.092863 0.101771 0.0928636 0.129174 0.12628 1.00668e-08 6.89392e-09 1.00748e-08 6.89822e-09 1.19135e-08 1.61342e-08 0 0 5.75445e-07 4.93163e-07 0 0 0 0 0 0 0 0
70 6785000 0.98214 0.982155 -0.0067883 -0.00616767 -0.0124082 -0.0122772 0.187622 0.187571 -0.00574505 -0.0119646 0.0116209 0.0264957 -0.0704507 -0.0620577 -0.00141342 -0.00458971 0.00442825 0.0119864 -0.0592426 -0.0922432 -1.62077e-05 -1.85269e-05 -5.79862e-05 -5.81149e-05 1.73838e-06 4.95723e-06 0 0 -0.00118033 -0.00121454 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 3.92316e-05 1.50546e-05 0.000304838 0.000304623 0.000304811 0.000304639 0.00109743 0.000423399 0.155251 0.178366 0.155256 0.178364 0.0622365 0.0572474 0.123826 0.112603 0.123827 0.112604 0.131649 0.128568 1.00669e-08 6.894e-09 1.00749e-08 6.89831e-09 1.19118e-08 1.60963e-08 0 0 5.48844e-07 4.70725e-07 0 0 0 0 0 0 0 0
71 6885000 0.982133 0.982148 -0.0066136 -0.00609531 -0.0123239 -0.0122122 0.187667 0.187617 -0.00522643 -0.0108719 0.00894474 0.0223544 -0.0668843 -0.0588591 -0.00127005 -0.00401913 0.00348281 0.00997255 -0.0579695 -0.0911462 -1.5842e-05 -1.80196e-05 -5.79961e-05 -5.811e-05 1.71753e-06 4.76473e-06 0 0 -0.00119171 -0.00122399 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 3.26685e-05 1.41447e-05 0.000304279 0.000275024 0.000304269 0.000275037 0.000914263 0.000398027 0.120744 0.163938 0.120747 0.163935 0.0600308 0.0552251 0.0940814 0.0916392 0.0940822 0.0916395 0.129809 0.126744 8.4379e-09 6.41212e-09 8.44446e-09 6.41608e-09 1.19071e-08 1.60383e-08 0 0 5.15385e-07 4.42523e-07 0 0 0 0 0 0 0 0
72 6985000 0.982177 0.982162 -0.00657213 -0.0060405 -0.0122854 -0.0121725 0.187439 0.187546 -0.00613563 -0.0122216 0.00972837 0.0241256 -0.0629413 -0.0553072 -0.00188596 -0.00523423 0.00440964 0.0122966 -0.0551094 -0.088494 -1.58421e-05 -1.80194e-05 -5.79972e-05 -5.81087e-05 1.75447e-06 4.77531e-06 0 0 -0.00120451 -0.00123474 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 2.80168e-05 1.33816e-05 0.000305936 0.000275845 0.000305939 0.00027586 0.000784113 0.000376426 0.133395 0.189758 0.133397 0.189754 0.0578957 0.0532738 0.112637 0.112268 0.112638 0.112268 0.12797 0.124928 8.43799e-09 6.41219e-09 8.44455e-09 6.41615e-09 1.19013e-08 1.5972e-08 0 0 4.84094e-07 4.16161e-07 0 0 0 0 0 0 0 0
73 7085000 0.98216 0.982142 -0.00649522 -0.00607565 -0.0121931 -0.0121052 0.187541 0.187655 -0.00626568 -0.0114295 0.0125995 0.024777 -0.0626713 -0.0553161 -0.00167256 -0.00444916 0.00371238 0.010205 -0.0560218 -0.0895366 -1.54952e-05 -1.75937e-05 -5.7979e-05 -5.80897e-05 1.73677e-06 4.62317e-06 0 0 -0.00121168 -0.00124043 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 2.45667e-05 1.2732e-05 0.00030191 0.000239407 0.000301922 0.000239418 0.000687036 0.000357925 0.113467 0.17001 0.113468 0.170007 0.0558521 0.0514099 0.0873495 0.091521 0.0873503 0.091521 0.126181 0.123166 7.25076e-09 6.10998e-09 7.25628e-09 6.11372e-09 1.18924e-08 1.58969e-08 0 0 4.54968e-07 3.91627e-07 0 0 0 0 0 0 0 0
74 7185000 0.982138 0.982126 -0.00643656 -0.00600667 -0.0122594 -0.0121691 0.187655 0.187732 -0.00735696 -0.0128656 0.0142704 0.0272412 -0.0610995 -0.0539849 -0.00240364 -0.00572026 0.0051097 0.0128632 -0.057747 -0.0913707 -1.54966e-05 -1.7599e-05 -5.79778e-05 -5.80836e-05 1.68144e-06 4.36874e-06 0 0 -0.00121762 -0.00124504 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 2.18858e-05 1.21728e-05 0.000303539 0.000239796 0.000303556 0.000239808 0.000612021 0.000342021 0.129944 0.19496 0.129945 0.194957 0.0538781 0.0496138 0.103923 0.112973 0.103924 0.112973 0.124397 0.121415 7.25086e-09 6.11003e-09 7.25638e-09 6.11378e-09 1.18816e-08 1.58127e-08 0 0 4.27742e-07 3.68696e-07 0 0 0 0 0 0 0 0
75 7285000 0.982157 0.982135 -0.0064183 -0.00613942 -0.0122664 -0.0122136 0.187555 0.187682 -0.00710323 -0.0104868 0.0170889 0.0253697 -0.0568271 -0.0501402 -0.00320066 -0.00472637 0.00665931 0.0104895 -0.0530881 -0.0869795 -1.54966e-05 -1.72547e-05 -5.79779e-05 -5.80628e-05 1.71337e-06 4.32694e-06 0 0 -0.00123106 -0.00125657 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.97539e-05 1.16812e-05 0.000305531 0.000200322 0.000305555 0.000200328 0.000552455 0.0003283 0.149159 0.169302 0.149159 0.1693 0.0519915 0.0478994 0.123665 0.0916353 0.123667 0.0916351 0.122664 0.119718 7.25095e-09 5.93999e-09 7.25647e-09 5.94361e-09 1.18678e-08 1.57191e-08 0 0 4.02405e-07 3.47351e-07 0 0 0 0 0 0 0 0
76 7385000 0.982186 0.982156 -0.00639496 -0.00606356 -0.0122627 -0.0121973 0.187402 0.187577 -0.00823351 -0.0128326 0.0175176 0.0284024 -0.0533787 -0.0470497 -0.0028141 -0.00588271 0.00610605 0.0132711 -0.0496037 -0.0837193 -1.51335e-05 -1.72524e-05 -5.79507e-05 -5.80606e-05 1.74421e-06 4.34987e-06 0 0 -0.00124233 -0.00126613 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.80181e-05 1.12612e-05 0.000295069 0.00020049 0.000295094 0.000200499 0.000504132 0.000316433 0.13684 0.192265 0.136839 0.192263 0.0501722 0.0462494 0.0980679 0.113487 0.0980687 0.113487 0.120941 0.118035 6.38663e-09 5.94004e-09 6.39139e-09 5.94367e-09 1.18502e-08 1.56158e-08 0 0 3.78722e-07 3.27395e-07 0 0 0 0 0 0 0 0
77 7485000 0.982229 0.98218 -0.00635757 -0.00618158 -0.0122957 -0.0122674 0.187178 0.187439 -0.00628522 -0.00856096 0.020183 0.0257964 -0.0488459 -0.0428099 -0.00353862 -0.00463527 0.00800403 0.010697 -0.0460044 -0.0802051 -1.51305e-05 -1.69924e-05 -5.79528e-05 -5.80535e-05 1.89798e-06 4.63534e-06 0 0 -0.00125296 -0.00127528 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.69619e-05 1.10529e-05 0.000296717 0.000162214 0.000296743 0.000162216 0.000474392 0.00031052 0.158846 0.162051 0.158845 0.16205 0.0495034 0.0456369 0.117343 0.0913129 0.117344 0.0913126 0.122934 0.119893 6.38672e-09 5.8568e-09 6.39149e-09 5.86037e-09 1.1835e-08 1.55317e-08 0 0 3.61992e-07 3.13292e-07 0 0 0 0 0 0 0 0
78 7585000 0.982256 0.982202 -0.00651597 -0.00626445 -0.0122756 -0.0122312 0.187028 0.187322 -0.00464342 -0.00818922 0.0194101 0.027969 -0.0443779 -0.038743 -0.00286472 -0.00549452 0.00710875 0.0133449 -0.0396874 -0.074173 -1.4755e-05 -1.6986e-05 -5.79379e-05 -5.80525e-05 1.9735e-06 4.78345e-06 0 0 -0.001266 -0.00128655 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.57166e-05 1.07333e-05 0.000278674 0.000162406 0.0002787 0.000162411 0.000439618 0.000301348 0.147972 0.182291 0.14797 0.18229 0.0477773 0.044076 0.0948292 0.112987 0.0948297 0.112987 0.121171 0.118181 5.76898e-09 5.85683e-09 5.77321e-09 5.86042e-09 1.18109e-08 1.54109e-08 0 0 3.40998e-07 2.95587e-07 0 0 0 0 0 0 0 0
79 7685000 0.982262 0.982208 -0.00654217 -0.00643907 -0.0123374 -0.0123211 0.186991 0.187281 -0.00525002 -0.00664475 0.0226183 0.0256738 -0.0424011 -0.0371757 -0.00336878 -0.00413007 0.00926538 0.0106538 -0.0329992 -0.0677852 -1.47548e-05 -1.68223e-05 -5.79355e-05 -5.80472e-05 1.9643e-06 4.70282e-06 0 0 -0.00127878 -0.0012977 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.46695e-05 1.04496e-05 0.000279832 0.000128599 0.000279861 0.0001286 0.000410299 0.000293405 0.171837 0.150026 0.171834 0.150026 0.0461314 0.042588 0.114556 0.090218 0.114557 0.0902178 0.119463 0.116524 5.76906e-09 5.82277e-09 5.7733e-09 5.82634e-09 1.17831e-08 1.52803e-08 0 0 3.21455e-07 2.79093e-07 0 0 0 0 0 0 0 0
80 7785000 0.982256 0.982207 -0.0065264 -0.00632381 -0.0123557 -0.0123231 0.187022 0.187288 -0.00272371 -0.00534957 0.0205165 0.0270097 -0.0439841 -0.038844 -0.00260964 -0.00474513 0.00805321 0.0132264 -0.0370073 -0.0718125 -1.44004e-05 -1.6825e-05 -5.79455e-05 -5.80453e-05 1.90981e-06 4.594e-06 0 0 -0.00127904 -0.00129739 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.3776e-05 1.02138e-05 0.000253949 0.000129034 0.000253973 0.000129036 0.000385328 0.000286521 0.158545 0.167295 0.158542 0.167295 0.0445476 0.0411581 0.0935964 0.111169 0.0935966 0.111169 0.117771 0.114887 5.3471e-09 5.8228e-09 5.35098e-09 5.82638e-09 1.17506e-08 1.51396e-08 0 0 3.03183e-07 2.63661e-07 0 0 0 0 0 0 0 0
81 7885000 0.982244 0.982195 -0.00655322 -0.00648293 -0.0124292 -0.0124143 0.18708 0.187339 -0.00432941 -0.00513499 0.0240532 0.0251264 -0.0434957 -0.0385064 -0.00305248 -0.00352995 0.0102657 0.0104175 -0.0396511 -0.0745318 -1.44004e-05 -1.67355e-05 -5.79449e-05 -5.80486e-05 1.90443e-06 4.55048e-06 0 0 -0.00128092 -0.00129859 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.30252e-05 1.00126e-05 0.0002546 0.00010136 0.000254626 0.000101359 0.000363889 0.000280547 0.182878 0.135288 0.182875 0.135289 0.0430251 0.0397835 0.114199 0.0883202 0.114199 0.08832 0.116098 0.11327 5.34719e-09 5.81198e-09 5.35106e-09 5.81557e-09 1.17136e-08 1.49886e-08 0 0 2.86097e-07 2.49219e-07 0 0 0 0 0 0 0 0
82 7985000 0.98225 0.982201 -0.00661143 -0.00642023 -0.0123535 -0.0123263 0.187053 0.187317 -0.00313083 -0.00511938 0.0214238 0.0265124 -0.0392903 -0.0345919 -0.00238055 -0.00408575 0.00874738 0.0129595 -0.0357985 -0.0708954 -1.40866e-05 -1.67289e-05 -5.79719e-05 -5.80476e-05 1.98126e-06 4.69025e-06 0 0 -0.00128968 -0.00130609 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.23678e-05 9.84417e-06 0.000222448 0.000102201 0.000222468 0.000102202 0.000345377 0.000275396 0.164684 0.149665 0.16468 0.149666 0.0415739 0.0384746 0.0935208 0.108137 0.0935207 0.108137 0.114479 0.111707 5.07989e-09 5.81199e-09 5.08354e-09 5.8156e-09 1.16717e-08 1.48282e-08 0 0 2.7018e-07 2.35751e-07 0 0 0 0 0 0 0 0
83 8085000 0.982227 0.982186 -0.00650469 -0.00630072 -0.0123512 -0.0123213 0.187177 0.187401 -0.00225337 -0.00437373 0.0244581 0.0299161 -0.0395193 -0.034862 -0.00261409 -0.00452438 0.0110232 0.0157644 -0.0382627 -0.0732883 -1.40917e-05 -1.674e-05 -5.79659e-05 -5.80371e-05 1.72696e-06 4.17976e-06 0 0 -0.00129131 -0.00130732 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.19741e-05 9.81359e-06 0.000222688 0.000103334 0.000222708 0.000103335 0.000334395 0.000274391 0.188331 0.164806 0.188328 0.164807 0.041031 0.0379855 0.114954 0.131919 0.114953 0.131919 0.116192 0.113318 5.07998e-09 5.81202e-09 5.08363e-09 5.81565e-09 1.16371e-08 1.47016e-08 0 0 2.5894e-07 2.26232e-07 0 0 0 0 0 0 0 0
84 8185000 0.982214 0.982176 -0.00668734 -0.00647493 -0.012283 -0.0122587 0.187245 0.187454 -0.000974271 -0.00258131 0.0247439 0.0293109 -0.0356833 -0.0313237 -0.00185852 -0.00321609 0.00935402 0.0129227 -0.0334855 -0.0687527 -1.38418e-05 -1.67017e-05 -5.79988e-05 -5.80323e-05 1.60603e-06 3.92053e-06 0 0 -0.00130029 -0.00131518 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.14568e-05 9.68069e-06 0.000187419 8.22481e-05 0.000187433 8.22483e-05 0.000319965 0.000270475 0.164628 0.131698 0.164627 0.131699 0.0396614 0.0367508 0.0937173 0.104211 0.0937171 0.104211 0.114553 0.111741 4.92768e-09 5.80978e-09 4.93121e-09 5.81343e-09 1.15861e-08 1.45245e-08 0 0 2.44797e-07 2.14243e-07 0 0 0 0 0 0 0 0
85 8285000 0.982224 0.982187 -0.00667846 -0.00645188 -0.0122693 -0.0122426 0.187191 0.187397 0.00124337 -0.000493042 0.0271871 0.0321683 -0.0329125 -0.0287394 -0.00186266 -0.00338684 0.0119308 0.0159803 -0.0319891 -0.067394 -1.38418e-05 -1.67028e-05 -5.79956e-05 -5.80272e-05 1.55955e-06 3.77744e-06 0 0 -0.00130516 -0.00131927 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.10029e-05 9.56398e-06 0.000187424 8.38894e-05 0.000187439 8.38912e-05 0.000307371 0.000267121 0.186481 0.14415 0.18648 0.144152 0.0383461 0.0355655 0.115589 0.126132 0.115589 0.126132 0.112936 0.110188 4.92776e-09 5.80978e-09 4.93128e-09 5.81346e-09 1.15296e-08 1.4338e-08 0 0 2.31558e-07 2.03009e-07 0 0 0 0 0 0 0 0
86 8385000 0.982225 0.982187 -0.00677915 -0.00652159 -0.0122594 -0.0122391 0.187182 0.187392 -0.000613645 -0.00202607 0.023134 0.0279964 -0.0309678 -0.0270389 -0.00119852 -0.00230212 0.00982395 0.0131089 -0.0282536 -0.0638553 -1.36519e-05 -1.66885e-05 -5.80387e-05 -5.80265e-05 1.59535e-06 3.78839e-06 0 0 -0.00131198 -0.00132516 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.06089e-05 9.47099e-06 0.000152716 6.85819e-05 0.000152725 6.85822e-05 0.000296332 0.000264248 0.158345 0.114851 0.158344 0.114852 0.0370929 0.0344357 0.0934911 0.0997551 0.0934909 0.0997551 0.111374 0.108687 4.85227e-09 5.80962e-09 4.85573e-09 5.81332e-09 1.14676e-08 1.41431e-08 0 0 2.19206e-07 1.92515e-07 0 0 0 0 0 0 0 0
87 8485000 0.982255 0.982213 -0.00669197 -0.00641901 -0.0122576 -0.0122347 0.187032 0.187262 -0.00101486 -0.00257656 0.0257558 0.0311145 -0.03143 -0.0275645 -0.00125372 -0.0025064 0.0122288 0.0160218 -0.0322799 -0.0678959 -1.36451e-05 -1.66772e-05 -5.80463e-05 -5.80375e-05 1.9329e-06 4.31512e-06 0 0 -0.00131104 -0.00132382 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 1.02702e-05 9.39595e-06 0.000152698 7.07874e-05 0.000152707 7.07888e-05 0.000286646 0.000261796 0.177742 0.125144 0.177741 0.125144 0.0358896 0.033351 0.115247 0.11976 0.115246 0.119761 0.109834 0.10721 4.85234e-09 5.80961e-09 4.85579e-09 5.81334e-09 1.13999e-08 1.39397e-08 0 0 2.07635e-07 1.82673e-07 0 0 0 0 0 0 0 0
88 8585000 0.982266 0.982224 -0.00678311 -0.00646883 -0.0123527 -0.0123359 0.186964 0.187196 0.000301874 -0.00108381 0.022059 0.0278371 -0.0259923 -0.022386 -0.000872753 -0.0018366 0.00985418 0.0132013 -0.0268789 -0.0627184 -1.35206e-05 -1.66778e-05 -5.80767e-05 -5.80314e-05 1.91856e-06 4.22613e-06 0 0 -0.00131883 -0.00133068 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 9.95828e-06 9.32321e-06 0.000121556 6.02188e-05 0.000121558 6.02186e-05 0.000278144 0.000259723 0.147227 0.099941 0.147227 0.0999411 0.0347431 0.0323172 0.0924779 0.0950892 0.0924777 0.0950892 0.108345 0.105782 4.82128e-09 5.80959e-09 4.82471e-09 5.81334e-09 1.13265e-08 1.3729e-08 0 0 1.9683e-07 1.7347e-07 0 0 0 0 0 0 0 0
89 8685000 0.982297 0.982252 -0.00683014 -0.00649989 -0.0124405 -0.0124213 0.186794 0.187039 0.000255486 -0.00128858 0.0226707 0.0290586 -0.0271191 -0.023603 -0.000883413 -0.00199347 0.0120775 0.016032 -0.0285384 -0.0644285 -1.35163e-05 -1.66721e-05 -5.80802e-05 -5.80357e-05 2.11374e-06 4.4638e-06 0 0 -0.00131966 -0.00133107 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 9.68807e-06 9.2623e-06 0.00012171 6.3009e-05 0.000121713 6.30102e-05 0.00027067 0.000257965 0.163891 0.108593 0.163891 0.108593 0.0336421 0.0313243 0.113567 0.113253 0.113567 0.113253 0.106878 0.104376 4.82134e-09 5.80957e-09 4.82477e-09 5.81336e-09 1.12471e-08 1.35107e-08 0 0 1.86698e-07 1.6483e-07 0 0 0 0 0 0 0 0
90 8785000 0.982294 0.982251 -0.00691172 -0.00654077 -0.0123922 -0.0123788 0.186806 0.18705 0.00150029 6.83366e-05 0.0187933 0.0258323 -0.0259397 -0.0225732 -0.000569335 -0.00145042 0.00944472 0.0131038 -0.0250863 -0.0610511 -1.34502e-05 -1.66775e-05 -5.80953e-05 -5.80272e-05 1.98842e-06 4.19566e-06 0 0 -0.0013252 -0.001336 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 9.56558e-06 9.32349e-06 9.58087e-05 5.61272e-05 9.58068e-05 5.6128e-05 0.000267345 0.000259545 0.13339 0.0873984 0.133391 0.0873978 0.033226 0.0309526 0.0906204 0.0904513 0.0906203 0.0904513 0.108316 0.105741 4.8117e-09 5.80957e-09 4.81512e-09 5.81338e-09 1.11837e-08 1.33424e-08 0 0 1.79517e-07 1.58701e-07 0 0 0 0 0 0 0 0
91 8885000 0.982331 0.982284 -0.00697661 -0.00658961 -0.012388 -0.0123728 0.186609 0.186873 0.00185949 0.000269124 0.0205179 0.0282764 -0.0223575 -0.0192493 -0.000380559 -0.00140881 0.0114344 0.0158357 -0.0192377 -0.0554383 -1.34395e-05 -1.66615e-05 -5.80975e-05 -5.80311e-05 2.37374e-06 4.67637e-06 0 0 -0.00133253 -0.0013424 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 9.35499e-06 9.28294e-06 9.62846e-05 5.95004e-05 9.62839e-05 5.95034e-05 0.000261423 0.000258258 0.147333 0.0948601 0.147334 0.094859 0.0321891 0.0300173 0.110626 0.106932 0.110626 0.106932 0.106843 0.104332 4.81176e-09 5.80954e-09 4.81518e-09 5.81339e-09 1.10939e-08 1.31126e-08 0 0 1.70471e-07 1.50971e-07 0 0 0 0 0 0 0 0
92 8985000 0.982369 0.98232 -0.00700141 -0.0065801 -0.0123034 -0.0122933 0.186416 0.186688 0.00105636 -0.000446041 0.018268 0.026706 -0.0203317 -0.0173191 -0.000196441 -0.00103163 0.00890234 0.0130667 -0.0208571 -0.0571187 -1.34014e-05 -1.66352e-05 -5.81187e-05 -5.80496e-05 2.91628e-06 5.43655e-06 0 0 -0.00133288 -0.00134234 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 9.1703e-06 9.25239e-06 7.60225e-05 5.53907e-05 7.60185e-05 5.53939e-05 0.000256221 0.000257173 0.118545 0.0772323 0.118546 0.0772309 0.0312009 0.0291253 0.0880611 0.0860075 0.0880611 0.0860075 0.105421 0.102972 4.81006e-09 5.8094e-09 4.81347e-09 5.81328e-09 1.09984e-08 1.28776e-08 0 0 1.62009e-07 1.4373e-07 0 0 0 0 0 0 0 0
93 9085000 0.982421 0.98237 -0.00702819 -0.00659063 -0.0123737 -0.0123614 0.186134 0.186421 0.00149625 -0.000188343 0.0208119 0.0300673 -0.0215759 -0.0186961 -7.48274e-05 -0.0010684 0.0108097 0.0158575 -0.0204758 -0.0568419 -1.33879e-05 -1.66154e-05 -5.81294e-05 -5.80635e-05 3.52793e-06 6.24396e-06 0 0 -0.00133492 -0.00134385 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 9.006e-06 9.22163e-06 7.69191e-05 5.93355e-05 7.69155e-05 5.93402e-05 0.000251662 0.000256256 0.130092 0.0839439 0.130093 0.0839421 0.0302519 0.0282685 0.10672 0.101001 0.10672 0.101001 0.104021 0.101633 4.81012e-09 5.80937e-09 4.81352e-09 5.81328e-09 1.0897e-08 1.26374e-08 0 0 1.54059e-07 1.36919e-07 0 0 0 0 0 0 0 0
94 9185000 0.982454 0.982402 -0.00710584 -0.00664263 -0.0124023 -0.0123952 0.185954 0.186249 0.00446131 0.00291022 0.0167888 0.0266519 -0.0195879 -0.0168399 0.000133669 -0.000632009 0.00856656 0.0133667 -0.0202305 -0.0567013 -1.33729e-05 -1.65665e-05 -5.81406e-05 -5.80872e-05 4.07377e-06 6.94419e-06 0 0 -0.00133683 -0.00134526 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.86454e-06 9.20034e-06 6.18534e-05 5.72595e-05 6.18473e-05 5.72641e-05 0.000247657 0.000255463 0.104164 0.0694371 0.104165 0.069435 0.0293402 0.027445 0.0850157 0.081866 0.0850158 0.0818658 0.102644 0.100317 4.81014e-09 5.80805e-09 4.81354e-09 5.81199e-09 1.07896e-08 1.23925e-08 0 0 1.46589e-07 1.30511e-07 0 0 0 0 0 0 0 0
95 9285000 0.982479 0.982424 -0.00697071 -0.00649151 -0.012228 -0.0122187 0.185839 0.186148 0.00667343 0.00493718 0.0180256 0.0287878 -0.0177532 -0.0151595 0.000747894 -0.000178883 0.0102872 0.016119 -0.0174048 -0.054016 -1.33645e-05 -1.65562e-05 -5.81431e-05 -5.80899e-05 4.39401e-06 7.26487e-06 0 0 -0.00134063 -0.00134851 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.74291e-06 9.18234e-06 6.32232e-05 6.1755e-05 6.32179e-05 6.17619e-05 0.000244163 0.000254791 0.113661 0.0757316 0.113662 0.075729 0.0284713 0.0266596 0.102221 0.0955929 0.102221 0.0955925 0.101314 0.0990459 4.81019e-09 5.80802e-09 4.81359e-09 5.812e-09 1.06769e-08 1.21443e-08 0 0 1.3959e-07 1.245e-07 0 0 0 0 0 0 0 0
96 9385000 0.982472 0.982414 -0.00687734 -0.00645132 -0.012268 -0.0122423 0.18588 0.186202 0.00682212 0.0048386 0.0186499 0.0261755 -0.0161558 -0.0136044 0.00145755 0.000287653 0.0121371 0.013543 -0.0171797 -0.0537789 -1.3369e-05 -1.65033e-05 -5.81363e-05 -5.81068e-05 4.13937e-06 6.78623e-06 0 0 -0.00134213 -0.00134983 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.73208e-06 9.27231e-06 6.48349e-05 6.11251e-05 6.48291e-05 6.11313e-05 0.000243826 0.000257223 0.123601 0.0638524 0.123603 0.0638495 0.0281494 0.0263729 0.122426 0.0780988 0.122426 0.0780985 0.102593 0.100269 4.81025e-09 5.80298e-09 4.81365e-09 5.80697e-09 1.05888e-08 1.19562e-08 0 0 1.34624e-07 1.20229e-07 0 0 0 0 0 0 0 0
97 9485000 0.982501 0.982441 -0.00699011 -0.00648066 -0.0123205 -0.0123143 0.185719 0.186056 0.00599315 0.00427216 0.0143852 0.0265 -0.0137484 -0.0113537 0.00154162 0.000715806 0.00952244 0.0161557 -0.0130986 -0.0498506 -1.33693e-05 -1.64939e-05 -5.81333e-05 -5.81071e-05 4.42276e-06 7.02915e-06 0 0 -0.00134648 -0.00135363 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.63023e-06 9.25331e-06 5.43905e-05 6.615e-05 5.43833e-05 6.6158e-05 0.000241114 0.000256692 0.0989248 0.0700494 0.0989266 0.0700456 0.0273306 0.0256323 0.0974546 0.0907856 0.0974549 0.0907851 0.101263 0.0989985 4.8101e-09 5.80295e-09 4.81348e-09 5.80697e-09 1.04665e-08 1.17031e-08 0 0 1.28343e-07 1.14823e-07 0 0 0 0 0 0 0 0
98 9585000 0.982474 0.982408 -0.00702805 -0.0065691 -0.012298 -0.0122729 0.185863 0.186227 0.00546157 0.00331598 0.0134474 0.0225956 -0.014319 -0.0119134 0.00203951 0.000743174 0.0109001 0.0134143 -0.0160404 -0.0527595 -1.33784e-05 -1.64105e-05 -5.81267e-05 -5.81434e-05 4.01673e-06 6.32386e-06 0 0 -0.00134525 -0.00135242 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.55295e-06 9.24459e-06 5.64979e-05 6.64883e-05 5.64917e-05 6.64971e-05 0.000238747 0.000256193 0.107213 0.0603382 0.107215 0.0603342 0.0265439 0.0249201 0.115812 0.074755 0.115812 0.0747546 0.0999551 0.0977504 4.81014e-09 5.78975e-09 4.81352e-09 5.79379e-09 1.03389e-08 1.14478e-08 0 0 1.22429e-07 1.09726e-07 0 0 0 0 0 0 0 0
99 9685000 0.982486 0.982416 -0.00708925 -0.00656179 -0.0122321 -0.0122257 0.185799 0.186186 0.00467084 0.00291523 0.0108056 0.0240005 -0.0110338 -0.00872306 0.00191255 0.00114029 0.00849878 0.0158482 -0.0135112 -0.0503219 -1.33883e-05 -1.64141e-05 -5.81159e-05 -5.81352e-05 3.93213e-06 6.05017e-06 0 0 -0.00134813 -0.00135496 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.47465e-06 9.22704e-06 4.95186e-05 7.20112e-05 4.95119e-05 7.20225e-05 0.00023671 0.000255741 0.086289 0.0666882 0.0862907 0.0666832 0.0257934 0.0242401 0.092674 0.0866289 0.0926743 0.086628 0.0986914 0.0965441 4.80983e-09 5.78972e-09 4.8132e-09 5.79379e-09 1.02067e-08 1.11916e-08 0 0 1.16877e-07 1.04936e-07 0 0 0 0 0 0 0 0
100 9785000 0.982473 0.982396 -0.00707295 -0.00659563 -0.0121843 -0.012157 0.185874 0.186297 0.00592486 0.0036443 0.0122593 0.0227153 -0.0115362 -0.00924631 0.00246498 0.00108792 0.00967008 0.0132186 -0.0138284 -0.0506496 -1.34001e-05 -1.6291e-05 -5.81032e-05 -5.81896e-05 3.34367e-06 5.10068e-06 0 0 -0.00134878 -0.00135553 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.40834e-06 9.20895e-06 5.21248e-05 7.29066e-05 5.21189e-05 7.29184e-05 0.000234947 0.000255298 0.0933615 0.0587195 0.0933638 0.0587148 0.025072 0.023586 0.10932 0.0718682 0.109321 0.0718675 0.0974496 0.0953584 4.80987e-09 5.76214e-09 4.81324e-09 5.76619e-09 1.00696e-08 1.09346e-08 0 0 1.11644e-07 1.00415e-07 0 0 0 0 0 0 0 0
101 9885000 0.982491 0.982412 -0.00709079 -0.00655767 -0.0121092 -0.012099 0.185782 0.186217 0.00738789 0.00556856 0.0090907 0.0230774 -0.00983774 -0.00761221 0.00224866 0.00151855 0.00742178 0.0153924 -0.0139179 -0.0507896 -1.33978e-05 -1.62827e-05 -5.81064e-05 -5.81953e-05 3.69381e-06 5.43643e-06 0 0 -0.00134947 -0.00135597 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.35733e-06 9.20087e-06 4.77869e-05 7.88911e-05 4.77807e-05 7.89053e-05 0.000233424 0.000254855 0.0758923 0.0654518 0.0758944 0.0654461 0.0243834 0.0229614 0.0880566 0.0831518 0.088057 0.0831506 0.0962491 0.0942121 4.80978e-09 5.7621e-09 4.81315e-09 5.76619e-09 9.92839e-09 1.06778e-08 0 0 1.06725e-07 9.61611e-08 0 0 0 0 0 0 0 0
102 9985000 0.982465 0.982379 -0.00708801 -0.00660567 -0.0121845 -0.0121505 0.185916 0.186387 0.00889065 0.00641266 0.00850377 0.0199482 -0.00874166 -0.00652218 0.00304057 0.00152812 0.00824319 0.0127575 -0.0149381 -0.0518007 -1.34092e-05 -1.61155e-05 -5.80953e-05 -5.82822e-05 3.14146e-06 4.56291e-06 0 0 -0.00134945 -0.00135592 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.31419e-06 9.18995e-06 5.08839e-05 7.99562e-05 5.08777e-05 7.99698e-05 0.000232111 0.000254396 0.0821179 0.0588023 0.0821203 0.0587968 0.0237212 0.02236 0.103175 0.0694601 0.103175 0.0694592 0.0950692 0.0930853 4.80982e-09 5.7121e-09 4.81318e-09 5.71614e-09 9.78291e-09 1.04213e-08 0 0 1.02084e-07 9.21424e-08 0 0 0 0 0 0 0 0
103 10085000 0.982457 0.982367 -0.00707194 -0.00654496 -0.0123241 -0.0123065 0.185949 0.186443 0.0070664 0.00516124 0.00382526 0.0182599 -0.00753524 -0.00534162 0.00281245 0.00212643 0.00618643 0.0146277 -0.0133407 -0.050187 -1.34142e-05 -1.61277e-05 -5.80877e-05 -5.82686e-05 2.74839e-06 3.95119e-06 0 0 -0.00135113 -0.00135745 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.36049e-06 9.28245e-06 4.85124e-05 8.63557e-05 4.85046e-05 8.63698e-05 0.000233473 0.000256936 0.0676838 0.0660952 0.0676857 0.0660882 0.0234824 0.0221478 0.0837195 0.080367 0.08372 0.0803655 0.0961867 0.094161 4.80982e-09 5.7121e-09 4.81317e-09 5.71617e-09 9.67125e-09 1.02296e-08 0 0 9.87784e-08 8.92778e-08 0 0 0 0 0 0 0 0
104 10185000 0.982419 0.982321 -0.00704652 -0.00650551 -0.0122432 -0.0122225 0.186156 0.186694 0.00489826 0.00274993 0.00415075 0.019596 -0.0058436 -0.00364431 0.00339016 0.00250058 0.00660014 0.016538 -0.013354 -0.0501842 -1.34311e-05 -1.61547e-05 -5.80701e-05 -5.82455e-05 1.90957e-06 2.74753e-06 0 0 -0.00135163 -0.00135791 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.32954e-06 9.27148e-06 5.2084e-05 9.30386e-05 5.20771e-05 9.30556e-05 0.000232483 0.00025642 0.0734113 0.0742536 0.0734134 0.0742452 0.0228576 0.0215797 0.0975166 0.0930481 0.0975172 0.0930459 0.0950105 0.0930386 4.80985e-09 5.71207e-09 4.81319e-09 5.71617e-09 9.51928e-09 9.97516e-09 0 0 9.45884e-08 8.56431e-08 0 0 0 0 0 0 0 0
105 10285000 0.98245 0.982351 -0.00711275 -0.00660355 -0.0121508 -0.0121208 0.185993 0.186537 0.00438579 0.0022741 0.00276498 0.0172801 -0.00688634 -0.00475442 0.00274617 0.00199996 0.00488916 0.0136119 -0.0132416 -0.0501279 -1.34126e-05 -1.59186e-05 -5.80895e-05 -5.83864e-05 2.372e-06 3.22987e-06 0 0 -0.00135208 -0.00135814 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.29916e-06 9.25434e-06 5.11401e-05 9.3943e-05 5.11338e-05 9.39602e-05 0.00023164 0.000255881 0.0615652 0.068365 0.0615672 0.0683571 0.022261 0.0210369 0.0797412 0.078272 0.0797416 0.0782702 0.0938733 0.0919529 4.8087e-09 5.63034e-09 4.81204e-09 5.63435e-09 9.36433e-09 9.72296e-09 0 0 9.06418e-08 8.22152e-08 0 0 0 0 0 0 0 0
106 10385000 0.982476 0.982375 -0.00712362 -0.00660237 -0.0120518 -0.0120182 0.185865 0.186419 0.00718801 0.0069531 0.00201435 0.00288639 -0.00298405 -0.00293252 0.000774448 0.000764022 3.00987e-05 6.91822e-05 -0.0114163 -0.0485443 -1.34045e-05 -1.59096e-05 -5.80942e-05 -5.8391e-05 2.72489e-06 3.56275e-06 0 0 -0.00135338 -0.00135918 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.27429e-06 9.23716e-06 5.51688e-05 0.000100972 5.51636e-05 0.000100993 0.000230909 0.000255296 0.0347595 0.0348985 0.0347596 0.0348985 0.0374564 0.0374559 0.12528 0.12528 0.08678 0.0851462 4.80874e-09 5.6303e-09 4.81206e-09 5.63435e-09 9.20635e-09 9.47293e-09 0 0 8.71036e-08 7.91359e-08 0 0 0 0 0 0 0 0
107 10485000 0.982464 0.982357 -0.00703651 -0.00650283 -0.0120027 -0.0119655 0.18593 0.18652 0.00747662 0.00697386 0.0013724 0.00323354 -0.00193119 -0.00183703 0.00149988 0.00145266 0.000196693 0.000372235 -0.00675368 -0.0441115 -1.34135e-05 -1.59239e-05 -5.80775e-05 -5.83716e-05 2.18056e-06 2.76456e-06 0 0 -0.00135663 -0.0013622 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.25018e-06 9.21533e-06 5.9438e-05 0.000108283 5.94331e-05 0.000108306 0.000230276 0.000254665 0.0354828 0.0361205 0.0354829 0.0361204 0.0375607 0.0375589 0.126254 0.126259 0.126254 0.126259 0.0808894 0.0794979 4.80877e-09 5.63027e-09 4.81209e-09 5.63435e-09 9.0457e-09 9.22552e-09 0 0 8.41249e-08 7.6535e-08 0 0 0 0 0 0 0 0
108 10585000 0.982484 0.982376 -0.00698381 -0.00644019 -0.0119454 -0.0118923 0.185832 0.186427 0.00609668 0.00532214 0.00064535 0.00325481 -0.00063084 -0.00050772 0.00117096 0.00108861 -0.00344862 -0.00317399 -0.00580416 -0.0433366 -1.34295e-05 -1.59386e-05 -5.81898e-05 -5.85614e-05 2.73085e-06 3.33243e-06 0 0 -0.00135712 -0.0013625 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.23836e-06 9.20221e-06 6.37568e-05 0.000115242 6.37522e-05 0.000115267 0.000229718 0.000253984 0.0320569 0.0333337 0.032057 0.0333333 0.0352721 0.0352689 0.084862 0.0848766 0.084862 0.0848766 0.0763588 0.0751591 4.79966e-09 5.60278e-09 4.80297e-09 5.60686e-09 8.88309e-09 8.98153e-09 0 0 8.1581e-08 7.43078e-08 0 0 0 0 0 0 0 0
109 10685000 0.982497 0.982386 -0.00694293 -0.00638705 -0.0119807 -0.0119235 0.185761 0.186373 0.00658377 0.00549718 -0.00169698 0.00193789 -0.000521176 -0.000363454 0.00179782 0.00162251 -0.00350563 -0.002919 -0.00490566 -0.0425342 -1.34307e-05 -1.59418e-05 -5.81872e-05 -5.85574e-05 2.6531e-06 3.16009e-06 0 0 -0.00135772 -0.00136303 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.3052e-06 9.28258e-06 6.84941e-05 0.000123074 6.84894e-05 0.000123101 0.000231687 0.000256262 0.0336846 0.0361852 0.0336848 0.0361843 0.0353175 0.0353122 0.0865836 0.0866481 0.0865836 0.0866481 0.0744977 0.0734122 4.79971e-09 5.60278e-09 4.80302e-09 5.60689e-09 8.75997e-09 8.80085e-09 0 0 7.99102e-08 7.28423e-08 0 0 0 0 0 0 0 0
110 10785000 0.982505 0.982389 -0.00694757 -0.00640039 -0.012085 -0.0120135 0.185714 0.186349 0.0073339 0.00600021 -0.00294898 0.00113392 0.00036227 0.000536427 0.00171207 0.0015024 -0.00315653 -0.00252141 -0.00196399 -0.0397345 -1.33764e-05 -1.57771e-05 -5.82904e-05 -5.87398e-05 2.55649e-06 2.9387e-06 0 0 -0.0013595 -0.00136465 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.28769e-06 9.25453e-06 7.26273e-05 0.000128461 7.26223e-05 0.000128488 0.000231244 0.000255472 0.0313817 0.0347389 0.0313821 0.0347378 0.0331901 0.0331836 0.0657142 0.0658033 0.0657142 0.0658033 0.0717274 0.0707771 4.76314e-09 5.49808e-09 4.76641e-09 5.50209e-09 8.59431e-09 8.56299e-09 0 0 7.79341e-08 7.11064e-08 0 0 0 0 0 0 0 0
111 10885000 0.982532 0.982417 -0.00692748 -0.00636907 -0.0121331 -0.0120574 0.185566 0.186202 0.00786231 0.00617936 -0.00296605 0.00213903 0.000563778 0.000759117 0.00247349 0.00211361 -0.0035085 -0.00241444 -0.00134342 -0.0392346 -1.33606e-05 -1.57586e-05 -5.8305e-05 -5.87546e-05 3.31707e-06 3.74265e-06 0 0 -0.0013598 -0.00136478 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.28071e-06 9.23494e-06 7.77875e-05 0.000136681 7.77826e-05 0.000136711 0.000230826 0.000254614 0.0339912 0.0392907 0.0339918 0.039289 0.0330662 0.0330581 0.0680221 0.0682749 0.0680221 0.0682748 0.0700823 0.0692415 4.76317e-09 5.49806e-09 4.76644e-09 5.5021e-09 8.42731e-09 8.32896e-09 0 0 7.62135e-08 6.95923e-08 0 0 0 0 0 0 0 0
112 10985000 0.982545 0.982426 -0.0069214 -0.00636836 -0.012237 -0.0121468 0.185491 0.186147 0.00618119 0.0042401 0.00252048 0.00792654 0.00256604 0.00277735 0.0022355 0.00184352 -0.00265984 -0.00157113 0.00148578 -0.0365117 -1.34575e-05 -1.57641e-05 -5.83999e-05 -5.89188e-05 3.2701e-06 3.58897e-06 0 0 -0.00136096 -0.00136583 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.26318e-06 9.19974e-06 8.11031e-05 0.000138759 8.10977e-05 0.000138786 0.000230451 0.000253722 0.0323526 0.0383542 0.0323536 0.0383528 0.0310525 0.0310438 0.0552021 0.0554735 0.0552021 0.0554735 0.0684194 0.067676 4.68114e-09 5.27808e-09 4.68433e-09 5.28189e-09 8.2596e-09 8.09928e-09 0 0 7.47012e-08 6.82606e-08 0 0 0 0 0 0 0 0
113 11085000 0.982504 0.982378 -0.00705184 -0.00648731 -0.0122209 -0.0121263 0.185706 0.1864 0.00703182 0.00469469 0.00480332 0.0112365 0.00444282 0.00467954 0.00286943 0.00226313 -0.00235468 -0.000674048 0.00414787 -0.0339174 -1.34728e-05 -1.57853e-05 -5.8382e-05 -5.88984e-05 2.48186e-06 2.58951e-06 0 0 -0.00136224 -0.00136709 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.25648e-06 9.17485e-06 8.66061e-05 0.000147147 8.66024e-05 0.000147178 0.000230077 0.00025276 0.0359879 0.0445529 0.0359895 0.0445511 0.030787 0.0307768 0.058071 0.0586911 0.0580711 0.0586909 0.0678402 0.0671759 4.68117e-09 5.27806e-09 4.68436e-09 5.28191e-09 8.09124e-09 7.87391e-09 0 0 7.33767e-08 6.70927e-08 0 0 0 0 0 0 0 0
114 11185000 0.982505 0.982373 -0.00707679 -0.00655648 -0.0121803 -0.0120911 0.185703 0.186423 0.00680491 0.00454585 0.00654997 0.0127269 0.00767957 0.00792501 0.00327233 0.00274055 -0.00167144 -0.000189417 0.00882245 -0.0293297 -1.33744e-05 -1.53861e-05 -5.83625e-05 -5.88817e-05 2.03908e-06 2.00635e-06 0 0 -0.00136391 -0.00136868 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.2374e-06 9.13257e-06 8.83792e-05 0.00014442 8.83764e-05 0.00014445 0.000229728 0.000251766 0.034579 0.0432227 0.0345808 0.043221 0.0288837 0.028873 0.0491241 0.0496993 0.0491242 0.0496992 0.0668009 0.0662102 4.53899e-09 4.92804e-09 4.54209e-09 4.93154e-09 7.92278e-09 7.6532e-09 0 0 7.22064e-08 6.6061e-08 0 0 0 0 0 0 0 0
115 11285000 0.982494 0.982359 -0.00708448 -0.00655439 -0.0122151 -0.0121216 0.185756 0.186496 0.00596352 0.00332692 0.00613038 0.0132663 0.00874235 0.00901048 0.00386831 0.00309129 -0.000981562 0.00116625 0.00862134 -0.0295709 -1.33795e-05 -1.53938e-05 -5.83589e-05 -5.88766e-05 1.80869e-06 1.6887e-06 0 0 -0.00136344 -0.00136824 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.2288e-06 9.10168e-06 9.41095e-05 0.000152696 9.41072e-05 0.000152728 0.000229364 0.000250705 0.0392336 0.0508623 0.0392359 0.0508597 0.0284959 0.0284838 0.0525789 0.0537318 0.0525792 0.0537316 0.0668742 0.0663425 4.53902e-09 4.92803e-09 4.54212e-09 4.93156e-09 7.75434e-09 7.43716e-09 0 0 7.11792e-08 6.51545e-08 0 0 0 0 0 0 0 0
116 11385000 0.982495 0.982358 -0.00700845 -0.00653932 -0.0121918 -0.0120816 0.185756 0.186504 0.00470355 0.001938 0.00661387 0.0130202 0.00783225 0.00811902 0.00324165 0.0024837 -0.000615183 0.00113376 0.00675774 -0.031451 -1.33113e-05 -1.49797e-05 -5.85916e-05 -5.92227e-05 1.67622e-06 1.51785e-06 0 0 -0.00136216 -0.00136704 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.30266e-06 9.16621e-06 9.36761e-05 0.000144536 9.36732e-05 0.000144561 0.00023144 0.000252507 0.0376083 0.048285 0.0376106 0.0482828 0.0268577 0.0268443 0.0456633 0.046623 0.0456635 0.0466227 0.0672766 0.0667863 4.3297e-09 4.46483e-09 4.33266e-09 4.46791e-09 7.62808e-09 7.27805e-09 0 0 7.04872e-08 6.45453e-08 0 0 0 0 0 0 0 0
117 11485000 0.98252 0.982382 -0.00692363 -0.00644696 -0.0121702 -0.0120552 0.185629 0.186382 0.00326696 0.000104855 0.00596444 0.0132178 0.00950627 0.00980938 0.00359244 0.00253846 3.5837e-05 0.00246716 0.00996826 -0.0283071 -1.33078e-05 -1.49761e-05 -5.85924e-05 -5.92238e-05 1.81711e-06 1.64154e-06 0 0 -0.00136316 -0.00136793 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.28447e-06 9.12131e-06 9.94889e-05 0.000152413 9.94863e-05 0.000152441 0.000231055 0.000251333 0.0432048 0.0570129 0.0432076 0.0570097 0.0263927 0.0263775 0.0497376 0.051498 0.049738 0.0514976 0.0677365 0.0672924 4.32973e-09 4.46483e-09 4.33269e-09 4.46793e-09 7.4604e-09 7.07041e-09 0 0 6.96636e-08 6.38184e-08 0 0 0 0 0 0 0 0
118 11585000 0.98252 0.98238 -0.00702696 -0.00662519 -0.0121307 -0.0120116 0.18563 0.18639 0.0047724 0.00173464 0.00568865 0.0118426 0.0100175 0.0103248 0.00309687 0.00217201 0.000108956 0.00196057 0.0113204 -0.0270141 -1.31866e-05 -1.44588e-05 -5.8784e-05 -5.94745e-05 1.68206e-06 1.47562e-06 0 0 -0.00136394 -0.00136867 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.2689e-06 9.07583e-06 9.64227e-05 0.000139342 9.64208e-05 0.000139364 0.000230648 0.000250111 0.0409087 0.0525736 0.0409114 0.0525712 0.0247373 0.0247216 0.0438684 0.0452097 0.0438687 0.0452094 0.0671552 0.0667581 4.05678e-09 3.93147e-09 4.05954e-09 3.93407e-09 7.29362e-09 6.86771e-09 0 0 6.89325e-08 6.3175e-08 0 0 0 0 0 0 0 0
119 11685000 0.982529 0.982389 -0.0069894 -0.0065821 -0.0120789 -0.0119552 0.185588 0.186348 0.00513982 0.00170877 0.00806404 0.0149332 0.0117537 0.0120835 0.00360079 0.0023527 0.000793884 0.00329663 0.0115453 -0.0268237 -1.31854e-05 -1.44573e-05 -5.87861e-05 -5.94765e-05 1.75475e-06 1.55425e-06 0 0 -0.00136358 -0.0013683 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.2553e-06 9.03421e-06 0.000102163 0.00014659 0.000102162 0.000146614 0.000230214 0.000248842 0.047277 0.0619253 0.0472805 0.0619226 0.0242083 0.0241907 0.0485747 0.0508812 0.0485752 0.0508807 0.0677997 0.0674377 4.05681e-09 3.93147e-09 4.05957e-09 3.93409e-09 7.12795e-09 6.67009e-09 0 0 6.82922e-08 6.26106e-08 0 0 0 0 0 0 0 0
120 11785000 0.982552 0.982415 -0.00711995 -0.00681891 -0.0120276 -0.011896 0.185464 0.186206 0.00358269 0.000346436 0.00798569 0.0129996 0.0125724 0.0129017 0.00291215 0.00183889 -0.000313071 0.00125808 0.0143129 -0.0241231 -1.26871e-05 -1.34781e-05 -5.91932e-05 -5.99659e-05 2.30942e-06 2.18128e-06 0 0 -0.00136413 -0.00136874 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.24052e-06 8.9883e-06 9.64471e-05 0.00013011 9.64463e-05 0.000130127 0.000229742 0.00024752 0.0439875 0.0555157 0.0439907 0.0555139 0.0226855 0.0226672 0.0431518 0.0447873 0.0431521 0.044787 0.0672505 0.0669261 3.73506e-09 3.38191e-09 3.7376e-09 3.38404e-09 6.96335e-09 6.47715e-09 0 0 6.77224e-08 6.21106e-08 0 0 0 0 0 0 0 0
121 11885000 0.982544 0.982408 -0.00720233 -0.00689815 -0.0119275 -0.0117913 0.185508 0.186248 0.00624737 0.00263096 0.00826979 0.0138044 0.011607 0.0119586 0.00333238 0.00191585 0.000454994 0.00255368 0.0156383 -0.0228224 -1.26948e-05 -1.34862e-05 -5.91858e-05 -5.9959e-05 1.93001e-06 1.81058e-06 0 0 -0.00136416 -0.00136879 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.2218e-06 8.94015e-06 0.000101972 0.000136589 0.000101973 0.00013661 0.000229251 0.000246174 0.050946 0.0651009 0.0509501 0.0650988 0.0221237 0.022103 0.0484674 0.0511431 0.048468 0.0511426 0.067945 0.0676471 3.73509e-09 3.38192e-09 3.73764e-09 3.38407e-09 6.80063e-09 6.28964e-09 0 0 6.72244e-08 6.16726e-08 0 0 0 0 0 0 0 0
122 11985000 0.982559 0.982425 -0.00729453 -0.00705336 -0.0119749 -0.011862 0.18542 0.186148 0.00726238 0.00432563 0.00940221 0.0138555 0.0107314 0.0110989 0.00380247 0.00279642 -0.000355878 0.0011472 0.0130941 -0.0253822 -1.25763e-05 -1.30539e-05 -5.91508e-05 -5.98606e-05 2.00245e-06 1.93092e-06 0 0 -0.00136326 -0.00136793 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.28384e-06 8.98371e-06 9.39776e-05 0.000118496 9.39791e-05 0.00011851 0.000231167 0.000247588 0.0464759 0.0569705 0.0464793 0.0569692 0.0209221 0.0208992 0.0431063 0.0448999 0.0431067 0.0448996 0.0685375 0.0682603 3.38591e-09 2.86124e-09 3.38821e-09 2.86296e-09 6.67961e-09 6.15213e-09 0 0 6.68864e-08 6.13781e-08 0 0 0 0 0 0 0 0
123 12085000 0.982542 0.982409 -0.0072135 -0.00697065 -0.0120307 -0.0119136 0.185509 0.186231 0.0088651 0.00560668 0.00917182 0.0140327 0.0133305 0.0137143 0.00461834 0.00330128 0.000534116 0.00250278 0.0198603 -0.018659 -1.25812e-05 -1.30588e-05 -5.9142e-05 -5.98541e-05 1.72238e-06 1.6791e-06 0 0 -0.00136493 -0.0013695 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.26888e-06 8.93884e-06 9.9176e-05 0.000124166 9.91773e-05 0.000124181 0.000230591 0.000246134 0.0537605 0.0663911 0.0537646 0.0663894 0.02036 0.0203342 0.0489704 0.0517887 0.0489711 0.0517882 0.0692188 0.0689619 3.38594e-09 2.86126e-09 3.38825e-09 2.86299e-09 6.52003e-09 5.97334e-09 0 0 6.64865e-08 6.10273e-08 0 0 0 0 0 0 0 0
124 12185000 0.982536 0.982404 -0.00710327 -0.00690449 -0.011986 -0.01187 0.185548 0.186264 0.00828546 0.00520268 0.00862472 0.0126124 0.0126762 0.013074 0.00369711 0.00254901 0.00147517 0.00292487 0.0215087 -0.0170384 -1.27619e-05 -1.30213e-05 -5.94359e-05 -6.01355e-05 1.12704e-06 1.11182e-06 0 0 -0.00136506 -0.00136967 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.23663e-06 8.87402e-06 8.95711e-05 0.000106055 8.95711e-05 0.000106063 0.000229983 0.000244653 0.0481608 0.0570901 0.0481638 0.0570889 0.0191127 0.0190854 0.0434395 0.0452533 0.04344 0.045253 0.068574 0.0683418 3.03235e-09 2.39797e-09 3.0344e-09 2.39933e-09 6.36225e-09 5.79923e-09 0 0 6.61255e-08 6.07138e-08 0 0 0 0 0 0 0 0
125 12285000 0.982523 0.982392 -0.00715516 -0.00695586 -0.0119744 -0.0118547 0.185619 0.186324 0.00591851 0.00252793 0.00731018 0.0116177 0.0110873 0.0115123 0.00441827 0.00294601 0.00226493 0.00412962 0.0221197 -0.0164374 -1.2769e-05 -1.30277e-05 -5.94294e-05 -6.013e-05 7.77892e-07 8.13544e-07 0 0 -0.00136492 -0.00136954 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.21566e-06 8.82313e-06 9.43709e-05 0.000110947 9.43721e-05 0.000110957 0.000229335 0.000243142 0.0555758 0.0661335 0.055579 0.0661315 0.0185641 0.0185332 0.0497621 0.052516 0.0497629 0.0525155 0.0691649 0.0689474 3.03239e-09 2.398e-09 3.03444e-09 2.39936e-09 6.20701e-09 5.63039e-09 0 0 6.58126e-08 6.04406e-08 0 0 0 0 0 0 0 0
126 12385000 0.982532 0.982404 -0.00721463 -0.00706742 -0.0118861 -0.011776 0.185576 0.186263 0.00443037 0.00146008 0.00534219 0.008536 0.0115774 0.0120194 0.00353873 0.00237299 0.00164408 0.00284769 0.0192355 -0.0193394 -1.26225e-05 -1.26661e-05 -5.97219e-05 -6.03812e-05 5.32305e-07 6.40439e-07 0 0 -0.001364 -0.0013687 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.18097e-06 8.75702e-06 8.38906e-05 9.38807e-05 8.38909e-05 9.38856e-05 0.00022865 0.000241606 0.0489925 0.0561678 0.0489947 0.0561663 0.0174551 0.0174223 0.0439446 0.0456694 0.0439452 0.0456692 0.0684559 0.0682581 2.69311e-09 2.0029e-09 2.6949e-09 2.00393e-09 6.05387e-09 5.46615e-09 0 0 6.55256e-08 6.01936e-08 0 0 0 0 0 0 0 0
127 12485000 0.982508 0.982384 -0.0072159 -0.00706924 -0.0118937 -0.0117802 0.185699 0.18637 0.00480927 0.00156012 0.0060953 0.009514 0.0154454 0.0159134 0.00400904 0.00253175 0.00219853 0.0037329 0.0212804 -0.0173053 -1.2628e-05 -1.26705e-05 -5.97162e-05 -6.03771e-05 2.5605e-07 4.3093e-07 0 0 -0.00136416 -0.00136886 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.16335e-06 8.71054e-06 8.82616e-05 9.80678e-05 8.82625e-05 9.80737e-05 0.00022792 0.000240039 0.0563012 0.0646285 0.056304 0.0646268 0.0169371 0.0169 0.0506205 0.0531605 0.0506213 0.0531601 0.0689302 0.0687426 2.69314e-09 2.00292e-09 2.69494e-09 2.00398e-09 5.90352e-09 5.30702e-09 0 0 6.52787e-08 5.99793e-08 0 0 0 0 0 0 0 0
128 12585000 0.982484 0.982362 -0.00731744 -0.0072202 -0.0118358 -0.0117421 0.185829 0.186481 0.0072385 0.00471344 0.00116227 0.00347131 0.0171169 0.0175973 0.00466632 0.00368044 0.000117224 0.000972831 0.0225911 -0.016019 -1.21185e-05 -1.20004e-05 -5.97603e-05 -6.0363e-05 -1.25778e-07 1.26099e-07 0 0 -0.00136407 -0.00136879 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.13803e-06 8.65588e-06 7.75898e-05 8.26413e-05 7.75893e-05 8.26429e-05 0.000227147 0.000238447 0.0490494 0.0545264 0.0490512 0.0545251 0.0159606 0.015921 0.044488 0.0460549 0.0444885 0.0460546 0.0681599 0.0679878 2.38116e-09 1.67553e-09 2.38271e-09 1.67632e-09 5.7555e-09 5.15238e-09 0 0 6.50458e-08 5.97811e-08 0 0 0 0 0 0 0 0
129 12685000 0.982485 0.982367 -0.00729251 -0.00719653 -0.0118498 -0.0117531 0.185819 0.186456 0.00739904 0.00464829 -0.000730671 0.0017136 0.0172547 0.0177659 0.0053434 0.00409314 0.000138297 0.00123158 0.0255163 -0.0130871 -1.21218e-05 -1.20027e-05 -5.97565e-05 -6.03607e-05 -2.94973e-07 1.46683e-08 0 0 -0.00136433 -0.00136903 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.19347e-06 8.69193e-06 8.15342e-05 8.62173e-05 8.15341e-05 8.62192e-05 0.000228733 0.000239462 0.0561851 0.0624221 0.0561868 0.0624203 0.0156487 0.0156029 0.0514146 0.0536576 0.0514153 0.0536572 0.0697032 0.0695318 2.38122e-09 1.67558e-09 2.38277e-09 1.67638e-09 5.64634e-09 5.03954e-09 0 0 6.48984e-08 5.96544e-08 0 0 0 0 0 0 0 0
130 12785000 0.98254 0.982428 -0.00748164 -0.00742121 -0.011725 -0.0116434 0.18553 0.186133 0.0081849 0.00602966 -0.0028314 -0.00124889 0.0184451 0.0189569 0.00511594 0.00430057 -0.00263831 -0.00209042 0.0271028 -0.0115405 -1.15404e-05 -1.13378e-05 -5.98123e-05 -6.03737e-05 5.47455e-07 9.52522e-07 0 0 -0.00136425 -0.00136885 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.15564e-06 8.62519e-06 7.11548e-05 7.26049e-05 7.11538e-05 7.26041e-05 0.000227877 0.00023781 0.048534 0.0525021 0.0485355 0.052501 0.0147866 0.0147378 0.0449909 0.0463659 0.0449913 0.0463657 0.0688524 0.0686938 2.10242e-09 1.40834e-09 2.10373e-09 1.40892e-09 5.50304e-09 4.89295e-09 0 0 6.46982e-08 5.94863e-08 0 0 0 0 0 0 0 0
131 12885000 0.982578 0.982471 -0.00746687 -0.00740835 -0.011658 -0.0115736 0.185333 0.185906 0.00792096 0.00557862 -0.00432253 -0.00267166 0.0192852 0.0198158 0.0059588 0.00491897 -0.00299578 -0.00228648 0.0304504 -0.00820342 -1.15318e-05 -1.13273e-05 -5.98197e-05 -6.03829e-05 9.64571e-07 1.4526e-06 0 0 -0.00136452 -0.00136904 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.11881e-06 8.56047e-06 7.4695e-05 7.56614e-05 7.46949e-05 7.56615e-05 0.000226993 0.000236152 0.0553762 0.0597869 0.0553777 0.0597855 0.0143587 0.014304 0.0520763 0.0539914 0.0520769 0.053991 0.0690888 0.0689337 2.10246e-09 1.40837e-09 2.10378e-09 1.40897e-09 5.36282e-09 4.75108e-09 0 0 6.45338e-08 5.93457e-08 0 0 0 0 0 0 0 0
132 12985000 0.982616 0.982514 -0.00745757 -0.00741433 -0.0116275 -0.0115529 0.185135 0.18568 0.00626745 0.00421322 -0.00240633 -0.00105074 0.0196646 0.0202071 0.00457545 0.00375224 -0.00227742 -0.00173705 0.031983 -0.00669357 -1.17496e-05 -1.14603e-05 -6.0025e-05 -6.05316e-05 1.31763e-06 1.88556e-06 0 0 -0.00136443 -0.00136893 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.07539e-06 8.48975e-06 6.49314e-05 6.38344e-05 6.49292e-05 6.38312e-05 0.000226069 0.000234478 0.0475783 0.0502674 0.0475794 0.0502665 0.0136114 0.0135532 0.0454148 0.0465901 0.0454152 0.0465899 0.0681982 0.0680531 1.85828e-09 1.19195e-09 1.8594e-09 1.19237e-09 5.22524e-09 4.61341e-09 0 0 6.43596e-08 5.92018e-08 0 0 0 0 0 0 0 0
133 13085000 0.982629 0.982533 -0.00746771 -0.00742675 -0.0115491 -0.0114722 0.185069 0.185584 0.0072286 0.00500842 -0.00236348 -0.000967515 0.0180851 0.0186491 0.00524507 0.00420973 -0.00247013 -0.00179257 0.0319801 -0.00669647 -1.1739e-05 -1.14477e-05 -6.00357e-05 -6.05431e-05 1.84695e-06 2.49068e-06 0 0 -0.00136406 -0.00136852 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.04926e-06 8.43784e-06 6.81034e-05 6.64571e-05 6.81022e-05 6.64549e-05 0.000225093 0.000232776 0.0540906 0.0569778 0.054092 0.0569768 0.0132346 0.0131697 0.0525818 0.054173 0.0525823 0.0541728 0.0683125 0.0681684 1.85833e-09 1.19199e-09 1.85945e-09 1.19243e-09 5.09062e-09 4.48007e-09 0 0 6.42225e-08 5.90857e-08 0 0 0 0 0 0 0 0
134 13185000 0.982638 0.982547 -0.0074748 -0.00744864 -0.0114919 -0.0114236 0.185025 0.185514 0.00333555 0.00137026 -0.00379023 -0.00276407 0.0172117 0.01779 0.00212525 0.00128284 -0.00343403 -0.00299587 0.0329723 -0.00572048 -1.17235e-05 -1.13816e-05 -6.04258e-05 -6.08634e-05 2.12066e-06 2.83739e-06 0 0 -0.00136391 -0.00136835 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.01478e-06 8.37826e-06 5.91204e-05 5.62622e-05 5.9117e-05 5.62571e-05 0.000224092 0.000231074 0.046339 0.0479753 0.0463399 0.0479746 0.0125921 0.0125231 0.0457451 0.0467277 0.0457454 0.0467275 0.0673966 0.0672603 1.64702e-09 1.01701e-09 1.64798e-09 1.01732e-09 4.95895e-09 4.35092e-09 0 0 6.40632e-08 5.89564e-08 0 0 0 0 0 0 0 0
135 13285000 0.982641 0.982553 -0.00748816 -0.00746423 -0.011472 -0.0114018 0.18501 0.185481 0.00231159 0.000198799 -0.00477195 -0.00373558 0.0154454 0.0160572 0.0023394 0.00129338 -0.00384679 -0.00330556 0.0336136 -0.00505426 -1.17251e-05 -1.1382e-05 -6.04247e-05 -6.08632e-05 2.04645e-06 2.81867e-06 0 0 -0.00136374 -0.00136819 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.05947e-06 8.40403e-06 6.19645e-05 5.85254e-05 6.19617e-05 5.85207e-05 0.000225385 0.000231827 0.0524969 0.0541458 0.0524977 0.0541448 0.0124048 0.0123273 0.0529335 0.054224 0.052934 0.0542238 0.0685768 0.0684345 1.64708e-09 1.01707e-09 1.64804e-09 1.01739e-09 4.86225e-09 4.25683e-09 0 0 6.3977e-08 5.88846e-08 0 0 0 0 0 0 0 0
136 13385000 0.982632 0.982548 -0.00742959 -0.00741744 -0.0115731 -0.0115138 0.185057 0.185507 0.00138613 -0.000366005 -0.00323267 -0.00241553 0.0145211 0.0151558 0.00180713 0.0010385 -0.00287214 -0.00244655 0.0335471 -0.00512329 -1.18971e-05 -1.14917e-05 -6.04351e-05 -6.08343e-05 1.72789e-06 2.57699e-06 0 0 -0.00136347 -0.00136796 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 8.01642e-06 8.33691e-06 5.38224e-05 4.97695e-05 5.38168e-05 4.97617e-05 0.000224307 0.000230085 0.0449197 0.0457023 0.0449204 0.0457017 0.0118484 0.0117663 0.045982 0.046787 0.0459823 0.0467869 0.0676172 0.067481 1.46541e-09 8.75342e-10 1.46622e-09 8.75557e-10 4.73573e-09 4.13472e-09 0 0 6.3821e-08 5.87596e-08 0 0 0 0 0 0 0 0
137 13485000 0.982629 0.982549 -0.00740202 -0.00739244 -0.0115303 -0.0114694 0.185077 0.185503 0.00198935 0.000112184 -0.00148874 -0.000682876 0.0152855 0.015952 0.00197313 0.00102395 -0.00306066 -0.00255395 0.0323361 -0.00631495 -1.18984e-05 -1.14914e-05 -6.04348e-05 -6.08348e-05 1.67262e-06 2.59195e-06 0 0 -0.00136304 -0.00136756 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.97887e-06 8.27609e-06 5.63778e-05 5.1734e-05 5.63728e-05 5.17268e-05 0.000223195 0.000228335 0.0506998 0.0513566 0.0507007 0.0513561 0.0115762 0.0114857 0.0531449 0.0541658 0.0531453 0.0541656 0.0675509 0.0674114 1.46546e-09 8.7539e-10 1.46628e-09 8.75617e-10 4.61221e-09 4.01652e-09 0 0 6.37155e-08 5.86722e-08 0 0 0 0 0 0 0 0
138 13585000 0.982601 0.982526 -0.00740344 -0.00740349 -0.0116106 -0.011556 0.185216 0.18562 0.00570301 0.0041803 -0.00174755 -0.00115316 0.016679 0.017368 0.00457861 0.00395581 -0.00249259 -0.00210575 0.0305556 -0.00809498 -1.18266e-05 -1.14001e-05 -6.00685e-05 -6.04941e-05 1.36636e-06 2.36269e-06 0 0 -0.00136247 -0.00136705 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.94207e-06 8.21724e-06 4.90699e-05 4.42212e-05 4.90634e-05 4.42123e-05 0.000222055 0.000226583 0.0433823 0.0434777 0.0433829 0.0434773 0.0111048 0.0110093 0.0461329 0.0467784 0.0461332 0.0467783 0.0665924 0.0664575 1.30968e-09 7.60128e-10 1.31037e-09 7.60276e-10 4.49168e-09 3.90212e-09 0 0 6.35578e-08 5.85473e-08 0 0 0 0 0 0 0 0
139 13685000 0.982632 0.982561 -0.00734041 -0.00734316 -0.0115226 -0.0114661 0.185059 0.185439 0.00506926 0.00343543 -0.00325554 -0.00269477 0.0162843 0.0169959 0.00510945 0.00432886 -0.00274393 -0.00229946 0.0329965 -0.00564141 -1.18217e-05 -1.13939e-05 -6.00728e-05 -6.04994e-05 1.60642e-06 2.65574e-06 0 0 -0.00136257 -0.00136711 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.89446e-06 8.1479e-06 5.13743e-05 4.59387e-05 5.13684e-05 4.59304e-05 0.0002209 0.000224844 0.0488277 0.0486938 0.0488282 0.0486932 0.0108838 0.0107792 0.0532352 0.054019 0.0532355 0.0540188 0.0664607 0.0663207 1.30973e-09 7.60179e-10 1.31043e-09 7.60338e-10 4.37412e-09 3.79141e-09 0 0 6.3461e-08 5.8468e-08 0 0 0 0 0 0 0 0
140 13785000 0.982616 0.982549 -0.00728972 -0.00730264 -0.011642 -0.0115863 0.185141 0.185499 0.0116747 0.0102761 -6.68541e-05 0.000303245 0.0164236 0.0171573 0.00849679 0.00798023 -0.00059718 -0.000224326 0.0326118 -0.00602324 -1.19371e-05 -1.14683e-05 -5.95712e-05 -6.00633e-05 1.28709e-06 2.41055e-06 0 0 -0.00136215 -0.00136673 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.85072e-06 8.08374e-06 4.48498e-05 3.94832e-05 4.48423e-05 3.94734e-05 0.000219717 0.000223102 0.0418452 0.0413855 0.0418458 0.0413853 0.0104879 0.0103778 0.0462088 0.0467125 0.046209 0.0467124 0.0655145 0.0653775 1.17601e-09 6.65865e-10 1.17661e-09 6.65959e-10 4.25953e-09 3.68427e-09 0 0 6.32948e-08 5.83374e-08 0 0 0 0 0 0 0 0
141 13885000 0.982643 0.98258 -0.00721273 -0.00722862 -0.0116095 -0.0115516 0.185005 0.185339 0.0127515 0.0112432 0.000860137 0.00117311 0.0176827 0.0184337 0.00968974 0.00902804 -0.000530422 -0.00012371 0.0349857 -0.00363787 -1.19269e-05 -1.1457e-05 -5.95804e-05 -6.00732e-05 1.78888e-06 2.94882e-06 0 0 -0.00136224 -0.00136676 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.80976e-06 8.02293e-06 4.69372e-05 4.09961e-05 4.69299e-05 4.09864e-05 0.00021851 0.000221361 0.0469541 0.0461889 0.0469549 0.0461887 0.0103153 0.0101954 0.053228 0.0538051 0.0532283 0.053805 0.0653345 0.0651907 1.17606e-09 6.65919e-10 1.17667e-09 6.66023e-10 4.14786e-09 3.58061e-09 0 0 6.32024e-08 5.82626e-08 0 0 0 0 0 0 0 0
142 13985000 0.982653 0.982594 -0.0072678 -0.00728767 -0.0113641 -0.0113164 0.184964 0.185279 0.0128276 0.0115597 0.00191553 0.00210248 0.016694 0.0174635 0.00757401 0.00706891 -0.00187512 -0.00156986 0.0353357 -0.00327774 -1.1842e-05 -1.13734e-05 -5.99422e-05 -6.03508e-05 2.11445e-06 3.30266e-06 0 0 -0.00136202 -0.00136653 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.84784e-06 8.0449e-06 4.1123e-05 3.54316e-05 4.11153e-05 3.54216e-05 0.000219478 0.000221868 0.0403274 0.0394167 0.0403283 0.039417 0.0100875 0.00996042 0.0462217 0.0466 0.0462218 0.0465999 0.0654636 0.0653169 1.06091e-09 5.88184e-10 1.06142e-09 5.8824e-10 4.06595e-09 3.50501e-09 0 0 6.30463e-08 5.81413e-08 0 0 0 0 0 0 0 0
143 14085000 0.98259 0.982534 -0.00725728 -0.00727986 -0.0112979 -0.0112487 0.185304 0.185599 0.0101097 0.00875627 -0.00242113 -0.00230022 0.0185164 0.0193418 0.00880965 0.00817373 -0.00192185 -0.0016006 0.0338492 -0.00471228 -1.18652e-05 -1.13949e-05 -5.99218e-05 -6.03319e-05 9.83529e-07 2.27379e-06 0 0 -0.00136157 -0.00136619 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.80495e-06 7.98345e-06 4.30222e-05 3.67737e-05 4.30152e-05 3.67643e-05 0.000218208 0.000220104 0.0451243 0.0438513 0.0451248 0.0438511 0.0099574 0.00981993 0.053142 0.0535389 0.0531423 0.0535388 0.0652436 0.0650883 1.06096e-09 5.88242e-10 1.06148e-09 5.88306e-10 3.95929e-09 3.40713e-09 0 0 6.29553e-08 5.80682e-08 0 0 0 0 0 0 0 0
144 14185000 0.982546 0.982495 -0.00723829 -0.0072673 -0.0112358 -0.011192 0.185537 0.185811 0.00787104 0.00671554 -0.00100823 -0.00102542 0.0174774 0.0183484 0.00815018 0.00767645 -0.00140294 -0.001143 0.0316187 -0.00691233 -1.19677e-05 -1.14697e-05 -5.99492e-05 -6.03377e-05 2.24132e-07 1.6042e-06 0 0 -0.00136064 -0.0013654 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.76004e-06 7.92105e-06 3.78434e-05 3.19611e-05 3.78356e-05 3.1951e-05 0.000216924 0.000218348 0.0388482 0.0375681 0.0388485 0.037568 0.00968046 0.00953698 0.0461826 0.0464496 0.0461828 0.0464496 0.064318 0.0641634 9.61338e-10 5.23671e-10 9.61784e-10 5.23695e-10 3.85548e-09 3.31242e-09 0 0 6.27542e-08 5.79106e-08 0 0 0 0 0 0 0 0
145 14285000 0.98254 0.982492 -0.00716278 -0.00719466 -0.0112253 -0.0111799 0.185577 0.185831 0.00887987 0.00764412 -0.001494 -0.00159218 0.016328 0.0172242 0.00885494 0.00826083 -0.00158745 -0.00133331 0.0353256 -0.00317873 -1.19686e-05 -1.14696e-05 -5.99479e-05 -6.03376e-05 1.76348e-07 1.60184e-06 0 0 -0.00136094 -0.00136567 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.71762e-06 7.86162e-06 3.958e-05 3.31607e-05 3.95722e-05 3.31505e-05 0.000215622 0.000216599 0.0433863 0.041699 0.0433867 0.0416989 0.00959185 0.00943732 0.0529943 0.0532334 0.0529946 0.0532333 0.0640785 0.0639136 9.61396e-10 5.23731e-10 9.61848e-10 5.23764e-10 3.75445e-09 3.22081e-09 0 0 6.26614e-08 5.78365e-08 0 0 0 0 0 0 0 0
146 14385000 0.982544 0.9825 -0.00724114 -0.00727409 -0.0111723 -0.011132 0.185551 0.185785 0.00967303 0.00860828 -0.00412453 -0.0042727 0.0163774 0.017282 0.00842342 0.00797527 -0.00275743 -0.00253974 0.0388941 0.000386501 -1.18693e-05 -1.13879e-05 -6.00415e-05 -6.04e-05 3.9593e-07 1.85234e-06 0 0 -0.0013611 -0.00136577 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.67387e-06 7.80195e-06 3.49572e-05 2.89785e-05 3.49487e-05 2.89679e-05 0.0002143 0.000214853 0.0374551 0.0358666 0.0374554 0.0358665 0.00936514 0.00920448 0.046101 0.0462685 0.0461012 0.0462685 0.0631828 0.0630176 8.74685e-10 4.69641e-10 8.75074e-10 4.69643e-10 3.65607e-09 3.13207e-09 0 0 6.24357e-08 5.76592e-08 0 0 0 0 0 0 0 0
147 14485000 0.982516 0.982475 -0.00734339 -0.00737905 -0.0111373 -0.0110956 0.185702 0.185916 0.00767621 0.006541 -0.0039139 -0.00414824 0.0201286 0.0210741 0.00921442 0.00865567 -0.00316907 -0.00297017 0.0411611 0.00269828 -1.18825e-05 -1.14e-05 -6.00293e-05 -6.03893e-05 -2.58795e-07 1.27164e-06 0 0 -0.00136118 -0.00136588 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.62459e-06 7.73717e-06 3.65519e-05 3.00577e-05 3.65444e-05 3.00479e-05 0.000212979 0.000213129 0.0417142 0.0396882 0.0417144 0.039688 0.00931397 0.00914182 0.0527991 0.0528986 0.0527993 0.0528986 0.0629361 0.0627591 8.74746e-10 4.69704e-10 8.75141e-10 4.69714e-10 3.56049e-09 3.04632e-09 0 0 6.23381e-08 5.75817e-08 0 0 0 0 0 0 0 0
148 14585000 0.982501 0.982463 -0.00741219 -0.00745025 -0.0109908 -0.0109614 0.185787 0.185984 0.00601251 0.00516354 -0.00366664 -0.00393615 0.0187514 0.0197354 0.00598216 0.00558502 -0.00385817 -0.00367724 0.0390051 0.000582037 -1.19377e-05 -1.14425e-05 -6.03504e-05 -6.06217e-05 -4.69432e-07 1.1049e-06 0 0 -0.00136048 -0.00136526 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.65354e-06 7.75221e-06 3.24192e-05 2.641e-05 3.24112e-05 2.63999e-05 0.000213727 0.000213492 0.0361161 0.0342699 0.0361165 0.0342699 0.00921705 0.00903711 0.0459865 0.0460642 0.0459867 0.0460641 0.0630659 0.062882 7.989e-10 4.24066e-10 7.99238e-10 4.24049e-10 3.49054e-09 2.98381e-09 0 0 6.21116e-08 5.74039e-08 0 0 0 0 0 0 0 0
149 14685000 0.982518 0.982484 -0.00738582 -0.00742662 -0.0110455 -0.0110153 0.185695 0.185873 0.00533071 0.00443654 -0.00370474 -0.00406599 0.0184986 0.0195111 0.00654105 0.00605742 -0.0042086 -0.00405932 0.0394784 0.00109254 -1.19341e-05 -1.14382e-05 -6.03541e-05 -6.06256e-05 -2.82455e-07 1.31776e-06 0 0 -0.00136024 -0.00136502 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.60352e-06 7.68784e-06 3.38908e-05 2.73881e-05 3.38826e-05 2.73777e-05 0.000212359 0.000211758 0.040157 0.0378471 0.0401573 0.0378471 0.00919834 0.00900644 0.0525686 0.0525434 0.0525688 0.0525433 0.0628149 0.0626171 7.98963e-10 4.24132e-10 7.99307e-10 4.24121e-10 3.39953e-09 2.90285e-09 0 0 6.20083e-08 5.73221e-08 0 0 0 0 0 0 0 0
150 14785000 0.982553 0.982523 -0.00737772 -0.0074363 -0.0110302 -0.011003 0.185507 0.185667 0.00684806 0.00612978 0.00241525 0.0017268 0.018237 0.0192478 0.0053319 0.00497149 0.000791459 0.000855876 0.0414323 0.00303924 -1.24154e-05 -1.17957e-05 -6.02882e-05 -6.05699e-05 1.31938e-07 1.73796e-06 0 0 -0.00136052 -0.00136521 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.5494e-06 7.62039e-06 3.01819e-05 2.41901e-05 3.01734e-05 2.41795e-05 0.000210983 0.000210035 0.0348704 0.0328033 0.0348708 0.0328035 0.00904974 0.00885185 0.045846 0.0458415 0.0458461 0.0458414 0.0619784 0.0617784 7.32157e-10 3.8528e-10 7.32455e-10 3.8525e-10 3.311e-09 2.82442e-09 0 0 6.17219e-08 5.70954e-08 0 0 0 0 0 0 0 0
151 14885000 0.982588 0.982561 -0.00730447 -0.00736643 -0.0109547 -0.0109267 0.18533 0.185471 0.00547946 0.0047289 0.000381319 -0.000437415 0.0218105 0.0228422 0.00593623 0.00550307 0.000935021 0.000923821 0.042366 0.00400495 -1.24063e-05 -1.17863e-05 -6.02967e-05 -6.05784e-05 5.83396e-07 2.19713e-06 0 0 -0.00136031 -0.00136497 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.49823e-06 7.55635e-06 3.15445e-05 2.50812e-05 3.15363e-05 2.50708e-05 0.000209604 0.000208329 0.0386857 0.036138 0.038686 0.0361381 0.00906121 0.00885113 0.0523124 0.0521741 0.0523125 0.0521741 0.06174 0.0615247 7.32222e-10 3.85347e-10 7.32526e-10 3.85325e-10 3.22506e-09 2.74863e-09 0 0 6.1609e-08 5.7006e-08 0 0 0 0 0 0 0 0
152 14985000 0.982591 0.982568 -0.00743426 -0.00749384 -0.0108444 -0.0108234 0.185316 0.185439 0.00482569 0.00425314 -0.00107573 -0.00183183 0.02458 0.0256349 0.0047552 0.00444014 -0.000564214 -0.000524721 0.04376 0.00541783 -1.23226e-05 -1.17284e-05 -6.04545e-05 -6.06869e-05 7.76036e-07 2.41416e-06 0 0 -0.00135956 -0.00136426 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.45211e-06 7.49826e-06 2.82052e-05 2.22655e-05 2.81967e-05 2.22549e-05 0.000208209 0.000206625 0.0336803 0.0314258 0.0336806 0.0314259 0.00894489 0.00872912 0.0456855 0.0456049 0.0456856 0.0456049 0.0609512 0.0607329 6.73064e-10 3.52035e-10 6.73316e-10 3.51987e-10 3.14148e-09 2.6752e-09 0 0 6.12871e-08 5.67501e-08 0 0 0 0 0 0 0 0
153 15085000 0.982588 0.982568 -0.00737588 -0.00743863 -0.0109291 -0.0109076 0.185329 0.185434 0.00480158 0.0042095 -0.000329579 -0.00121389 0.028448 0.0295324 0.00524649 0.0048743 -0.000667472 -0.000710392 0.0461898 0.00788977 -1.23241e-05 -1.17292e-05 -6.04531e-05 -6.0686e-05 6.98739e-07 2.37085e-06 0 0 -0.00135952 -0.00136421 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.40274e-06 7.43719e-06 2.94729e-05 2.30836e-05 2.94639e-05 2.3072e-05 0.000206819 0.000204945 0.037303 0.0345542 0.0373033 0.0345545 0.00898291 0.00875482 0.0520366 0.0517946 0.0520367 0.0517946 0.060733 0.0604977 6.7313e-10 3.52109e-10 6.73389e-10 3.52059e-10 3.06037e-09 2.60423e-09 0 0 6.1162e-08 5.66511e-08 0 0 0 0 0 0 0 0
154 15185000 0.982581 0.982564 -0.00750359 -0.00756807 -0.010984 -0.0109678 0.185359 0.185445 0.00338397 0.00295161 -0.00132198 -0.002225 0.0288288 0.0299425 0.00419679 0.00393041 -0.000644514 -0.000659958 0.0467623 0.00848918 -1.23632e-05 -1.17633e-05 -6.05315e-05 -6.07348e-05 5.54586e-07 2.26708e-06 0 0 -0.00135881 -0.00136356 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.35169e-06 7.37533e-06 2.64555e-05 2.05939e-05 2.64458e-05 2.05816e-05 0.000205423 0.000203276 0.03258 0.0301615 0.0325802 0.0301617 0.00889347 0.00866014 0.0455098 0.0453578 0.0455099 0.0453578 0.0599929 0.059754 6.20434e-10 3.23324e-10 6.20656e-10 3.23255e-10 2.98153e-09 2.53546e-09 0 0 6.08019e-08 5.63634e-08 0 0 0 0 0 0 0 0
155 15285000 0.982598 0.982584 -0.007603 -0.00767068 -0.0110131 -0.0109967 0.185263 0.185335 0.00322842 0.00279093 -0.00197282 -0.00301207 0.0286288 0.029777 0.00454534 0.00423772 -0.00076312 -0.000876242 0.0465829 0.00837272 -1.23568e-05 -1.17563e-05 -6.05404e-05 -6.07427e-05 9.43412e-07 2.65206e-06 0 0 -0.0013582 -0.00136297 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.37418e-06 7.38641e-06 2.76385e-05 2.13484e-05 2.76286e-05 2.13359e-05 0.000205961 0.000203514 0.0360404 0.0331157 0.0360406 0.033116 0.00902913 0.00878135 0.0517497 0.0514111 0.0517499 0.0514112 0.0607081 0.060443 6.20517e-10 3.23406e-10 6.20729e-10 3.23334e-10 2.92391e-09 2.48538e-09 0 0 6.07004e-08 5.62833e-08 0 0 0 0 0 0 0 0
156 15385000 0.982564 0.982553 -0.00767519 -0.00774479 -0.0110278 -0.0110156 0.18544 0.185493 0.0041973 0.00388828 0.000429746 -0.00062891 0.028267 0.0294587 0.00369142 0.0034667 -0.000496814 -0.000573198 0.0458167 0.00765081 -1.24151e-05 -1.1807e-05 -6.05896e-05 -6.07708e-05 5.99532e-07 2.36235e-06 0 0 -0.00135701 -0.00136189 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.32842e-06 7.33088e-06 2.48984e-05 1.91348e-05 2.48875e-05 1.91218e-05 0.000204532 0.000201839 0.0315666 0.0290033 0.031567 0.0290037 0.00895922 0.00870676 0.0453238 0.0451041 0.045324 0.0451041 0.0599957 0.0597264 5.73301e-10 2.98337e-10 5.73469e-10 2.9825e-10 2.84898e-09 2.42041e-09 0 0 6.03001e-08 5.59621e-08 0 0 0 0 0 0 0 0
157 15485000 0.982558 0.982551 -0.00771345 -0.00778621 -0.0109882 -0.0109757 0.18547 0.185507 0.00319801 0.00289084 -0.00190311 -0.00310432 0.0282736 0.0294993 0.00405039 0.00379556 -0.000534119 -0.000723415 0.0467003 0.00858653 -1.2414e-05 -1.18054e-05 -6.05915e-05 -6.07727e-05 6.72846e-07 2.45471e-06 0 0 -0.0013566 -0.0013615 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.28266e-06 7.27566e-06 2.60052e-05 1.98339e-05 2.59942e-05 1.98208e-05 0.000203109 0.000200187 0.0348699 0.031793 0.0348703 0.0317934 0.00903991 0.00877516 0.0514569 0.0510273 0.0514571 0.0510274 0.0598289 0.0595392 5.73379e-10 2.98414e-10 5.73536e-10 2.98325e-10 2.77629e-09 2.35758e-09 0 0 6.01469e-08 5.58401e-08 0 0 0 0 0 0 0 0
158 15585000 0.982556 0.982552 -0.00780447 -0.00786264 -0.010984 -0.0109685 0.185478 0.185499 0.00652792 0.00612597 -0.00443956 -0.00532971 0.0278513 0.0291018 0.00594491 0.00567826 -0.00417758 -0.00419101 0.0456801 0.00759392 -1.20737e-05 -1.15763e-05 -6.05626e-05 -6.0749e-05 8.94817e-07 2.68688e-06 0 0 -0.00135545 -0.00136041 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.23792e-06 7.22218e-06 2.35053e-05 1.78562e-05 2.34935e-05 1.78427e-05 0.000201683 0.000198546 0.0306238 0.0279337 0.0306242 0.0279341 0.00898777 0.00871907 0.0451313 0.0448465 0.0451315 0.0448466 0.0591663 0.058872 5.30838e-10 2.76419e-10 5.30962e-10 2.7632e-10 2.70567e-09 2.2967e-09 0 0 5.97042e-08 5.54832e-08 0 0 0 0 0 0 0 0
159 15685000 0.982584 0.982582 -0.00777016 -0.00783096 -0.0109755 -0.0109596 0.185334 0.185342 0.00822915 0.00781993 -0.00758044 -0.0085919 0.0282308 0.0295079 0.00667003 0.00636429 -0.00478073 -0.0048897 0.0467808 0.00874069 -1.20683e-05 -1.15705e-05 -6.05694e-05 -6.07552e-05 1.20948e-06 2.99628e-06 0 0 -0.00135505 -0.00136001 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.18459e-06 7.16051e-06 2.45443e-05 1.85076e-05 2.4532e-05 1.84937e-05 0.000200267 0.00019693 0.0337828 0.0305745 0.0337832 0.0305749 0.00908448 0.00880377 0.0511616 0.0506455 0.0511619 0.0506457 0.0590292 0.0587134 5.30917e-10 2.76498e-10 5.31032e-10 2.76397e-10 2.63708e-09 2.23776e-09 0 0 5.95316e-08 5.53451e-08 0 0 0 0 0 0 0 0
160 15785000 0.982618 -0.0077929 -0.00785935 -0.0108818 -0.0108717 0.185155 0.185152 0.00544488 0.00521887 -0.00772272 -0.00883379 0.0276048 0.0288952 0.0052636 0.00506582 -0.0038577 -0.00397044 0.0479756 0.00995316 -1.22018e-05 -1.16693e-05 -6.0652e-05 -6.08097e-05 1.68243e-06 3.45287e-06 0 0 -0.00135419 -0.00135917 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.13209e-06 7.10035e-06 2.22542e-05 1.67327e-05 2.22417e-05 1.6719e-05 0.000198856 0.000195332 0.0297481 0.0269469 0.0297484 0.0269472 0.00904592 0.00876214 0.0449351 0.0445873 0.0449353 0.0445874 0.0584149 0.0580945 4.92412e-10 2.5707e-10 4.92501e-10 2.56963e-10 2.57053e-09 2.18068e-09 0 0 5.90451e-08 5.4951e-08 0 0 0 0 0 0 0 0
161 15885000 0.982587 0.98259 -0.00783795 -0.00790708 -0.0109289 -0.0109185 0.185318 0.185299 0.00406606 0.00384406 -0.00570848 -0.00695127 0.0287368 0.0300838 0.00567068 0.00545061 -0.00453237 -0.00476189 0.0480341 0.0101069 -1.22084e-05 -1.16755e-05 -6.06451e-05 -6.08035e-05 1.3294e-06 3.14026e-06 0 0 -0.00135353 -0.00135857 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.15043e-06 7.10931e-06 2.32321e-05 1.73427e-05 2.32191e-05 1.73285e-05 0.000199258 0.000195493 0.032773 0.0294517 0.0327734 0.0294522 0.0092281 0.00893004 0.0508672 0.0502679 0.0508674 0.0502681 0.0591824 0.0588291 4.92496e-10 2.57154e-10 4.92581e-10 2.57047e-10 2.52193e-09 2.13911e-09 0 0 5.89046e-08 5.48387e-08 0 0 0 0 0 0 0 0
162 15985000 0.982591 0.982597 -0.00766386 -0.00773663 -0.0108872 -0.0108805 0.185303 0.185268 0.00268366 0.00258364 -0.00425408 -0.0055533 0.0252175 0.0266217 0.00460038 0.0044529 -0.0035709 -0.00377369 0.0457692 0.00790911 -1.23089e-05 -1.17555e-05 -6.06792e-05 -6.08223e-05 1.22658e-06 3.06946e-06 0 0 -0.00135133 -0.00135655 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.09512e-06 7.04716e-06 2.11257e-05 1.5743e-05 2.11118e-05 1.57282e-05 0.000197834 0.000193904 0.0289345 0.0260367 0.0289348 0.0260371 0.00919774 0.00889757 0.0447373 0.0443282 0.0447375 0.0443283 0.0585975 0.0582395 4.57496e-10 2.39882e-10 4.57559e-10 2.39771e-10 2.45872e-09 2.08512e-09 0 0 5.83748e-08 5.44075e-08 0 0 0 0 0 0 0 0
163 16085000 0.982592 0.982601 -0.007627 -0.00770252 -0.0108759 -0.010869 0.1853 0.185249 0.00113761 0.00104946 -0.00540286 -0.00684468 0.0237569 0.025202 0.00472703 0.00456951 -0.00407223 -0.00441128 0.0472597 0.00946573 -1.23148e-05 -1.17611e-05 -6.06728e-05 -6.08168e-05 9.03042e-07 2.78297e-06 0 0 -0.00135109 -0.00135633 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 7.0361e-06 6.9816e-06 2.20473e-05 1.63157e-05 2.2033e-05 1.63006e-05 0.000196418 0.000192335 0.0318493 0.0284292 0.0318496 0.0284296 0.00931958 0.00900821 0.0505762 0.0498968 0.0505765 0.049897 0.0585333 0.0581513 4.57575e-10 2.39963e-10 4.57634e-10 2.39851e-10 2.39735e-09 2.03284e-09 0 0 5.81633e-08 5.42369e-08 0 0 0 0 0 0 0 0
164 16185000 0.982578 0.98259 -0.00755065 -0.00763025 -0.0108001 -0.0107998 0.185383 0.185314 -0.0022377 -0.00213035 -0.00372685 -0.00521652 0.0226045 0.0241063 0.00260748 0.00254975 -0.00316257 -0.0034618 0.04408 0.00635544 -1.2443e-05 -1.18616e-05 -6.07586e-05 -6.08692e-05 5.30425e-07 2.45859e-06 0 0 -0.00134926 -0.00135464 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.98197e-06 6.9214e-06 2.01009e-05 1.48665e-05 2.00862e-05 1.48513e-05 0.000195006 0.00019078 0.0281771 0.0251965 0.0281773 0.0251968 0.00929578 0.00898336 0.0445399 0.0440708 0.0445401 0.0440709 0.0579934 0.057607 4.25626e-10 2.24507e-10 4.25667e-10 2.24393e-10 2.3378e-09 1.98218e-09 0 0 5.75891e-08 5.37674e-08 0 0 0 0 0 0 0 0
165 16285000 0.982573 0.982588 -0.00760165 -0.00768414 -0.0107312 -0.010731 0.185412 0.185331 -0.00189515 -0.00175851 -0.0051716 -0.00681566 0.0221437 0.0236737 0.00238157 0.00233651 -0.00362146 -0.00407741 0.045434 0.00776514 -1.24415e-05 -1.186e-05 -6.07605e-05 -6.08709e-05 6.15853e-07 2.5471e-06 0 0 -0.00134903 -0.0013544 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.93665e-06 6.87008e-06 2.09711e-05 1.54064e-05 2.09566e-05 1.53914e-05 0.000193591 0.000189235 0.0309793 0.0274785 0.0309796 0.0274789 0.00942591 0.0091029 0.0502898 0.0495327 0.05029 0.0495329 0.0579683 0.0575572 4.25706e-10 2.24589e-10 4.25743e-10 2.24475e-10 2.27998e-09 1.93311e-09 0 0 5.73543e-08 5.3577e-08 0 0 0 0 0 0 0 0
166 16385000 0.982584 0.9826 -0.00755745 -0.0076408 -0.0107217 -0.0107165 0.185358 0.185266 0.000173118 0.000200093 -0.00445104 -0.00611674 0.0227469 0.0242903 0.00328933 0.00318851 -0.00288182 -0.0032756 0.0453288 0.00768354 -1.24612e-05 -1.18846e-05 -6.06577e-05 -6.08004e-05 9.0641e-07 2.82767e-06 0 0 -0.001348 -0.00135339 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.89e-06 6.81798e-06 1.91666e-05 1.40884e-05 1.91519e-05 1.40734e-05 0.000192187 0.000187709 0.0274656 0.0244166 0.027466 0.0244169 0.00940562 0.00908272 0.044344 0.0438161 0.0443442 0.0438163 0.0574703 0.0570553 3.96456e-10 2.10683e-10 3.9648e-10 2.10569e-10 2.22387e-09 1.88555e-09 0 0 5.67366e-08 5.30695e-08 0 0 0 0 0 0 0 0
167 16485000 0.98258 0.982599 -0.00765914 -0.00774536 -0.0107054 -0.0107 0.185374 0.185269 0.00254609 0.00259175 -0.00590495 -0.00773317 0.0246019 0.0261664 0.00342124 0.00332312 -0.00346512 -0.00403335 0.0487125 0.0111158 -1.24634e-05 -1.18866e-05 -6.06551e-05 -6.07983e-05 7.80539e-07 2.71723e-06 0 0 -0.00134828 -0.00135362 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.83862e-06 6.76144e-06 1.99901e-05 1.45995e-05 1.99754e-05 1.45846e-05 0.000190795 0.000186206 0.0301618 0.0265966 0.0301623 0.0265971 0.00954151 0.00920874 0.0500087 0.0491765 0.050009 0.0491767 0.0574835 0.0570435 3.96538e-10 2.10765e-10 3.96558e-10 2.10652e-10 2.16939e-09 1.83947e-09 0 0 5.64774e-08 5.28582e-08 0 0 0 0 0 0 0 0
168 16585000 0.982577 0.982599 -0.00765259 -0.00774129 -0.0107133 -0.0107096 0.18539 0.185272 0.00661121 0.00672359 -0.00672373 -0.00857831 0.0280183 0.029609 0.0030615 0.00299941 -0.0028056 -0.00330525 0.0493777 0.0118373 -1.25441e-05 -1.19542e-05 -6.06586e-05 -6.07965e-05 7.15049e-07 2.6656e-06 0 0 -0.00134748 -0.00135284 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.84824e-06 6.76387e-06 1.83117e-05 1.33961e-05 1.82968e-05 1.33811e-05 0.000191079 0.000186305 0.0267906 0.0236879 0.0267911 0.0236885 0.00959242 0.00925778 0.0441503 0.0435649 0.0441505 0.0435651 0.0578483 0.0573924 3.69688e-10 1.98191e-10 3.697e-10 1.98078e-10 2.12958e-09 1.80583e-09 0 0 5.5887e-08 5.23708e-08 0 0 0 0 0 0 0 0
169 16685000 0.982589 0.982612 -0.00771091 -0.00780256 -0.0106479 -0.0106442 0.185328 0.1852 0.00780197 0.00794088 -0.0104894 -0.0125166 0.0282909 0.0299078 0.0037813 0.00373283 -0.00364539 -0.00433935 0.0507336 0.013249 -1.25406e-05 -1.19506e-05 -6.06627e-05 -6.08001e-05 9.1268e-07 2.85479e-06 0 0 -0.00134706 -0.00135242 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.79933e-06 6.71036e-06 1.90917e-05 1.3881e-05 1.90769e-05 1.38662e-05 0.000189679 0.00018481 0.0293951 0.0257808 0.0293957 0.0257814 0.00973292 0.00938911 0.0497335 0.0488285 0.0497338 0.0488287 0.0578997 0.0574179 3.6977e-10 1.98274e-10 3.69779e-10 1.98162e-10 2.07785e-09 1.76218e-09 0 0 5.56074e-08 5.21417e-08 0 0 0 0 0 0 0 0
170 16785000 0.982609 0.982634 -0.00757639 -0.00767315 -0.0105521 -0.0105525 0.185234 0.185093 0.00928912 0.00956769 -0.0104852 -0.0125917 0.0270243 0.0286709 0.00311503 0.00313563 -0.00288148 -0.00352441 0.0498458 0.012407 -1.26726e-05 -1.20518e-05 -6.07014e-05 -6.08224e-05 1.03215e-06 2.97681e-06 0 0 -0.00134544 -0.00135087 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.74583e-06 6.6528e-06 1.75247e-05 1.27769e-05 1.75099e-05 1.27622e-05 0.000188295 0.000183338 0.0261714 0.0230248 0.026172 0.0230255 0.00971056 0.00936937 0.0439598 0.0433182 0.04396 0.0433183 0.0574619 0.0569781 3.45058e-10 1.8684e-10 3.45058e-10 1.86728e-10 2.02764e-09 1.71986e-09 0 0 5.49082e-08 5.15619e-08 0 0 0 0 0 0 0 0
171 16885000 0.98265 0.982677 -0.00754548 -0.00764536 -0.0106448 -0.0106454 0.185013 0.184864 0.00805512 0.00837476 -0.0105669 -0.012859 0.0282606 0.0299418 0.00397556 0.00402866 -0.00391738 -0.00478066 0.0489862 0.0116157 -1.26654e-05 -1.20446e-05 -6.07097e-05 -6.08296e-05 1.43598e-06 3.35743e-06 0 0 -0.0013443 -0.00134978 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.69155e-06 6.59467e-06 1.82653e-05 1.32391e-05 1.82497e-05 1.32237e-05 0.000186921 0.000181885 0.0286853 0.0250342 0.028686 0.0250349 0.00985229 0.00950289 0.0494661 0.0484908 0.0494664 0.048491 0.0575487 0.0570393 3.45141e-10 1.86924e-10 3.45139e-10 1.86814e-10 1.97888e-09 1.67883e-09 0 0 5.46035e-08 5.1311e-08 0 0 0 0 0 0 0 0
172 16985000 0.982649 0.982678 -0.00757604 -0.00767889 -0.0106596 -0.0106568 0.185014 0.184853 0.00786908 0.00811294 -0.0108872 -0.0132338 0.0283658 0.030068 0.00361479 0.00361066 -0.00314265 -0.00392959 0.0479709 0.0106372 -1.27508e-05 -1.21185e-05 -6.06484e-05 -6.07914e-05 1.51958e-06 3.44444e-06 0 0 -0.00134293 -0.00134845 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.64457e-06 6.54407e-06 1.6798e-05 1.22223e-05 1.67826e-05 1.22072e-05 0.000185547 0.000180439 0.0255836 0.022407 0.0255842 0.0224075 0.00982529 0.00947987 0.043773 0.0430766 0.0437732 0.0430767 0.0571371 0.0566272 3.22344e-10 1.76478e-10 3.22336e-10 1.7637e-10 1.93152e-09 1.639e-09 0 0 5.38656e-08 5.06961e-08 0 0 0 0 0 0 0 0
173 17085000 0.98264 0.982672 -0.00767854 -0.00778453 -0.0105922 -0.0105893 0.185059 0.184885 0.0087498 0.00902732 -0.0134013 -0.0159451 0.0285204 0.0302698 0.00445017 0.0044732 -0.00437343 -0.00540434 0.0477499 0.0105004 -1.27532e-05 -1.21206e-05 -6.06465e-05 -6.07896e-05 1.4082e-06 3.35041e-06 0 0 -0.00134193 -0.00134751 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.59647e-06 6.49256e-06 1.75006e-05 1.26627e-05 1.74855e-05 1.26479e-05 0.000184189 0.000179017 0.02802 0.0243458 0.0280207 0.0243464 0.00996632 0.00961367 0.049206 0.048163 0.0492063 0.0481633 0.0572565 0.0567214 3.22428e-10 1.76563e-10 3.22419e-10 1.76456e-10 1.88556e-09 1.60041e-09 0 0 5.35361e-08 5.04233e-08 0 0 0 0 0 0 0 0
174 17185000 0.982595 0.98263 -0.00776432 -0.0078637 -0.0105028 -0.0105036 0.1853 0.185111 0.00824264 0.00859074 -0.0176217 -0.0199211 0.0296571 0.0314322 0.0029245 0.00297284 -0.00762189 -0.00840549 0.0503905 0.0132046 -1.27113e-05 -1.21109e-05 -6.07217e-05 -6.08393e-05 1.00403e-06 2.98425e-06 0 0 -0.00134137 -0.00134694 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.61016e-06 6.50024e-06 1.61221e-05 1.17221e-05 1.61075e-05 1.17078e-05 0.000184391 0.000179072 0.0250331 0.0218379 0.0250337 0.0218384 0.0100086 0.0096574 0.0435903 0.0428408 0.0435905 0.0428409 0.0576971 0.0571474 3.01362e-10 1.66982e-10 3.01348e-10 1.66876e-10 1.85198e-09 1.57223e-09 0 0 5.28526e-08 5.0002e-08 0 0 0 0 0 0 0 0
175 17285000 0.982565 0.982603 -0.00771931 -0.00782164 -0.0104983 -0.0104991 0.185462 0.185258 0.00863591 0.0090231 -0.0182558 -0.0207427 0.0291315 0.030956 0.00375276 0.00383807 -0.00938531 -0.0104072 0.0508785 0.0137834 -1.27189e-05 -1.2118e-05 -6.07144e-05 -6.08326e-05 6.12297e-07 2.62943e-06 0 0 -0.00134058 -0.00134619 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.56311e-06 6.45016e-06 1.67902e-05 1.21435e-05 1.67753e-05 1.21289e-05 0.000183032 0.000177661 0.0273961 0.0237119 0.0273968 0.0237125 0.0101487 0.00979124 0.048954 0.0478463 0.0489542 0.0478465 0.0578501 0.0572754 3.01447e-10 1.67068e-10 3.01431e-10 1.66964e-10 1.80831e-09 1.53563e-09 0 0 5.25036e-08 5.0002e-08 0 0 0 0 0 0 0 0
176 17385000 0.982605 0.982644 -0.00766416 -0.00777791 -0.0104765 -0.0104707 0.185253 0.18504 0.00555052 0.00581229 -0.0191998 -0.0219917 0.0291245 0.030953 0.00508051 0.00508108 -0.00657591 -0.00765642 0.051438 0.014361 -1.29205e-05 -1.22666e-05 -6.0571e-05 -6.07367e-05 9.12368e-07 2.90991e-06 0 0 -0.00133929 -0.00134492 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.50808e-06 6.39264e-06 1.5492e-05 1.12699e-05 1.54773e-05 1.12557e-05 0.000181691 0.000176272 0.0245165 0.0213139 0.0245168 0.0213142 0.0101083 0.00975742 0.0434125 0.0426117 0.0434127 0.0426119 0.0574773 0.0569054 2.81946e-10 1.58239e-10 2.81925e-10 1.58136e-10 1.76588e-09 1.50007e-09 0 0 5.17017e-08 5.0001e-08 0 0 0 0 0 0 0 0
177 17485000 0.982594 0.982635 -0.0076651 -0.00778213 -0.0105293 -0.0105233 0.18531 0.185085 0.00321561 0.00350966 -0.0201827 -0.0231917 0.0285793 0.0304478 0.00545104 0.00548012 -0.00851748 -0.0098874 0.0519005 0.0149038 -1.29235e-05 -1.22694e-05 -6.05684e-05 -6.07342e-05 7.65212e-07 2.77994e-06 0 0 -0.00133848 -0.00134413 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.46083e-06 6.34283e-06 1.61278e-05 1.1674e-05 1.61127e-05 1.16593e-05 0.000180356 0.000174898 0.026809 0.0231274 0.0268093 0.0231277 0.0102444 0.00988861 0.0487098 0.0475408 0.0487101 0.047541 0.0576565 0.0570608 2.82031e-10 1.58326e-10 2.8201e-10 1.58224e-10 1.7247e-09 1.46561e-09 0 0 5.13297e-08 5.0001e-08 0 0 0 0 0 0 0 0
178 17585000 0.982595 0.982638 -0.00763376 -0.00776008 -0.0104557 -0.0104598 0.185311 0.185074 0.00056702 0.00119875 -0.0167464 -0.0199052 0.0275622 0.0294591 0.0022998 0.00251408 -0.00680065 -0.00811492 0.0500065 0.0130625 -1.31518e-05 -1.24392e-05 -6.06732e-05 -6.07977e-05 7.66612e-07 2.78947e-06 0 0 -0.00133656 -0.00134228 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.41354e-06 6.29327e-06 1.49024e-05 1.08598e-05 1.48875e-05 1.08453e-05 0.000179033 0.000173538 0.0240279 0.0208294 0.0240282 0.0208296 0.0101959 0.00984839 0.0432393 0.0423896 0.0432395 0.0423897 0.0573024 0.0567114 2.6396e-10 1.50164e-10 2.63934e-10 1.50064e-10 1.68468e-09 1.43212e-09 0 0 5.05019e-08 5e-08 0 0 0 0 0 0 0 0
179 17685000 0.982622 0.982667 -0.00773153 -0.00786134 -0.0103749 -0.0103791 0.185167 0.18492 -0.000455949 0.000231721 -0.0175221 -0.0209194 0.0288442 0.0307571 0.00232583 0.00260635 -0.00853626 -0.0101783 0.0523348 0.0154416 -1.31507e-05 -1.24381e-05 -6.06744e-05 -6.07987e-05 8.27715e-07 2.84711e-06 0 0 -0.00133638 -0.00134207 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.3589e-06 6.23671e-06 1.55072e-05 1.12471e-05 1.54926e-05 1.12331e-05 0.000177732 0.000172207 0.0262511 0.0225854 0.0262514 0.0225857 0.0103267 0.00997596 0.0484735 0.0472466 0.0484737 0.0472468 0.057504 0.0568905 2.64047e-10 1.50252e-10 2.6402e-10 1.50152e-10 1.64583e-09 1.39965e-09 0 0 5.01084e-08 5e-08 0 0 0 0 0 0 0 0
180 17785000 0.982665 0.982713 -0.0077298 -0.00786612 -0.0103351 -0.0103329 0.184938 0.184681 0.00159701 0.00212826 -0.0161199 -0.0196755 0.0286479 0.0305323 0.00307682 0.00323302 -0.00765746 -0.00923477 0.0559784 0.0190631 -1.32866e-05 -1.25456e-05 -6.05545e-05 -6.07183e-05 9.42782e-07 2.95288e-06 0 0 -0.00133649 -0.00134206 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.29999e-06 6.17628e-06 1.4348e-05 1.04852e-05 1.43338e-05 1.04715e-05 0.000176446 0.000170894 0.0235632 0.0203801 0.0235636 0.0203804 0.0102695 0.00992883 0.0430708 0.0421746 0.0430709 0.0421748 0.0571644 0.0565575 2.47285e-10 1.42682e-10 2.47254e-10 1.42584e-10 1.60806e-09 1.36809e-09 0 0 5e-08 0 0 0 0 0 0 0 0
181 17885000 0.982673 0.982722 -0.00768031 -0.00782035 -0.0104418 -0.0104395 0.184894 0.184629 0.0038321 0.0044084 -0.0186646 -0.022483 0.028136 0.0300247 0.0034048 0.00361553 -0.0094142 -0.0113605 0.0609618 0.0241015 -1.32853e-05 -1.25444e-05 -6.05554e-05 -6.07192e-05 9.97957e-07 3.00169e-06 0 0 -0.00133723 -0.00134271 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.30385e-06 6.17549e-06 1.4925e-05 1.08585e-05 1.49099e-05 1.0844e-05 0.000176586 0.000170924 0.0257292 0.0220898 0.0257297 0.0220902 0.0104742 0.0101282 0.0482447 0.0469639 0.0482449 0.0469641 0.0582194 0.0575736 2.47375e-10 1.42773e-10 2.47344e-10 1.42676e-10 1.58047e-09 1.34505e-09 0 0 5.0002e-08 0 0 0 0 0 0 0 0
182 17985000 0.982681 0.982732 -0.00756031 -0.00771869 -0.0104224 -0.0104186 0.184859 0.184581 0.00296427 0.00359474 -0.0134579 -0.017746 0.0278582 0.029745 0.00279763 0.00301684 -0.00434519 -0.00639336 0.061064 0.0242174 -1.36241e-05 -1.27909e-05 -6.04638e-05 -6.06536e-05 9.68519e-07 2.97936e-06 0 0 -0.00133631 -0.00134177 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.25435e-06 6.12455e-06 1.38263e-05 1.0143e-05 1.38113e-05 1.01287e-05 0.000175296 0.000169616 0.0231232 0.0199657 0.0231237 0.019966 0.0104071 0.0100729 0.042907 0.0419673 0.0429071 0.0419674 0.0578807 0.0572439 2.31811e-10 1.35729e-10 2.31777e-10 1.35633e-10 1.54456e-09 1.31506e-09 0 0 5.0001e-08 0 0 0 0 0 0 0 0
183 18085000 0.982681 0.982735 -0.00764889 -0.00781145 -0.010385 -0.0103812 0.184854 0.184565 0.00314233 0.00382686 -0.0143415 -0.0189327 0.0274841 0.0294072 0.00317561 0.00346191 -0.00576436 -0.0082561 0.0604401 0.023672 -1.36241e-05 -1.27907e-05 -6.04643e-05 -6.0654e-05 9.8789e-07 3.00446e-06 0 0 -0.00133509 -0.00134059 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.20925e-06 6.07796e-06 1.43756e-05 1.05018e-05 1.43608e-05 1.04876e-05 0.000174016 0.000168324 0.0252258 0.0216258 0.0252263 0.0216262 0.0105266 0.0101928 0.0480232 0.0466929 0.0480234 0.0466931 0.0581214 0.0574654 2.31898e-10 1.35817e-10 2.31864e-10 1.35723e-10 1.50968e-09 1.28597e-09 0 0 5.0001e-08 0 0 0 0 0 0 0 0
184 18185000 0.982723 0.982777 -0.00766464 -0.00782793 -0.0104185 -0.0104115 0.184633 0.184337 0.00279857 0.00338476 -0.0129932 -0.0175269 0.0281825 0.030105 0.00363988 0.00383552 -0.00471407 -0.00694635 0.0587499 0.0219986 -1.37066e-05 -1.28695e-05 -6.04027e-05 -6.06095e-05 1.44717e-06 3.43296e-06 0 0 -0.00133318 -0.0013387 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.16147e-06 6.02902e-06 1.33328e-05 9.82788e-06 1.33182e-05 9.81384e-06 0.00017275 0.000167048 0.0226959 0.0195756 0.0226964 0.0195759 0.0104509 0.0101301 0.0427474 0.0417674 0.0427476 0.0417675 0.0577898 0.057145 2.17442e-10 1.29247e-10 2.17407e-10 1.29155e-10 1.47577e-09 1.25767e-09 0 0 5.0001e-08 0 0 0 0 0 0 0 0
185 18285000 0.982721 0.982778 -0.00770429 -0.00787179 -0.0103918 -0.0103846 0.184639 0.184331 0.00358057 0.00421654 -0.0140812 -0.0189288 0.0274469 0.0294063 0.00389815 0.00415644 -0.00605376 -0.0087546 0.0577663 0.0210946 -1.3706e-05 -1.28688e-05 -6.04038e-05 -6.06103e-05 1.49633e-06 3.48498e-06 0 0 -0.00133178 -0.00133735 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.11849e-06 5.98483e-06 1.38568e-05 1.01738e-05 1.38421e-05 1.01598e-05 0.000171492 0.000165785 0.0247419 0.0211929 0.0247425 0.0211932 0.0105625 0.0102438 0.0478075 0.0464324 0.0478077 0.0464326 0.0580358 0.0573742 2.1753e-10 1.29336e-10 2.17495e-10 1.29246e-10 1.4428e-09 1.23019e-09 0 0 5e-08 0 0 0 0 0 0 0 0
186 18385000 0.982702 0.982761 -0.00762774 -0.00779468 -0.0103975 -0.0103839 0.184746 0.184425 0.00379595 0.00422517 -0.012978 -0.0177422 0.0272244 0.029184 0.0053139 0.00541409 -0.00498142 -0.0073954 0.0573674 0.020713 -1.37762e-05 -1.29434e-05 -6.02878e-05 -6.05268e-05 1.3746e-06 3.37959e-06 0 0 -0.00133053 -0.00133608 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.07779e-06 5.94303e-06 1.28656e-05 9.53679e-06 1.28511e-05 9.52286e-06 0.000170247 0.000164536 0.0222897 0.0192152 0.0222901 0.0192155 0.0104785 0.0101739 0.0425917 0.0415748 0.0425918 0.0415749 0.057708 0.0570598 2.04099e-10 1.23194e-10 2.04063e-10 1.23106e-10 1.41077e-09 1.20348e-09 0 0 5e-08 0 0 0 0 0 0 0 0
187 18485000 0.982709 0.98277 -0.00766568 -0.00783682 -0.0104105 -0.0103965 0.184703 0.184374 0.00663408 0.00710053 -0.0130352 -0.018125 0.0269218 0.028894 0.00591875 0.00606394 -0.00628916 -0.00919619 0.0599743 0.0233882 -1.3773e-05 -1.29404e-05 -6.02909e-05 -6.05296e-05 1.54156e-06 3.53312e-06 0 0 -0.00133052 -0.00133603 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.08311e-06 5.94449e-06 1.33659e-05 9.87094e-06 1.33512e-05 9.85683e-06 0.000170343 0.000164546 0.0242829 0.0207937 0.0242835 0.0207942 0.0106688 0.0103635 0.0475984 0.0461834 0.0475986 0.0461836 0.0588183 0.0581362 2.0419e-10 1.23287e-10 2.04154e-10 1.23199e-10 1.38737e-09 1.18398e-09 0 0 5.0002e-08 0 0 0 0 0 0 0 0
188 18585000 0.982686 0.982749 -0.00750534 -0.00767702 -0.0103028 -0.0102923 0.184838 0.184497 0.00562368 0.00619929 -0.0122435 -0.0172238 0.0266036 0.0285636 0.00491616 0.00511675 -0.00523027 -0.0078228 0.0616367 0.0250506 -1.38878e-05 -1.30452e-05 -6.03084e-05 -6.05336e-05 1.42123e-06 3.42644e-06 0 0 -0.00132975 -0.00133519 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 6.04434e-06 5.90483e-06 1.24224e-05 9.26684e-06 1.24079e-05 9.25291e-06 0.000169104 0.00016331 0.0219015 0.0188811 0.021902 0.0188816 0.010576 0.0102855 0.04244 0.0413899 0.0424402 0.0413901 0.0584819 0.0578157 1.91705e-10 1.17532e-10 1.91669e-10 1.17447e-10 1.35687e-09 1.15856e-09 0 0 5.0002e-08 0 0 0 0 0 0 0 0
189 18685000 0.982701 0.982766 -0.00749169 -0.00766759 -0.0102524 -0.0102416 0.184763 0.184412 0.00520073 0.0058235 -0.0116232 -0.0169337 0.025119 0.0271027 0.00546192 0.0057237 -0.00642418 -0.00953098 0.0610443 0.0245221 -1.38861e-05 -1.30436e-05 -6.03105e-05 -6.05353e-05 1.52451e-06 3.5253e-06 0 0 -0.00132858 -0.00133404 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.99875e-06 5.85863e-06 1.28997e-05 9.58932e-06 1.28852e-05 9.57542e-06 0.000167883 0.000162097 0.0238433 0.020423 0.0238439 0.0204235 0.0106755 0.0103896 0.0473949 0.0459452 0.0473952 0.0459454 0.0587454 0.0580673 1.91794e-10 1.17622e-10 1.91759e-10 1.17539e-10 1.32722e-09 1.13385e-09 0 0 5.0001e-08 0 0 0 0 0 0 0 0
190 18785000 0.982704 0.982771 -0.00742789 -0.00760246 -0.0101503 -0.0101386 0.184754 0.184391 0.00412983 0.00470891 -0.0111448 -0.0163077 0.0244318 0.0264372 0.00550724 0.00571567 -0.00539145 -0.00814937 0.0576987 0.02123 -1.39648e-05 -1.31246e-05 -6.02746e-05 -6.05044e-05 1.55189e-06 3.55908e-06 0 0 -0.00132558 -0.00133109 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.9555e-06 5.81488e-06 1.20008e-05 9.01498e-06 1.19868e-05 9.00154e-06 0.000166675 0.000160898 0.0215251 0.0185674 0.0215255 0.0185678 0.0105757 0.010305 0.0422917 0.0412125 0.0422919 0.0412126 0.0584075 0.0577474 1.80187e-10 1.12222e-10 1.80151e-10 1.12141e-10 1.29839e-09 1.10983e-09 0 0 5.0001e-08 0 0 0 0 0 0 0 0
191 18885000 0.982699 0.982769 -0.00738724 -0.00756605 -0.010164 -0.0101521 0.184782 0.184406 0.00315581 0.00378118 -0.0111868 -0.0166837 0.0229298 0.0249813 0.00584382 0.00611418 -0.00656836 -0.00985808 0.0546483 0.0182775 -1.39675e-05 -1.31271e-05 -6.02725e-05 -6.05024e-05 1.43355e-06 3.45661e-06 0 0 -0.00132351 -0.00132909 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.91145e-06 5.7704e-06 1.24571e-05 9.32707e-06 1.24427e-05 9.31336e-06 0.000165481 0.000159715 0.0234158 0.0200737 0.0234163 0.0200741 0.0106687 0.0104034 0.0471962 0.0457172 0.0471965 0.0457174 0.0586712 0.0580021 1.80276e-10 1.12313e-10 1.80242e-10 1.12234e-10 1.27035e-09 1.08647e-09 0 0 5e-08 0 0 0 0 0 0 0 0
192 18985000 0.982679 0.98275 -0.00737064 -0.00754817 -0.0102138 -0.0102036 0.184886 0.1845 0.00180488 0.00247472 -0.0109417 -0.0162719 0.023467 0.025485 0.00489899 0.00517587 -0.00549076 -0.00841016 0.0574893 0.0210879 -1.40567e-05 -1.32158e-05 -6.02749e-05 -6.04971e-05 1.42639e-06 3.44931e-06 0 0 -0.00132319 -0.00132866 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.87553e-06 5.73392e-06 1.16008e-05 8.78044e-06 1.15865e-05 8.76668e-06 0.000164292 0.000158541 0.0211622 0.0182742 0.0211626 0.0182745 0.0105629 0.0103128 0.0421466 0.0410422 0.0421468 0.0410423 0.0583301 0.0576807 1.69486e-10 1.07237e-10 1.69452e-10 1.07161e-10 1.24308e-09 1.06375e-09 0 0 5e-08 0 0 0 0 0 0 0 0
193 19085000 0.982685 0.982758 -0.00744955 -0.0076313 -0.0102228 -0.0102124 0.184852 0.184457 -0.000221638 0.000498986 -0.0114045 -0.0170723 0.0239569 0.0260142 0.00501797 0.00536667 -0.00657033 -0.010039 0.0536318 0.0173198 -1.40547e-05 -1.3214e-05 -6.02774e-05 -6.0499e-05 1.55189e-06 3.56909e-06 0 0 -0.00132087 -0.00132641 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.8351e-06 5.69314e-06 1.20369e-05 9.08246e-06 1.20225e-05 9.06873e-06 0.000163121 0.000157386 0.0230012 0.0197451 0.0230016 0.0197454 0.0106496 0.0104057 0.0470023 0.0454994 0.0470026 0.0454996 0.0585913 0.0579356 1.69577e-10 1.07329e-10 1.69543e-10 1.07254e-10 1.21655e-09 1.04166e-09 0 0 5e-08 0 0 0 0 0 0 0 0
194 19185000 0.982662 0.982738 -0.00734403 -0.00752401 -0.010356 -0.0103459 0.184971 0.184562 -0.00150161 -0.000790137 -0.0109821 -0.01647 0.0239857 0.0260426 0.00420633 0.0045199 -0.00556291 -0.0086444 0.0536503 0.0173802 -1.41402e-05 -1.33021e-05 -6.0256e-05 -6.04768e-05 1.30108e-06 3.34096e-06 0 0 -0.00131991 -0.00132541 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.83771e-06 5.69272e-06 1.12206e-05 8.5609e-06 1.12057e-05 8.54654e-06 0.000163181 0.000157379 0.0208075 0.0179961 0.0208078 0.0179964 0.0106253 0.0103927 0.0420043 0.0408789 0.0420045 0.040879 0.0591063 0.058453 1.59548e-10 1.02556e-10 1.59515e-10 1.02483e-10 1.19715e-09 1.02549e-09 0 0 5.0002e-08 0 0 0 0 0 0 0 0
195 19285000 0.982662 0.982739 -0.00728831 -0.00747246 -0.0103078 -0.0102976 0.184978 0.184559 -0.00263484 -0.00187321 -0.0113048 -0.0171355 0.0243331 0.0264054 0.00403438 0.00442226 -0.00667975 -0.0103266 0.053699 0.0174812 -1.41418e-05 -1.33036e-05 -6.02547e-05 -6.04755e-05 1.22844e-06 3.27402e-06 0 0 -0.00131903 -0.00132451 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.79489e-06 5.64981e-06 1.16375e-05 8.85325e-06 1.16225e-05 8.83886e-06 0.000162022 0.000156241 0.022603 0.0194387 0.0226032 0.0194389 0.0107079 0.0104819 0.0468123 0.0452909 0.0468125 0.0452911 0.0593703 0.0587133 1.59639e-10 1.02648e-10 1.59606e-10 1.02576e-10 1.17186e-09 1.00442e-09 0 0 5.0001e-08 0 0 0 0 0 0 0 0
196 19385000 0.98266 0.98274 -0.00737869 -0.00756348 -0.0101981 -0.0101867 0.184989 0.184558 -0.00260618 -0.00188399 -0.0076929 -0.0134334 0.0260041 0.028066 0.0034523 0.00378078 -0.00445228 -0.00776835 0.0524692 0.0162587 -1.42592e-05 -1.34134e-05 -6.02082e-05 -6.04361e-05 1.10853e-06 3.16584e-06 0 0 -0.00131724 -0.00132269 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.75124e-06 5.60624e-06 1.08573e-05 8.35307e-06 1.08433e-05 8.33953e-06 0.000160878 0.000155119 0.0204628 0.0177335 0.020463 0.0177338 0.010591 0.0103797 0.0418642 0.0407221 0.0418644 0.0407222 0.0590086 0.0583747 1.50314e-10 9.81493e-11 1.50282e-10 9.808e-11 1.14726e-09 9.83924e-10 0 0 5.0001e-08 0 0 0 0 0 0 0 0
197 19485000 0.982618 0.982701 -0.00743404 -0.00762305 -0.0101007 -0.010089 0.185213 0.184769 -0.00356913 -0.00279744 -0.00804589 -0.0141383 0.0252806 0.0273638 0.0031083 0.00351206 -0.0052386 -0.00914509 0.0521863 0.0160372 -1.42642e-05 -1.34181e-05 -6.02036e-05 -6.04319e-05 8.60062e-07 2.93812e-06 0 0 -0.00131614 -0.00132158 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.71794e-06 5.5727e-06 1.12561e-05 8.63625e-06 1.12424e-05 8.62311e-06 0.000159736 0.000154001 0.0222154 0.0191487 0.0222156 0.019149 0.0106684 0.0104639 0.0466253 0.0450912 0.0466256 0.0450913 0.0592659 0.058631 1.50405e-10 9.82416e-11 1.50374e-10 9.81735e-11 1.12332e-09 9.63974e-10 0 0 5.0001e-08 0 0 0 0 0 0 0 0
198 19585000 0.982598 0.982682 -0.00735902 -0.00753983 -0.010206 -0.0101908 0.185319 0.184866 -0.00557738 -0.00498769 -0.0101351 -0.0158447 0.0267258 0.0287848 0.00352987 0.00377249 -0.00548663 -0.00883943 0.0523466 0.0161804 -1.42529e-05 -1.34398e-05 -6.01458e-05 -6.03845e-05 7.94168e-07 2.87632e-06 0 0 -0.00131488 -0.00132024 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.68253e-06 5.53722e-06 1.05119e-05 8.15739e-06 1.04978e-05 8.14389e-06 0.000158608 0.000152899 0.0201311 0.0174879 0.0201312 0.0174881 0.0105471 0.0103567 0.0417262 0.0405716 0.0417264 0.0405718 0.0588923 0.0582817 1.41736e-10 9.40003e-11 1.41705e-10 9.39347e-11 1.1e-09 9.44541e-10 0 0 5e-08 0 0 0 0 0 0 0 0
199 19685000 0.982612 0.982698 -0.00738251 -0.00756738 -0.0102201 -0.0102046 0.18524 0.18478 -0.00698298 -0.0063508 -0.00928341 -0.0153389 0.0259687 0.0280331 0.00293593 0.00324067 -0.00646177 -0.0104026 0.0521804 0.0160513 -1.42501e-05 -1.34373e-05 -6.01488e-05 -6.0387e-05 9.51233e-07 3.01735e-06 0 0 -0.00131379 -0.00131914 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.64258e-06 5.4974e-06 1.08941e-05 8.43244e-06 1.08799e-05 8.41885e-06 0.000157499 0.000151817 0.0218412 0.0188762 0.0218413 0.0188764 0.0106199 0.0104363 0.0464418 0.0449002 0.0464421 0.0449004 0.0591413 0.0585321 1.41828e-10 9.40929e-11 1.41797e-10 9.40285e-11 1.07732e-09 9.25636e-10 0 0 5e-08 0 0 0 0 0 0 0 0
200 19785000 0.9826 0.982688 -0.00745442 -0.00763414 -0.0102161 -0.010194 0.185301 0.18483 -0.00759621 -0.00722471 -0.00749426 -0.0132915 0.0247672 0.0268374 0.0051594 0.00525273 -0.00541513 -0.00889415 0.0491278 0.0130568 -1.42712e-05 -1.348e-05 -6.00304e-05 -6.02949e-05 8.4981e-07 2.9265e-06 0 0 -0.00131135 -0.00131669 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.64487e-06 5.49713e-06 1.01827e-05 7.97216e-06 1.0169e-05 7.95895e-06 0.000157537 0.000151802 0.0198118 0.0172577 0.0198118 0.0172579 0.0105857 0.0104123 0.0415903 0.0404274 0.0415904 0.0404276 0.0596431 0.0590411 1.3377e-10 9.00928e-11 1.33741e-10 9.00304e-11 1.06073e-09 9.11803e-10 0 0 5.0002e-08 0 0 0 0 0 0 0 0
201 19885000 0.982579 0.982668 -0.00746628 -0.00765004 -0.0103058 -0.0102832 0.185411 0.184928 -0.0073906 -0.00699105 -0.00724743 -0.0133903 0.0245093 0.0265972 0.00435778 0.00449053 -0.00611018 -0.010185 0.0479132 0.0118991 -1.4275e-05 -1.34838e-05 -6.00269e-05 -6.02916e-05 6.56827e-07 2.74744e-06 0 0 -0.00130997 -0.00131531 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.60716e-06 5.45962e-06 1.05492e-05 8.23936e-06 1.05351e-05 8.22577e-06 0.000156436 0.000150731 0.0214798 0.0186196 0.0214798 0.0186198 0.0106558 0.0104892 0.0462617 0.0447178 0.0462619 0.044718 0.0598902 0.0592918 1.33862e-10 9.01858e-11 1.33833e-10 9.01245e-11 1.03908e-09 8.93755e-10 0 0 5.0002e-08 0 0 0 0 0 0 0 0
202 19985000 0.982599 0.982691 -0.00748586 -0.00766718 -0.0104323 -0.0104052 0.185294 0.184803 -0.00764407 -0.00741723 -0.00688918 -0.0128516 0.0219643 0.0240394 0.00464823 0.00464149 -0.0041927 -0.00785877 0.0442495 0.0082414 -1.43382e-05 -1.35554e-05 -5.99343e-05 -6.02181e-05 7.30384e-07 2.81504e-06 0 0 -0.00130694 -0.00131227 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.56325e-06 5.41621e-06 9.86975e-06 7.79694e-06 9.8555e-06 7.7832e-06 0.000155352 0.000149678 0.0195018 0.0170397 0.0195019 0.0170398 0.0105283 0.0103743 0.0414564 0.0402894 0.0414565 0.0402895 0.0594922 0.0589199 1.2637e-10 8.64073e-11 1.26342e-10 8.63483e-11 1.01799e-09 8.76165e-10 0 0 5.0001e-08 0 0 0 0 0 0 0 0
203 20085000 0.982611 0.982703 -0.00749516 -0.00768044 -0.0104423 -0.0104147 0.185234 0.184736 -0.00720198 -0.00696038 -0.00966194 -0.0159765 0.0220634 0.0241243 0.00388267 0.00389909 -0.00504681 -0.00932668 0.0474488 0.0114385 -1.43383e-05 -1.35556e-05 -5.99341e-05 -6.02178e-05 7.21927e-07 2.79969e-06 0 0 -0.00130731 -0.00131254 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.52134e-06 5.37478e-06 1.02209e-05 8.05614e-06 1.02066e-05 8.04232e-06 0.000154281 0.00014864 0.0211323 0.0183789 0.0211323 0.018379 0.010595 0.0104475 0.0460846 0.0445435 0.0460847 0.0445436 0.0597291 0.0591622 1.26462e-10 8.65007e-11 1.26435e-10 8.64427e-11 9.97468e-10 8.59043e-10 0 0 5.0001e-08 0 0 0 0 0 0 0 0
204 20185000 0.982594 0.982689 -0.00749104 -0.0076714 -0.010542 -0.0105118 0.185316 0.184808 -0.00621488 -0.00608668 -0.00745913 -0.0134883 0.0228842 0.0249158 0.00497779 0.00490907 -0.00422856 -0.00801048 0.0470485 0.0110124 -1.4376e-05 -1.361e-05 -5.98627e-05 -6.01558e-05 5.19846e-07 2.61025e-06 -7.6708e-11 -5.29974e-11 7.97556e-11 5.64413e-11 -0.00130601 -0.00131117 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.48275e-06 5.33663e-06 9.571e-06 7.62973e-06 9.5565e-06 7.61576e-06 0.000153219 0.00014761 0.0194546 0.0170868 0.0194547 0.017087 0.0104667 0.0103308 0.0413245 0.0401572 0.0413246 0.0401574 0.0593251 0.0587843 1.19495e-10 8.29306e-11 1.19468e-10 8.28746e-11 9.77468e-10 8.42353e-10 4.00001e-06 4.00001e-06 5e-08 0 0 0 0 0 0 0 0
205 20285000 0.982607 0.982703 -0.00748659 -0.00767085 -0.0105704 -0.0105396 0.185246 0.18473 -0.00936041 -0.00922076 -0.00805778 -0.014433 0.023202 0.0252311 0.00423109 0.00417621 -0.00492915 -0.00933079 0.047749 0.0117335 -1.43772e-05 -1.36113e-05 -5.98616e-05 -6.01547e-05 4.61609e-07 2.55069e-06 3.2967e-09 3.52332e-09 -3.42388e-09 -3.74905e-09 -0.0013054 -0.00131051 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.43993e-06 5.29443e-06 9.90804e-06 7.88164e-06 9.89334e-06 7.86751e-06 0.000152175 0.0001466 0.0220847 0.019441 0.0220853 0.0194417 0.010531 0.0104013 0.0459191 0.0443857 0.0459192 0.0443858 0.0595515 0.0590177 1.19588e-10 8.30243e-11 1.19561e-10 8.29693e-11 9.57997e-10 8.26102e-10 4.00002e-06 4.00002e-06 5e-08 0 0 0 0 0 0 0 0
206 20385000 0.982602 0.982699 -0.00742964 -0.00760821 -0.0105603 -0.0105269 0.185275 0.184755 -0.010084 -0.010069 -0.00661706 -0.01263 0.022241 0.0242305 0.00521305 0.00506825 -0.00411811 -0.00799294 0.047216 0.0111595 -1.43976e-05 -1.36513e-05 -5.97939e-05 -6.00959e-05 6.3277e-07 2.7024e-06 -3.22544e-06 -3.88873e-06 -1.37292e-06 -3.10428e-06 -0.00130364 -0.00130867 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.40937e-06 5.26413e-06 9.28914e-06 7.47206e-06 9.2746e-06 7.45806e-06 0.00015113 0.00014559 0.0216937 0.0194579 0.0216949 0.0194593 0.0104035 0.0102843 0.0412081 0.0400464 0.0412083 0.0400465 0.059142 0.058634 1.13133e-10 7.96621e-11 1.13107e-10 7.9609e-11 9.3902e-10 8.10255e-10 3.97883e-06 3.97862e-06 3.97883e-06 3.97862e-06 5e-08 0 0 0 0 0 0 0 0
207 20485000 0.98262 0.982718 -0.00744543 -0.00762779 -0.0105312 -0.0104971 0.185182 0.184653 -0.0144736 -0.0144545 -0.00783378 -0.0141697 0.0228495 0.0248559 0.00396049 0.003818 -0.00481696 -0.00930845 0.0468048 0.0108242 -1.43991e-05 -1.36528e-05 -5.97926e-05 -6.00946e-05 5.63883e-07 2.63541e-06 -3.20875e-06 -3.87099e-06 -1.39009e-06 -3.12253e-06 -0.00130262 -0.00130764 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.40302e-06 5.25597e-06 9.6128e-06 7.71693e-06 9.59826e-06 7.70295e-06 0.000151157 0.000145576 0.025735 0.0232545 0.0257372 0.0232569 0.0105572 0.0104413 0.0458373 0.0443218 0.0458375 0.044322 0.060252 0.0597373 1.13228e-10 7.97576e-11 1.13202e-10 7.97052e-11 9.25131e-10 7.98661e-10 3.97884e-06 3.97863e-06 3.97884e-06 3.97863e-06 5.0002e-08 0 0 0 0 0 0 0 0
208 20585000 0.982655 0.982754 -0.00740911 -0.00758552 -0.010535 -0.0104973 0.184995 0.184464 -0.0137785 -0.0139188 -0.00808877 -0.0139205 0.0225122 0.0244757 0.00503612 0.00477727 -0.00408673 -0.00801774 0.0452012 0.00917312 -1.44054e-05 -1.3681e-05 -5.97112e-05 -6.00259e-05 8.75281e-07 2.91534e-06 -1.25669e-05 -1.47034e-05 -2.63259e-06 -7.79515e-06 -0.00130074 -0.0013057 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.36419e-06 5.21782e-06 9.04217e-06 7.33629e-06 9.02775e-06 7.32242e-06 0.00015013 0.000144586 0.0259118 0.0239058 0.0259149 0.023909 0.0104286 0.0103224 0.0411678 0.0400269 0.041168 0.040027 0.0598254 0.0593367 1.07376e-10 7.6659e-11 1.07352e-10 7.66084e-11 9.06993e-10 7.83508e-10 3.89837e-06 3.89655e-06 3.89838e-06 3.89655e-06 5.0001e-08 0 0 0 0 0 0 0 0
209 20685000 0.982647 0.982748 -0.00733779 -0.0075179 -0.0105285 -0.01049 0.185039 0.184498 -0.0158482 -0.0159908 -0.00730354 -0.0134202 0.0234777 0.0254401 0.00360233 0.00332959 -0.00481659 -0.00934413 0.0455894 0.00958323 -1.44096e-05 -1.36852e-05 -5.97072e-05 -6.00221e-05 6.5739e-07 2.7088e-06 -1.25447e-05 -1.46782e-05 -2.6574e-06 -7.82235e-06 -0.00130003 -0.00130494 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.32469e-06 5.17906e-06 9.35384e-06 7.57484e-06 9.33923e-06 7.56081e-06 0.000149118 0.000143612 0.0311224 0.0289187 0.0311271 0.0289235 0.0104919 0.0103909 0.045951 0.0444797 0.0459512 0.0444799 0.0600373 0.0595582 1.0747e-10 7.67533e-11 1.07446e-10 7.67036e-11 8.89327e-10 7.68744e-10 3.89838e-06 3.89656e-06 3.89839e-06 3.89656e-06 5.0001e-08 0 0 0 0 0 0 0 0
210 20785000 0.982671 0.982773 -0.00686916 -0.00704411 -0.010465 -0.0104252 0.184934 0.184389 -0.0169178 -0.0171202 -0.00426918 -0.00970259 0.011174 0.0130932 0.00296123 0.0026452 -0.00401814 -0.0079356 0.0442285 0.00817562 -1.44273e-05 -1.37206e-05 -5.96557e-05 -5.99752e-05 7.46141e-07 2.78379e-06 -2.50134e-05 -2.92946e-05 -4.13688e-06 -1.40703e-05 -0.00129843 -0.00130326 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.28537e-06 5.14054e-06 8.86095e-06 7.24456e-06 8.8458e-06 7.22998e-06 0.000148118 0.00014265 0.0310559 0.0293852 0.0310612 0.0293907 0.0103646 0.0102722 0.0412805 0.0401886 0.0412807 0.0401888 0.0596068 0.0591529 1.02384e-10 7.40179e-11 1.02361e-10 7.39698e-11 8.72101e-10 7.54342e-10 3.73907e-06 3.73251e-06 3.73907e-06 3.73252e-06 5.0001e-08 0 0 0 0 0 0 0 0
211 20885000 0.982732 0.982836 0.00198829 0.00181178 -0.00678806 -0.00675237 0.184899 0.184347 -0.0232046 -0.0234009 0.00722391 0.00152382 -0.102275 -0.100369 0.000887512 0.000551581 -0.00384167 -0.00831487 0.0386654 0.00261793 -1.44271e-05 -1.37206e-05 -5.96559e-05 -5.99751e-05 7.60796e-07 2.78904e-06 -2.49636e-05 -2.92402e-05 -4.18391e-06 -1.41223e-05 -0.00129773 -0.00130252 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.24823e-06 5.1042e-06 9.15277e-06 7.46836e-06 9.14325e-06 7.45952e-06 0.000147142 0.000141711 0.0372485 0.0354105 0.0372554 0.0354175 0.0104251 0.0103378 0.0463465 0.0449611 0.0463469 0.0449615 0.059803 0.0593597 1.02477e-10 7.41119e-11 1.02455e-10 7.40655e-11 8.55306e-10 7.40297e-10 3.73908e-06 3.73252e-06 3.73908e-06 3.73253e-06 5e-08 0 0 0 0 0 0 0 0
212 20985000 0.982733 0.982838 0.0057307 0.00556368 -0.0030596 -0.00302306 0.184916 0.184361 -0.0320535 -0.0323192 0.0248344 0.0200383 -0.243442 -0.24161 0.000584024 0.000171631 -0.00260979 -0.00633788 0.0253246 -0.0108402 -1.43896e-05 -1.37128e-05 -5.95982e-05 -5.9924e-05 7.33922e-07 2.74991e-06 -4.3257e-05 -5.02151e-05 1.08967e-05 -4.20299e-06 -0.00130087 -0.00130547 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.21394e-06 5.07062e-06 8.75623e-06 7.20186e-06 8.75809e-06 7.20409e-06 0.000146162 0.000140769 0.0362639 0.0349553 0.0362693 0.0349608 0.010296 0.0102165 0.0415982 0.0405908 0.0415985 0.0405912 0.0593696 0.0589506 9.82596e-11 7.18148e-11 9.82401e-11 7.17708e-11 8.38937e-10 7.26601e-10 3.50408e-06 3.48862e-06 3.50408e-06 3.48863e-06 5e-08 0 0 0 0 0 0 0 0
213 21085000 0.982672 0.982779 0.00430308 0.00413235 -0.00330179 -0.00326332 0.185274 0.184712 -0.0453716 -0.0456296 0.04082 0.035827 -0.361117 -0.35929 -0.00328351 -0.00372227 0.000726793 -0.00349066 -0.00403991 -0.0401706 -1.43906e-05 -1.37139e-05 -5.95972e-05 -5.9923e-05 6.83072e-07 2.69529e-06 -4.32807e-05 -5.02347e-05 1.09179e-05 -4.18573e-06 -0.00130116 -0.0013057 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.233e-06 5.08733e-06 9.05155e-06 7.43238e-06 9.05033e-06 7.43157e-06 0.000146151 0.000140728 0.0429065 0.0414854 0.0429116 0.0414908 0.0104447 0.0103677 0.0470527 0.0457975 0.0470533 0.0457982 0.0604622 0.0600418 9.83548e-11 7.19107e-11 9.8336e-11 7.18675e-11 8.26957e-10 7.16579e-10 3.50409e-06 3.48863e-06 3.50409e-06 3.48864e-06 5.0002e-08 0 0 0 0 0 0 0 0
214 21185000 0.982619 0.982725 0.00152867 0.00136924 -0.00489183 -0.00484624 0.185565 0.185004 -0.0458106 -0.0462009 0.043261 0.0393833 -0.486053 -0.484309 -0.00214019 -0.00272448 9.61769e-05 -0.00321003 -0.0377 -0.0739986 -1.4247e-05 -1.3623e-05 -5.95261e-05 -5.98635e-05 7.66177e-07 2.75052e-06 -7.40221e-05 -8.40561e-05 6.83868e-05 4.91774e-05 -0.00130905 -0.00131332 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.21694e-06 5.07141e-06 8.78425e-06 7.25921e-06 8.77768e-06 7.25314e-06 0.000145159 0.000139777 0.0403364 0.0394079 0.0403404 0.0394122 0.0103155 0.0102453 0.0421073 0.041216 0.0421077 0.0412165 0.0600135 0.0596169 9.50414e-11 7.00906e-11 9.50259e-11 7.00506e-11 8.11289e-10 7.0346e-10 3.21573e-06 3.18767e-06 3.21575e-06 3.1877e-06 5.0002e-08 0 0 0 0 0 0 0 0
215 21285000 0.982569 0.982676 -0.000686723 -0.000850243 -0.00626608 -0.00621809 0.185793 0.185224 -0.0455938 -0.0459965 0.0462914 0.0422641 -0.616091 -0.614355 -0.0067397 -0.00736392 0.00458862 0.000887622 -0.0938215 -0.130116 -1.4251e-05 -1.3627e-05 -5.95224e-05 -5.986e-05 5.69743e-07 2.56053e-06 -7.39937e-05 -8.40208e-05 6.83533e-05 4.91376e-05 -0.00130868 -0.0013129 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.18985e-06 5.04487e-06 9.07778e-06 7.49032e-06 9.06804e-06 7.48108e-06 0.000144188 0.000138847 0.0470545 0.0460583 0.0470592 0.0460632 0.0103743 0.010308 0.0479586 0.0468728 0.0479594 0.0468736 0.0601966 0.0598117 9.51349e-11 7.01851e-11 9.51207e-11 7.01465e-11 7.96011e-10 6.90665e-10 3.21573e-06 3.18767e-06 3.21576e-06 3.1877e-06 5.0001e-08 0 0 0 0 0 0 0 0
216 21385000 0.982523 0.982631 -0.00215579 -0.00231522 -0.00692837 -0.00687507 0.185998 0.185428 -0.0386956 -0.0391078 0.0422437 0.0391149 -0.740305 -0.738633 -0.00501759 -0.0056691 0.00753011 0.00453198 -0.155416 -0.191837 -1.42006e-05 -1.36e-05 -5.94488e-05 -5.97986e-05 5.09404e-07 2.4867e-06 -0.000101372 -0.000114489 8.72877e-05 6.41172e-05 -0.00131479 -0.00131879 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.16581e-06 5.0213e-06 8.93294e-06 7.40475e-06 8.92241e-06 7.39466e-06 0.000143226 0.000137926 0.042888 0.0422894 0.0428923 0.042294 0.0102477 0.0101871 0.0427292 0.041974 0.0427297 0.0419746 0.0597468 0.0593844 9.268e-11 6.8833e-11 9.26691e-11 6.87974e-11 7.81111e-10 6.78178e-10 2.90409e-06 2.86151e-06 2.90412e-06 2.86156e-06 5.0001e-08 0 0 0 0 0 0 0 0
217 21485000 0.982497 0.982605 -0.00300189 -0.00316467 -0.00737092 -0.00731601 0.18611 0.185537 -0.0337097 -0.0341407 0.0389534 0.0357176 -0.875698 -0.874034 -0.00870909 -0.00940316 0.0116246 0.00830944 -0.240014 -0.276428 -1.41982e-05 -1.35981e-05 -5.94505e-05 -5.97999e-05 6.17736e-07 2.57744e-06 -0.000101185 -0.000114295 8.71586e-05 6.39831e-05 -0.00131339 -0.00131736 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.14144e-06 4.99746e-06 9.22344e-06 7.63427e-06 9.21252e-06 7.62375e-06 0.000142276 0.000137018 0.0493763 0.0487422 0.0493817 0.0487478 0.0103067 0.0102493 0.0489285 0.0480309 0.0489294 0.048032 0.0599215 0.0595708 9.27739e-11 6.89278e-11 9.27643e-11 6.88936e-11 7.66579e-10 6.65996e-10 2.90409e-06 2.86152e-06 2.90412e-06 2.86156e-06 5e-08 0 0 0 0 0 0 0 0
218 21585000 0.982499 0.982607 -0.00343534 -0.00359563 -0.00735821 -0.00730122 0.186093 0.185522 -0.0250469 -0.0253891 0.0350159 0.032578 -0.998878 -0.997287 -0.00746324 -0.00808103 0.013118 0.0104472 -0.325234 -0.36179 -1.41564e-05 -1.35722e-05 -5.94209e-05 -5.97723e-05 7.06419e-07 2.63808e-06 -0.0001069 -0.000122428 8.4219e-05 5.78368e-05 -0.00132136 -0.00132508 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.10988e-06 4.96672e-06 9.18941e-06 7.62882e-06 9.17908e-06 7.61883e-06 0.000141348 0.000136129 0.0439215 0.0435709 0.0439264 0.0435759 0.0101821 0.0101296 0.043376 0.0427612 0.0433766 0.0427619 0.0594715 0.059142 9.1044e-11 6.79795e-11 9.10367e-11 6.79476e-11 7.52404e-10 6.54106e-10 2.59627e-06 2.53938e-06 2.5963e-06 2.53943e-06 5e-08 0 0 0 0 0 0 0 0
219 21685000 0.982488 0.982597 -0.00378648 -0.00394967 -0.00721072 -0.00715241 0.186146 0.185572 -0.0220413 -0.0223987 0.0308525 0.0283485 -1.13227 -1.13068 -0.00981194 -0.0104655 0.0164569 0.0135409 -0.439375 -0.475907 -1.41527e-05 -1.35692e-05 -5.9423e-05 -5.97741e-05 8.67113e-07 2.77906e-06 -0.000106494 -0.000122017 8.39549e-05 5.75712e-05 -0.00131859 -0.00132232 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.08425e-06 4.94174e-06 9.47988e-06 7.85877e-06 9.47041e-06 7.84956e-06 0.000140424 0.000135247 0.0499811 0.0496147 0.0499872 0.049621 0.0102411 0.0101912 0.049838 0.0491258 0.0498392 0.049127 0.0596387 0.0593206 9.11382e-11 6.80745e-11 9.11322e-11 6.8044e-11 7.38572e-10 6.42501e-10 2.59627e-06 2.53938e-06 2.59631e-06 2.53944e-06 5e-08 0 0 0 0 0 0 0 0
220 21785000 0.982505 0.982613 -0.00415226 -0.00431215 -0.00731874 -0.00725534 0.186046 0.185474 -0.0123405 -0.0126423 0.0263065 0.0244942 -1.25994 -1.25841 -0.00246739 -0.0030983 0.0150968 0.0127791 -0.552239 -0.588856 -1.4067e-05 -1.3506e-05 -5.93626e-05 -5.97252e-05 1.10599e-06 2.98254e-06 -0.000129509 -0.000147535 7.84966e-05 5.02352e-05 -0.0013255 -0.00132903 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.08567e-06 4.94174e-06 9.53928e-06 7.9217e-06 9.53001e-06 7.91266e-06 0.000140419 0.000135218 0.0436918 0.0435061 0.043697 0.0435114 0.0102062 0.010159 0.0439754 0.0434919 0.0439762 0.0434928 0.0600784 0.059771 8.99695e-11 6.74437e-11 8.99649e-11 6.74146e-11 7.28441e-10 6.33999e-10 2.31069e-06 2.24122e-06 2.31073e-06 2.24128e-06 5.0002e-08 0 0 0 0 0 0 0 0
221 21885000 0.982497 0.982607 -0.00444152 -0.00460443 -0.00743632 -0.00737152 0.186076 0.185497 -0.00870506 -0.00901883 0.0219879 0.0201373 -1.38109 -1.37956 -0.00354198 -0.00420478 0.0175554 0.0150562 -0.691792 -0.728379 -1.407e-05 -1.35091e-05 -5.93587e-05 -5.97215e-05 9.35857e-07 2.81995e-06 -0.0001292 -0.000147221 7.8259e-05 4.99985e-05 -0.00132296 -0.00132648 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.0499e-06 4.90705e-06 9.83405e-06 8.15556e-06 9.82489e-06 8.14659e-06 0.000139515 0.000134356 0.0492209 0.0490301 0.0492271 0.0490365 0.0102663 0.0102211 0.0506028 0.0500569 0.0506041 0.0500584 0.0602436 0.0599476 9.0064e-11 6.75389e-11 9.00606e-11 6.75111e-11 7.15186e-10 6.2287e-10 2.31069e-06 2.24122e-06 2.31074e-06 2.24128e-06 5.0001e-08 0 0 0 0 0 0 0 0
222 21985000 0.982514 0.982623 -0.00512895 -0.00528914 -0.00773443 -0.00766641 0.185958 0.185379 -0.00758989 -0.00779929 0.0182301 0.0169844 -1.36906 -1.36757 0.000401991 -0.000178892 0.014566 0.0125949 -0.826847 -0.863528 -1.39875e-05 -1.34463e-05 -5.93263e-05 -5.96927e-05 1.01084e-06 2.87342e-06 -0.000112861 -0.000132551 5.50593e-05 2.57446e-05 -0.00132766 -0.001331 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 5.01357e-06 4.87185e-06 9.96621e-06 8.27191e-06 9.95736e-06 8.26319e-06 0.000138622 0.000133505 0.042511 0.0424307 0.0425163 0.0424361 0.0101441 0.0101016 0.0444774 0.0441086 0.0444784 0.0441096 0.0597823 0.059505 8.92986e-11 6.71375e-11 8.92965e-11 6.71112e-11 7.02254e-10 6.12004e-10 2.05666e-06 1.97704e-06 2.05672e-06 1.97711e-06 5.0001e-08 0 0 0 0 0 0 0 0
223 22085000 0.982507 0.982616 -0.00587051 -0.00603391 -0.00852687 -0.00845715 0.185939 0.185359 -0.00446836 -0.00467532 0.0145918 0.0133698 -1.34974 -1.34826 -0.000265676 -0.00086957 0.0161636 0.0140713 -0.968664 -1.00534 -1.39835e-05 -1.3443e-05 -5.93285e-05 -5.96947e-05 1.18545e-06 3.02662e-06 -0.000112487 -0.000132186 5.4838e-05 2.55344e-05 -0.00132536 -0.00132869 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 4.98574e-06 4.84483e-06 1.0268e-05 8.51185e-06 1.02581e-05 8.50208e-06 0.000137729 0.000132654 0.0474613 0.0473863 0.0474677 0.0473928 0.0102046 0.0101632 0.0511614 0.0507579 0.051163 0.0507595 0.0599413 0.0596747 8.93935e-11 6.72334e-11 8.93923e-11 6.72075e-11 6.89628e-10 6.01391e-10 2.05666e-06 1.97704e-06 2.05672e-06 1.97712e-06 5.0001e-08 0 0 0 0 0 0 0 0
224 22185000 0.982523 0.982632 -0.00631853 -0.00647854 -0.00882939 -0.00875477 0.185826 0.185244 0.00146024 0.00133503 0.0108353 0.0100641 -1.36461 -1.36317 0.00628137 0.00572812 0.0117846 0.0101434 -1.10988 -1.1466 -1.38816e-05 -1.33643e-05 -5.92799e-05 -5.96548e-05 1.32213e-06 3.14493e-06 -0.000104565 -0.000125836 3.38128e-05 4.40457e-06 -0.00132316 -0.00132644 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 4.952e-06 4.81218e-06 1.0456e-05 8.66894e-06 1.0446e-05 8.65901e-06 0.000136854 0.000131821 0.0407627 0.0407381 0.0407682 0.0407437 0.0100841 0.0100449 0.044856 0.0445825 0.0448571 0.0445837 0.0594769 0.0592273 8.89191e-11 6.69981e-11 8.89176e-11 6.69725e-11 6.77297e-10 5.91021e-10 1.83469e-06 1.7477e-06 1.83475e-06 1.74778e-06 5e-08 0 0 0 0 0 0 0 0
225 22285000 0.98251 0.98262 -0.00704307 -0.00720593 -0.00907081 -0.00899444 0.185856 0.185268 0.00743231 0.00730874 0.00572912 0.00497824 -1.36261 -1.36118 0.00670892 0.00614179 0.012652 0.0109362 -1.25241 -1.28912 -1.38826e-05 -1.33656e-05 -5.92773e-05 -5.96523e-05 1.23474e-06 3.05717e-06 -0.000104253 -0.000125526 3.35911e-05 4.18874e-06 -0.00132099 -0.00132426 0.204182 0.203458 0.00196632 0.00195935 0.433697 0.434775 0 0 0 0 0 4.91997e-06 4.78119e-06 1.07626e-05 8.91238e-06 1.07533e-05 8.9031e-06 0.000135988 0.000130997 0.0451944 0.0451729 0.0452011 0.0451797 0.0101452 0.0101065 0.0515248 0.0512351 0.0515265 0.0512369 0.0596305 0.0593908 8.90147e-11 6.70942e-11 8.90131e-11 6.7069e-11 6.65264e-10 5.80896e-10 1.83469e-06 1.7477e-06 1.83476e-06 1.74778e-06 5e-08 0 0 0 0 0 0 0 0
226 22385000 0.98269 0.982754 -0.0074254 -0.00758158 -0.00926491 -0.00918538 0.184878 0.184534 0.00923438 0.00918722 -0.00350679 -0.00392521 -1.36449 -1.36307 0.0120836 0.0115677 0.00314665 0.00180938 -1.39677 -1.43346 -1.37749e-05 -1.32829e-05 -5.92294e-05 -5.96124e-05 1.17017e-06 2.99725e-06 -7.66589e-05 -9.91456e-05 2.7017e-05 -1.74772e-06 -0.00131709 -0.00132035 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 8.01411e-05 7.97548e-05 1.11295e-05 9.24725e-06 1.10525e-05 9.17893e-06 0.00228333 0.00227958 0.0387229 0.038721 0.0387286 0.0387268 0.0101149 0.0100764 0.0451083 0.0449112 0.0451095 0.0449126 0.0600634 0.0598323 8.87281e-11 6.69672e-11 8.87262e-11 6.6942e-11 6.59402e-10 5.75969e-10 1.64419e-06 1.5522e-06 1.64427e-06 1.55229e-06 5.0002e-08 0 0 0 0 0 0 0 0
227 22485000 0.982381 0.982448 -0.00758241 -0.00774155 -0.00971006 -0.00962932 0.186481 0.186129 0.013749 0.013706 -0.0100052 -0.0104026 -1.36922 -1.36781 0.0132158 0.0126943 0.00245647 0.00107957 -1.53808 -1.57477 -1.37743e-05 -1.32825e-05 -5.92286e-05 -5.96117e-05 1.17079e-06 3.00014e-06 -7.64135e-05 -9.88998e-05 2.68531e-05 -1.90791e-06 -0.00131544 -0.00131867 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.64374e-05 5.62001e-05 1.11419e-05 9.25976e-06 1.10766e-05 9.20122e-06 0.00160776 0.00160596 0.042855 0.0428419 0.0428617 0.0428487 0.0101774 0.0101371 0.0516733 0.0514763 0.0516752 0.0514782 0.0602168 0.0599948 8.8828e-11 6.70671e-11 8.88261e-11 6.70419e-11 6.59501e-10 5.76066e-10 1.64419e-06 1.5522e-06 1.64427e-06 1.55229e-06 5.0002e-08 0 0 0 0 0 0 0 0
228 22585000 0.982484 0.982551 -0.00744103 -0.00760369 -0.0102954 -0.0102135 0.185914 0.185556 0.0223125 0.0223618 -0.016438 -0.0166368 -1.36893 -1.36755 0.0249696 0.0244845 -0.00549684 -0.00657335 -1.68089 -1.71762 -1.36577e-05 -1.31924e-05 -5.91737e-05 -5.95686e-05 1.17347e-06 3.0061e-06 -8.12665e-05 -0.000104965 1.47469e-05 -1.29283e-05 -0.00131271 -0.00131591 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.36124e-05 4.34454e-05 1.11824e-05 9.29969e-06 1.11125e-05 9.23536e-06 0.00124066 0.00123962 0.0371096 0.0370466 0.0371156 0.0370525 0.0100599 0.0100196 0.0452166 0.0450825 0.045218 0.045084 0.0597455 0.0595374 8.86378e-11 6.69935e-11 8.86356e-11 6.69683e-11 6.59594e-10 5.76159e-10 1.47328e-06 1.37959e-06 1.47336e-06 1.37968e-06 5.0001e-08 0 0 0 0 0 0 0 0
229 22685000 0.982427 0.982495 -0.00737165 -0.00753692 -0.010495 -0.0104117 0.186208 0.185843 0.0246091 0.0246769 -0.0212905 -0.0214839 -1.37237 -1.371 0.0273088 0.026828 -0.00743129 -0.00852594 -1.82475 -1.86148 -1.36568e-05 -1.31917e-05 -5.91723e-05 -5.95674e-05 1.17368e-06 3.00952e-06 -8.09042e-05 -0.00010461 1.45025e-05 -1.31628e-05 -0.0013103 -0.00131348 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.55477e-05 3.54211e-05 1.12296e-05 9.34421e-06 1.11661e-05 9.28557e-06 0.00101008 0.00100941 0.0412038 0.041062 0.0412109 0.041069 0.0101236 0.0100823 0.0516104 0.0514917 0.0516126 0.0514939 0.0598948 0.0596941 8.87377e-11 6.70935e-11 8.87355e-11 6.70682e-11 6.59686e-10 5.76251e-10 1.47328e-06 1.37959e-06 1.47336e-06 1.37969e-06 5.0001e-08 0 0 0 0 0 0 0 0
230 22785000 0.982376 0.982446 -0.0073159 -0.00748589 -0.0108837 -0.0108012 0.186455 0.186082 0.0277617 0.0279745 -0.0272632 -0.0273817 -1.37645 -1.3751 0.0360714 0.0356089 -0.0165989 -0.0174513 -1.97266 -2.00942 -1.35159e-05 -1.3083e-05 -5.90869e-05 -5.95005e-05 1.17294e-06 3.01451e-06 -6.20321e-05 -8.71829e-05 -6.43153e-06 -3.24348e-05 -0.00130571 -0.00130887 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 2.99079e-05 2.98075e-05 1.12778e-05 9.39308e-06 1.12156e-05 9.33475e-06 0.000851901 0.000851441 0.0359903 0.0357671 0.0359967 0.0357733 0.0100088 0.0099684 0.0451969 0.0451146 0.0451985 0.0451163 0.0594279 0.0592393 8.85141e-11 6.69986e-11 8.85119e-11 6.69733e-11 6.5977e-10 5.76337e-10 1.3163e-06 1.22419e-06 1.31638e-06 1.22428e-06 5e-08 0 0 0 0 0 0 0 0
231 22885000 0.982534 0.982605 -0.00750566 -0.00767805 -0.0112126 -0.0111284 0.185594 0.185214 0.0308722 0.031124 -0.0320127 -0.0321496 -1.3783 -1.37695 0.038964 0.0385233 -0.0194839 -0.0203476 -2.11693 -2.15369 -1.35147e-05 -1.30821e-05 -5.90856e-05 -5.94995e-05 1.18261e-06 3.02591e-06 -6.17026e-05 -8.68643e-05 -6.68629e-06 -3.26768e-05 -0.00130338 -0.00130653 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 2.57701e-05 2.56877e-05 1.13462e-05 9.4569e-06 1.1289e-05 9.40222e-06 0.000736648 0.000736311 0.0399986 0.0396462 0.0400064 0.0396537 0.0100736 0.0100331 0.0514468 0.0513835 0.0514493 0.051386 0.0595738 0.0593911 8.8614e-11 6.70985e-11 8.86117e-11 6.70732e-11 6.5985e-10 5.7642e-10 1.3163e-06 1.22419e-06 1.31639e-06 1.22429e-06 5e-08 0 0 0 0 0 0 0 0
232 22985000 0.982664 0.982736 -0.00743752 -0.00761514 -0.0115797 -0.0114969 0.184885 0.184498 0.0322222 0.0326747 -0.0354984 -0.0356575 -1.38262 -1.38128 0.0475663 0.047143 -0.0293882 -0.0300626 -2.26911 -2.30588 -1.3362e-05 -1.29644e-05 -5.89861e-05 -5.94221e-05 1.19389e-06 3.04262e-06 -4.09754e-05 -6.76067e-05 -2.81098e-05 -5.22439e-05 -0.00129745 -0.00130061 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 2.26231e-05 2.2554e-05 1.13938e-05 9.50678e-06 1.13367e-05 9.45209e-06 0.000648919 0.000648658 0.0351196 0.0346994 0.0351269 0.0347063 0.00996141 0.00992272 0.0451008 0.0450563 0.0451027 0.0450582 0.0591119 0.0589397 8.82858e-11 6.69425e-11 8.82836e-11 6.69173e-11 6.59921e-10 5.76496e-10 1.17384e-06 1.08552e-06 1.17392e-06 1.08561e-06 5e-08 0 0 0 0 0 0 0 0
233 23085000 0.982719 0.982793 -0.0074494 -0.00762942 -0.0118996 -0.0118151 0.184573 0.184177 0.0359427 0.036458 -0.0403742 -0.0405781 -1.37993 -1.37859 0.0509593 0.0505838 -0.0332114 -0.0339036 -2.40841 -2.44517 -1.33618e-05 -1.29642e-05 -5.89858e-05 -5.94218e-05 1.19334e-06 3.04269e-06 -4.09144e-05 -6.7543e-05 -2.81499e-05 -5.22852e-05 -0.00129705 -0.00130017 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 2.06909e-05 2.06291e-05 1.1478e-05 9.58335e-06 1.1421e-05 9.52864e-06 0.000595829 0.000595602 0.0389967 0.0384139 0.0390055 0.0384222 0.0101138 0.0100752 0.0512322 0.0512013 0.051235 0.0512041 0.060146 0.0599736 8.83857e-11 6.70425e-11 8.83834e-11 6.70172e-11 6.59995e-10 5.76575e-10 1.17384e-06 1.08552e-06 1.17392e-06 1.08562e-06 5.0002e-08 0 0 0 0 0 0 0 0
234 23185000 0.982708 0.982783 -0.00740739 -0.00759195 -0.0120888 -0.0120053 0.184619 0.184215 0.0404909 0.0412109 -0.0401367 -0.0403987 -1.38323 -1.38191 0.0619863 0.061635 -0.0431294 -0.0436812 -2.55568 -2.59247 -1.32359e-05 -1.28672e-05 -5.88912e-05 -5.93484e-05 1.18657e-06 3.04094e-06 -2.87776e-05 -5.66157e-05 -3.98123e-05 -6.25834e-05 -0.00129269 -0.00129578 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.85969e-05 1.85434e-05 1.15197e-05 9.6291e-06 1.14654e-05 9.57689e-06 0.000537201 0.00053701 0.034333 0.0337205 0.0343416 0.0337285 0.0100021 0.00996598 0.0449644 0.0449426 0.0449665 0.0449447 0.0596757 0.0595128 8.79306e-11 6.6813e-11 8.79286e-11 6.67879e-11 6.6005e-10 5.76639e-10 1.0463e-06 9.63027e-07 1.04637e-06 9.63112e-07 5.0001e-08 0 0 0 0 0 0 0 0
235 23285000 0.982755 0.982832 -0.00788154 -0.00806825 -0.0122182 -0.0121326 0.184341 0.183929 0.0442768 0.0450782 -0.0447856 -0.0451126 -1.37916 -1.37785 0.0661555 0.0658791 -0.0474195 -0.0479996 -2.69992 -2.73672 -1.32346e-05 -1.28662e-05 -5.88897e-05 -5.93472e-05 1.19153e-06 3.04769e-06 -2.84741e-05 -5.63239e-05 -4.00499e-05 -6.28096e-05 -0.00129051 -0.00129359 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.69003e-05 1.68534e-05 1.16111e-05 9.71024e-06 1.15638e-05 9.665e-06 0.000489117 0.000488947 0.038041 0.0372475 0.0380513 0.0372571 0.0100698 0.0100352 0.0509969 0.0509775 0.0510001 0.0509806 0.059821 0.0596622 8.80304e-11 6.69129e-11 8.80283e-11 6.68878e-11 6.60096e-10 5.76697e-10 1.0463e-06 9.63028e-07 1.04638e-06 9.63118e-07 5.0001e-08 0 0 0 0 0 0 0 0
236 23385000 0.982718 0.982797 -0.00785181 -0.00804523 -0.0123269 -0.0122411 0.18453 0.18411 0.0482045 0.0491658 -0.0435174 -0.0440277 -1.38055 -1.37927 0.0770325 0.0767793 -0.0512064 -0.0516793 -2.84064 -2.87749 -1.30772e-05 -1.27445e-05 -5.88369e-05 -5.93058e-05 1.17361e-06 3.03358e-06 -2.94237e-05 -5.77201e-05 -7.0292e-05 -9.14896e-05 -0.00128907 -0.00129207 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.54789e-05 1.54373e-05 1.16506e-05 9.7545e-06 1.16059e-05 9.71178e-06 0.000448988 0.000448831 0.0335294 0.032754 0.0335384 0.0327624 0.00996047 0.0099291 0.0448102 0.0447968 0.0448125 0.0447992 0.0593566 0.0592063 8.74576e-11 6.66147e-11 8.74558e-11 6.65899e-11 6.60129e-10 5.76745e-10 9.33688e-07 8.55923e-07 9.33755e-07 8.56002e-07 5.0001e-08 0 0 0 0 0 0 0 0
237 23485000 0.982766 0.982845 -0.00794445 -0.00813989 -0.012595 -0.0125072 0.184255 0.183827 0.0515878 0.0526419 -0.0448911 -0.0454988 -1.38221 -1.38094 0.0819828 0.0818295 -0.0556584 -0.0561862 -2.98435 -3.02121 -1.30757e-05 -1.27434e-05 -5.88357e-05 -5.93048e-05 1.1864e-06 3.04676e-06 -2.91784e-05 -5.74855e-05 -7.0522e-05 -9.17093e-05 -0.00128707 -0.00129005 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.4302e-05 1.42646e-05 1.17559e-05 9.84685e-06 1.17124e-05 9.80517e-06 0.000414971 0.000414821 0.0370451 0.0360821 0.037056 0.0360922 0.0100281 0.00999905 0.0507567 0.0507312 0.0507603 0.0507347 0.0594949 0.0593481 8.75574e-11 6.67146e-11 8.75555e-11 6.66897e-11 6.6015e-10 5.76784e-10 9.33688e-07 8.55924e-07 9.3376e-07 8.56007e-07 5e-08 0 0 0 0 0 0 0 0
238 23585000 0.982791 0.982872 -0.00819568 -0.00839425 -0.0125357 -0.0124491 0.184112 0.183676 0.0515429 0.0527932 -0.0472664 -0.0479208 -1.38167 -1.38041 0.0888136 0.0886801 -0.0661592 -0.0665895 -3.1302 -3.1671 -1.2984e-05 -1.26716e-05 -5.87352e-05 -5.92264e-05 1.19386e-06 3.05633e-06 -9.14616e-06 -3.834e-05 -7.72521e-05 -9.79129e-05 -0.00128421 -0.00128714 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.32887e-05 1.32547e-05 1.17948e-05 9.89006e-06 1.17565e-05 9.85353e-06 0.000385795 0.000385646 0.0326559 0.0317589 0.0326655 0.0317678 0.00992107 0.0098957 0.0446499 0.044633 0.0446526 0.0446356 0.0590367 0.0588977 8.68935e-11 6.63624e-11 8.6892e-11 6.63379e-11 6.60157e-10 5.76812e-10 8.3556e-07 7.6319e-07 8.35619e-07 7.63261e-07 5e-08 0 0 0 0 0 0 0 0
239 23685000 0.982798 0.982881 -0.00882733 -0.0090279 -0.0130301 -0.0129411 0.184011 0.183567 0.0492645 0.0506256 -0.0493282 -0.0500456 -1.2857 -1.28445 0.0938685 0.0938645 -0.0710545 -0.0715534 -3.26819 -3.30508 -1.29831e-05 -1.26709e-05 -5.87345e-05 -5.92259e-05 1.20243e-06 3.06481e-06 -9.02173e-06 -3.82244e-05 -7.73762e-05 -9.80282e-05 -0.00128313 -0.00128605 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.26302e-05 1.25978e-05 1.19151e-05 9.99469e-06 1.18781e-05 9.95917e-06 0.000366562 0.000366404 0.0359028 0.0348293 0.0359135 0.0348392 0.0100764 0.010053 0.0505165 0.0504721 0.0505204 0.0504759 0.0600681 0.0599281 8.69934e-11 6.64623e-11 8.69917e-11 6.64378e-11 6.60178e-10 5.76851e-10 8.35562e-07 7.63193e-07 8.35625e-07 7.63267e-07 5.0002e-08 0 0 0 0 0 0 0 0
240 23785000 0.982787 0.98287 -0.0106096 -0.010816 -0.0157113 -0.0156194 0.183768 0.183316 0.0449305 0.0463738 -0.0441256 -0.044875 -0.96843 -0.967204 0.104019 0.104005 -0.0750357 -0.0754629 -3.39107 -3.42799 -1.28608e-05 -1.25751e-05 -5.87056e-05 -5.92024e-05 1.22073e-06 3.08284e-06 -1.24579e-05 -4.1589e-05 -9.62285e-05 -0.0001162 -0.00127863 -0.00128151 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.18475e-05 1.18173e-05 1.19874e-05 1.00694e-05 1.19377e-05 1.00206e-05 0.00034365 0.000343487 0.0314783 0.0305325 0.0314873 0.0305409 0.00996955 0.009949 0.0444864 0.0444568 0.0444893 0.0444597 0.0596026 0.0594701 8.62668e-11 6.60718e-11 8.62655e-11 6.60476e-11 6.60159e-10 5.76859e-10 7.50898e-07 6.83486e-07 7.50949e-07 6.83549e-07 5.0002e-08 0 0 0 0 0 0 0 0
241 23885000 0.982695 0.982779 -0.0139561 -0.0141661 -0.0198409 -0.0197454 0.183636 0.183178 0.0396273 0.041215 -0.0433639 -0.0440499 -0.537882 -0.536667 0.108214 0.108351 -0.0793628 -0.0798612 -3.46946 -3.5064 -1.28601e-05 -1.25745e-05 -5.87047e-05 -5.92017e-05 1.2208e-06 3.08374e-06 -1.23108e-05 -4.14459e-05 -9.6342e-05 -0.00011631 -0.00127755 -0.0012804 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.11406e-05 1.1112e-05 1.21597e-05 1.02234e-05 1.2091e-05 1.01554e-05 0.000323461 0.000323289 0.0342998 0.0332136 0.0343109 0.0332238 0.0100403 0.0100214 0.050262 0.0501921 0.0502663 0.0501962 0.0597435 0.059614 8.63665e-11 6.61716e-11 8.63651e-11 6.61473e-11 6.60124e-10 5.76855e-10 7.50898e-07 6.83487e-07 7.50954e-07 6.83555e-07 5.0001e-08 0 0 0 0 0 0 0 0
242 23985000 0.982629 0.982714 -0.0162211 -0.0164348 -0.0223228 -0.0222222 0.18352 0.183054 0.041354 0.0429585 -0.040221 -0.0408754 -0.153715 -0.152504 0.116988 0.117088 -0.081363 -0.0817828 -3.53791 -3.57481 -1.27546e-05 -1.2491e-05 -5.86747e-05 -5.91776e-05 1.2121e-06 3.0766e-06 -1.57577e-05 -4.48364e-05 -0.000112544 -0.000132085 -0.00125402 -0.00125699 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 1.05084e-05 1.04814e-05 1.22569e-05 1.03157e-05 1.21794e-05 1.02393e-05 0.000305575 0.000305392 0.0300565 0.0291182 0.030067 0.0291279 0.00993645 0.00992007 0.0443129 0.0442654 0.0443161 0.0442686 0.0592848 0.0591623 8.55769e-11 6.57422e-11 8.55758e-11 6.57183e-11 6.60071e-10 5.76838e-10 6.77556e-07 6.14712e-07 6.77603e-07 6.14772e-07 5.0001e-08 0 0 0 0 0 0 0 0
243 24085000 0.982656 0.982743 -0.0158627 -0.0160773 -0.0213974 -0.021295 0.183514 0.18304 0.0468928 0.048608 -0.0476554 -0.0483465 0.0906041 0.091806 0.121344 0.121609 -0.0857146 -0.0862001 -3.54131 -3.57824 -1.27543e-05 -1.24907e-05 -5.86736e-05 -5.91767e-05 1.19778e-06 3.06457e-06 -1.5611e-05 -4.46946e-05 -0.000112625 -0.000132161 -0.00125325 -0.00125617 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 9.94501e-06 9.91957e-06 1.23783e-05 1.04154e-05 1.23125e-05 1.03509e-05 0.00028967 0.000289476 0.032731 0.0316546 0.032744 0.0316666 0.0100087 0.00999484 0.0499884 0.0498902 0.0499932 0.0498948 0.0594256 0.059306 8.56767e-11 6.5842e-11 8.56753e-11 6.5818e-11 6.59999e-10 5.76806e-10 6.77556e-07 6.14714e-07 6.77608e-07 6.14777e-07 5e-08 0 0 0 0 0 0 0 0
244 24185000 0.982774 0.982863 -0.0130776 -0.0132914 -0.0177378 -0.0176329 0.183491 0.183008 0.0579637 0.0596137 -0.0523583 -0.0531238 0.0829724 0.0841572 0.129487 0.129695 -0.0904768 -0.0908798 -3.55762 -3.59454 -1.26945e-05 -1.24422e-05 -5.86346e-05 -5.91453e-05 1.20364e-06 3.06704e-06 -1.3833e-05 -4.28882e-05 -0.000119736 -0.000139323 -0.00123432 -0.0012373 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 9.45795e-06 9.43412e-06 1.24236e-05 1.04498e-05 1.23782e-05 1.04057e-05 0.000275416 0.000275207 0.028877 0.0279389 0.0288885 0.0279496 0.00990621 0.00989669 0.0441273 0.0440592 0.044131 0.0440627 0.0589738 0.0588609 8.48608e-11 6.53947e-11 8.48598e-11 6.5371e-11 6.59908e-10 5.7676e-10 6.14499e-07 5.55692e-07 6.14544e-07 5.55749e-07 5e-08 0 0 0 0 0 0 0 0
245 24285000 0.98287 0.982961 -0.0106382 -0.0108518 -0.0142582 -0.0141523 0.183438 0.182947 0.0609121 0.0626373 -0.0555528 -0.0564765 0.0577785 0.0589526 0.135475 0.135852 -0.0959269 -0.0964141 -3.55383 -3.59078 -1.26937e-05 -1.24416e-05 -5.86339e-05 -5.91448e-05 1.20892e-06 3.07209e-06 -1.37236e-05 -4.27813e-05 -0.000119837 -0.000139424 -0.00123339 -0.00123634 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 9.01174e-06 8.98921e-06 1.2542e-05 1.0544e-05 1.25132e-05 1.05162e-05 0.000262544 0.000262319 0.031472 0.0303952 0.0314851 0.0304072 0.00997815 0.00997273 0.049711 0.049582 0.0497162 0.0495871 0.0591147 0.059005 8.49605e-11 6.54945e-11 8.49592e-11 6.54707e-11 6.59797e-10 5.76698e-10 6.145e-07 5.55694e-07 6.14549e-07 5.55754e-07 5e-08 0 0 0 0 0 0 0 0
246 24385000 0.982934 0.983026 -0.00972201 -0.00993814 -0.0131727 -0.0130641 0.183229 0.18273 0.055342 0.0569377 -0.0490851 -0.0501547 0.0742245 0.0753723 0.143306 0.143599 -0.0965253 -0.0969754 -3.55007 -3.58704 -1.26163e-05 -1.23792e-05 -5.8651e-05 -5.91563e-05 1.22995e-06 3.09105e-06 -2.01097e-05 -4.85365e-05 -0.00013443 -0.000154058 -0.00123229 -0.00123518 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 8.70479e-06 8.68236e-06 1.26281e-05 1.06174e-05 1.26029e-05 1.05934e-05 0.00025377 0.000253521 0.027774 0.0268493 0.0277845 0.0268589 0.00996025 0.00995877 0.0439347 0.0438443 0.0439387 0.0438482 0.059543 0.0594366 8.41854e-11 6.50682e-11 8.41844e-11 6.50448e-11 6.59723e-10 5.76665e-10 5.61494e-07 5.05937e-07 5.61536e-07 5.0599e-07 5.0002e-08 0 0 0 0 0 0 0 0
247 24485000 0.982974 0.983067 -0.00994215 -0.0101598 -0.013238 -0.0131272 0.183 0.182494 0.0495536 0.0512199 -0.0445423 -0.0457647 0.0723706 0.0735029 0.148533 0.148988 -0.101195 -0.10176 -3.5422 -3.57921 -1.26157e-05 -1.23786e-05 -5.86522e-05 -5.91572e-05 1.26937e-06 3.1252e-06 -2.02261e-05 -4.8637e-05 -0.000134435 -0.000154075 -0.00123244 -0.00123528 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 8.33443e-06 8.31261e-06 1.2789e-05 1.07515e-05 1.2765e-05 1.07287e-05 0.00024285 0.000242582 0.0301663 0.0291186 0.0301779 0.0291292 0.0100334 0.0100363 0.0494234 0.0492642 0.049429 0.0492696 0.0596885 0.0595856 8.4285e-11 6.51679e-11 8.42838e-11 6.51444e-11 6.59573e-10 5.76574e-10 5.61495e-07 5.05939e-07 5.61541e-07 5.05996e-07 5.0001e-08 0 0 0 0 0 0 0 0
248 24585000 0.982933 0.983027 -0.0106432 -0.0108637 -0.0133437 -0.0132287 0.183173 0.18266 0.0473781 0.0488477 -0.0391087 -0.0404742 0.0677436 0.0688348 0.15372 0.15406 -0.0982439 -0.0987676 -3.53651 -3.57358 -1.2546e-05 -1.23217e-05 -5.86941e-05 -5.91884e-05 1.26702e-06 3.12245e-06 -2.872e-05 -5.64231e-05 -0.000150054 -0.000169925 -0.00123132 -0.00123409 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 8.00794e-06 7.98653e-06 1.28893e-05 1.08368e-05 1.28686e-05 1.08176e-05 0.000232863 0.000232575 0.0266506 0.0257595 0.0266599 0.0257681 0.00993155 0.00993889 0.0437335 0.0436209 0.0437378 0.043625 0.0592369 0.0591406 8.35671e-11 6.47727e-11 8.35661e-11 6.47495e-11 6.594e-10 5.76465e-10 5.17207e-07 4.64187e-07 5.17249e-07 4.64239e-07 5.0001e-08 0 0 0 0 0 0 0 0
249 24685000 0.982917 0.983012 -0.0111581 -0.01138 -0.0131754 -0.0130581 0.18324 0.18272 0.0439568 0.045477 -0.0376721 -0.0392013 0.0668915 0.0679682 0.158337 0.158825 -0.102018 -0.102686 -3.52972 -3.56682 -1.25461e-05 -1.23217e-05 -5.8694e-05 -5.91883e-05 1.26473e-06 3.12017e-06 -2.87135e-05 -5.64107e-05 -0.000150055 -0.000169931 -0.00123131 -0.00123403 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 7.69941e-06 7.67831e-06 1.30595e-05 1.09777e-05 1.30429e-05 1.09625e-05 0.000223722 0.000223412 0.0288616 0.027862 0.0288718 0.0278714 0.0100051 0.010017 0.0491225 0.0489356 0.0491283 0.0489412 0.0593828 0.0592907 8.36667e-11 6.48724e-11 8.36655e-11 6.48491e-11 6.59202e-10 5.76337e-10 5.17208e-07 4.64189e-07 5.17253e-07 4.64244e-07 5.0001e-08 0 0 0 0 0 0 0 0
250 24785000 0.982942 0.983039 -0.0113068 -0.0115306 -0.0125392 -0.0124191 0.183139 0.182612 0.0414789 0.0428539 -0.0346022 -0.0362014 0.0591983 0.0602403 0.161737 0.16213 -0.0985226 -0.0991174 -3.52724 -3.5644 -1.24916e-05 -1.22763e-05 -5.87065e-05 -5.91968e-05 1.27177e-06 3.12726e-06 -3.18186e-05 -5.91337e-05 -0.00016319 -0.000183488 -0.00123042 -0.00123308 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 7.40531e-06 7.38448e-06 1.3162e-05 1.10629e-05 1.31501e-05 1.10525e-05 0.000215331 0.000214999 0.0255242 0.024681 0.0255323 0.0246884 0.00990383 0.00992011 0.043521 0.0433877 0.0435254 0.0433919 0.0589327 0.058847 8.30213e-11 6.45178e-11 8.30202e-11 6.44947e-11 6.58978e-10 5.76188e-10 4.80476e-07 4.29357e-07 4.8052e-07 4.29409e-07 5e-08 0 0 0 0 0 0 0 0
251 24885000 0.982945 0.983043 -0.0111497 -0.0113745 -0.0120307 -0.0119085 0.183169 0.182635 0.0385107 0.0399183 -0.0373011 -0.0390744 0.0488873 0.0499173 0.165758 0.166291 -0.102124 -0.102887 -3.52408 -3.56127 -1.24907e-05 -1.22755e-05 -5.87061e-05 -5.91965e-05 1.28632e-06 3.13989e-06 -3.17427e-05 -5.90595e-05 -0.000163285 -0.000183582 -0.00122962 -0.00123225 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 7.14729e-06 7.12654e-06 1.33417e-05 1.12107e-05 1.33319e-05 1.12024e-05 0.000207581 0.000207226 0.0275717 0.0266335 0.0275804 0.0266415 0.00997744 0.00999854 0.0488059 0.0485949 0.0488117 0.0486005 0.0590791 0.058998 8.31209e-11 6.46175e-11 8.31195e-11 6.45943e-11 6.58728e-10 5.76021e-10 4.80478e-07 4.2936e-07 4.80524e-07 4.29414e-07 5e-08 0 0 0 0 0 0 0 0
252 24985000 0.982926 0.983026 -0.0109545 -0.0111819 -0.0117977 -0.0116724 0.183294 0.182752 0.0312576 0.032492 -0.0319002 -0.0337716 0.0414268 0.0424305 0.167 0.167421 -0.0939907 -0.0946959 -3.52159 -3.55881 -1.24183e-05 -1.22157e-05 -5.87392e-05 -5.92216e-05 1.28748e-06 3.14124e-06 -3.73741e-05 -6.42948e-05 -0.000181679 -0.000202367 -0.00122916 -0.00123173 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 6.97506e-06 6.95357e-06 1.34531e-05 1.13027e-05 1.34433e-05 1.12946e-05 0.000202276 0.000201889 0.0244138 0.0236272 0.0244206 0.0236335 0.00996205 0.00998708 0.0432954 0.0431437 0.0432998 0.0431479 0.0595135 0.0594366 8.25574e-11 6.43097e-11 8.25562e-11 6.42869e-11 6.58548e-10 5.75907e-10 4.50228e-07 4.00464e-07 4.50272e-07 4.00515e-07 5.0002e-08 0 0 0 0 0 0 0 0
253 25085000 0.982924 0.983025 -0.0112926 -0.0115212 -0.0118556 -0.0117279 0.183282 0.182733 0.0270851 0.0283448 -0.0306368 -0.0326835 0.0383195 0.0393103 0.169844 0.170389 -0.0971628 -0.0980629 -3.5234 -3.56064 -1.24166e-05 -1.22144e-05 -5.87371e-05 -5.92199e-05 1.28127e-06 3.13587e-06 -3.71016e-05 -6.40438e-05 -0.000181905 -0.000202577 -0.00122712 -0.00122967 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 6.73987e-06 6.71827e-06 1.36464e-05 1.14616e-05 1.36378e-05 1.14547e-05 0.000195518 0.000195104 0.0263021 0.0254337 0.0263096 0.0254406 0.0100369 0.0100668 0.0484721 0.0482415 0.0484778 0.048247 0.0596649 0.0595935 8.26569e-11 6.44094e-11 8.26555e-11 6.43865e-11 6.5825e-10 5.75702e-10 4.50229e-07 4.00467e-07 4.50277e-07 4.0052e-07 5.0002e-08 0 0 0 0 0 0 0 0
254 25185000 0.982875 0.982978 -0.0115409 -0.0117705 -0.011705 -0.0115731 0.183539 0.182982 0.0238885 0.024927 -0.0245288 -0.0265671 0.0383684 0.0393177 0.171787 0.17219 -0.0902849 -0.0910699 -3.52111 -3.55842 -1.23853e-05 -1.21867e-05 -5.87793e-05 -5.92526e-05 1.25997e-06 3.116e-06 -4.40872e-05 -7.07457e-05 -0.00019268 -0.000213948 -0.00122591 -0.00122839 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 6.53653e-06 6.51466e-06 1.37635e-05 1.15574e-05 1.37565e-05 1.15521e-05 0.000189227 0.000188787 0.0233202 0.0225959 0.0233262 0.0226014 0.00993654 0.00997025 0.0430553 0.0428882 0.0430596 0.0428924 0.059215 0.0591501 8.21781e-11 6.4151e-11 8.21768e-11 6.41283e-11 6.57922e-10 5.75475e-10 4.25459e-07 3.76603e-07 4.25505e-07 3.76655e-07 5.0001e-08 0 0 0 0 0 0 0 0
255 25285000 0.982828 0.982932 -0.0116898 -0.0119203 -0.0110628 -0.0109287 0.183822 0.183257 0.0178437 0.0188882 -0.0252485 -0.0274631 0.0331512 0.0340868 0.173839 0.174346 -0.092752 -0.093749 -3.51854 -3.55588 -1.23859e-05 -1.21872e-05 -5.87779e-05 -5.92514e-05 1.216e-06 3.07712e-06 -4.39802e-05 -7.06423e-05 -0.000192703 -0.000213968 -0.00122558 -0.00122802 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 6.34358e-06 6.32138e-06 1.39643e-05 1.17213e-05 1.39607e-05 1.17195e-05 0.000183381 0.000182913 0.0250692 0.0242744 0.0250757 0.0242804 0.0100116 0.0100502 0.0481203 0.0478748 0.0481258 0.0478801 0.059367 0.0593082 8.22776e-11 6.42507e-11 8.2276e-11 6.42279e-11 6.57565e-10 5.75225e-10 4.25461e-07 3.76606e-07 4.25509e-07 3.7666e-07 5.0001e-08 0 0 0 0 0 0 0 0
256 25385000 0.982829 0.982934 -0.0118471 -0.0120792 -0.0108767 -0.0107391 0.183819 0.183248 0.0110014 0.0118948 -0.0181285 -0.0203666 0.0314619 0.0323576 0.171094 0.171499 -0.0827726 -0.0836726 -3.51939 -3.55679 -1.23238e-05 -1.21351e-05 -5.88017e-05 -5.927e-05 1.218e-06 3.07757e-06 -4.67951e-05 -7.33679e-05 -0.000208551 -0.000230298 -0.00122348 -0.00122587 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 6.15608e-06 6.13349e-06 1.40868e-05 1.18206e-05 1.40842e-05 1.18199e-05 0.000177934 0.000177438 0.0222661 0.0216052 0.0222713 0.02161 0.00991235 0.00995439 0.0428001 0.042621 0.0428043 0.042625 0.0589236 0.0588713 8.18837e-11 6.40425e-11 8.18821e-11 6.40199e-11 6.57176e-10 5.74951e-10 4.05304e-07 3.56996e-07 4.05352e-07 3.57049e-07 5e-08 0 0 0 0 0 0 0 0
257 25485000 0.98282 0.982926 -0.0118916 -0.0121248 -0.0105773 -0.0104376 0.183881 0.183303 0.00473808 0.00562891 -0.0167661 -0.0191813 0.0305592 0.0314405 0.171819 0.172313 -0.0845137 -0.0856456 -3.51805 -3.55547 -1.23236e-05 -1.21349e-05 -5.88006e-05 -5.92692e-05 1.20099e-06 3.06207e-06 -4.66947e-05 -7.32723e-05 -0.000208618 -0.000230361 -0.00122288 -0.00122523 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.98123e-06 5.95819e-06 1.42997e-05 1.19943e-05 1.42982e-05 1.19947e-05 0.000172848 0.000172322 0.0238851 0.0231639 0.0238908 0.0231692 0.00998743 0.0100342 0.0477513 0.0474955 0.0477565 0.0475005 0.0590763 0.0590305 8.19831e-11 6.41421e-11 8.19813e-11 6.41194e-11 6.56757e-10 5.74653e-10 4.05305e-07 3.56999e-07 4.05356e-07 3.57054e-07 5e-08 0 0 0 0 0 0 0 0
258 25585000 0.982806 0.982914 -0.0121277 -0.01236 -0.0103993 -0.0102561 0.18395 0.183365 0.00115598 0.00187223 -0.0144848 -0.0167842 0.0323439 0.0331905 0.169555 0.169932 -0.0784747 -0.0794216 -3.51641 -3.55389 -1.23169e-05 -1.21268e-05 -5.88179e-05 -5.92828e-05 1.17839e-06 3.04142e-06 -4.8721e-05 -7.52948e-05 -0.000214704 -0.000237018 -0.00122222 -0.00122452 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.81705e-06 5.79348e-06 1.44269e-05 1.20967e-05 1.44264e-05 1.20983e-05 0.000168088 0.000167531 0.0212548 0.0206563 0.0212593 0.0206606 0.00988914 0.00993897 0.0425303 0.0423424 0.0425342 0.0423462 0.0586393 0.0585998 8.1671e-11 6.39829e-11 8.16692e-11 6.39604e-11 6.56304e-10 5.7433e-10 3.89006e-07 3.40965e-07 3.89057e-07 3.4102e-07 5e-08 0 0 0 0 0 0 0 0
259 25685000 0.982818 0.982927 -0.0116076 -0.011841 -0.010098 -0.009953 0.183937 0.183344 -0.000274164 0.000425134 -0.013654 -0.0161384 0.0214661 0.0223061 0.169596 0.170044 -0.0799149 -0.0811005 -3.5165 -3.55399 -1.23157e-05 -1.21259e-05 -5.8817e-05 -5.92822e-05 1.18728e-06 3.04856e-06 -4.86035e-05 -7.51871e-05 -0.000214824 -0.00023713 -0.00122122 -0.0012235 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.70688e-06 5.68209e-06 1.46504e-05 1.22787e-05 1.46486e-05 1.2279e-05 0.000164871 0.000164273 0.0227655 0.0221147 0.0227702 0.0221192 0.0100485 0.0101032 0.0473666 0.0471048 0.0473714 0.0471094 0.0596696 0.0596362 8.17705e-11 6.40826e-11 8.17686e-11 6.406e-11 6.55968e-10 5.74095e-10 3.8901e-07 3.40971e-07 3.89062e-07 3.41026e-07 5.0002e-08 0 0 0 0 0 0 0 0
260 25785000 0.982835 0.982946 -0.0114154 -0.0116481 -0.00940447 -0.00925596 0.18389 0.183291 -0.00994226 -0.0093859 -0.00693241 -0.00932842 0.0202378 0.0210416 0.163947 0.164296 -0.072421 -0.073443 -3.51937 -3.55692 -1.22886e-05 -1.21017e-05 -5.8828e-05 -5.92912e-05 1.18785e-06 3.04758e-06 -4.85599e-05 -7.52702e-05 -0.000223491 -0.000246261 -0.00121917 -0.0012214 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.55736e-06 5.53198e-06 1.47795e-05 1.23818e-05 1.47788e-05 1.23833e-05 0.000160626 0.000159996 0.0203036 0.0197638 0.0203075 0.0197675 0.00994948 0.0100068 0.0422467 0.0420532 0.0422503 0.0420567 0.0592258 0.0591987 8.15361e-11 6.39706e-11 8.15342e-11 6.39481e-11 6.55455e-10 5.73726e-10 3.75934e-07 3.27942e-07 3.75986e-07 3.27997e-07 5.0001e-08 0 0 0 0 0 0 0 0
261 25885000 0.982804 0.982916 -0.0114787 -0.0117126 -0.00944969 -0.00929914 0.184051 0.183444 -0.016941 -0.0164077 -0.00457704 -0.00714351 0.0226353 0.0234234 0.162537 0.16294 -0.0729717 -0.0742411 -3.51816 -3.55574 -1.22895e-05 -1.21026e-05 -5.8826e-05 -5.92895e-05 1.11925e-06 2.98666e-06 -4.84444e-05 -7.51607e-05 -0.00022352 -0.000246286 -0.00121883 -0.00122102 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.41865e-06 5.39253e-06 1.50138e-05 1.25725e-05 1.50128e-05 1.25737e-05 0.000156636 0.000155973 0.021706 0.0211214 0.0217102 0.0211256 0.0100254 0.0100872 0.0469682 0.0467043 0.0469726 0.0467085 0.0593841 0.0593648 8.16354e-11 6.40701e-11 8.16333e-11 6.40476e-11 6.5491e-10 5.73331e-10 3.75936e-07 3.27945e-07 3.75989e-07 3.28002e-07 5.0001e-08 0 0 0 0 0 0 0 0
262 25985000 0.982797 0.98291 -0.011612 -0.0118451 -0.00962216 -0.00946947 0.184073 0.18346 -0.0248218 -0.0243624 9.23048e-05 -0.00235343 0.0158553 0.0166084 0.152402 0.152758 -0.0660169 -0.0670931 -3.51843 -3.55607 -1.22652e-05 -1.2081e-05 -5.88081e-05 -5.92755e-05 1.10419e-06 2.97171e-06 -4.39236e-05 -7.07558e-05 -0.000231303 -0.000254458 -0.00121756 -0.0012197 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.28868e-06 5.26176e-06 1.51484e-05 1.26802e-05 1.51465e-05 1.26806e-05 0.000152879 0.000152183 0.0194083 0.0189226 0.0194117 0.0189259 0.00992702 0.009991 0.0419509 0.0417547 0.0419542 0.0417579 0.0589464 0.0589331 8.14713e-11 6.40011e-11 8.14691e-11 6.39788e-11 6.54327e-10 5.72907e-10 3.6552e-07 3.17418e-07 3.65574e-07 3.17474e-07 5.0001e-08 0 0 0 0 0 0 0 0
263 26085000 0.982829 0.982943 -0.0113158 -0.0115499 -0.00957649 -0.00942197 0.183925 0.183305 -0.0301852 -0.0297601 0.000870812 -0.00174711 0.0142184 0.0149582 0.149628 0.150027 -0.0659586 -0.0672876 -3.51884 -3.55651 -1.22638e-05 -1.20798e-05 -5.88082e-05 -5.92756e-05 1.14357e-06 3.00492e-06 -4.38725e-05 -7.07073e-05 -0.000231392 -0.000254545 -0.00121688 -0.00121898 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.16409e-06 5.13636e-06 1.53923e-05 1.28782e-05 1.53891e-05 1.28774e-05 0.000149347 0.000148616 0.0207244 0.0201993 0.0207281 0.020203 0.0100018 0.01007 0.0465588 0.0462961 0.0465627 0.0462999 0.0590997 0.0590945 8.15706e-11 6.41006e-11 8.15682e-11 6.40782e-11 6.53708e-10 5.72455e-10 3.65522e-07 3.17422e-07 3.65577e-07 3.17478e-07 5e-08 0 0 0 0 0 0 0 0
264 26185000 0.982824 0.98294 -0.0112931 -0.0115245 -0.0101021 -0.00994349 0.183924 0.183298 -0.035796 -0.0355138 0.0044418 0.00199798 0.00977287 0.0104829 0.140966 0.141267 -0.0619364 -0.0630342 -3.5222 -3.55991 -1.22622e-05 -1.20767e-05 -5.88052e-05 -5.92738e-05 1.17045e-06 3.02669e-06 -4.16772e-05 -6.87633e-05 -0.000234318 -0.000257645 -0.00121506 -0.00121712 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 5.05309e-06 5.02442e-06 1.55288e-05 1.29874e-05 1.5523e-05 1.29842e-05 0.000146007 0.000145241 0.0185764 0.0181389 0.0185793 0.0181419 0.00990418 0.00997408 0.0416447 0.0414484 0.0416477 0.0414513 0.0586678 0.0586683 8.14694e-11 6.40708e-11 8.1467e-11 6.40485e-11 6.5305e-10 5.71974e-10 3.5731e-07 3.08982e-07 3.57364e-07 3.09038e-07 5e-08 0 0 0 0 0 0 0 0
265 26285000 0.982822 0.982939 -0.0113612 -0.011594 -0.0104151 -0.0102544 0.183913 0.183281 -0.0375331 -0.0372955 0.00574464 0.00312647 0.00380734 0.00451018 0.137284 0.13761 -0.0614615 -0.0628119 -3.52333 -3.56106 -1.22621e-05 -1.20767e-05 -5.88038e-05 -5.92726e-05 1.13568e-06 2.99503e-06 -4.15661e-05 -6.86618e-05 -0.000234399 -0.000257718 -0.00121441 -0.00121645 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.97296e-06 4.94274e-06 1.57834e-05 1.3194e-05 1.57763e-05 1.31897e-05 0.00014381 0.000142997 0.0198184 0.0193455 0.0198213 0.0193485 0.0100643 0.0101387 0.0461412 0.0458826 0.0461447 0.045886 0.0597049 0.0597141 8.15688e-11 6.41704e-11 8.15663e-11 6.4148e-11 6.52559e-10 5.7162e-10 3.57314e-07 3.08988e-07 3.57368e-07 3.09044e-07 5.0002e-08 0 0 0 0 0 0 0 0
266 26385000 0.982853 0.982971 -0.0108519 -0.0110817 -0.0103912 -0.010229 0.183778 0.183139 -0.0429695 -0.0427979 0.0104166 0.00796384 0.00689702 0.0075736 0.124995 0.125281 -0.0563044 -0.0574301 -3.52337 -3.56114 -1.22488e-05 -1.20649e-05 -5.87829e-05 -5.92562e-05 1.11409e-06 2.97483e-06 -3.68137e-05 -6.3999e-05 -0.000238881 -0.000262314 -0.00121426 -0.00121625 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.85994e-06 4.82884e-06 1.59176e-05 1.33011e-05 1.59083e-05 1.32946e-05 0.000140809 0.000139959 0.0178084 0.017413 0.0178105 0.0174151 0.00996542 0.010041 0.0413305 0.0411363 0.0413332 0.0411388 0.0592657 0.0592804 8.15217e-11 6.41744e-11 8.15191e-11 6.41521e-11 6.51834e-10 5.71086e-10 3.50908e-07 3.02279e-07 3.50962e-07 3.02335e-07 5.0002e-08 0 0 0 0 0 0 0 0
267 26485000 0.982861 0.982981 -0.0106073 -0.0108383 -0.0102812 -0.0101171 0.183753 0.183108 -0.0464017 -0.0462765 0.0134014 0.0107869 0.0159905 0.0166541 0.120529 0.12083 -0.055135 -0.0565139 -3.52227 -3.56007 -1.22492e-05 -1.20652e-05 -5.87824e-05 -5.92557e-05 1.09026e-06 2.95248e-06 -3.67942e-05 -6.39766e-05 -0.000238883 -0.000262318 -0.00121425 -0.0012162 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.75857e-06 4.72648e-06 1.61802e-05 1.35136e-05 1.61701e-05 1.35065e-05 0.000137968 0.000137081 0.0189741 0.0185472 0.0189761 0.0185494 0.0100407 0.0101199 0.0457184 0.045466 0.0457214 0.045469 0.0594242 0.0594477 8.16209e-11 6.42739e-11 8.16181e-11 6.42515e-11 6.51071e-10 5.70524e-10 3.50911e-07 3.02283e-07 3.50964e-07 3.02339e-07 5.0001e-08 0 0 0 0 0 0 0 0
268 26585000 0.982848 0.982969 -0.0101153 -0.0103419 -0.0105554 -0.0103871 0.183837 0.183186 -0.0469455 -0.0469466 0.0186541 0.0162117 0.0163559 0.016988 0.111904 0.112121 -0.0508827 -0.052029 -3.52256 -3.56041 -1.22392e-05 -1.20566e-05 -5.87733e-05 -5.9249e-05 1.05561e-06 2.91897e-06 -3.494e-05 -6.24549e-05 -0.000241393 -0.000264673 -0.00121265 -0.00121456 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.66732e-06 4.63413e-06 1.63136e-05 1.36204e-05 1.63005e-05 1.36105e-05 0.000135274 0.000134349 0.0170994 0.0167398 0.0171006 0.0167411 0.00994233 0.0100222 0.0410105 0.0408199 0.0410128 0.0408222 0.0589906 0.059019 8.16171e-11 6.43055e-11 8.16144e-11 6.42833e-11 6.50267e-10 5.69928e-10 3.45964e-07 2.96992e-07 3.46016e-07 2.97046e-07 5.0001e-08 0 0 0 0 0 0 0 0
269 26685000 0.982841 0.982964 -0.00999544 -0.0102231 -0.0102648 -0.0100946 0.183896 0.183239 -0.0489712 -0.0490283 0.023406 0.0207991 0.0154923 0.0161103 0.107094 0.107307 -0.0487789 -0.0501775 -3.52108 -3.55896 -1.22402e-05 -1.20575e-05 -5.87719e-05 -5.92478e-05 9.93074e-07 2.86238e-06 -3.48919e-05 -6.24075e-05 -0.000241405 -0.000264684 -0.0012126 -0.00121447 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.57717e-06 4.54291e-06 1.65846e-05 1.38395e-05 1.65719e-05 1.38299e-05 0.00013273 0.000131766 0.0182152 0.0178254 0.0182161 0.0178265 0.0100172 0.0101005 0.0452936 0.0450489 0.0452962 0.0450515 0.059149 0.0591864 8.17162e-11 6.44049e-11 8.17134e-11 6.43826e-11 6.49424e-10 5.69304e-10 3.45966e-07 2.96996e-07 3.46018e-07 2.9705e-07 5e-08 0 0 0 0 0 0 0 0
270 26785000 0.982862 0.982985 -0.00983321 -0.0100543 -0.0097568 -0.00958317 0.18382 0.183157 -0.0543074 -0.054462 0.0247524 0.0223467 0.0141411 0.0147337 0.0959522 0.0961118 -0.0463284 -0.0474756 -3.52379 -3.56172 -1.22255e-05 -1.20458e-05 -5.87514e-05 -5.92318e-05 9.68442e-07 2.83767e-06 -3.09705e-05 -5.87158e-05 -0.000243279 -0.00026615 -0.00121068 -0.00121251 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.48877e-06 4.45346e-06 1.67114e-05 1.39409e-05 1.66994e-05 1.39321e-05 0.000130322 0.000129319 0.0164648 0.0161333 0.0164654 0.016134 0.00991948 0.010003 0.0406874 0.0405017 0.0406893 0.0405036 0.0587207 0.0587625 8.17458e-11 6.4458e-11 8.17431e-11 6.4436e-11 6.48537e-10 5.68645e-10 3.42204e-07 2.92872e-07 3.42253e-07 2.92924e-07 5e-08 0 0 0 0 0 0 0 0
271 26885000 0.982891 0.983016 -0.00923174 -0.00945408 -0.00984586 -0.0096706 0.183691 0.183024 -0.0601664 -0.0603901 0.02732 0.0247583 0.00977473 0.0103582 0.0901923 0.0903326 -0.0437293 -0.0451249 -3.52309 -3.56105 -1.22244e-05 -1.20448e-05 -5.87523e-05 -5.92325e-05 1.01873e-06 2.87958e-06 -3.09747e-05 -5.87154e-05 -0.000243302 -0.000266177 -0.00121049 -0.00121228 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.40862e-06 4.37213e-06 1.69927e-05 1.41682e-05 1.69785e-05 1.41575e-05 0.000128037 0.000126995 0.0175359 0.0171748 0.0175365 0.0171755 0.0099941 0.0100806 0.0448707 0.0446346 0.0448728 0.0446368 0.0588791 0.0589298 8.18449e-11 6.45574e-11 8.18421e-11 6.45353e-11 6.47611e-10 5.67956e-10 3.42206e-07 2.92876e-07 3.42254e-07 2.92927e-07 5e-08 0 0 0 0 0 0 0 0
272 26985000 0.982885 0.98301 -0.00874856 -0.00896551 -0.0103346 -0.0101555 0.183723 0.183049 -0.0659871 -0.0663049 0.031168 0.0287798 0.00780453 0.00836775 0.0788657 0.0789579 -0.0400748 -0.0412439 -3.52758 -3.56557 -1.22002e-05 -1.20258e-05 -5.87321e-05 -5.92168e-05 9.88699e-07 2.85001e-06 -2.78054e-05 -5.58636e-05 -0.000245951 -0.000268394 -0.00120809 -0.00120986 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.35911e-06 4.32071e-06 1.71161e-05 1.42681e-05 1.70988e-05 1.42544e-05 0.000126598 0.000125503 0.0158996 0.0155887 0.0158999 0.0155891 0.00998011 0.0100671 0.0403644 0.0401844 0.040366 0.040186 0.0593227 0.059379 8.1897e-11 6.46255e-11 8.18944e-11 6.46037e-11 6.4691e-10 5.67438e-10 3.3939e-07 2.89704e-07 3.39434e-07 2.89752e-07 5.0002e-08 0 0 0 0 0 0 0 0
273 27085000 0.982885 0.983011 -0.00857843 -0.00879661 -0.0106675 -0.0104861 0.183712 0.183033 -0.0682911 -0.0686799 0.0382355 0.0356962 0.0116367 0.0121825 0.0720778 0.072134 -0.0365868 -0.0380013 -3.53097 -3.56899 -1.21984e-05 -1.20244e-05 -5.873e-05 -5.92152e-05 9.7532e-07 2.83495e-06 -2.75956e-05 -5.56789e-05 -0.000246174 -0.000268592 -0.0012065 -0.00120825 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.28679e-06 4.24712e-06 1.74065e-05 1.45028e-05 1.73875e-05 1.44875e-05 0.000124516 0.00012338 0.0169251 0.0165852 0.0169249 0.0165852 0.0100554 0.010145 0.0444534 0.0442261 0.044455 0.0442279 0.0594856 0.0595509 8.1996e-11 6.47249e-11 8.19933e-11 6.47031e-11 6.45909e-10 5.66691e-10 3.39392e-07 2.89708e-07 3.39436e-07 2.89756e-07 5.0001e-08 0 0 0 0 0 0 0 0
274 27185000 0.982891 0.983019 -0.00864484 -0.00885664 -0.0105763 -0.0103906 0.183678 0.182995 -0.0732143 -0.0736983 0.0414971 0.0391312 0.0128894 0.0134167 0.0625859 0.0625973 -0.0328775 -0.0340678 -3.53346 -3.57152 -1.21712e-05 -1.20035e-05 -5.87143e-05 -5.92029e-05 9.6371e-07 2.82156e-06 -2.56721e-05 -5.40777e-05 -0.000248117 -0.000269987 -0.00120504 -0.00120674 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.21713e-06 4.1762e-06 1.75195e-05 1.4595e-05 1.75005e-05 1.45798e-05 0.00012254 0.000121362 0.0153919 0.0150953 0.0153914 0.015095 0.00995679 0.0100458 0.0400443 0.0398701 0.0400455 0.0398713 0.0590545 0.0591233 8.20584e-11 6.48005e-11 8.20561e-11 6.4779e-11 6.44861e-10 5.65906e-10 3.37312e-07 2.87297e-07 3.3735e-07 2.87342e-07 5.0001e-08 0 0 0 0 0 0 0 0
275 27285000 0.982899 0.983027 -0.00881183 -0.00902531 -0.0114981 -0.0113101 0.183577 0.182889 -0.0798938 -0.0804315 0.0473005 0.0448393 0.115736 0.116251 0.05497 0.0549291 -0.0284512 -0.0298832 -3.5316 -3.56969 -1.21699e-05 -1.20025e-05 -5.87133e-05 -5.92021e-05 9.65735e-07 2.81998e-06 -2.55469e-05 -5.39661e-05 -0.000248258 -0.000270114 -0.00120404 -0.00120573 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.14929e-06 4.10702e-06 1.78199e-05 1.48379e-05 1.77979e-05 1.48199e-05 0.000120664 0.000119444 0.0163049 0.0159877 0.0163043 0.0159872 0.0100317 0.0101222 0.0440434 0.0438248 0.0440446 0.0438261 0.0592171 0.0592946 8.21573e-11 6.48997e-11 8.2155e-11 6.48783e-11 6.43773e-10 5.65091e-10 3.37315e-07 2.87302e-07 3.37351e-07 2.87345e-07 5.0001e-08 0 0 0 0 0 0 0 0
276 27385000 0.982858 0.982988 -0.0101697 -0.0103787 -0.0139733 -0.013776 0.18355 0.182859 -0.083366 -0.0839443 0.0522104 0.0500432 0.431605 0.432084 0.0470233 0.0469192 -0.0232465 -0.0244654 -3.51336 -3.55152 -1.21324e-05 -1.19735e-05 -5.86804e-05 -5.91769e-05 9.66051e-07 2.81266e-06 -2.34566e-05 -5.27383e-05 -0.000250901 -0.000272094 -0.0011991 -0.00120076 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.08893e-06 4.04509e-06 1.79365e-05 1.49351e-05 1.79082e-05 1.49112e-05 0.000118868 0.000117606 0.0146316 0.0143782 0.0146308 0.0143775 0.00993236 0.0100193 0.039723 0.039555 0.0397239 0.0395559 0.0587853 0.0588655 8.22214e-11 6.49772e-11 8.22195e-11 6.49562e-11 6.42634e-10 5.64235e-10 3.35786e-07 2.85477e-07 3.35817e-07 2.85516e-07 5e-08 0 0 0 0 0 0 0 0
277 27485000 0.982804 0.982934 -0.0116112 -0.0118226 -0.0159451 -0.0157444 0.183598 0.182902 -0.0863859 -0.0869621 0.0577208 0.0555558 0.750679 0.751146 0.03849 0.0383278 -0.0177318 -0.0191663 -3.45574 -3.49392 -1.21321e-05 -1.19734e-05 -5.86779e-05 -5.91749e-05 9.01037e-07 2.75195e-06 -2.33099e-05 -5.26092e-05 -0.000251058 -0.000272232 -0.00119816 -0.0011998 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 4.03106e-06 3.98563e-06 1.82488e-05 1.51883e-05 1.82156e-05 1.516e-05 0.000117165 0.000115861 0.0153314 0.0150773 0.0153302 0.0150763 0.0100067 0.0100932 0.043612 0.0434042 0.0436129 0.0434051 0.0589474 0.0590355 8.23203e-11 6.50765e-11 8.23184e-11 6.50555e-11 6.41457e-10 5.6335e-10 3.35788e-07 2.85482e-07 3.35817e-07 2.85519e-07 5e-08 0 0 0 0 0 0 0 0
278 27585000 0.982825 0.982956 -0.0116152 -0.0118161 -0.0149571 -0.0147479 0.183567 0.182868 -0.0795653 -0.080238 0.0587175 0.0567522 0.855308 0.855688 0.0314072 0.0312006 -0.0154845 -0.0166737 -3.39495 -3.43324 -1.20764e-05 -1.19303e-05 -5.8642e-05 -5.91476e-05 8.86199e-07 2.71978e-06 -2.04974e-05 -5.05819e-05 -0.000253853 -0.00027386 -0.00118298 -0.00118466 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.99519e-06 3.9478e-06 1.83757e-05 1.52908e-05 1.83466e-05 1.52665e-05 0.000116174 0.000114812 0.0139499 0.0137316 0.0139481 0.0137299 0.00999228 0.0100775 0.0393851 0.0392248 0.0393857 0.0392255 0.0593946 0.0594872 8.23906e-11 6.5158e-11 8.23892e-11 6.51375e-11 6.40564e-10 5.62683e-10 3.34618e-07 2.84033e-07 3.34641e-07 2.84065e-07 5.0002e-08 0 0 0 0 0 0 0 0
279 27685000 0.982893 0.983025 -0.0104683 -0.010668 -0.0120647 -0.011854 0.183483 0.18278 -0.0759941 -0.0768183 0.0545478 0.0523916 0.762342 0.762714 0.0236665 0.0233842 -0.00975773 -0.0111521 -3.31682 -3.35515 -1.20744e-05 -1.19287e-05 -5.8641e-05 -5.91468e-05 9.0717e-07 2.73381e-06 -2.03458e-05 -5.04486e-05 -0.000254036 -0.000274024 -0.0011817 -0.00118337 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.93877e-06 3.89029e-06 1.868e-05 1.55346e-05 1.86588e-05 1.55179e-05 0.000114641 0.000113235 0.0149339 0.0146794 0.0149321 0.0146777 0.0100671 0.0101546 0.0431814 0.0429843 0.0431819 0.0429849 0.0595609 0.0596611 8.24895e-11 6.52572e-11 8.2488e-11 6.52367e-11 6.39307e-10 5.61736e-10 3.34621e-07 2.84037e-07 3.34641e-07 2.84068e-07 5.0002e-08 0 0 0 0 0 0 0 0
280 27785000 0.982928 0.98306 -0.00913445 -0.00932519 -0.0104794 -0.0102641 0.183466 0.182759 -0.0740758 -0.075015 0.049951 0.0479237 0.749749 0.750133 0.0187596 0.0184526 -0.00904204 -0.0102233 -3.24302 -3.28136 -1.20356e-05 -1.18991e-05 -5.86231e-05 -5.91324e-05 9.43197e-07 2.76426e-06 -1.97483e-05 -5.03125e-05 -0.000254309 -0.000273405 -0.00118283 -0.00118445 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.88925e-06 3.83946e-06 1.87913e-05 1.56263e-05 1.87721e-05 1.56115e-05 0.000113171 0.000111722 0.0137308 0.0134964 0.0137293 0.0134948 0.0099666 0.0100527 0.0390551 0.0389019 0.0390555 0.0389023 0.0591255 0.0592269 8.25399e-11 6.53272e-11 8.25392e-11 6.53073e-11 6.37997e-10 5.60747e-10 3.33768e-07 2.82964e-07 3.33781e-07 2.82989e-07 5.0001e-08 0 0 0 0 0 0 0 0
281 27885000 0.982925 0.983058 -0.0087477 -0.00893935 -0.0105573 -0.01034 0.183496 0.182786 -0.0805873 -0.0816284 0.0556657 0.0535257 0.791409 0.791785 0.011038 0.0106311 -0.0038109 -0.00519984 -3.16836 -3.20673 -1.2034e-05 -1.18979e-05 -5.8622e-05 -5.91316e-05 9.48066e-07 2.76383e-06 -1.96183e-05 -5.01981e-05 -0.000254467 -0.000273545 -0.00118177 -0.00118338 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.84346e-06 3.79218e-06 1.9113e-05 1.58858e-05 1.90923e-05 1.58697e-05 0.000111769 0.000110277 0.0146046 0.0143423 0.0146028 0.0143405 0.0100413 0.0101284 0.0427809 0.0425918 0.042781 0.0425921 0.059291 0.0593996 8.26386e-11 6.54263e-11 8.2638e-11 6.54065e-11 6.36649e-10 5.59727e-10 3.33771e-07 2.82969e-07 3.33781e-07 2.82992e-07 5.0001e-08 0 0 0 0 0 0 0 0
282 27985000 0.982924 0.983057 -0.00920327 -0.00938487 -0.0109404 -0.0107145 0.183459 0.182746 -0.0803952 -0.0815621 0.0560478 0.0540573 0.77874 0.779094 0.00682248 0.00638833 -0.00354813 -0.00471807 -3.09797 -3.13639 -1.19698e-05 -1.18487e-05 -5.85851e-05 -5.91022e-05 9.53314e-07 2.76009e-06 -1.7896e-05 -4.92325e-05 -0.000256363 -0.000274154 -0.00117708 -0.00117866 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.7974e-06 3.74463e-06 1.92125e-05 1.59708e-05 1.91914e-05 1.59544e-05 0.000110433 0.000108897 0.013474 0.0132278 0.0134722 0.0132261 0.00994161 0.0100268 0.0387443 0.0385964 0.0387444 0.0385965 0.05886 0.0589692 8.26588e-11 6.54782e-11 8.26593e-11 6.54592e-11 6.35246e-10 5.58665e-10 3.33142e-07 2.82184e-07 3.33145e-07 2.82201e-07 5e-08 0 0 0 0 0 0 0 0
283 28085000 0.982945 0.983079 -0.00953636 -0.00971888 -0.0109465 -0.0107181 0.183327 0.182613 -0.0839011 -0.0852013 0.0560233 0.0539041 0.784973 0.785328 -0.00135339 -0.00191157 0.00209105 0.000715123 -3.02022 -3.05866 -1.19682e-05 -1.18473e-05 -5.85868e-05 -5.91036e-05 1.03943e-06 2.83146e-06 -1.79106e-05 -4.92397e-05 -0.000256372 -0.000274167 -0.00117696 -0.00117853 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.75359e-06 3.69935e-06 1.95408e-05 1.62356e-05 1.95201e-05 1.62197e-05 0.000109166 0.000107585 0.014374 0.0140926 0.0143723 0.0140909 0.0100156 0.0101017 0.0424058 0.0422223 0.0424057 0.0422222 0.0590246 0.0591407 8.27575e-11 6.55773e-11 8.2758e-11 6.55584e-11 6.33805e-10 5.57573e-10 3.33145e-07 2.82189e-07 3.33144e-07 2.82203e-07 5e-08 0 0 0 0 0 0 0 0
284 28185000 0.982948 0.983083 -0.00903554 -0.00920746 -0.0112464 -0.0110121 0.183317 0.1826 -0.0832708 -0.0846723 0.0511408 0.0491819 0.790807 0.791155 -0.00704884 -0.00760657 0.00131445 0.000153068 -2.946 -2.98447 -1.18976e-05 -1.17931e-05 -5.85561e-05 -5.90785e-05 1.04254e-06 2.82771e-06 -1.62359e-05 -4.80889e-05 -0.000258545 -0.000275026 -0.00117443 -0.00117597 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.71265e-06 3.6569e-06 1.96175e-05 1.63048e-05 1.95947e-05 1.62868e-05 0.000107957 0.000106332 0.0132918 0.0130255 0.0132905 0.0130241 0.00991604 0.00999996 0.0384538 0.0383091 0.0384536 0.038309 0.0585979 0.058714 8.27321e-11 6.56014e-11 8.27337e-11 6.55835e-11 6.32309e-10 5.56436e-10 3.32648e-07 2.81614e-07 3.32638e-07 2.81622e-07 5e-08 0 0 0 0 0 0 0 0
285 28285000 0.982968 0.983103 -0.00852369 -0.00869654 -0.011538 -0.0113016 0.183219 0.182499 -0.0883206 -0.0898653 0.0536467 0.051566 0.791373 0.791724 -0.0155852 -0.0162914 0.00660052 0.00523746 -2.86935 -2.90783 -1.18952e-05 -1.17911e-05 -5.85565e-05 -5.90789e-05 1.10707e-06 2.88009e-06 -1.6145e-05 -4.80077e-05 -0.000258676 -0.000275143 -0.00117352 -0.00117506 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.69114e-06 3.63312e-06 1.99537e-05 1.65762e-05 1.99287e-05 1.65563e-05 0.000107337 0.00010565 0.0141984 0.013892 0.014197 0.0138905 0.0100747 0.0101602 0.0420598 0.0418787 0.0420594 0.0418784 0.0596376 0.0597637 8.2831e-11 6.57007e-11 8.28328e-11 6.56829e-11 6.31185e-10 5.55589e-10 3.32653e-07 2.8162e-07 3.3264e-07 2.81626e-07 5.0002e-08 0 0 0 0 0 0 0 0
286 28385000 0.982956 0.983092 -0.00856215 -0.0087259 -0.0121714 -0.0119249 0.183238 0.182518 -0.0881812 -0.0898497 0.0554364 0.053495 0.79238 0.792727 -0.0194335 -0.0201488 0.00863466 0.00746234 -2.79655 -2.83506 -1.18197e-05 -1.17329e-05 -5.84967e-05 -5.90308e-05 1.18376e-06 2.94108e-06 -1.35962e-05 -4.64826e-05 -0.000261594 -0.000276838 -0.00117084 -0.00117235 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.65835e-06 3.59866e-06 2.00048e-05 1.66278e-05 1.99777e-05 1.6606e-05 0.000106225 0.000104493 0.0131753 0.0128817 0.0131741 0.0128803 0.00997399 0.010057 0.0381863 0.0380423 0.0381859 0.038042 0.0592025 0.0593279 8.2747e-11 6.56888e-11 8.275e-11 6.5672e-11 6.29605e-10 5.54386e-10 3.32205e-07 2.81183e-07 3.32184e-07 2.81183e-07 5.0001e-08 0 0 0 0 0 0 0 0
287 28485000 0.982953 0.983089 -0.00888574 -0.00905038 -0.0126731 -0.0124237 0.183205 0.182482 -0.0894677 -0.0912941 0.057758 0.0556954 0.793499 0.79384 -0.0282848 -0.029177 0.0142706 0.0128989 -2.7219 -2.76043 -1.18174e-05 -1.17311e-05 -5.8495e-05 -5.90294e-05 1.18553e-06 2.93622e-06 -1.33989e-05 -4.63122e-05 -0.000261844 -0.000277057 -0.00116921 -0.00117072 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.62207e-06 3.56082e-06 2.03474e-05 1.69046e-05 2.0319e-05 1.68816e-05 0.000105174 0.000103398 0.0140873 0.013749 0.0140859 0.0137474 0.0100482 0.0101316 0.0417466 0.0415643 0.041746 0.0415638 0.0593699 0.0595013 8.28456e-11 6.57878e-11 8.28487e-11 6.57711e-11 6.27987e-10 5.53154e-10 3.32209e-07 2.81188e-07 3.32184e-07 2.81185e-07 5.0001e-08 0 0 0 0 0 0 0 0
288 28585000 0.982987 0.983123 -0.00898251 -0.0091317 -0.0126536 -0.0123953 0.183019 0.182295 -0.0826345 -0.0845872 0.0523702 0.0505013 0.790836 0.791181 -0.0308891 -0.0317764 0.0112113 0.0100696 -2.64635 -2.68491 -1.17004e-05 -1.16406e-05 -5.84466e-05 -5.89894e-05 1.24598e-06 2.9833e-06 -1.12912e-05 -4.49545e-05 -0.000265794 -0.000279081 -0.0011675 -0.00116896 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.58366e-06 3.52098e-06 2.03662e-05 1.69332e-05 2.0338e-05 1.69105e-05 0.000104176 0.000102355 0.0131143 0.0127875 0.0131131 0.012786 0.00994752 0.0100284 0.0379449 0.0377986 0.0379443 0.0377982 0.058939 0.0590692 8.26894e-11 6.57311e-11 8.2694e-11 6.57156e-11 6.26312e-10 5.51875e-10 3.3174e-07 2.80826e-07 3.31706e-07 2.80816e-07 5.0001e-08 0 0 0 0 0 0 0 0
289 28685000 0.982983 0.98312 -0.00878077 -0.00892989 -0.0120444 -0.0117836 0.18309 0.182364 -0.0823097 -0.0844371 0.0522731 0.0502898 0.791671 0.792011 -0.0391251 -0.0402184 0.0164706 0.015137 -2.57129 -2.60987 -1.16984e-05 -1.16391e-05 -5.84448e-05 -5.89879e-05 1.23772e-06 2.96897e-06 -1.11103e-05 -4.47984e-05 -0.000266025 -0.000279283 -0.00116602 -0.00116747 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.55385e-06 3.48963e-06 2.07113e-05 1.72118e-05 2.06845e-05 1.71905e-05 0.000103224 0.000101358 0.0140368 0.0136602 0.0140356 0.0136586 0.0100202 0.0101012 0.0414688 0.0412814 0.041468 0.0412807 0.0590998 0.0592354 8.2788e-11 6.58301e-11 8.27926e-11 6.58147e-11 6.24597e-10 5.50566e-10 3.31743e-07 2.80831e-07 3.31705e-07 2.80818e-07 5e-08 0 0 0 0 0 0 0 0
290 28785000 0.983004 0.98314 -0.00816145 -0.00830017 -0.0118646 -0.0115932 0.183021 0.182295 -0.0777518 -0.080009 0.0513937 0.0495528 0.790257 0.79059 -0.0410242 -0.0421044 0.0176993 0.0165511 -2.49908 -2.53769 -1.16101e-05 -1.15707e-05 -5.83665e-05 -5.89239e-05 1.3243e-06 3.03673e-06 -7.64126e-06 -4.24706e-05 -0.000269644 -0.000281578 -0.00116248 -0.00116392 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.52387e-06 3.45811e-06 2.06951e-05 1.72159e-05 2.06679e-05 1.71943e-05 0.000102317 0.000100407 0.0130984 0.0127341 0.0130974 0.0127327 0.00992009 0.00999835 0.0377314 0.0375798 0.0377308 0.0375792 0.0586729 0.0588068 8.25463e-11 6.57199e-11 8.25525e-11 6.57058e-11 6.22828e-10 5.49213e-10 3.31189e-07 2.80489e-07 3.31142e-07 2.80469e-07 5e-08 0 0 0 0 0 0 0 0
291 28885000 0.983031 0.983168 -0.00798417 -0.0081231 -0.011604 -0.01133 0.182899 0.182172 -0.0816041 -0.0840488 0.052234 0.0502895 0.78956 0.789899 -0.0489657 -0.0502826 0.0228721 0.021535 -2.42295 -2.46157 -1.16077e-05 -1.15687e-05 -5.83667e-05 -5.89241e-05 1.38235e-06 3.0823e-06 -7.53542e-06 -4.23766e-05 -0.000269796 -0.000281713 -0.00116146 -0.00116289 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.50873e-06 3.44071e-06 2.10462e-05 1.74999e-05 2.10193e-05 1.74785e-05 0.000101935 9.99611e-05 0.0140362 0.0136165 0.0140353 0.0136152 0.0100785 0.0101576 0.0412281 0.0410313 0.0412272 0.0410304 0.0597164 0.0598592 8.26452e-11 6.58191e-11 8.26514e-11 6.58051e-11 6.21501e-10 5.48203e-10 3.31194e-07 2.80495e-07 3.31144e-07 2.80473e-07 5.0002e-08 0 0 0 0 0 0 0 0
292 28985000 0.983018 0.983156 -0.00777781 -0.00790241 -0.0118401 -0.0115541 0.182961 0.182234 -0.0770193 -0.0796118 0.0481341 0.0463818 0.788678 0.789013 -0.047912 -0.0492147 0.0216162 0.0204919 -2.35176 -2.39039 -1.14827e-05 -1.14714e-05 -5.82817e-05 -5.88538e-05 1.41663e-06 3.1037e-06 -4.05766e-06 -4.00905e-05 -0.000274853 -0.000284925 -0.00115771 -0.00115912 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.48467e-06 3.41495e-06 2.09925e-05 1.74781e-05 2.09648e-05 1.74559e-05 0.000101101 9.90829e-05 0.0131256 0.0127199 0.0131251 0.0127189 0.00997706 0.0100532 0.0375476 0.0373872 0.0375469 0.0373864 0.0592807 0.0594214 8.23057e-11 6.56474e-11 8.23143e-11 6.56348e-11 6.19647e-10 5.46783e-10 3.30501e-07 2.80125e-07 3.30442e-07 2.80096e-07 5.0002e-08 0 0 0 0 0 0 0 0
293 29085000 0.983019 0.983157 -0.00766575 -0.00779065 -0.0118843 -0.0115956 0.182958 0.18223 -0.0797999 -0.0825951 0.0494145 0.0475658 0.788383 0.788722 -0.055815 -0.057389 0.0264658 0.0251618 -2.27487 -2.31352 -1.14813e-05 -1.14703e-05 -5.82813e-05 -5.88534e-05 1.43526e-06 3.11286e-06 -3.97365e-06 -4.00183e-05 -0.000274966 -0.000285022 -0.00115702 -0.00115842 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.4589e-06 3.3876e-06 2.13483e-05 1.77664e-05 2.13203e-05 1.77439e-05 0.000100313 9.82502e-05 0.0140787 0.0136125 0.0140783 0.0136115 0.0100501 0.0101259 0.0410255 0.0408151 0.0410246 0.0408142 0.059444 0.0595889 8.24038e-11 6.5746e-11 8.24133e-11 6.57342e-11 6.17753e-10 5.4533e-10 3.30505e-07 2.8013e-07 3.30441e-07 2.80098e-07 5.0001e-08 0 0 0 0 0 0 0 0
294 29185000 0.983046 0.983183 -0.00763213 -0.00774304 -0.0121245 -0.0118213 0.1828 0.182074 -0.075254 -0.0782209 0.046774 0.0451128 0.782604 0.782937 -0.0531088 -0.0546694 0.0255297 0.0244314 -2.2064 -2.24508 -1.13503e-05 -1.13678e-05 -5.81687e-05 -5.87605e-05 1.5306e-06 3.18674e-06 8.4374e-07 -3.66964e-05 -0.000280442 -0.000288652 -0.0011522 -0.00115359 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.43127e-06 3.35848e-06 2.12528e-05 1.77151e-05 2.12246e-05 1.76924e-05 9.95646e-05 9.74569e-05 0.0131937 0.0127436 0.0131937 0.0127429 0.00994924 0.010022 0.0373944 0.0372218 0.0373937 0.037221 0.0590125 0.0591547 8.19566e-11 6.55054e-11 8.19687e-11 6.54957e-11 6.15806e-10 5.43833e-10 3.29629e-07 2.79692e-07 3.29557e-07 2.79653e-07 5.0001e-08 0 0 0 0 0 0 0 0
295 29285000 0.98303 0.983167 -0.00787892 -0.00798996 -0.0121609 -0.0118546 0.182874 0.182148 -0.0767137 -0.0798943 0.0517461 0.0499959 0.785006 0.785343 -0.0606688 -0.0625386 0.0304991 0.0292303 -2.12948 -2.16817 -1.13484e-05 -1.13664e-05 -5.8169e-05 -5.87608e-05 1.58223e-06 3.22471e-06 9.09802e-07 -3.66382e-05 -0.000280537 -0.000288734 -0.00115169 -0.00115307 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.41209e-06 3.33761e-06 2.16117e-05 1.80065e-05 2.15838e-05 1.79841e-05 9.88472e-05 9.66954e-05 0.0141614 0.0136458 0.0141613 0.013645 0.0100219 0.0100941 0.0408622 0.0406338 0.0408613 0.0406329 0.0591744 0.0593203 8.20547e-11 6.5604e-11 8.20677e-11 6.5595e-11 6.13818e-10 5.42305e-10 3.29633e-07 2.79697e-07 3.29556e-07 2.79655e-07 5e-08 0 0 0 0 0 0 0 0
296 29385000 0.983039 0.983177 -0.00834137 -0.00843987 -0.0116757 -0.0113575 0.182833 0.182108 -0.0720082 -0.075311 0.049996 0.0484219 0.787211 0.787556 -0.0585919 -0.0604037 0.0313222 0.0302469 -2.05435 -2.09305 -1.12347e-05 -1.12772e-05 -5.80731e-05 -5.86797e-05 1.65452e-06 3.28072e-06 4.80468e-06 -3.39223e-05 -0.000285254 -0.000291922 -0.00114988 -0.00115123 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.3901e-06 3.3141e-06 2.14699e-05 1.79221e-05 2.14448e-05 1.79022e-05 9.81681e-05 9.59725e-05 0.0132833 0.0127884 0.0132835 0.0127878 0.00992158 0.00999061 0.0372721 0.037084 0.0372715 0.0370832 0.0587469 0.0588897 8.14915e-11 6.5289e-11 8.15068e-11 6.52816e-11 6.11777e-10 5.40733e-10 3.2854e-07 2.79157e-07 3.28456e-07 2.79109e-07 5e-08 0 0 0 0 0 0 0 0
297 29485000 0.983051 0.983188 -0.00839229 -0.00849073 -0.0115424 -0.0112213 0.182774 0.182052 -0.0740846 -0.0776237 0.049845 0.04819 0.788475 0.788827 -0.0658521 -0.0680073 0.0363375 0.0351005 -1.97761 -2.01631 -1.12314e-05 -1.12744e-05 -5.80754e-05 -5.86816e-05 1.78812e-06 3.3903e-06 4.84682e-06 -3.38767e-05 -0.000285348 -0.00029201 -0.00114915 -0.0011505 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.37075e-06 3.29318e-06 2.18311e-05 1.82159e-05 2.18063e-05 1.81963e-05 9.75224e-05 9.52831e-05 0.0142698 0.0137044 0.0142702 0.0137039 0.0099937 0.0100619 0.0407369 0.0404866 0.0407361 0.0404856 0.0589075 0.0590534 8.159e-11 6.53879e-11 8.16052e-11 6.53805e-11 6.09697e-10 5.3913e-10 3.28545e-07 2.79163e-07 3.28456e-07 2.79111e-07 5e-08 0 0 0 0 0 0 0 0
298 29585000 0.983068 0.983205 -0.00831821 -0.00840268 -0.0115551 -0.0112233 0.182688 0.181966 -0.0692272 -0.0728787 0.0471338 0.0456831 0.790295 0.790666 -0.062973 -0.0650496 0.0355556 0.0345276 -1.89955 -1.93824 -1.1097e-05 -1.1168e-05 -5.79794e-05 -5.8599e-05 1.87904e-06 3.4662e-06 8.72132e-06 -3.10693e-05 -0.000290815 -0.000295765 -0.00114895 -0.00115025 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.36485e-06 3.28492e-06 2.16447e-05 1.81e-05 2.162e-05 1.80805e-05 9.73432e-05 9.50402e-05 0.0134004 0.01286 0.013401 0.0128598 0.00997739 0.0100434 0.0371803 0.0369735 0.0371797 0.0369728 0.0593518 0.0594985 8.09052e-11 6.49935e-11 8.09223e-11 6.49879e-11 6.08123e-10 5.3792e-10 3.27213e-07 2.78496e-07 3.27119e-07 2.7844e-07 5.0002e-08 0 0 0 0 0 0 0 0
299 29685000 0.983093 0.983229 -0.00838674 -0.00847091 -0.0113491 -0.0110142 0.182564 0.181845 -0.073354 -0.0772643 0.0452746 0.0437554 0.786084 0.78646 -0.0700749 -0.072532 0.0402122 0.0390362 -1.82475 -1.86345 -1.1093e-05 -1.11647e-05 -5.79807e-05 -5.86001e-05 1.99599e-06 3.56e-06 8.84523e-06 -3.09549e-05 -0.000291016 -0.000295944 -0.00114752 -0.00114882 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.34431e-06 3.26292e-06 2.20074e-05 1.83957e-05 2.19832e-05 1.83767e-05 9.67578e-05 9.44115e-05 0.0144118 0.0137954 0.0144129 0.0137954 0.0100502 0.0101153 0.0406492 0.0403733 0.0406486 0.0403724 0.0595159 0.0596651 8.10037e-11 6.50924e-11 8.10206e-11 6.50868e-11 6.05962e-10 5.36251e-10 3.27217e-07 2.78502e-07 3.27119e-07 2.78443e-07 5.0001e-08 0 0 0 0 0 0 0 0
300 29785000 0.983101 0.983237 -0.00825849 -0.00832929 -0.0118834 -0.0115361 0.182492 0.181775 -0.0687648 -0.0728123 0.037401 0.0360813 0.782412 0.782794 -0.0650965 -0.0674718 0.0377426 0.0367697 -1.75259 -1.7913 -1.09556e-05 -1.10552e-05 -5.78612e-05 -5.84976e-05 2.1297e-06 3.66866e-06 1.39271e-05 -2.71572e-05 -0.000296653 -0.000299857 -0.00114453 -0.00114581 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.32723e-06 3.24427e-06 2.17738e-05 1.82463e-05 2.17482e-05 1.82259e-05 9.61968e-05 9.38077e-05 0.0135462 0.0129598 0.0135477 0.0129602 0.00994912 0.010011 0.0371186 0.0368903 0.0371181 0.0368896 0.0590838 0.059229 8.01914e-11 6.46139e-11 8.021e-11 6.46099e-11 6.03748e-10 5.34539e-10 3.25625e-07 2.77685e-07 3.25521e-07 2.77621e-07 5.0001e-08 0 0 0 0 0 0 0 0
301 29885000 0.983106 0.983241 -0.00776056 -0.00783095 -0.0122752 -0.0119245 0.182462 0.181749 -0.0687259 -0.0730551 0.0370148 0.0356345 0.778739 0.779122 -0.0718681 -0.0746708 0.0414244 0.0403198 -1.68056 -1.71929 -1.09503e-05 -1.10512e-05 -5.78612e-05 -5.8498e-05 2.24018e-06 3.75563e-06 1.41703e-05 -2.69723e-05 -0.000296996 -0.000300126 -0.00114241 -0.00114369 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.31195e-06 3.22737e-06 2.21388e-05 1.8545e-05 2.21111e-05 1.85227e-05 9.56647e-05 9.32334e-05 0.0145756 0.013909 0.0145774 0.0139095 0.0100215 0.0100822 0.0405983 0.0402935 0.040598 0.0402928 0.0592464 0.0593937 8.02895e-11 6.47126e-11 8.03089e-11 6.4709e-11 6.01496e-10 5.32796e-10 3.2563e-07 2.77691e-07 3.25521e-07 2.77624e-07 5.0001e-08 0 0 0 0 0 0 0 0
302 29985000 0.983103 0.983239 -0.00788696 -0.00794104 -0.012351 -0.0119906 0.182466 0.181756 -0.0632587 -0.0676796 0.0320737 0.0309378 0.775707 0.776089 -0.0672122 -0.0698908 0.0372114 0.0363368 -1.61094 -1.64968 -1.07888e-05 -1.09217e-05 -5.77622e-05 -5.84103e-05 2.28938e-06 3.78808e-06 1.84138e-05 -2.36627e-05 -0.000303944 -0.000305129 -0.00113845 -0.00113971 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.2967e-06 3.21062e-06 2.18546e-05 1.83586e-05 2.18276e-05 1.83367e-05 9.51588e-05 9.26856e-05 0.0137019 0.0130719 0.0137038 0.0130727 0.00992013 0.00997763 0.0370856 0.0368336 0.0370855 0.036833 0.058813 0.058956 7.93477e-11 6.41473e-11 7.93697e-11 6.4146e-11 5.9919e-10 5.31007e-10 3.23771e-07 2.76712e-07 3.23657e-07 2.7664e-07 5e-08 0 0 0 0 0 0 0 0
303 30085000 0.983103 0.983239 -0.00804522 -0.00809906 -0.0124954 -0.0121314 0.182448 0.181737 -0.0630623 -0.0677717 0.0317828 0.0305952 0.773728 0.77411 -0.0735247 -0.0766629 0.0404305 0.0394403 -1.53708 -1.57583 -1.07892e-05 -1.09224e-05 -5.77593e-05 -5.84078e-05 2.19848e-06 3.69717e-06 1.8543e-05 -2.35573e-05 -0.000304102 -0.000305264 -0.00113713 -0.0011384 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.27752e-06 3.19008e-06 2.22185e-05 1.86572e-05 2.21914e-05 1.86353e-05 9.46845e-05 9.21698e-05 0.0147487 0.0140348 0.014751 0.0140357 0.00999215 0.0100484 0.0405812 0.040245 0.0405812 0.0402445 0.0589742 0.0591187 7.94458e-11 6.42459e-11 7.94685e-11 6.42452e-11 5.96849e-10 5.2919e-10 3.23776e-07 2.76718e-07 3.23658e-07 2.76644e-07 5e-08 0 0 0 0 0 0 0 0
304 30185000 0.98308 0.983217 -0.00803445 -0.00808061 -0.0125153 -0.0121402 0.182571 0.181858 -0.0565065 -0.0612936 0.0282705 0.0272049 0.773639 0.774024 -0.0668405 -0.0698294 0.0391634 0.0383142 -1.46519 -1.50396 -1.07043e-05 -1.08534e-05 -5.76211e-05 -5.8287e-05 2.12766e-06 3.62678e-06 2.43028e-05 -1.90635e-05 -0.000307657 -0.000307776 -0.0011346 -0.00113584 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.27871e-06 3.18886e-06 2.18855e-05 1.84349e-05 2.18591e-05 1.84134e-05 9.46391e-05 9.20614e-05 0.013861 0.013191 0.0138634 0.0131921 0.00997593 0.0100298 0.0370791 0.0368014 0.0370792 0.0368011 0.05942 0.0595641 7.83774e-11 6.35942e-11 7.84022e-11 6.35955e-11 5.95082e-10 5.27822e-10 3.21655e-07 2.7557e-07 3.21534e-07 2.75493e-07 5.0002e-08 0 0 0 0 0 0 0 0
305 30285000 0.983069 0.983205 -0.00807132 -0.00811686 -0.0125183 -0.0121397 0.18263 0.181919 -0.0554512 -0.0605426 0.0272422 0.0261304 0.773885 0.774272 -0.072383 -0.0758701 0.0419541 0.0409973 -1.39287 -1.43164 -1.07012e-05 -1.08511e-05 -5.76202e-05 -5.82863e-05 2.1674e-06 3.65058e-06 2.44914e-05 -1.8901e-05 -0.000307916 -0.000307999 -0.0011328 -0.00113404 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.26753e-06 3.17614e-06 2.22481e-05 1.87334e-05 2.22218e-05 1.87121e-05 9.42027e-05 9.15846e-05 0.0149216 0.0141649 0.0149244 0.0141662 0.0100486 0.0101011 0.0405946 0.0402253 0.040595 0.040225 0.0595846 0.0597298 7.84754e-11 6.36928e-11 7.8501e-11 6.36947e-11 5.92664e-10 5.25942e-10 3.2166e-07 2.75577e-07 3.21535e-07 2.75496e-07 5.0002e-08 0 0 0 0 0 0 0 0
306 30385000 0.98306 0.983195 -0.00806098 -0.00809661 -0.0124533 -0.012062 0.182684 0.181978 -0.0474537 -0.0526485 0.0214886 0.0205227 0.77148 0.771869 -0.0641301 -0.0674681 0.039535 0.0387348 -1.32491 -1.3637 -1.05835e-05 -1.07545e-05 -5.74617e-05 -5.81476e-05 2.34281e-06 3.79424e-06 3.15525e-05 -1.32394e-05 -0.000312947 -0.000311742 -0.00112854 -0.00112978 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.26041e-06 3.16742e-06 2.18676e-05 1.84754e-05 2.18424e-05 1.8455e-05 9.37847e-05 9.11266e-05 0.0140199 0.0133141 0.0140227 0.0133156 0.00994666 0.00999587 0.0370961 0.0367918 0.0370966 0.0367917 0.0591466 0.0592868 7.72847e-11 6.29557e-11 7.73125e-11 6.29598e-11 5.90195e-10 5.24018e-10 3.19291e-07 2.74261e-07 3.19162e-07 2.74177e-07 5.0001e-08 0 0 0 0 0 0 0 0
307 30485000 0.983089 0.983224 -0.00808392 -0.00811895 -0.0125954 -0.0122005 0.182516 0.181815 -0.0498491 -0.0553648 0.020529 0.0195293 0.77245 0.772847 -0.0689497 -0.0728277 0.0416825 0.0407856 -1.25313 -1.29192 -1.05785e-05 -1.07504e-05 -5.74624e-05 -5.81482e-05 2.4645e-06 3.89027e-06 3.17552e-05 -1.30604e-05 -0.000313239 -0.000311995 -0.00112659 -0.00112785 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.24492e-06 3.15062e-06 2.22286e-05 1.87738e-05 2.22031e-05 1.87531e-05 9.33977e-05 9.07002e-05 0.0150955 0.0143004 0.0150988 0.0143022 0.0100192 0.0100668 0.0406348 0.0402313 0.0406355 0.0402314 0.0593098 0.0594505 7.73828e-11 6.30543e-11 7.74113e-11 6.30589e-11 5.87692e-10 5.22067e-10 3.19296e-07 2.74268e-07 3.19164e-07 2.74181e-07 5.0001e-08 0 0 0 0 0 0 0 0
308 30585000 0.983106 0.983239 -0.00839633 -0.00842206 -0.0128909 -0.0124873 0.182392 0.181697 -0.0446043 -0.050143 0.0178099 0.0169689 0.772087 0.772491 -0.0618373 -0.0654953 0.0385534 0.0378177 -1.1814 -1.22021 -1.0464e-05 -1.06554e-05 -5.73324e-05 -5.80305e-05 2.60708e-06 4.00604e-06 3.74881e-05 -8.28661e-06 -0.000318079 -0.000315662 -0.00112397 -0.00112521 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.23213e-06 3.1365e-06 2.18039e-05 1.84823e-05 2.17789e-05 1.84619e-05 9.30277e-05 9.02913e-05 0.0141741 0.0134374 0.0141772 0.0134391 0.00991807 0.00996252 0.0371336 0.0368022 0.0371343 0.0368023 0.058876 0.0590116 7.6077e-11 6.22349e-11 7.61073e-11 6.22415e-11 5.8514e-10 5.20073e-10 3.16696e-07 2.72788e-07 3.16562e-07 2.727e-07 5e-08 0 0 0 0 0 0 0 0
309 30685000 0.983124 0.983257 -0.00877634 -0.00880141 -0.0131297 -0.012722 0.182258 0.181567 -0.0426827 -0.0485618 0.0153288 0.0144556 0.770983 0.77139 -0.0662609 -0.0704961 0.0402526 0.0394336 -1.11033 -1.14915 -1.04607e-05 -1.0653e-05 -5.73315e-05 -5.80298e-05 2.65054e-06 4.03224e-06 3.77032e-05 -8.11043e-06 -0.000318369 -0.000315903 -0.00112179 -0.00112305 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.21716e-06 3.12027e-06 2.21622e-05 1.87798e-05 2.21373e-05 1.87593e-05 9.26808e-05 8.99064e-05 0.0152671 0.0144387 0.0152707 0.0144407 0.00999012 0.0100329 0.0406977 0.0402602 0.0406988 0.0402606 0.0590379 0.0591734 7.61751e-11 6.23336e-11 7.62061e-11 6.23405e-11 5.82555e-10 5.18053e-10 3.16702e-07 2.72795e-07 3.16564e-07 2.72705e-07 5e-08 0 0 0 0 0 0 0 0
310 30785000 0.983152 0.983285 -0.00848439 -0.00850967 -0.0128537 -0.0124409 0.182139 0.18145 -0.0350602 -0.0408793 0.0102288 0.00936385 0.769542 0.769945 -0.0591437 -0.0630761 0.0399945 0.0392263 -1.04039 -1.07923 -1.04502e-05 -1.06417e-05 -5.72023e-05 -5.7911e-05 2.67341e-06 4.0409e-06 4.33229e-05 -3.33799e-06 -0.00031875 -0.00031617 -0.00111851 -0.00111979 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.20206e-06 3.10409e-06 2.16939e-05 1.8454e-05 2.16702e-05 1.84346e-05 9.23544e-05 8.95423e-05 0.0143249 0.013562 0.0143283 0.013564 0.0098895 0.00992923 0.0371884 0.0368301 0.0371894 0.0368305 0.0586083 0.0587387 7.47632e-11 6.14361e-11 7.47956e-11 6.14448e-11 5.79923e-10 5.15992e-10 3.13895e-07 2.71162e-07 3.13757e-07 2.71071e-07 5e-08 0 0 0 0 0 0 0 0
311 30885000 0.983144 0.983277 -0.00785584 -0.00788038 -0.012718 -0.0123019 0.182221 0.181531 -0.0345264 -0.0406949 0.0059004 0.00500233 0.767197 0.76761 -0.0625498 -0.0670851 0.0408533 0.0399978 -0.968073 -1.0069 -1.0449e-05 -1.06409e-05 -5.72008e-05 -5.79096e-05 2.65522e-06 4.01552e-06 4.34705e-05 -3.21241e-06 -0.000318939 -0.000316332 -0.00111693 -0.00111821 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.20732e-06 3.107e-06 2.20482e-05 1.87493e-05 2.20236e-05 1.87292e-05 9.24317e-05 8.95589e-05 0.0154336 0.0145774 0.0154375 0.0145796 0.010046 0.0100847 0.0407797 0.0403091 0.0407813 0.0403098 0.0596451 0.0597788 7.48618e-11 6.1535e-11 7.48946e-11 6.15441e-11 5.77951e-10 5.14453e-10 3.13902e-07 2.7117e-07 3.13762e-07 2.71077e-07 5.0002e-08 0 0 0 0 0 0 0 0
312 30985000 0.983145 0.983277 -0.00802524 -0.00804027 -0.0126778 -0.0122555 0.182212 0.181525 -0.0270492 -0.0331827 0.00113125 0.000400666 0.768658 0.769072 -0.0526991 -0.0569425 0.0350265 0.0343403 -0.898982 -0.937826 -1.033e-05 -1.05405e-05 -5.70697e-05 -5.77874e-05 2.68004e-06 4.02621e-06 4.91713e-05 1.73023e-06 -0.000324096 -0.000320351 -0.00111372 -0.00111499 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.1975e-06 3.09596e-06 2.15412e-05 1.83926e-05 2.15179e-05 1.83735e-05 9.21323e-05 8.92234e-05 0.0144631 0.0136801 0.0144668 0.0136823 0.00994435 0.00997998 0.0372574 0.0368733 0.0372587 0.0368739 0.059207 0.0593353 7.33541e-11 6.05645e-11 7.33879e-11 6.0575e-11 5.75249e-10 5.12333e-10 3.10915e-07 2.69395e-07 3.10775e-07 2.69301e-07 5.0001e-08 0 0 0 0 0 0 0 0
313 31085000 0.983107 0.983239 -0.00817448 -0.00818885 -0.0127877 -0.0123615 0.182402 0.181716 -0.0251413 -0.0316315 -0.001926 -0.00268426 0.767649 0.768071 -0.0552617 -0.060139 0.0349207 0.0341603 -0.824911 -0.863755 -1.03297e-05 -1.05406e-05 -5.70685e-05 -5.77862e-05 2.65195e-06 3.98963e-06 4.9258e-05 1.80328e-06 -0.000324201 -0.000320441 -0.00111275 -0.00111403 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.19405e-06 3.09104e-06 2.18914e-05 1.8686e-05 2.18681e-05 1.86669e-05 9.18436e-05 8.88997e-05 0.0155816 0.0147047 0.0155857 0.0147071 0.0100169 0.0100507 0.0408762 0.040374 0.0408781 0.0403749 0.0593709 0.0594982 7.34523e-11 6.06631e-11 7.34866e-11 6.06741e-11 5.72517e-10 5.10187e-10 3.10922e-07 2.69402e-07 3.10779e-07 2.69307e-07 5.0001e-08 0 0 0 0 0 0 0 0
314 31185000 0.983121 0.983252 -0.0083109 -0.00832274 -0.0129389 -0.0125108 0.182307 0.181628 -0.0206282 -0.0269805 -0.00522775 -0.00591836 0.769143 0.76957 -0.0470488 -0.0515396 0.0313564 0.0306831 -0.755062 -0.793916 -1.02821e-05 -1.04973e-05 -5.69603e-05 -5.76811e-05 2.83642e-06 4.14217e-06 5.41195e-05 6.20666e-06 -0.000326138 -0.000322011 -0.00111015 -0.00111143 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.18641e-06 3.08217e-06 2.13503e-05 1.83011e-05 2.13276e-05 1.82824e-05 9.15744e-05 8.8596e-05 0.0145875 0.0137902 0.0145912 0.0137924 0.00991598 0.00994682 0.0373369 0.0369285 0.0373385 0.0369294 0.0589371 0.0590589 7.18622e-11 5.96269e-11 7.18973e-11 5.96392e-11 5.6974e-10 5.08003e-10 3.07791e-07 2.67504e-07 3.07649e-07 2.67409e-07 5.0001e-08 0 0 0 0 0 0 0 0
315 31285000 0.98314 0.98327 -0.00857917 -0.00859023 -0.0130199 -0.0125879 0.182188 0.181515 -0.0173758 -0.0240884 -0.00873823 -0.00945397 0.773041 0.773476 -0.0489022 -0.0540502 0.0307003 0.0299579 -0.683433 -0.722284 -1.02779e-05 -1.04939e-05 -5.69612e-05 -5.76817e-05 2.94799e-06 4.22889e-06 5.42947e-05 6.36324e-06 -0.000326382 -0.000322223 -0.0011082 -0.0011095 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.17675e-06 3.07138e-06 2.16955e-05 1.85917e-05 2.16731e-05 1.85733e-05 9.13224e-05 8.83103e-05 0.0157059 0.0148157 0.0157101 0.0148183 0.00998727 0.0100162 0.0409825 0.0404512 0.0409847 0.0404524 0.0590942 0.0592146 7.19604e-11 5.97255e-11 7.19959e-11 5.97382e-11 5.66931e-10 5.05791e-10 3.07797e-07 2.67511e-07 3.07653e-07 2.67414e-07 5e-08 0 0 0 0 0 0 0 0
316 31385000 0.983153 0.983282 -0.00835699 -0.00836635 -0.0128284 -0.012398 0.182144 0.181472 -0.0115176 -0.0180248 -0.0143558 -0.0150107 0.77237 0.772804 -0.0405074 -0.045199 0.026691 0.0260324 -0.610581 -0.649449 -1.0247e-05 -1.04641e-05 -5.68746e-05 -5.75927e-05 2.89666e-06 4.17172e-06 5.79772e-05 9.88169e-06 -0.000327755 -0.00032338 -0.0011057 -0.001107 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.1656e-06 3.05928e-06 2.11244e-05 1.81808e-05 2.11028e-05 1.81631e-05 9.10876e-05 8.80423e-05 0.014692 0.0138867 0.0146958 0.013889 0.00988704 0.00991313 0.0374231 0.0369926 0.037425 0.0369937 0.0586647 0.0587797 7.03032e-11 5.86325e-11 7.0339e-11 5.86462e-11 5.64082e-10 5.03545e-10 3.04561e-07 2.65512e-07 3.04419e-07 2.65416e-07 5e-08 0 0 0 0 0 0 0 0
317 31485000 0.983136 0.983266 -0.00810704 -0.00811594 -0.0131398 -0.0127059 0.182222 0.18155 -0.0111881 -0.0180637 -0.0188785 -0.0195551 0.769209 0.769659 -0.0416907 -0.0470531 0.0249892 0.0242643 -0.535437 -0.574289 -1.02465e-05 -1.04639e-05 -5.68741e-05 -5.75922e-05 2.89436e-06 4.16095e-06 5.80331e-05 9.92989e-06 -0.000327824 -0.000323439 -0.00110503 -0.00110634 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.17406e-06 3.06545e-06 2.14648e-05 1.8469e-05 2.14419e-05 1.84499e-05 9.12409e-05 8.81382e-05 0.0158298 0.0149306 0.015834 0.0149331 0.010044 0.0100686 0.0410952 0.0405376 0.0410977 0.0405391 0.059704 0.0598206 7.04019e-11 5.87315e-11 7.0438e-11 5.87454e-11 5.61952e-10 5.01868e-10 3.04568e-07 2.6552e-07 3.04425e-07 2.65423e-07 5.0002e-08 0 0 0 0 0 0 0 0
318 31585000 0.983161 0.98329 -0.0079162 -0.00792751 -0.0136173 -0.013182 0.182062 0.181396 -0.00682425 -0.0135164 -0.0195261 -0.0202148 0.772822 0.773278 -0.0311573 -0.036078 0.0225195 0.0218162 -0.464013 -0.502873 -1.02442e-05 -1.04572e-05 -5.67387e-05 -5.74617e-05 3.02175e-06 4.26294e-06 6.40091e-05 1.53677e-05 -0.000327894 -0.0003236 -0.00110231 -0.00110363 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.1644e-06 3.05482e-06 2.08694e-05 1.80363e-05 2.08455e-05 1.80162e-05 9.10282e-05 8.7894e-05 0.0147842 0.013976 0.0147878 0.0139782 0.00994271 0.00996458 0.0375136 0.0370635 0.0375156 0.0370647 0.059266 0.059377 6.8689e-11 5.7588e-11 6.87249e-11 5.76027e-11 5.59042e-10 4.99569e-10 3.01252e-07 2.63434e-07 3.01111e-07 2.63339e-07 5.0002e-08 0 0 0 0 0 0 0 0
319 31685000 0.983186 0.983314 -0.00791582 -0.00792659 -0.0140926 -0.0136535 0.181889 0.181229 -0.00843944 -0.0155041 -0.0218787 -0.0225868 0.769143 0.769613 -0.0319343 -0.0375473 0.0203735 0.0196022 -0.394517 -0.433373 -1.02389e-05 -1.04528e-05 -5.674e-05 -5.74628e-05 3.16966e-06 4.38177e-06 6.42345e-05 1.55706e-05 -0.0003282 -0.000323867 -0.00109956 -0.00110092 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.15557e-06 3.04498e-06 2.12041e-05 1.8321e-05 2.11788e-05 1.82997e-05 9.08267e-05 8.76621e-05 0.0159246 0.0150239 0.0159286 0.0150263 0.0100147 0.0100346 0.04121 0.0406298 0.0412128 0.0406315 0.0594254 0.0595342 6.87873e-11 5.76867e-11 6.88235e-11 5.77016e-11 5.56102e-10 4.97242e-10 3.01259e-07 2.63442e-07 3.01117e-07 2.63346e-07 5.0001e-08 0 0 0 0 0 0 0 0
320 31785000 0.9832 0.983327 -0.00808007 -0.00809981 -0.0147615 -0.0143205 0.181757 0.181103 0.000418667 -0.00644066 -0.023228 -0.0240741 0.768992 0.769467 -0.0208952 -0.0260308 0.0208396 0.0199943 -0.323074 -0.361938 -1.03106e-05 -1.05075e-05 -5.65768e-05 -5.73076e-05 3.29856e-06 4.48561e-06 7.14e-05 2.20546e-05 -0.000325132 -0.000321506 -0.00109701 -0.00109839 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.14777e-06 3.03623e-06 2.05889e-05 1.78693e-05 2.05628e-05 1.7847e-05 9.06355e-05 8.74414e-05 0.0148621 0.0140558 0.0148656 0.014058 0.00991411 0.00993128 0.0376051 0.0371382 0.0376074 0.0371397 0.0589919 0.0590951 6.70346e-11 5.65028e-11 6.70704e-11 5.65182e-11 5.53127e-10 4.94885e-10 2.97902e-07 2.61294e-07 2.97763e-07 2.612e-07 5.0001e-08 0 0 0 0 0 0 0 0
321 31885000 0.98321 0.983336 -0.00785506 -0.00787391 -0.0145635 -0.0141188 0.181728 0.181079 0.00453225 -0.00270284 -0.0267658 -0.0276474 0.767714 0.768199 -0.0206183 -0.0264631 0.0182757 0.0173454 -0.253823 -0.292682 -1.03068e-05 -1.05044e-05 -5.65771e-05 -5.73078e-05 3.38908e-06 4.55398e-06 7.16137e-05 2.2245e-05 -0.000325402 -0.000321742 -0.00109431 -0.00109572 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.14273e-06 3.0302e-06 2.09154e-05 1.81484e-05 2.08896e-05 1.81264e-05 9.04549e-05 8.72324e-05 0.0160017 0.0151049 0.0160056 0.0151073 0.00998572 0.0100008 0.0413247 0.0407254 0.0413276 0.0407273 0.05915 0.0592507 6.71329e-11 5.66014e-11 6.71691e-11 5.66172e-11 5.50123e-10 4.92501e-10 2.97909e-07 2.61302e-07 2.97769e-07 2.61207e-07 5e-08 0 0 0 0 0 0 0 0
322 31985000 0.983201 0.983327 -0.00803523 -0.00805983 -0.0141422 -0.013699 0.181798 0.18115 0.0123106 0.0053475 -0.0259118 -0.0268698 0.764372 0.764854 -0.00931705 -0.0146201 0.0174405 0.0164935 -0.187431 -0.226311 -1.03615e-05 -1.05456e-05 -5.64457e-05 -5.71775e-05 3.36282e-06 4.51824e-06 7.73671e-05 2.76665e-05 -0.000323324 -0.000320181 -0.00108993 -0.0010914 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.13818e-06 3.02476e-06 2.0282e-05 1.76775e-05 2.02587e-05 1.76578e-05 9.02843e-05 8.70343e-05 0.0149199 0.0141209 0.0149234 0.014123 0.00988587 0.00989846 0.0376956 0.037215 0.037698 0.0372165 0.0587209 0.0588162 6.53538e-11 5.53856e-11 6.53892e-11 5.54015e-11 5.47087e-10 4.90089e-10 2.94542e-07 2.59112e-07 2.94406e-07 2.5902e-07 5e-08 0 0 0 0 0 0 0 0
323 32085000 0.983219 0.983343 -0.00841754 -0.00844136 -0.0137727 -0.0133254 0.181716 0.181071 0.0128301 0.00549286 -0.0305126 -0.0315068 0.766756 0.767254 -0.00803751 -0.0140587 0.0146813 0.0136374 -0.116528 -0.155399 -1.03598e-05 -1.05443e-05 -5.64452e-05 -5.71769e-05 3.38782e-06 4.529e-06 7.75211e-05 2.78019e-05 -0.000323504 -0.000320337 -0.0010879 -0.00108938 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.13047e-06 3.01627e-06 2.06012e-05 1.79518e-05 2.05799e-05 1.79339e-05 9.01265e-05 8.68499e-05 0.0160555 0.0151685 0.0160592 0.0151708 0.00995731 0.00996778 0.0414356 0.0408213 0.0414387 0.0408233 0.0588778 0.0589703 6.54521e-11 5.54842e-11 6.54879e-11 5.55004e-11 5.44023e-10 4.87652e-10 2.94549e-07 2.5912e-07 2.94413e-07 2.59027e-07 5e-08 0 0 0 0 0 0 0 0
324 32185000 0.983211 0.983335 -0.00857977 -0.00861457 -0.0140497 -0.0136069 0.181731 0.181087 0.0171378 0.0101527 -0.031689 -0.0328331 0.766797 0.767299 0.00230265 -0.00309774 0.0158187 0.0146971 -0.0473825 -0.0862616 -1.04817e-05 -1.06423e-05 -5.63305e-05 -5.70595e-05 3.38299e-06 4.51556e-06 8.25398e-05 3.26846e-05 -0.00031857 -0.000316417 -0.00108429 -0.00108583 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.13852e-06 3.0224e-06 1.99592e-05 1.747e-05 1.99382e-05 1.74522e-05 9.03481e-05 8.70189e-05 0.0149509 0.0141644 0.014954 0.0141663 0.00994136 0.00994975 0.0377822 0.037291 0.0377847 0.0372926 0.0593199 0.0594097 6.3661e-11 5.42459e-11 6.36956e-11 5.4262e-11 5.41727e-10 4.85828e-10 2.91204e-07 2.5691e-07 2.91072e-07 2.56821e-07 5.0002e-08 0 0 0 0 0 0 0 0
325 32285000 0.983227 0.983351 -0.00850308 -0.00853755 -0.0143064 -0.0138598 0.181626 0.180986 0.0193081 0.0119488 -0.0361914 -0.0373843 0.765312 0.76583 0.00414237 -0.00197889 0.0123896 0.0111523 0.0216534 -0.0172141 -1.04781e-05 -1.06394e-05 -5.6331e-05 -5.70599e-05 3.47752e-06 4.58852e-06 8.27412e-05 3.28651e-05 -0.000318811 -0.000316627 -0.00108156 -0.00108314 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.13245e-06 3.01552e-06 2.02732e-05 1.77414e-05 2.02512e-05 1.77227e-05 9.02052e-05 8.68512e-05 0.0160901 0.0152175 0.0160935 0.0152195 0.0100136 0.0100198 0.0415394 0.0409142 0.0415426 0.0409162 0.0594804 0.059567 6.37593e-11 5.43445e-11 6.37943e-11 5.4361e-11 5.38612e-10 4.83344e-10 2.91211e-07 2.56918e-07 2.91079e-07 2.56829e-07 5.0001e-08 0 0 0 0 0 0 0 0
326 32385000 0.983209 0.983333 -0.00851057 -0.0085533 -0.0144189 -0.0139792 0.181714 0.181076 0.0255728 0.0186095 -0.0352413 -0.0365249 0.763975 0.764495 0.0144705 0.00901143 0.0123321 0.0110791 0.0944001 0.0555225 -1.05786e-05 -1.07205e-05 -5.62429e-05 -5.69638e-05 3.4543e-06 4.55738e-06 8.65647e-05 3.6807e-05 -0.000314767 -0.000313398 -0.00107893 -0.00108055 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.13005e-06 3.01229e-06 1.96248e-05 1.72496e-05 1.96033e-05 1.72312e-05 9.00672e-05 8.66895e-05 0.0149719 0.014201 0.0149748 0.0142028 0.00991338 0.00991731 0.037863 0.0373645 0.0378656 0.0373662 0.0590474 0.0591287 6.19677e-11 5.30916e-11 6.20013e-11 5.31078e-11 5.3547e-10 4.80834e-10 2.87913e-07 2.54706e-07 2.87786e-07 2.54621e-07 5.0001e-08 0 0 0 0 0 0 0 0
327 32485000 0.983225 0.983348 -0.0114152 -0.0114564 -0.0123544 -0.0119091 0.181619 0.180982 0.0528188 0.0446693 -0.102795 -0.104362 -0.108627 -0.108101 0.0188618 0.0126265 0.00363739 0.00223724 0.102934 0.0640683 -1.05787e-05 -1.07207e-05 -5.62411e-05 -5.69622e-05 3.40938e-06 4.50651e-06 8.6594e-05 3.68309e-05 -0.000314792 -0.000313419 -0.00107851 -0.00108013 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.12123e-06 3.00307e-06 1.99257e-05 1.75105e-05 1.99163e-05 1.75033e-05 8.99448e-05 8.65445e-05 0.0179005 0.0168291 0.0179025 0.0168296 0.00978728 0.0097965 0.0417272 0.0410846 0.0417304 0.0410867 0.0591979 0.0592765 6.20664e-11 5.31905e-11 6.20995e-11 5.32064e-11 5.32303e-10 4.78302e-10 0 0 0 0 0 0 0 0 0 0 0
328 32585000 0.983237 0.983358 -0.0113268 -0.0113888 -0.0123064 -0.0118735 0.181563 0.180931 0.0518041 0.0442818 -0.101385 -0.103307 -0.110019 -0.109485 0.0297178 0.0242629 0.00307106 0.00145237 0.0850367 0.0461586 -1.08487e-05 -1.09461e-05 -5.61571e-05 -5.6866e-05 3.53597e-06 4.60931e-06 8.6594e-05 3.68309e-05 -0.000314792 -0.000313419 -0.00107851 -0.00108013 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.11747e-06 2.99865e-06 1.91248e-05 1.68936e-05 1.91155e-05 1.68864e-05 8.98219e-05 8.64002e-05 0.0170847 0.0160722 0.0170867 0.0160728 0.00941992 0.00943194 0.0380571 0.0375432 0.0380597 0.0375449 0.0587286 0.0588031 6.00353e-11 5.1752e-11 6.00638e-11 5.17652e-11 5.29106e-10 4.75743e-10 0 0 0 0 0 0 0 0 0 0 0
329 32685000 0.983242 0.983363 -0.0113153 -0.0113772 -0.0121731 -0.0117368 0.181547 0.180915 0.0486592 0.0407911 -0.108072 -0.110081 -0.111818 -0.111265 0.0347891 0.0285636 -0.00740841 -0.0092236 0.0702748 0.0314137 -1.08483e-05 -1.09459e-05 -5.61565e-05 -5.68653e-05 3.53231e-06 4.59679e-06 8.6594e-05 3.68309e-05 -0.000314792 -0.000313419 -0.00107851 -0.00108013 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.11286e-06 2.99341e-06 1.94217e-05 1.71531e-05 1.94122e-05 1.71459e-05 8.9709e-05 8.62667e-05 0.0189467 0.0177469 0.0189496 0.017748 0.00922381 0.00923906 0.0420603 0.0413856 0.0420637 0.0413878 0.0588025 0.0588756 6.01341e-11 5.1851e-11 6.0162e-11 5.18638e-11 5.25891e-10 4.73165e-10 0 0 0 0 0 0 0 0 0 0 0
330 32785000 0.983246 0.983366 -0.0110909 -0.0111758 -0.0122405 -0.0118184 0.181536 0.180906 0.045928 0.0387653 -0.103372 -0.105812 -0.112439 -0.111873 0.0431784 0.0377837 -0.0060933 -0.00814189 0.0553965 0.0165387 -1.11609e-05 -1.12103e-05 -5.60739e-05 -5.67693e-05 3.65087e-06 4.6962e-06 8.6594e-05 3.68309e-05 -0.000314792 -0.000313419 -0.00107851 -0.00108013 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.12362e-06 3.00241e-06 1.85024e-05 1.64359e-05 1.84924e-05 1.6428e-05 8.99692e-05 8.64793e-05 0.0180226 0.0169106 0.0180256 0.0169119 0.00896819 0.0089866 0.0383261 0.0377893 0.0383288 0.0377911 0.059161 0.059233 5.79818e-11 5.03079e-11 5.80048e-11 5.03177e-11 5.23486e-10 4.7124e-10 0 0 0 0 0 0 0 0 0 0 0
331 32885000 0.983266 0.983385 -0.0110659 -0.0111511 -0.0123052 -0.0118798 0.181425 0.180798 0.0467131 0.039234 -0.111134 -0.113707 -0.113759 -0.113175 0.0478627 0.0417363 -0.0168393 -0.0191388 0.0417332 0.00289907 -1.11596e-05 -1.12092e-05 -5.6075e-05 -5.67701e-05 3.71043e-06 4.74182e-06 8.6594e-05 3.68309e-05 -0.000314792 -0.000313419 -0.00107851 -0.00108013 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.11768e-06 2.99598e-06 1.87891e-05 1.66882e-05 1.87785e-05 1.66799e-05 8.98693e-05 8.63605e-05 0.0199774 0.0186747 0.0199815 0.0186766 0.00878846 0.00881031 0.042437 0.041728 0.0424405 0.0417303 0.0591668 0.0592384 5.80806e-11 5.04069e-11 5.8103e-11 5.04164e-11 5.2023e-10 4.68623e-10 2.87917e-07 2.54711e-07 2.8779e-07 2.54625e-07 5.0003e-08 0 0 0 0 0 0 0 0
332 32985000 0.983278 0.983396 -0.0108957 -0.0109995 -0.0122563 -0.0118475 0.181372 0.180749 0.04318 0.0364774 -0.106527 -0.109443 -0.112749 -0.112153 0.0542468 0.0489922 -0.017267 -0.0196935 0.0291095 -0.00972228 -1.14404e-05 -1.14499e-05 -5.60235e-05 -5.67001e-05 3.85832e-06 4.86756e-06 8.66154e-05 3.68216e-05 -0.000315303 -0.000313872 -0.00107855 -0.00108016 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.11512e-06 2.99291e-06 1.77668e-05 1.58799e-05 1.7756e-05 1.58711e-05 8.97698e-05 8.62437e-05 0.0189539 0.0177647 0.018958 0.0177667 0.00849325 0.00851794 0.0386251 0.038065 0.0386279 0.0380669 0.0586129 0.0586821 5.58511e-11 4.87872e-11 5.58683e-11 4.87934e-11 5.16949e-10 4.65982e-10 2.87923e-07 2.54717e-07 2.87795e-07 2.54631e-07 5.00129e-08 0 0 0 0 0 0 0 0
333 33085000 0.983281 0.9834 -0.0108638 -0.0109681 -0.0122757 -0.0118638 0.181355 0.180731 0.0403805 0.0334007 -0.111603 -0.114679 -0.110522 -0.109902 0.0584544 0.0525173 -0.0281332 -0.0308595 0.0205835 -0.0182185 -1.14406e-05 -1.14502e-05 -5.60238e-05 -5.67002e-05 3.8588e-06 4.86221e-06 8.66148e-05 3.68211e-05 -0.000315302 -0.000313871 -0.00107855 -0.00108017 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.11134e-06 2.98863e-06 1.80416e-05 1.61236e-05 1.80304e-05 1.61145e-05 8.96789e-05 8.61362e-05 0.021066 0.0196769 0.0210714 0.0196798 0.00834809 0.00837635 0.042845 0.0421039 0.0428488 0.0421063 0.0585598 0.0586296 5.59499e-11 4.88861e-11 5.59666e-11 4.88921e-11 5.13653e-10 4.63325e-10 2.87933e-07 2.54727e-07 2.87805e-07 2.54641e-07 5.00229e-08 0 0 0 0 0 0 0 0
334 33185000 0.98329 0.983409 -0.0106579 -0.0107786 -0.0121837 -0.0117884 0.181325 0.180699 0.0356167 0.0294344 -0.107442 -0.110828 -0.108933 -0.108299 0.0631492 0.0580855 -0.0275099 -0.0303051 0.0144552 -0.0243402 -1.1721e-05 -1.16944e-05 -5.597e-05 -5.66282e-05 3.82844e-06 4.83009e-06 8.65839e-05 3.66213e-05 -0.000318029 -0.000316308 -0.0010788 -0.00108041 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.10583e-06 2.98283e-06 1.69405e-05 1.52408e-05 1.6929e-05 1.52314e-05 8.95929e-05 8.60348e-05 0.0199604 0.0187062 0.0199654 0.018709 0.00810197 0.00813306 0.0389448 0.0383641 0.0389477 0.0383661 0.0579862 0.0580545 5.36941e-11 4.72244e-11 5.37059e-11 4.72271e-11 5.10333e-10 4.60646e-10 2.87771e-07 2.54602e-07 2.87644e-07 2.54516e-07 5.00304e-08 0 0 0 0 0 0 0 0
335 33285000 0.983313 0.983431 -0.0107306 -0.0108518 -0.012196 -0.0117977 0.181194 0.180571 0.0334693 0.0270476 -0.110788 -0.114366 -0.108762 -0.108104 0.0665402 0.0608495 -0.0384273 -0.0415712 0.00594749 -0.032812 -1.1718e-05 -1.16918e-05 -5.59738e-05 -5.66313e-05 3.98977e-06 4.97021e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00107881 -0.00108043 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.10209e-06 2.97868e-06 1.72027e-05 1.54752e-05 1.71911e-05 1.54657e-05 8.95115e-05 8.59388e-05 0.022213 0.0207535 0.0222194 0.0207574 0.00799267 0.00802748 0.0432768 0.0425086 0.0432807 0.0425112 0.0578862 0.0579559 5.37929e-11 4.73233e-11 5.38042e-11 4.73259e-11 5.07001e-10 4.57952e-10 2.87781e-07 2.54612e-07 2.87654e-07 2.54526e-07 5.00403e-08 0 0 0 0 0 0 0 0
336 33385000 0.983328 0.983446 -0.010485 -0.0106273 -0.0122385 -0.0118556 0.181126 0.180504 0.0280479 0.0224591 -0.099495 -0.103559 -0.106415 -0.105744 0.0682241 0.0634141 -0.0314859 -0.0348014 -0.00247595 -0.0412282 -1.2094e-05 -1.20233e-05 -5.58967e-05 -5.65398e-05 4.05926e-06 5.02812e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.0010791 -0.00108071 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.0978e-06 2.97411e-06 1.60521e-05 1.45398e-05 1.604e-05 1.45297e-05 8.94331e-05 8.5847e-05 0.0207421 0.0194666 0.0207482 0.0194703 0.00779095 0.00782859 0.0392783 0.038682 0.0392813 0.0386841 0.0573029 0.0573718 5.1563e-11 4.56563e-11 5.15697e-11 4.56558e-11 5.03647e-10 4.55237e-10 0 0 5.00418e-08 0 0 0 0 0 0 0 0
337 33485000 0.983332 0.98345 -0.0104714 -0.0106145 -0.0121957 -0.0118099 0.181109 0.180485 0.0241899 0.0183889 -0.103161 -0.107453 -0.106343 -0.105649 0.0707925 0.0654136 -0.041588 -0.0453213 -0.0132182 -0.0519314 -1.20937e-05 -1.2023e-05 -5.58971e-05 -5.654e-05 4.07735e-06 5.04086e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.0010791 -0.00108071 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.10764e-06 2.98245e-06 1.63014e-05 1.47644e-05 1.62892e-05 1.47542e-05 8.9728e-05 8.61e-05 0.0227946 0.0213468 0.0228019 0.0213515 0.00777878 0.00782073 0.0437151 0.0429283 0.0437192 0.0429311 0.057997 0.0580703 5.1662e-11 4.57555e-11 5.16686e-11 4.57549e-11 5.01148e-10 4.53216e-10 0 0 5.00515e-08 0 0 0 0 0 0 0 0
338 33585000 0.98336 0.983477 -0.0101936 -0.0103497 -0.0121512 -0.0117798 0.180975 0.180352 0.0195428 0.0145162 -0.0959523 -0.100504 -0.102601 -0.101888 0.071783 0.0672396 -0.0358574 -0.0395705 -0.0190369 -0.057731 -1.2398e-05 -1.22967e-05 -5.5832e-05 -5.64594e-05 4.2218e-06 5.16805e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00107974 -0.00108134 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.10293e-06 2.97756e-06 1.51288e-05 1.37976e-05 1.51163e-05 1.3787e-05 8.96573e-05 8.60179e-05 0.0211351 0.019891 0.0211416 0.0198953 0.00761453 0.00765929 0.0396112 0.039006 0.0396144 0.0390082 0.0573959 0.057469 4.95011e-11 4.41157e-11 4.95034e-11 4.41123e-11 4.97767e-10 4.50472e-10 0 0 5.00437e-08 0 0 0 0 0 0 0 0
339 33685000 0.983369 0.983487 -0.0101881 -0.0103452 -0.0121428 -0.0117686 0.180925 0.180301 0.0157785 0.0105664 -0.0996772 -0.104481 -0.104209 -0.103474 0.0735864 0.0685326 -0.0456789 -0.0498601 -0.0275244 -0.0661834 -1.23971e-05 -1.22959e-05 -5.58332e-05 -5.64603e-05 4.27311e-06 5.21026e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00107977 -0.00108138 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.09984e-06 2.97421e-06 1.53653e-05 1.40123e-05 1.53526e-05 1.40016e-05 8.95899e-05 8.59399e-05 0.0231765 0.021772 0.0231843 0.0217772 0.00757007 0.00761885 0.044136 0.0433411 0.0441404 0.0433441 0.0572334 0.0573098 4.95997e-11 4.42146e-11 4.96019e-11 4.42111e-11 4.94377e-10 4.47717e-10 0 0 5.00524e-08 0 0 0 0 0 0 0 0
340 33785000 0.983382 0.983499 -0.00998351 -0.0101502 -0.0121287 -0.011766 0.18087 0.180244 0.0106958 0.0061529 -0.0919465 -0.0969165 -0.0984413 -0.0976914 0.0757249 0.0714237 -0.0390438 -0.0431212 -0.0335136 -0.0721574 -1.2684e-05 -1.25583e-05 -5.57354e-05 -5.63517e-05 4.24986e-06 5.1864e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.0010805 -0.0010821 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.09434e-06 2.96865e-06 1.41961e-05 1.3035e-05 1.41833e-05 1.3024e-05 8.95262e-05 8.58668e-05 0.0213673 0.0201765 0.0213741 0.020181 0.00744202 0.00749354 0.0399267 0.0393203 0.03993 0.0393226 0.05664 0.0567168 4.75413e-11 4.26294e-11 4.75397e-11 4.26234e-11 4.9097e-10 4.44943e-10 0 0 5.00318e-08 0 0 0 0 0 0 0 0
341 33885000 0.983398 0.983515 -0.0100227 -0.0101904 -0.0120886 -0.0117232 0.180784 0.180159 0.0073539 0.00265152 -0.0927636 -0.0980029 -0.0980454 -0.0972728 0.0765721 0.0718109 -0.0483249 -0.0529131 -0.04079 -0.0793943 -1.26816e-05 -1.25562e-05 -5.57381e-05 -5.63539e-05 4.37129e-06 5.29279e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00108058 -0.00108218 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.09173e-06 2.96583e-06 1.442e-05 1.32399e-05 1.44072e-05 1.32288e-05 8.94633e-05 8.57955e-05 0.0233712 0.0220337 0.0233793 0.0220393 0.00742673 0.00748235 0.0445217 0.0437295 0.0445261 0.0437327 0.0564606 0.0565415 4.76399e-11 4.27283e-11 4.76383e-11 4.27222e-11 4.87552e-10 4.42157e-10 0 0 5.00388e-08 0 0 0 0 0 0 0 0
342 33985000 0.983391 0.983509 -0.00976427 -0.00994049 -0.012215 -0.0118585 0.180827 0.180198 0.00436887 0.00025062 -0.0821334 -0.0875232 -0.0944102 -0.093623 0.0775873 0.0735091 -0.0391037 -0.0435621 -0.0439964 -0.0825813 -1.29837e-05 -1.28357e-05 -5.56127e-05 -5.62215e-05 4.3224e-06 5.24678e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00108152 -0.00108311 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.08916e-06 2.96313e-06 1.32767e-05 1.22714e-05 1.32635e-05 1.22598e-05 8.94018e-05 8.57268e-05 0.021448 0.0203261 0.0214551 0.020331 0.00733065 0.00738894 0.0402126 0.0396126 0.040216 0.039615 0.0558821 0.0559638 4.57087e-11 4.12195e-11 4.57038e-11 4.12112e-11 4.84123e-10 4.39358e-10 0 0 5.0005e-08 0 0 0 0 0 0 0 0
343 34085000 0.983396 0.983514 -0.00970041 -0.00987785 -0.0122211 -0.0118619 0.180802 0.18017 0.000946584 -0.00332181 -0.0864354 -0.09211 -0.0935005 -0.0926886 0.0778966 0.0734001 -0.0475635 -0.0525751 -0.050699 -0.0892355 -1.29836e-05 -1.28356e-05 -5.56131e-05 -5.62217e-05 4.32917e-06 5.25057e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00108163 -0.00108322 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.09894e-06 2.97162e-06 1.34888e-05 1.24669e-05 1.34752e-05 1.2455e-05 8.97129e-05 8.60015e-05 0.0234031 0.0221485 0.0234112 0.0221543 0.00739854 0.00746156 0.0448594 0.0440804 0.0448639 0.0440836 0.0564913 0.0565803 4.58077e-11 4.13186e-11 4.58028e-11 4.13104e-11 4.81572e-10 4.37277e-10 0 0 5.00108e-08 0 0 0 0 0 0 0 0
344 34185000 0.983397 0.983516 -0.00952656 -0.00970738 -0.0122516 -0.0119009 0.180804 0.180171 -0.00318908 -0.00691984 -0.0765384 -0.0821847 -0.0911656 -0.0903385 0.0793654 0.0755168 -0.0392871 -0.0440138 -0.0524824 -0.0909958 -1.32351e-05 -1.30729e-05 -5.55008e-05 -5.61014e-05 4.38262e-06 5.29734e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.0010824 -0.00108398 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.09736e-06 2.96993e-06 1.23879e-05 1.15223e-05 1.23742e-05 1.15102e-05 8.96541e-05 8.59375e-05 0.0213911 0.0203481 0.021398 0.0203531 0.0073285 0.00739411 0.04046 0.0398734 0.0404634 0.0398758 0.0559176 0.056008 4.40183e-11 3.99011e-11 4.40105e-11 3.98909e-11 4.78126e-10 4.34456e-10 0 0 5.00037e-08 0 0 0 0 0 0 0 0
345 34285000 0.983401 0.983519 -0.00941821 -0.00960031 -0.0123144 -0.0119611 0.180784 0.180151 -0.00317593 -0.00704253 -0.0798237 -0.085766 -0.0901349 -0.089289 0.0790765 0.0748492 -0.0471461 -0.0524524 -0.0597502 -0.0982248 -1.32338e-05 -1.30718e-05 -5.55022e-05 -5.61025e-05 4.44813e-06 5.3535e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.0010825 -0.00108407 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.09597e-06 2.96842e-06 1.25888e-05 1.17088e-05 1.25747e-05 1.16963e-05 8.95975e-05 8.58765e-05 0.0232866 0.0221248 0.0232945 0.0221305 0.00736495 0.00743478 0.0451399 0.0443831 0.0451445 0.0443864 0.0557375 0.0558336 4.41168e-11 3.99999e-11 4.41092e-11 3.99898e-11 4.74673e-10 4.31626e-10 0 0 5.0004e-08 5.00041e-08 0 0 0 0 0 0 0 0
346 34385000 0.983424 0.983543 -0.00920375 -0.00938656 -0.0123159 -0.011971 0.180667 0.180031 -0.00651938 -0.00986885 -0.0690607 -0.0748689 -0.0851312 -0.0842704 0.0787784 0.075178 -0.0387096 -0.0436356 -0.0629224 -0.101371 -1.34669e-05 -1.32948e-05 -5.5408e-05 -5.59992e-05 4.46594e-06 5.36789e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00108397 -0.00108554 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.08973e-06 2.96235e-06 1.15431e-05 1.08008e-05 1.15288e-05 1.07881e-05 8.95465e-05 8.58221e-05 0.0212078 0.0202492 0.0212145 0.0202542 0.00731924 0.00739149 0.0406631 0.0400958 0.0406665 0.0400983 0.0551903 0.0552881 4.24759e-11 3.86828e-11 4.24659e-11 3.86712e-11 4.71213e-10 4.28786e-10 0 0 5.0001e-08 0 0 0 0 0 0 0 0
347 34485000 0.983428 0.983547 -0.00928746 -0.0094715 -0.0122482 -0.0119006 0.180646 0.18001 -0.00942477 -0.0128984 -0.0725596 -0.0786622 -0.0836502 -0.0827644 0.0779808 0.074041 -0.0458588 -0.0513805 -0.066431 -0.104835 -1.34654e-05 -1.32936e-05 -5.54096e-05 -5.60006e-05 4.53459e-06 5.4274e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00108433 -0.00108589 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.08843e-06 2.96101e-06 1.17333e-05 1.09785e-05 1.17191e-05 1.09659e-05 8.94924e-05 8.57657e-05 0.0230373 0.0219732 0.0230449 0.0219789 0.00737817 0.00745464 0.045358 0.0446306 0.0453626 0.0446339 0.0550248 0.055129 4.25744e-11 3.87816e-11 4.25646e-11 3.87701e-11 4.67748e-10 4.25937e-10 0 0 5e-08 0 0 0 0 0 0 0 0
348 34585000 0.983434 0.983553 -0.00909251 -0.00927357 -0.0120647 -0.0117243 0.180637 0.179998 -0.0104566 -0.0130421 -0.0616945 -0.0671889 0.66225 0.663145 0.0778848 0.0745274 -0.0386066 -0.0436142 -0.041322 -0.0797037 -1.36507e-05 -1.34749e-05 -5.53191e-05 -5.59014e-05 4.52608e-06 5.4176e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00108569 -0.00108724 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.08535e-06 2.95802e-06 1.07508e-05 1.01158e-05 1.0737e-05 1.01035e-05 8.9441e-05 8.57128e-05 0.0197499 0.0189434 0.0197557 0.0189479 0.00735173 0.00742518 0.0407868 0.0402451 0.0407902 0.0402476 0.0545078 0.0546138 4.10824e-11 3.75693e-11 4.10708e-11 3.75565e-11 4.64277e-10 4.2308e-10 0 0 5e-08 0 0 0 0 0 0 0 0
349 34685000 0.98344 0.98356 -0.00907846 -0.00926064 -0.0117801 -0.0114371 0.180621 0.179981 -0.0126764 -0.0147792 -0.0588799 -0.0642053 1.65291 1.65381 0.0767357 0.0731437 -0.0446321 -0.0501807 0.0715211 0.0331661 -1.3651e-05 -1.34752e-05 -5.53188e-05 -5.5901e-05 4.51429e-06 5.40248e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00108543 -0.00108697 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.08248e-06 2.95523e-06 1.0931e-05 1.02851e-05 1.09179e-05 1.02734e-05 8.93906e-05 8.56619e-05 0.0198555 0.01905 0.0198614 0.0190545 0.00742868 0.00749931 0.0452981 0.044617 0.0453025 0.0446203 0.0543631 0.0544751 4.11809e-11 3.7668e-11 4.11695e-11 3.76555e-11 4.60804e-10 4.20216e-10 0 0 5e-08 0 0 0 0 0 0 0 0
350 34785000 0.983451 0.983569 -0.00892438 -0.00910198 -0.0115466 -0.0112075 0.180588 0.179953 -0.0135731 -0.0148354 -0.0481166 -0.0527349 2.61941 2.62008 0.0770266 0.0739439 -0.0375206 -0.0424845 0.233589 0.194956 -1.37972e-05 -1.36203e-05 -5.52336e-05 -5.58107e-05 4.5445e-06 5.41699e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00105945 -0.00106101 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.09197e-06 2.9637e-06 1.01263e-05 9.57218e-06 1.01137e-05 9.56083e-06 8.97092e-05 8.59506e-05 0.016854 0.0162508 0.0168585 0.0162544 0.00746905 0.00753572 0.0406905 0.0401801 0.0406938 0.0401826 0.0546143 0.0547303 3.99757e-11 3.66803e-11 3.9963e-11 3.66668e-11 4.5822e-10 4.18086e-10 0 0 5.0002e-08 0 0 0 0 0 0 0 0
351 34885000 0.983457 0.983575 -0.00890904 -0.00908769 -0.0112634 -0.0109215 0.180574 0.179939 -0.0157331 -0.016516 -0.045287 -0.0497357 3.60498 3.60563 0.0756091 0.0724213 -0.0421646 -0.0475812 0.523439 0.484785 -1.37979e-05 -1.3621e-05 -5.52325e-05 -5.58096e-05 4.53031e-06 5.39671e-06 8.65815e-05 3.66193e-05 -0.000318026 -0.000316307 -0.00105721 -0.00105876 0.204241 0.204284 0.0019669 0.00196732 0.43438 0.43436 0 0 0 0 0 3.08911e-06 2.961e-06 1.02993e-05 9.7355e-06 1.02872e-05 9.72468e-06 8.96592e-05 8.5902e-05 0.0169623 0.0163598 0.0169668 0.0163633 0.0075637 0.00762762 0.0449043 0.0442776 0.0449085 0.0442807 0.0544924 0.0546132 4.00741e-11 3.67789e-11 4.00617e-11 3.67657e-11 4.54741e-10 4.15211e-10 0 0 5.0001e-08 0 0 0 0 0 0 0 0
+3 -3
View File
@@ -94,9 +94,9 @@ class EkfInitializationTest : public ::testing::Test {
const Vector3f pos = _ekf->getPosition();
const Vector3f vel = _ekf->getVelocity();
EXPECT_TRUE(matrix::isEqual(pos, Vector3f{}, 0.001f))
EXPECT_TRUE(matrix::isEqual(pos, Vector3f{}, 0.002f))
<< "pos = " << pos(0) << ", " << pos(1) << ", " << pos(2);
EXPECT_TRUE(matrix::isEqual(vel, Vector3f{}, 0.002f))
EXPECT_TRUE(matrix::isEqual(vel, Vector3f{}, 0.003f))
<< "vel = " << vel(0) << ", " << vel(1) << ", " << vel(2);
}
@@ -105,7 +105,7 @@ class EkfInitializationTest : public ::testing::Test {
const Vector3f pos_var = _ekf->getPositionVariance();
const Vector3f vel_var = _ekf->getVelocityVariance();
const float pos_variance_limit = 0.2f;
const float pos_variance_limit = 0.1f;
EXPECT_TRUE(pos_var(0) > pos_variance_limit) << "pos_var(0)" << pos_var(0);
EXPECT_TRUE(pos_var(1) > pos_variance_limit) << "pos_var(1)" << pos_var(1);
EXPECT_TRUE(pos_var(2) > pos_variance_limit) << "pos_var(2)" << pos_var(2);