ekf2: allow filter init with only IMU (#21041)

- if mag enabled heading init is now pushed to controlMagFusion()
This commit is contained in:
Daniel Agar 2023-02-13 22:07:15 -05:00 committed by GitHub
parent d69d99b191
commit 2ea25804a1
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
9 changed files with 798 additions and 800 deletions

View File

@ -556,6 +556,12 @@ void Ekf::resetQuatCov()
rot_vec_var.setAll(sq(_params.initial_tilt_err));
initialiseQuatCovariances(rot_vec_var);
// update the yaw angle variance using the variance of the measurement
if (_params.mag_fusion_type <= MagFuseType::MAG_3D) {
// using magnetic heading tuning parameter
increaseQuatYawErrVariance(sq(fmaxf(_params.mag_heading_noise, 1.0e-2f)));
}
}
void Ekf::zeroQuatCov()

View File

@ -52,6 +52,8 @@ bool Ekf::init(uint64_t timestamp)
void Ekf::reset()
{
ECL_INFO("reset");
_state.vel.setZero();
_state.pos.setZero();
_state.delta_ang_bias.setZero();
@ -196,61 +198,13 @@ bool Ekf::initialiseFilter()
_gyro_lpf.update(imu_init.delta_ang / imu_init.delta_ang_dt);
}
// Sum the magnetometer measurements
if (_mag_buffer) {
magSample mag_sample;
if (_mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) {
if (mag_sample.time_us != 0) {
if (_mag_counter == 0) {
_mag_lpf.reset(mag_sample.mag);
} else {
_mag_lpf.update(mag_sample.mag);
}
_mag_counter++;
}
}
}
if (!initialiseTilt()) {
return false;
}
// calculate the initial magnetic field and yaw alignment
// but do not mark the yaw alignement complete as it needs to be
// reset once the leveling phase is done
if (_params.mag_fusion_type <= MagFuseType::MAG_3D) {
if (_mag_counter > 1) {
// rotate the magnetometer measurements into earth frame using a zero yaw angle
// the angle of the projection onto the horizontal gives the yaw angle
const Vector3f mag_earth_pred = updateYawInRotMat(0.f, _R_to_earth) * _mag_lpf.getState();
float yaw_new = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();
// update the rotation matrix using the new yaw value
_R_to_earth = updateYawInRotMat(yaw_new, Dcmf(_state.quat_nominal));
_state.quat_nominal = _R_to_earth;
// set the earth magnetic field states using the updated rotation
_state.mag_I = _R_to_earth * _mag_lpf.getState();
_state.mag_B.zero();
} else {
// not enough mag samples accumulated
return false;
}
}
// initialise the state covariance matrix now we have starting values for all the states
initialiseCovariance();
// update the yaw angle variance using the variance of the measurement
if (_params.mag_fusion_type <= MagFuseType::MAG_3D) {
// using magnetic heading tuning parameter
increaseQuatYawErrVariance(sq(fmaxf(_params.mag_heading_noise, 1.0e-2f)));
}
// Initialise the terrain estimator
initHagl();

View File

@ -222,8 +222,7 @@ bool Ekf::resetMagHeading()
const Vector3f mag_init = _mag_lpf.getState();
const bool mag_available = (_mag_counter != 0) && isNewestSampleRecent(_time_last_mag_buffer_push, 500'000)
&& !magFieldStrengthDisturbed(mag_init);
const bool mag_available = (_mag_counter > 1) && !magFieldStrengthDisturbed(mag_init);
// low pass filtered mag required
if (!mag_available) {
@ -244,7 +243,7 @@ bool Ekf::resetMagHeading()
float yaw_new = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();
float yaw_new_variance = sq(fmaxf(_params.mag_heading_noise, 1.e-2f));
ECL_INFO("reset mag heading %.3f -> %.3f rad", (double)getEulerYaw(_R_to_earth), (double)yaw_new);
ECL_INFO("reset mag heading %.3f -> %.3f rad (declination %.1f)", (double)getEulerYaw(_R_to_earth), (double)yaw_new, (double)getMagDeclination());
// update quaternion states and corresponding covarainces
resetQuatStateYaw(yaw_new, yaw_new_variance);

View File

@ -95,7 +95,7 @@ void Ekf::controlMagFusion()
resetEstimatorAidStatus(_aid_src_mag_heading);
_aid_src_mag_heading.timestamp_sample = mag_sample.time_us;
_aid_src_mag_heading.observation = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();;
_aid_src_mag_heading.observation = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();
_aid_src_mag_heading.innovation = wrap_pi(getEulerYaw(_R_to_earth) - _aid_src_mag_heading.observation);
// compute magnetometer innovations (for estimator_aid_src_mag logging)
@ -116,6 +116,45 @@ void Ekf::controlMagFusion()
_control_status.flags.mag_aligned_in_flight = false;
}
if (mag_data_ready && !_control_status.flags.tilt_align && !_control_status.flags.yaw_align) {
// calculate the initial magnetic field and yaw alignment
// but do not mark the yaw alignement complete as it needs to be
// reset once the leveling phase is done
if (_params.mag_fusion_type <= MagFuseType::MAG_3D) {
if ((_mag_counter > 1) && isTimedOut(_aid_src_mag_heading.time_last_fuse, (uint64_t)100'000)) {
// rotate the magnetometer measurements into earth frame using a zero yaw angle
// the angle of the projection onto the horizontal gives the yaw angle
const Vector3f mag_earth_pred = updateYawInRotMat(0.f, _R_to_earth) * _mag_lpf.getState();
const float yaw_new = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();
const float yaw_prev = getEulerYaw(_R_to_earth);
if (fabsf(yaw_new - yaw_prev) > math::radians(1.f)) {
ECL_INFO("mag heading init %.3f -> %.3f rad (declination %.1f)", (double)yaw_prev, (double)yaw_new, (double)getMagDeclination());
// update the rotation matrix using the new yaw value
_R_to_earth = updateYawInRotMat(yaw_new, Dcmf(_state.quat_nominal));
_state.quat_nominal = _R_to_earth;
// reset the output predictor state history to match the EKF initial values
_output_predictor.alignOutputFilter(_state.quat_nominal, _state.vel, _state.pos);
// set the earth magnetic field states using the updated rotation
_state.mag_I = _R_to_earth * _mag_lpf.getState();
_state.mag_B.zero();
_aid_src_mag_heading.time_last_fuse = _time_delayed_us;
_time_last_heading_fuse = _time_delayed_us;
_last_static_yaw = NAN;
}
}
}
return;
}
if (_params.mag_fusion_type >= MagFuseType::NONE
|| _control_status.flags.mag_fault
|| !_control_status.flags.tilt_align) {
@ -225,9 +264,9 @@ void Ekf::runInAirYawReset()
bool has_realigned_yaw = false;
// use yaw estimator if available
if (_control_status.flags.gps && isYawEmergencyEstimateAvailable() &&
(_mag_counter != 0) && isNewestSampleRecent(_time_last_mag_buffer_push, 500'000) // mag LPF available
) {
if (_control_status.flags.gps && isYawEmergencyEstimateAvailable()
&& (_mag_counter > 1) // mag LPF available
) {
resetQuatStateYaw(_yawEstimator.getYaw(), _yawEstimator.getYawVar());

View File

@ -49,7 +49,7 @@ void Ekf::controlZeroInnovationHeadingUpdate()
float obs_var = _control_status.flags.vehicle_at_rest ? 0.001f : 0.1f;
estimator_aid_source1d_s unused;
fuseYaw(innovation, obs_var, unused);
_time_last_heading_fuse = 0;
_last_static_yaw = NAN;
} else if (_control_status.flags.vehicle_at_rest) {

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]
10000,1,-0.011,-0.011,-0.00011,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
90000,1,-0.011,-0.01,-0.022,-0.00064,0.00067,-0.0094,-3e-05,1.5e-05,-0.0003,0,0,0,0,0,0,0.19,9.3e-10,0.4,0,0,0,0,0,1.5e-06,0.0025,0.0025,0.0021,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
190000,1,-0.011,-0.01,-0.022,-0.00081,-0.00015,-0.024,-7.2e-05,3.1e-05,-0.0015,4.3e-15,-9.3e-15,-2.4e-16,0,0,-2.3e-12,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0026,0.0026,0.0012,25,25,10,1e+02,1e+02,1.3,1e-06,1e-06,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
290000,1,-0.011,-0.011,-0.022,-0.00054,0.00017,-0.037,-3.4e-05,-1.7e-05,-0.0032,1e-12,1e-12,-2.5e-14,0,0,-2.2e-09,0.19,9.3e-10,0.4,0,0,0,0,0,1e-06,0.0027,0.0027,0.00084,25,25,9.6,0.31,0.31,0.44,1e-06,1e-06,9.8e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
390000,1,-0.011,-0.011,-0.022,0.00022,-9.4e-05,-0.046,-5e-05,8.8e-06,-0.0052,1e-12,1.7e-12,9.9e-14,0,0,-2.7e-08,0.19,9.3e-10,0.4,0,0,0,0,0,9.8e-07,0.0028,0.0028,0.00069,25,25,8.3,0.81,0.81,0.32,1e-06,1e-06,9.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
490000,1,-0.011,-0.011,-0.022,0.002,-0.001,-0.051,6.6e-05,-4.3e-05,-0.0068,-1.6e-10,8.1e-12,7.2e-12,0,0,-1.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1e-06,0.003,0.003,0.00062,7.8,7.8,6.2,0.29,0.29,0.31,1e-06,1e-06,9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
590000,1,-0.011,-0.012,-0.022,0.0034,-0.00072,-0.053,0.00035,-0.00013,-0.0083,-1.2e-10,1e-10,6.8e-12,0,0,-2.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0033,0.0033,0.0006,7.9,7.9,4.4,0.59,0.59,0.32,1e-06,1e-06,8.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
690000,1,-0.011,-0.012,-0.022,0.0041,-0.0015,-0.055,0.00024,-9.4e-05,-0.0089,-4.3e-09,-1.2e-08,2.7e-10,0,0,-4.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.2e-06,0.0036,0.0036,0.00059,2.6,2.6,2.9,0.23,0.23,0.3,1e-06,1e-06,7.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
790000,1,-0.011,-0.012,-0.022,0.0056,-0.0016,-0.059,0.00071,-0.00027,-0.01,-4.1e-09,-1.2e-08,2.7e-10,0,0,-7.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.3e-06,0.004,0.004,0.00059,2.7,2.7,2,0.38,0.38,0.29,1e-06,1e-06,6.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
890000,1,-0.011,-0.012,-0.022,0.0076,-0.0023,-0.074,0.00055,-0.0002,-0.017,-2.7e-08,-8.3e-08,1.5e-09,0,0,-7.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.4e-06,0.0043,0.0043,0.00059,1.3,1.3,2.1,0.19,0.19,0.44,1e-06,1e-06,6.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
990000,1,-0.011,-0.013,-0.022,0.011,-0.0042,-0.089,0.0015,-0.0005,-0.025,-2.7e-08,-8.3e-08,1.5e-09,0,0,-7.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-06,0.0048,0.0048,0.00058,1.4,1.4,2.1,0.28,0.28,0.63,1e-06,1e-06,5.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1090000,1,-0.011,-0.013,-0.022,0.012,-0.0049,-0.1,0.0012,-0.00043,-0.035,-1.3e-07,-4.1e-07,6.4e-09,0,0,-7.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.7e-06,0.0051,0.0051,0.00058,0.86,0.86,2.1,0.16,0.16,0.86,9.9e-07,9.9e-07,4.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1190000,1,-0.011,-0.013,-0.022,0.016,-0.0069,-0.12,0.0025,-0.001,-0.046,-1.3e-07,-4.1e-07,6.4e-09,0,0,-7.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.9e-06,0.0057,0.0057,0.00057,1,1,2.1,0.22,0.22,1.1,9.9e-07,9.9e-07,4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1290000,1,-0.011,-0.013,-0.022,0.016,-0.0067,-0.13,0.0019,-0.0008,-0.058,-4.7e-07,-1.4e-06,2.1e-08,0,0,-7.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2e-06,0.0058,0.0058,0.00056,0.79,0.79,2.1,0.14,0.14,1.4,9.6e-07,9.6e-07,3.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1390000,1,-0.011,-0.014,-0.022,0.021,-0.009,-0.14,0.0039,-0.0016,-0.072,-4.7e-07,-1.4e-06,2.1e-08,0,0,-7.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.3e-06,0.0064,0.0064,0.00055,1,1,2.1,0.19,0.19,1.8,9.6e-07,9.6e-07,3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1490000,1,-0.012,-0.014,-0.022,0.027,-0.011,-0.16,0.0063,-0.0025,-0.087,-4.7e-07,-1.4e-06,2.1e-08,0,0,-7.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.5e-06,0.0071,0.0071,0.00053,1.3,1.3,2.1,0.28,0.28,2.2,9.6e-07,9.6e-07,2.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1590000,1,-0.012,-0.014,-0.022,0.027,-0.0093,-0.17,0.0052,-0.002,-0.1,-1.2e-06,-3.5e-06,5.1e-08,0,0,-8.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.5e-06,0.0068,0.0068,0.00051,1.1,1.1,2.1,0.19,0.19,2.6,9.1e-07,9.1e-07,2.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1690000,1,-0.012,-0.014,-0.022,0.034,-0.013,-0.18,0.0082,-0.0031,-0.12,-1.2e-06,-3.5e-06,5.1e-08,0,0,-8.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.8e-06,0.0075,0.0075,0.0005,1.5,1.5,2.1,0.27,0.27,3.1,9.1e-07,9.1e-07,1.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1790000,1,-0.011,-0.014,-0.022,0.032,-0.013,-0.2,0.0064,-0.0025,-0.14,-2.5e-06,-7.2e-06,9.8e-08,0,0,-8.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.5e-06,0.0066,0.0066,0.00048,1.2,1.2,2.1,0.18,0.18,3.7,8.1e-07,8.1e-07,1.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1890000,1,-0.011,-0.014,-0.022,0.039,-0.015,-0.21,0.0099,-0.0039,-0.16,-2.5e-06,-7.2e-06,9.8e-08,0,0,-8.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.8e-06,0.0073,0.0073,0.00046,1.6,1.6,2.1,0.28,0.28,4.2,8.1e-07,8.1e-07,1.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1990000,1,-0.011,-0.014,-0.022,0.033,-0.013,-0.23,0.0072,-0.0028,-0.18,-4.2e-06,-1.2e-05,1.6e-07,0,0,-9.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.3e-06,0.0059,0.0059,0.00045,1.2,1.2,2.1,0.18,0.18,4.8,7e-07,7e-07,1.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2090000,1,-0.011,-0.014,-0.022,0.039,-0.016,-0.24,0.011,-0.0042,-0.21,-4.2e-06,-1.2e-05,1.6e-07,0,0,-9.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.5e-06,0.0064,0.0064,0.00043,1.5,1.5,2.2,0.28,0.28,5.5,7e-07,7e-07,1.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2190000,1,-0.011,-0.013,-0.022,0.031,-0.011,-0.26,0.0072,-0.0028,-0.23,-6.1e-06,-1.8e-05,2.2e-07,0,0,-9.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2e-06,0.0049,0.0049,0.00042,1.1,1.1,2.2,0.18,0.18,6.2,5.9e-07,5.9e-07,9.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2290000,1,-0.011,-0.014,-0.022,0.038,-0.014,-0.27,0.011,-0.004,-0.26,-6.1e-06,-1.8e-05,2.2e-07,0,0,-9.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.2e-06,0.0054,0.0054,0.0004,1.4,1.4,2.2,0.27,0.27,6.9,5.9e-07,5.9e-07,8.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2390000,1,-0.011,-0.013,-0.022,0.029,-0.01,-0.28,0.0068,-0.0026,-0.29,-7.8e-06,-2.3e-05,2.7e-07,0,0,-9.9e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-06,0.004,0.004,0.00039,0.99,0.99,2.2,0.17,0.17,7.7,4.9e-07,4.9e-07,7.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2490000,1,-0.011,-0.013,-0.022,0.034,-0.012,-0.3,0.01,-0.0037,-0.32,-7.8e-06,-2.3e-05,2.7e-07,0,0,-9.9e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.8e-06,0.0044,0.0044,0.00038,1.2,1.2,2.2,0.25,0.25,8.6,4.9e-07,4.9e-07,7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2590000,1,-0.011,-0.013,-0.022,0.026,-0.0082,-0.31,0.0063,-0.0022,-0.35,-9.3e-06,-2.8e-05,3e-07,0,0,-1e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.4e-06,0.0033,0.0033,0.00036,0.86,0.86,2.2,0.16,0.16,9.5,4.1e-07,4.1e-07,6.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2690000,1,-0.011,-0.013,-0.022,0.03,-0.0091,-0.32,0.0091,-0.0031,-0.38,-9.3e-06,-2.8e-05,3e-07,0,0,-1e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.5e-06,0.0036,0.0036,0.00035,1.1,1.1,2.3,0.24,0.24,10,4.1e-07,4.1e-07,5.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2790000,1,-0.011,-0.013,-0.022,0.023,-0.0067,-0.34,0.0058,-0.0019,-0.41,-1e-05,-3.2e-05,3.3e-07,0,0,-1e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.2e-06,0.0027,0.0027,0.00034,0.74,0.74,2.3,0.15,0.15,11,3.4e-07,3.4e-07,5.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2890000,1,-0.011,-0.013,-0.022,0.027,-0.0077,-0.35,0.0082,-0.0026,-0.44,-1e-05,-3.2e-05,3.3e-07,0,0,-1e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.3e-06,0.003,0.003,0.00033,0.93,0.93,2.3,0.22,0.22,12,3.4e-07,3.4e-07,4.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2990000,1,-0.011,-0.013,-0.022,0.022,-0.0056,-0.36,0.0053,-0.0016,-0.48,-1.1e-05,-3.5e-05,3.4e-07,0,0,-1e-06,0.19,9.3e-10,0.4,0,0,0,0,0,9.8e-07,0.0023,0.0023,0.00032,0.65,0.65,2.3,0.14,0.14,13,2.9e-07,2.9e-07,4.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3090000,1,-0.011,-0.013,-0.022,0.024,-0.006,-0.37,0.0076,-0.0022,-0.52,-1.1e-05,-3.5e-05,3.4e-07,0,0,-1e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.1e-06,0.0026,0.0026,0.00031,0.81,0.81,2.3,0.2,0.2,15,2.9e-07,2.9e-07,3.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3190000,1,-0.011,-0.012,-0.022,0.02,-0.0038,-0.39,0.0049,-0.0014,-0.56,-1.2e-05,-3.8e-05,3.6e-07,0,0,-9.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,8.5e-07,0.002,0.002,0.0003,0.58,0.58,2.4,0.14,0.14,16,2.5e-07,2.5e-07,3.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3290000,1,-0.011,-0.012,-0.022,0.023,-0.0047,-0.4,0.007,-0.0018,-0.59,-1.2e-05,-3.8e-05,3.6e-07,0,0,-9.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,9.2e-07,0.0022,0.0022,0.00029,0.72,0.72,2.4,0.19,0.19,17,2.5e-07,2.5e-07,3.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3390000,1,-0.011,-0.012,-0.022,0.018,-0.0036,-0.41,0.0046,-0.0011,-0.64,-1.2e-05,-4.1e-05,3.6e-07,0,0,-9.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,7.4e-07,0.0018,0.0018,0.00029,0.52,0.52,2.4,0.13,0.13,18,2.1e-07,2.1e-07,2.9e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3490000,1,-0.011,-0.012,-0.022,0.022,-0.0052,-0.43,0.0066,-0.0015,-0.68,-1.2e-05,-4.1e-05,3.6e-07,0,0,-9.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,7.9e-07,0.002,0.002,0.00028,0.65,0.65,2.4,0.18,0.18,20,2.1e-07,2.1e-07,2.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3590000,1,-0.011,-0.012,-0.022,0.024,-0.0067,-0.44,0.0089,-0.0021,-0.72,-1.2e-05,-4.1e-05,3.6e-07,0,0,-9.6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,8.5e-07,0.0022,0.0022,0.00027,0.79,0.79,2.5,0.24,0.24,21,2.1e-07,2.1e-07,2.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3690000,1,-0.011,-0.012,-0.022,0.019,-0.0069,-0.45,0.0062,-0.0016,-0.77,-1.3e-05,-4.3e-05,3.7e-07,0,0,-9.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6.9e-07,0.0017,0.0017,0.00026,0.59,0.59,2.5,0.17,0.17,22,1.7e-07,1.7e-07,2.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3790000,1,-0.011,-0.012,-0.022,0.022,-0.0092,-0.47,0.0082,-0.0024,-0.81,-1.3e-05,-4.3e-05,3.7e-07,0,0,-9.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,7.4e-07,0.0019,0.0019,0.00026,0.72,0.72,2.5,0.23,0.23,24,1.7e-07,1.7e-07,2.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3890000,1,-0.01,-0.012,-0.022,0.017,-0.0072,-0.48,0.0057,-0.0019,-0.86,-1.3e-05,-4.5e-05,3.8e-07,0,0,-8.9e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6e-07,0.0016,0.0016,0.00025,0.54,0.54,2.5,0.16,0.16,25,1.5e-07,1.5e-07,2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3990000,1,-0.01,-0.012,-0.022,0.02,-0.0079,-0.49,0.0076,-0.0027,-0.91,-1.3e-05,-4.5e-05,3.8e-07,0,0,-8.9e-07,0.19,9.3e-10,0.4,0,0,0,0,0,6.4e-07,0.0017,0.0017,0.00025,0.66,0.66,2.6,0.21,0.21,27,1.5e-07,1.5e-07,1.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4090000,1,-0.01,-0.012,-0.022,0.017,-0.0071,-0.51,0.0053,-0.002,-0.96,-1.4e-05,-4.7e-05,3.9e-07,0,0,-8.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,5.2e-07,0.0014,0.0014,0.00024,0.5,0.5,2.6,0.15,0.15,29,1.2e-07,1.2e-07,1.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4190000,1,-0.01,-0.012,-0.022,0.02,-0.0085,-0.52,0.0072,-0.0027,-1,-1.4e-05,-4.7e-05,3.9e-07,0,0,-8.5e-07,0.19,9.3e-10,0.4,0,0,0,0,0,5.5e-07,0.0015,0.0015,0.00023,0.6,0.6,2.6,0.2,0.2,30,1.2e-07,1.2e-07,1.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4290000,1,-0.01,-0.012,-0.022,0.017,-0.0051,-0.54,0.0051,-0.0019,-1.1,-1.5e-05,-4.9e-05,4e-07,0,0,-8.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,4.6e-07,0.0012,0.0012,0.00023,0.46,0.46,2.6,0.14,0.14,32,1e-07,1e-07,1.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4390000,1,-0.01,-0.012,-0.022,0.018,-0.005,-0.55,0.0069,-0.0025,-1.1,-1.5e-05,-4.9e-05,4e-07,0,0,-8.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,4.8e-07,0.0013,0.0013,0.00022,0.55,0.55,2.7,0.19,0.19,34,1e-07,1e-07,1.4e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4490000,1,-0.01,-0.012,-0.022,0.014,-0.0034,-0.57,0.0048,-0.0016,-1.2,-1.5e-05,-5e-05,4e-07,0,0,-7.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,4e-07,0.0011,0.0011,0.00022,0.42,0.42,2.7,0.14,0.14,36,8.2e-08,8.2e-08,1.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4590000,1,-0.01,-0.012,-0.022,0.017,-0.0042,-0.58,0.0064,-0.002,-1.2,-1.5e-05,-5e-05,4e-07,0,0,-7.8e-07,0.19,9.3e-10,0.4,0,0,0,0,0,4.2e-07,0.0012,0.0012,0.00021,0.51,0.51,2.7,0.18,0.18,38,8.2e-08,8.2e-08,1.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4690000,1,-0.01,-0.011,-0.022,0.014,-0.0037,-0.59,0.0046,-0.0013,-1.3,-1.5e-05,-5.2e-05,4.1e-07,0,0,-7.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,3.4e-07,0.00093,0.00093,0.00021,0.39,0.39,2.8,0.13,0.13,40,6.6e-08,6.6e-08,1.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4790000,1,-0.01,-0.011,-0.022,0.016,-0.0045,-0.61,0.006,-0.0017,-1.3,-1.5e-05,-5.2e-05,4.1e-07,0,0,-7.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,3.6e-07,0.001,0.001,0.00021,0.47,0.47,2.8,0.17,0.17,42,6.6e-08,6.6e-08,1.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4890000,1,-0.01,-0.011,-0.022,0.013,-0.0043,-0.62,0.0043,-0.0012,-1.4,-1.6e-05,-5.3e-05,4.1e-07,0,0,-7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,3e-07,0.00081,0.00081,0.0002,0.36,0.36,2.9,0.12,0.12,44,5.4e-08,5.4e-08,1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4990000,1,-0.01,-0.011,-0.022,0.015,-0.0044,-0.64,0.0057,-0.0017,-1.5,-1.6e-05,-5.3e-05,4.1e-07,0,0,-7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,3.1e-07,0.00087,0.00087,0.0002,0.43,0.43,2.9,0.16,0.16,46,5.4e-08,5.4e-08,9.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5090000,1,-0.01,-0.011,-0.022,0.012,-0.0033,-0.65,0.004,-0.0012,-1.5,-1.6e-05,-5.4e-05,4.2e-07,0,0,-6.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.6e-07,0.0007,0.0007,0.00019,0.33,0.33,2.9,0.12,0.12,48,4.3e-08,4.3e-08,8.9e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5190000,1,-0.01,-0.011,-0.022,0.013,-0.0041,-0.67,0.0052,-0.0016,-1.6,-1.6e-05,-5.4e-05,4.2e-07,0,0,-6.7e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.7e-07,0.00075,0.00075,0.00019,0.39,0.39,3,0.16,0.16,51,4.3e-08,4.3e-08,8.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5290000,1,-0.0099,-0.011,-0.022,0.0089,-0.0025,-0.68,0.0037,-0.0011,-1.7,-1.6e-05,-5.5e-05,4.2e-07,0,0,-6.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.3e-07,0.0006,0.0006,0.00019,0.3,0.3,3,0.11,0.11,53,3.5e-08,3.5e-08,8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5390000,1,-0.0099,-0.011,-0.022,0.0084,-0.0028,-0.69,0.0045,-0.0014,-1.7,-1.6e-05,-5.5e-05,4.2e-07,0,0,-6.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.4e-07,0.00065,0.00065,0.00018,0.35,0.35,3,0.15,0.15,56,3.5e-08,3.5e-08,7.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5490000,1,-0.0098,-0.011,-0.022,0.0058,-0.0019,-0.71,0.003,-0.00094,-1.8,-1.6e-05,-5.5e-05,4.2e-07,0,0,-6.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2e-07,0.00052,0.00052,0.00018,0.27,0.27,3.1,0.11,0.11,58,2.8e-08,2.8e-08,7.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5590000,1,-0.0098,-0.011,-0.022,0.0066,-0.0018,-0.72,0.0036,-0.0011,-1.9,-1.6e-05,-5.5e-05,4.2e-07,0,0,-6.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.1e-07,0.00056,0.00056,0.00018,0.32,0.32,3.1,0.14,0.14,61,2.8e-08,2.8e-08,6.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5690000,1,-0.0097,-0.011,-0.022,0.007,-0.00067,-0.74,0.0043,-0.0012,-2,-1.6e-05,-5.5e-05,4.2e-07,0,0,-6.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,2.1e-07,0.00059,0.0006,0.00017,0.37,0.37,3.2,0.18,0.18,63,2.8e-08,2.8e-08,6.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5790000,1,-0.0096,-0.011,-0.022,0.0051,0.0015,-0.75,0.0029,-0.00065,-2,-1.7e-05,-5.6e-05,4.2e-07,0,0,-6e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.8e-07,0.00048,0.00048,0.00017,0.29,0.29,3.2,0.13,0.13,66,2.3e-08,2.3e-08,6.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5890000,1,-0.0095,-0.011,-0.022,0.0063,0.0022,0.0028,0.0035,-0.0005,-3.7e+02,-1.7e-05,-5.6e-05,4.2e-07,0,0,-6.3e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.9e-07,0.00051,0.00051,0.00017,0.34,0.34,9.8,0.17,0.17,0.52,2.3e-08,2.3e-08,5.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5990000,1,-0.0095,-0.011,-0.022,0.0049,0.0042,0.015,0.0025,6.1e-05,-3.7e+02,-1.7e-05,-5.6e-05,4.2e-07,0,0,-7.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00041,0.00041,0.00017,0.26,0.26,8.8,0.13,0.13,0.33,1.8e-08,1.8e-08,5.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6090000,1,-0.0095,-0.011,-0.022,0.006,0.0057,-0.011,0.003,0.00058,-3.7e+02,-1.7e-05,-5.6e-05,4.2e-07,0,0,-6.2e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.7e-07,0.00044,0.00044,0.00016,0.31,0.31,7,0.16,0.16,0.33,1.8e-08,1.8e-08,5.3e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6190000,0.71,0.0014,-0.014,0.71,0.0041,0.0063,-0.005,0.0022,0.0009,-3.7e+02,-1.6e-05,-5.7e-05,4.2e-07,0,0,-8.6e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00081,0.00034,0.00034,0.00091,0.22,0.22,4.9,0.12,0.12,0.32,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6290000,0.71,0.0014,-0.014,0.71,0.0038,0.0077,-0.012,0.0026,0.0016,-3.7e+02,-1.6e-05,-5.7e-05,4.2e-07,0,0,-9.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00053,0.00034,0.00034,0.00059,0.23,0.23,3.2,0.15,0.15,0.3,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6390000,0.71,0.0014,-0.014,0.71,0.0024,0.0082,-0.05,0.0029,0.0024,-3.7e+02,-1.6e-05,-5.7e-05,4.6e-07,0,0,-3.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00041,0.00034,0.00034,0.00046,0.23,0.23,2.3,0.19,0.19,0.29,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6490000,0.71,0.0015,-0.014,0.71,0.0018,0.009,-0.052,0.0031,0.0033,-3.7e+02,-1.6e-05,-5.7e-05,4.4e-07,0,0,-8.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00033,0.00035,0.00035,0.00037,0.24,0.24,1.5,0.23,0.23,0.26,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6590000,0.71,0.0015,-0.014,0.71,0.00095,0.0091,-0.099,0.0033,0.0042,-3.7e+02,-1.6e-05,-5.7e-05,3.4e-07,0,0,9.7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00028,0.00035,0.00035,0.00031,0.25,0.25,1.1,0.27,0.27,0.23,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6690000,0.71,0.0015,-0.014,0.71,0.00098,0.01,-0.076,0.0034,0.0051,-3.7e+02,-1.6e-05,-5.7e-05,2.4e-07,0,0,-2.2e-06,0.21,0.0021,0.43,0,0,0,0,0,0.00024,0.00035,0.00035,0.00027,0.26,0.26,0.78,0.32,0.32,0.21,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6790000,0.71,0.0015,-0.014,0.71,-0.00069,0.01,-0.11,0.0034,0.0062,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-07,0,0,9.9e-08,0.21,0.0021,0.43,0,0,0,0,0,0.00022,0.00036,0.00036,0.00024,0.28,0.28,0.6,0.37,0.37,0.2,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6890000,0.71,0.0016,-0.014,0.71,-0.0031,0.011,-0.12,0.0032,0.0072,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-07,0,0,-4.1e-07,0.21,0.0021,0.43,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.46,0.43,0.43,0.18,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6990000,0.7,0.0016,-0.014,0.71,-0.0035,0.011,-0.12,0.0028,0.0083,-3.7e+02,-1.6e-05,-5.7e-05,3.3e-08,0,0,-3.4e-06,0.21,0.0021,0.43,0,0,0,0,0,0.00018,0.00037,0.00037,0.0002,0.32,0.32,0.36,0.5,0.5,0.16,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7090000,0.7,0.0016,-0.014,0.71,-0.0045,0.011,-0.13,0.0024,0.0094,-3.7e+02,-1.6e-05,-5.7e-05,-2.6e-07,0,0,-7e-06,0.21,0.0021,0.43,0,0,0,0,0,0.00017,0.00037,0.00037,0.00019,0.34,0.34,0.29,0.57,0.57,0.16,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7190000,0.7,0.0016,-0.014,0.71,-0.0066,0.011,-0.15,0.0019,0.01,-3.7e+02,-1.6e-05,-5.7e-05,-4e-07,0,0,-4.9e-06,0.21,0.0021,0.43,0,0,0,0,0,0.00016,0.00038,0.00038,0.00018,0.37,0.37,0.24,0.65,0.65,0.15,1.5e-08,1.5e-08,5.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7290000,0.7,0.0017,-0.014,0.71,-0.0085,0.011,-0.15,0.0011,0.012,-3.7e+02,-1.6e-05,-5.7e-05,-4.3e-07,0,0,-1.2e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00015,0.00039,0.00039,0.00017,0.4,0.4,0.2,0.74,0.74,0.14,1.5e-08,1.5e-08,5.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7390000,0.7,0.0017,-0.014,0.71,-0.0091,0.013,-0.16,0.0002,0.013,-3.7e+02,-1.6e-05,-5.7e-05,-4.2e-07,0,0,-1.3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00014,0.0004,0.0004,0.00016,0.43,0.43,0.18,0.84,0.84,0.13,1.5e-08,1.5e-08,5.1e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7490000,0.7,0.0018,-0.014,0.71,-0.011,0.013,-0.16,-0.00083,0.014,-3.7e+02,-1.6e-05,-5.7e-05,-4.7e-07,0,0,-2.1e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00014,0.00041,0.00041,0.00015,0.47,0.47,0.15,0.95,0.95,0.12,1.5e-08,1.5e-08,5.1e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7590000,0.7,0.0018,-0.014,0.71,-0.013,0.015,-0.17,-0.002,0.015,-3.7e+02,-1.6e-05,-5.7e-05,-3.2e-07,0,0,-3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00013,0.00042,0.00042,0.00014,0.51,0.51,0.14,1.1,1.1,0.12,1.4e-08,1.4e-08,5.1e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7690000,0.7,0.0019,-0.014,0.71,-0.016,0.015,-0.16,-0.0035,0.017,-3.7e+02,-1.6e-05,-5.7e-05,-3.7e-07,0,0,-5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00013,0.00043,0.00043,0.00014,0.55,0.55,0.13,1.2,1.2,0.11,1.4e-08,1.4e-08,5.1e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7790000,0.7,0.0019,-0.014,0.71,-0.018,0.016,-0.16,-0.0052,0.018,-3.7e+02,-1.6e-05,-5.7e-05,-7.9e-07,0,0,-7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00012,0.00044,0.00044,0.00013,0.6,0.6,0.12,1.3,1.3,0.11,1.4e-08,1.4e-08,5.1e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7890000,0.7,0.0019,-0.014,0.71,-0.021,0.018,-0.16,-0.0071,0.019,-3.7e+02,-1.6e-05,-5.7e-05,-6.9e-07,0,0,-9.6e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00012,0.00045,0.00045,0.00013,0.65,0.65,0.11,1.5,1.5,0.1,1.4e-08,1.4e-08,5.1e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
7990000,0.7,0.0019,-0.014,0.71,-0.023,0.019,-0.16,-0.0093,0.021,-3.7e+02,-1.6e-05,-5.7e-05,-5.7e-07,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.00012,0.00046,0.00046,0.00013,0.7,0.7,0.1,1.7,1.7,0.099,1.4e-08,1.4e-08,5e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
8090000,0.7,0.0019,-0.014,0.71,-0.025,0.02,-0.17,-0.012,0.023,-3.7e+02,-1.6e-05,-5.7e-05,-3.2e-07,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.00011,0.00047,0.00047,0.00012,0.75,0.75,0.1,1.8,1.8,0.097,1.4e-08,1.4e-08,5e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8190000,0.7,0.0019,-0.014,0.71,-0.029,0.022,-0.18,-0.014,0.025,-3.7e+02,-1.6e-05,-5.7e-05,-6.6e-07,0,0,-0.00013,0.21,0.0021,0.43,0,0,0,0,0,0.00011,0.00049,0.00049,0.00012,0.81,0.81,0.099,2,2,0.094,1.4e-08,1.4e-08,5e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8290000,0.7,0.002,-0.014,0.71,-0.031,0.022,-0.17,-0.017,0.026,-3.7e+02,-1.6e-05,-5.6e-05,-9e-07,0,0,-0.00017,0.21,0.0021,0.43,0,0,0,0,0,0.00011,0.0005,0.0005,0.00012,0.87,0.87,0.097,2.2,2.2,0.091,1.4e-08,1.4e-08,5e-09,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
8390000,0.7,0.002,-0.014,0.71,-0.033,0.024,-0.17,-0.02,0.029,-3.7e+02,-1.6e-05,-5.6e-05,-6.3e-07,0,0,-0.00021,0.21,0.0021,0.43,0,0,0,0,0,0.00011,0.00051,0.00051,0.00012,0.94,0.94,0.097,2.5,2.5,0.091,1.4e-08,1.4e-08,4.9e-09,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
8490000,0.7,0.002,-0.014,0.71,-0.036,0.025,-0.17,-0.024,0.03,-3.7e+02,-1.6e-05,-5.6e-05,-8.2e-07,0,0,-0.00025,0.21,0.0021,0.43,0,0,0,0,0,0.00011,0.00052,0.00052,0.00011,0.99,0.99,0.096,2.7,2.7,0.089,1.4e-08,1.4e-08,4.9e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
8590000,0.7,0.0021,-0.014,0.71,-0.039,0.027,-0.17,-0.027,0.032,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00029,0.21,0.0021,0.43,0,0,0,0,0,0.00011,0.00054,0.00054,0.00011,1.1,1.1,0.095,3,3,0.088,1.4e-08,1.4e-08,4.9e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
8690000,0.7,0.0021,-0.014,0.71,-0.042,0.028,-0.16,-0.031,0.034,-3.7e+02,-1.6e-05,-5.6e-05,-7.9e-07,0,0,-0.00035,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.00055,0.00055,0.00011,1.1,1.1,0.096,3.2,3.2,0.088,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
8790000,0.7,0.0021,-0.014,0.71,-0.045,0.03,-0.15,-0.036,0.036,-3.7e+02,-1.6e-05,-5.6e-05,-1.1e-06,0,0,-0.00041,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.00057,0.00057,0.00011,1.2,1.2,0.095,3.6,3.6,0.087,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,3.2e-06,0,0,0,0,0,0,0,0
8890000,0.7,0.0021,-0.014,0.71,-0.047,0.03,-0.15,-0.039,0.038,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00045,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.00058,0.00058,0.00011,1.3,1.3,0.095,3.8,3.8,0.086,1.3e-08,1.4e-08,4.8e-09,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
8990000,0.7,0.0022,-0.014,0.71,-0.05,0.03,-0.14,-0.044,0.04,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-06,0,0,-0.00051,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.0006,0.00059,0.00011,1.4,1.4,0.096,4.2,4.2,0.087,1.3e-08,1.4e-08,4.7e-09,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
9090000,0.7,0.0022,-0.014,0.71,-0.052,0.031,-0.14,-0.048,0.041,-3.7e+02,-1.6e-05,-5.6e-05,-1.9e-06,0,0,-0.00053,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.0006,0.0006,0.00011,1.4,1.4,0.095,4.5,4.5,0.086,1.3e-08,1.3e-08,4.7e-09,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
9190000,0.7,0.0022,-0.014,0.71,-0.055,0.032,-0.14,-0.053,0.044,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00057,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.00062,0.00062,0.0001,1.5,1.5,0.094,5,5,0.085,1.3e-08,1.3e-08,4.6e-09,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0
9290000,0.7,0.0022,-0.014,0.71,-0.055,0.032,-0.14,-0.056,0.045,-3.7e+02,-1.6e-05,-5.6e-05,-1.1e-06,0,0,-0.00061,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.00062,0.00062,0.0001,1.6,1.6,0.093,5.2,5.2,0.085,1.3e-08,1.3e-08,4.6e-09,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
9390000,0.7,0.0022,-0.014,0.71,-0.057,0.034,-0.14,-0.062,0.048,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00065,0.21,0.0021,0.43,0,0,0,0,0,0.0001,0.00064,0.00064,0.0001,1.7,1.7,0.093,5.7,5.7,0.086,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
9490000,0.7,0.0022,-0.014,0.71,-0.058,0.034,-0.13,-0.064,0.048,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,0,0,-0.00068,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00064,0.00064,0.0001,1.7,1.7,0.091,5.9,5.9,0.085,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0
9590000,0.7,0.0022,-0.014,0.71,-0.062,0.035,-0.13,-0.071,0.052,-3.7e+02,-1.6e-05,-5.6e-05,-4.9e-07,0,0,-0.00072,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00066,0.00066,0.0001,1.8,1.8,0.09,6.5,6.5,0.085,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
9690000,0.7,0.0023,-0.014,0.71,-0.062,0.036,-0.12,-0.072,0.051,-3.7e+02,-1.6e-05,-5.6e-05,-1.1e-06,0,0,-0.00077,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00066,0.00066,0.0001,1.8,1.8,0.089,6.7,6.7,0.086,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
9790000,0.7,0.0023,-0.014,0.71,-0.063,0.039,-0.11,-0.079,0.055,-3.7e+02,-1.6e-05,-5.6e-05,-7.7e-07,0,0,-0.00082,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00068,0.00068,0.0001,2,2,0.087,7.4,7.4,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
9890000,0.7,0.0023,-0.013,0.71,-0.067,0.04,-0.11,-0.086,0.058,-3.7e+02,-1.6e-05,-5.6e-05,-8.7e-07,0,0,-0.00085,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.0007,0.0007,0.0001,2.1,2.1,0.084,8.1,8.1,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0
9990000,0.7,0.0023,-0.014,0.71,-0.066,0.039,-0.1,-0.086,0.058,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00089,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.0007,0.0007,0.0001,2.1,2.1,0.083,8.2,8.2,0.086,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
10090000,0.7,0.0024,-0.014,0.71,-0.068,0.04,-0.096,-0.093,0.062,-3.7e+02,-1.6e-05,-5.6e-05,-1.1e-06,0,0,-0.00091,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00072,0.00072,0.0001,2.2,2.2,0.08,9,9,0.085,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
10190000,0.7,0.0023,-0.014,0.71,-0.066,0.041,-0.096,-0.092,0.06,-3.7e+02,-1.6e-05,-5.6e-05,-2e-06,0,0,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00071,0.00071,0.0001,2.2,2.2,0.078,9,9,0.084,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10290000,0.7,0.0023,-0.014,0.71,-0.069,0.041,-0.084,-0.1,0.064,-3.7e+02,-1.6e-05,-5.6e-05,-2.6e-06,0,0,-0.00098,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00073,0.00073,0.0001,2.4,2.4,0.076,9.8,9.8,0.085,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10390000,0.7,0.0023,-0.014,0.71,0.0089,-0.019,0.0096,0.00084,-0.0017,-3.7e+02,-1.6e-05,-5.6e-05,-2.6e-06,-6.6e-10,4.7e-10,-0.001,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00076,0.00076,0.0001,0.25,0.25,0.56,0.25,0.25,0.078,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
10490000,0.7,0.0024,-0.014,0.71,0.007,-0.017,0.023,0.0016,-0.0035,-3.7e+02,-1.6e-05,-5.6e-05,-3.2e-06,-1.7e-08,1.2e-08,-0.001,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00078,0.00078,9.9e-05,0.26,0.26,0.55,0.26,0.26,0.08,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10590000,0.7,0.0025,-0.014,0.71,0.0066,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-1.6e-05,-5.6e-05,-3.2e-06,-2.6e-06,5.1e-07,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00079,0.00079,9.9e-05,0.14,0.14,0.27,0.13,0.13,0.073,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10690000,0.7,0.0025,-0.014,0.71,0.0039,-0.0058,0.03,0.0024,-0.0014,-3.7e+02,-1.6e-05,-5.6e-05,-3.4e-06,-2.7e-06,5.2e-07,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00081,0.00081,9.9e-05,0.15,0.15,0.26,0.14,0.14,0.078,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10790000,0.7,0.0025,-0.014,0.71,0.0035,-0.003,0.024,0.0026,-0.00072,-3.7e+02,-1.5e-05,-5.5e-05,-3.4e-06,-4.2e-06,2.3e-06,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00078,0.00078,9.9e-05,0.11,0.11,0.17,0.091,0.091,0.072,1.1e-08,1.1e-08,3.7e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10890000,0.7,0.0025,-0.014,0.71,0.0016,-0.0017,0.02,0.0029,-0.00092,-3.7e+02,-1.5e-05,-5.5e-05,-3.4e-06,-4.2e-06,2.3e-06,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00081,0.00081,9.9e-05,0.13,0.13,0.16,0.098,0.098,0.075,1.1e-08,1.1e-08,3.6e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10990000,0.7,0.0024,-0.014,0.71,0.0047,0.0034,0.014,0.0046,-0.0022,-3.7e+02,-1.4e-05,-5.5e-05,-2.9e-06,-8.1e-06,9.2e-06,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00073,0.00073,9.9e-05,0.1,0.1,0.12,0.073,0.073,0.071,1.1e-08,1.1e-08,3.6e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11090000,0.7,0.0024,-0.014,0.71,0.003,0.0059,0.019,0.005,-0.0018,-3.7e+02,-1.4e-05,-5.5e-05,-2.5e-06,-8.2e-06,9.3e-06,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00076,0.00076,9.9e-05,0.13,0.13,0.11,0.08,0.08,0.074,1.1e-08,1.1e-08,3.5e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11190000,0.7,0.0023,-0.014,0.71,0.0084,0.0083,0.0077,0.0066,-0.0028,-3.7e+02,-1.3e-05,-5.5e-05,-2.9e-06,-9.2e-06,1.6e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00065,0.00065,9.9e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.4e-09,9.4e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11290000,0.7,0.0023,-0.014,0.71,0.0078,0.011,0.0074,0.0074,-0.0018,-3.7e+02,-1.3e-05,-5.5e-05,-3.7e-06,-9.2e-06,1.6e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00067,0.00067,9.9e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.4e-09,9.4e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11390000,0.7,0.0023,-0.014,0.71,0.0034,0.0092,0.0017,0.0054,-0.0019,-3.7e+02,-1.4e-05,-5.5e-05,-4.2e-06,-5e-06,1.3e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00056,0.00056,9.9e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-09,8.2e-09,3.3e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11490000,0.7,0.0024,-0.014,0.71,0.0005,0.012,0.0025,0.0056,-0.00089,-3.7e+02,-1.4e-05,-5.5e-05,-5.3e-06,-5e-06,1.3e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00058,0.00058,9.8e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-09,8.2e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11590000,0.7,0.0022,-0.014,0.71,-0.0033,0.01,-0.0034,0.0043,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-5.5e-06,-8.5e-07,1.2e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00047,0.00047,9.9e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-09,7.2e-09,3.2e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11690000,0.7,0.0022,-0.014,0.71,-0.0064,0.013,-0.0079,0.0038,-0.00027,-3.7e+02,-1.4e-05,-5.6e-05,-5.8e-06,-7.5e-07,1.2e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00049,0.00049,9.8e-05,0.13,0.13,0.046,0.063,0.063,0.066,7.2e-09,7.2e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11790000,0.7,0.0022,-0.014,0.71,-0.012,0.013,-0.0098,0.0017,0.00055,-3.7e+02,-1.4e-05,-5.6e-05,-5.9e-06,3.1e-07,1.1e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.0004,0.0004,9.8e-05,0.097,0.097,0.039,0.053,0.053,0.063,6.4e-09,6.4e-09,3e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11890000,0.7,0.0022,-0.014,0.71,-0.013,0.014,-0.011,0.00046,0.0019,-3.7e+02,-1.4e-05,-5.6e-05,-6.4e-06,2.5e-07,1.1e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00041,0.00041,9.8e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.4e-09,6.4e-09,3e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11990000,0.7,0.0022,-0.014,0.71,-0.014,0.014,-0.016,-0.00042,0.0023,-3.7e+02,-1.4e-05,-5.6e-05,-6.2e-06,1.7e-06,1.1e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00034,0.00034,9.8e-05,0.091,0.091,0.033,0.051,0.051,0.061,5.8e-09,5.8e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12090000,0.7,0.0022,-0.014,0.71,-0.016,0.016,-0.022,-0.0019,0.0038,-3.7e+02,-1.4e-05,-5.6e-05,-5.7e-06,1.8e-06,1.1e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00035,0.00035,9.8e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.8e-09,5.8e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12190000,0.7,0.0019,-0.014,0.71,-0.0091,0.013,-0.017,0.0014,0.0019,-3.7e+02,-1.3e-05,-5.7e-05,-5.5e-06,4.3e-06,1.6e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.0003,0.0003,9.8e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.3e-09,5.3e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12290000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.016,0.00033,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-5.3e-06,4.1e-06,1.7e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00031,0.00031,9.8e-05,0.1,0.1,0.028,0.06,0.06,0.059,5.3e-09,5.3e-09,2.7e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12390000,0.7,0.0015,-0.014,0.71,-0.006,0.011,-0.015,0.0029,0.0016,-3.7e+02,-1.3e-05,-5.8e-05,-5.6e-06,5.7e-06,2e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00027,0.00027,9.8e-05,0.079,0.079,0.026,0.05,0.05,0.057,4.9e-09,4.9e-09,2.7e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12490000,0.7,0.0015,-0.014,0.71,-0.0073,0.013,-0.018,0.0023,0.0029,-3.7e+02,-1.3e-05,-5.8e-05,-6.1e-06,5.6e-06,2e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00028,0.00028,9.7e-05,0.093,0.093,0.026,0.059,0.059,0.057,4.9e-09,4.9e-09,2.6e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12590000,0.7,0.0016,-0.014,0.71,-0.015,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-1.3e-05,-5.8e-05,-6e-06,7e-06,1.7e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00025,0.00025,9.8e-05,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-09,4.5e-09,2.5e-09,3.7e-06,3.7e-06,9.9e-07,0,0,0,0,0,0,0,0
12690000,0.7,0.0016,-0.014,0.71,-0.015,0.012,-0.027,-0.0044,0.0026,-3.7e+02,-1.3e-05,-5.8e-05,-6.2e-06,7.2e-06,1.7e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00026,0.00026,9.7e-05,0.086,0.086,0.025,0.058,0.058,0.055,4.5e-09,4.5e-09,2.5e-09,3.7e-06,3.7e-06,9.8e-07,0,0,0,0,0,0,0,0
12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0091,-0.03,-0.0077,0.0013,-3.7e+02,-1.4e-05,-5.8e-05,-6e-06,7.6e-06,1.7e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00023,0.00023,9.7e-05,0.069,0.069,0.024,0.049,0.049,0.053,4.3e-09,4.3e-09,2.4e-09,3.7e-06,3.7e-06,9.7e-07,0,0,0,0,0,0,0,0
12890000,0.7,0.0016,-0.013,0.71,-0.022,0.0091,-0.029,-0.0098,0.0022,-3.7e+02,-1.4e-05,-5.8e-05,-5.8e-06,6.9e-06,1.7e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00024,0.00024,9.7e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.3e-09,4.3e-09,2.4e-09,3.7e-06,3.7e-06,9.6e-07,0,0,0,0,0,0,0,0
12990000,0.7,0.0012,-0.014,0.71,-0.0089,0.0065,-0.03,-0.0011,0.0011,-3.7e+02,-1.3e-05,-5.9e-05,-5.1e-06,6.8e-06,1.9e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00022,0.00022,9.7e-05,0.064,0.064,0.025,0.049,0.049,0.052,4e-09,4e-09,2.3e-09,3.7e-06,3.7e-06,9.4e-07,0,0,0,0,0,0,0,0
13090000,0.7,0.0012,-0.014,0.71,-0.0097,0.0067,-0.03,-0.002,0.0018,-3.7e+02,-1.3e-05,-5.9e-05,-5.6e-06,6.4e-06,1.9e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00023,0.00023,9.7e-05,0.073,0.073,0.025,0.058,0.058,0.052,4e-09,4e-09,2.3e-09,3.7e-06,3.7e-06,9.4e-07,0,0,0,0,0,0,0,0
13190000,0.7,0.001,-0.014,0.71,-0.00048,0.0061,-0.027,0.0044,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-5.5e-06,5e-06,2e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00021,0.00021,9.6e-05,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-09,3.8e-09,2.2e-09,3.7e-06,3.7e-06,9.1e-07,0,0,0,0,0,0,0,0
13290000,0.7,0.001,-0.014,0.71,-0.00076,0.0069,-0.024,0.0043,0.0018,-3.7e+02,-1.2e-05,-5.9e-05,-4.9e-06,3.7e-06,2.1e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.9e-05,0.00022,0.00022,9.6e-05,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-09,3.8e-09,2.2e-09,3.7e-06,3.7e-06,9.1e-07,0,0,0,0,0,0,0,0
13390000,0.7,0.00085,-0.014,0.71,0.00016,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-4.4e-06,2e-06,2.1e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00021,0.00021,9.6e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-09,3.6e-09,2.1e-09,3.7e-06,3.7e-06,8.8e-07,0,0,0,0,0,0,0,0
13490000,0.7,0.00088,-0.014,0.71,-0.00036,0.0058,-0.019,0.0033,0.0016,-3.7e+02,-1.2e-05,-5.9e-05,-4e-06,1.1e-06,2.2e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00021,0.00021,9.6e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-09,3.6e-09,2.1e-09,3.7e-06,3.7e-06,8.7e-07,0,0,0,0,0,0,0,0
13590000,0.7,0.00082,-0.014,0.71,-2.4e-05,0.006,-0.021,0.0024,0.001,-3.7e+02,-1.2e-05,-5.9e-05,-4.2e-06,8.6e-07,2e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.0002,0.0002,9.6e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.5e-09,3.5e-09,2e-09,3.7e-06,3.7e-06,8.4e-07,0,0,0,0,0,0,0,0
13690000,0.7,0.00079,-0.014,0.71,0.00064,0.0078,-0.025,0.0024,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-3.5e-06,1.2e-06,2e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00021,0.00021,9.6e-05,0.06,0.06,0.029,0.056,0.056,0.05,3.5e-09,3.5e-09,2e-09,3.7e-06,3.7e-06,8.3e-07,0,0,0,0,0,0,0,0
13790000,0.7,0.00067,-0.014,0.71,0.0013,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-1.1e-05,-6e-05,-3.5e-06,-1e-06,1.9e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.0002,0.0002,9.5e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-09,3.3e-09,1.9e-09,3.6e-06,3.6e-06,7.9e-07,0,0,0,0,0,0,0,0
13890000,0.7,0.00064,-0.014,0.71,0.0018,0.0035,-0.031,0.0036,-0.00031,-3.7e+02,-1.1e-05,-6e-05,-3.1e-06,-7e-07,1.9e-05,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,9.8e-05,0.00021,0.00021,9.5e-05,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-09,3.3e-09,1.9e-09,3.6e-06,3.6e-06,7.8e-07,0,0,0,0,0,0,0,0
13990000,0.7,0.00057,-0.014,0.71,0.0021,0.001,-0.03,0.0044,-0.002,-3.7e+02,-1.1e-05,-6e-05,-2.9e-06,-3.4e-06,1.8e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.7e-05,0.0002,0.0002,9.5e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-09,3.1e-09,1.8e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0
14090000,0.7,0.00055,-0.014,0.71,0.0022,0.0011,-0.031,0.0046,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-2.2e-06,-3.2e-06,1.8e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.7e-05,0.0002,0.0002,9.5e-05,0.055,0.055,0.031,0.056,0.056,0.05,3.1e-09,3.1e-09,1.8e-09,3.6e-06,3.6e-06,7.3e-07,0,0,0,0,0,0,0,0
14190000,0.7,0.00045,-0.014,0.71,0.0056,0.00062,-0.033,0.0068,-0.0017,-3.7e+02,-1.1e-05,-6e-05,-1.8e-06,-3.1e-06,1.5e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.7e-05,0.0002,0.0002,9.5e-05,0.046,0.046,0.031,0.048,0.048,0.05,3e-09,3e-09,1.7e-09,3.6e-06,3.6e-06,6.9e-07,0,0,0,0,0,0,0,0
14290000,0.7,0.00045,-0.014,0.71,0.0063,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-1.5e-06,-3.7e-06,1.5e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.7e-05,0.0002,0.0002,9.4e-05,0.052,0.052,0.032,0.055,0.055,0.051,3e-09,3e-09,1.7e-09,3.6e-06,3.6e-06,6.7e-07,0,0,0,0,0,0,0,0
14390000,0.7,0.00037,-0.014,0.71,0.0082,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-1.1e-05,-6e-05,-8.6e-07,-3.8e-06,1.3e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.6e-05,0.00019,0.00019,9.4e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-09,2.8e-09,1.7e-09,3.6e-06,3.6e-06,6.3e-07,0,0,0,0,0,0,0,0
14490000,0.7,0.00035,-0.013,0.71,0.0082,0.0035,-0.037,0.0095,-0.0011,-3.7e+02,-1.1e-05,-6e-05,-6.2e-07,-3.3e-06,1.2e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.4e-05,0.051,0.051,0.032,0.055,0.055,0.051,2.8e-09,2.8e-09,1.6e-09,3.6e-06,3.6e-06,6.2e-07,0,0,0,0,0,0,0,0
14590000,0.7,0.00034,-0.013,0.71,0.0047,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-1.1e-05,-6.1e-05,-5.5e-07,-7e-06,1.6e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.6e-05,0.00019,0.00019,9.4e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.8e-07,0,0,0,0,0,0,0,0
14690000,0.7,0.0003,-0.013,0.71,0.0061,-0.0011,-0.034,0.0066,-0.0024,-3.7e+02,-1.1e-05,-6.1e-05,-5.6e-08,-8e-06,1.7e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.3e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.7e-09,2.7e-09,1.5e-09,3.6e-06,3.6e-06,5.6e-07,0,0,0,0,0,0,0,0
14790000,0.7,0.00032,-0.013,0.71,0.0029,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-1.1e-05,-6.1e-05,1.1e-07,-1.2e-05,2.2e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.3e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-09,2.5e-09,1.5e-09,3.6e-06,3.6e-06,5.3e-07,0,0,0,0,0,0,0,0
14890000,0.7,0.00031,-0.013,0.71,0.0045,-0.0017,-0.033,0.004,-0.0036,-3.7e+02,-1.1e-05,-6.1e-05,4.4e-07,-1.2e-05,2.2e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.048,0.048,0.031,0.054,0.054,0.052,2.5e-09,2.5e-09,1.5e-09,3.6e-06,3.6e-06,5.1e-07,0,0,0,0,0,0,0,0
14990000,0.7,0.00031,-0.013,0.71,0.0033,-0.0018,-0.029,0.0031,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,3.9e-07,-1.2e-05,2.4e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-09,2.3e-09,1.4e-09,3.6e-06,3.6e-06,4.8e-07,0,0,0,0,0,0,0,0
15090000,0.7,0.00023,-0.013,0.71,0.0037,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,4.4e-07,-1.2e-05,2.4e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-09,2.3e-09,1.4e-09,3.6e-06,3.6e-06,4.6e-07,0,0,0,0,0,0,0,0
15190000,0.7,0.00025,-0.013,0.71,0.0031,-0.0008,-0.029,0.0027,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,4.1e-07,-1.2e-05,2.6e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-09,2.2e-09,1.4e-09,3.5e-06,3.5e-06,4.3e-07,0,0,0,0,0,0,0,0
15290000,0.7,0.00021,-0.013,0.71,0.0037,-0.00064,-0.027,0.0031,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,7.4e-07,-1.3e-05,2.6e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.2e-05,0.046,0.046,0.03,0.054,0.054,0.052,2.2e-09,2.2e-09,1.3e-09,3.5e-06,3.5e-06,4.2e-07,0,0,0,0,0,0,0,0
15390000,0.7,0.00021,-0.013,0.71,0.0029,-0.00029,-0.024,0.00053,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,1.4e-06,-1.3e-05,2.9e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.4e-05,0.00018,0.00018,9.1e-05,0.04,0.04,0.029,0.047,0.047,0.051,2e-09,2e-09,1.3e-09,3.5e-06,3.5e-06,3.9e-07,0,0,0,0,0,0,0,0
15490000,0.7,0.00023,-0.013,0.71,0.0042,-0.00067,-0.024,0.00089,-0.0021,-3.7e+02,-1.2e-05,-6.1e-05,1.1e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.1e-05,0.045,0.045,0.029,0.053,0.053,0.053,2e-09,2e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0
15590000,0.7,0.00025,-0.013,0.71,0.0023,-0.00066,-0.023,-0.0013,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,9.1e-07,-1.3e-05,3.1e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.4e-05,0.00018,0.00018,9.1e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.5e-07,0,0,0,0,0,0,0,0
15690000,0.7,0.00025,-0.013,0.71,0.0027,-0.00084,-0.023,-0.0011,-0.0018,-3.7e+02,-1.2e-05,-6.1e-05,9.4e-07,-1.3e-05,3.1e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.3e-05,0.00018,0.00018,9.1e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0
15790000,0.7,0.00021,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00099,-0.0028,-3.7e+02,-1.2e-05,-6.1e-05,9.9e-07,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.8e-09,1.8e-09,1.2e-09,3.5e-06,3.5e-06,3.1e-07,0,0,0,0,0,0,0,0
15890000,0.7,0.00016,-0.013,0.71,0.0041,-0.003,-0.024,-0.0006,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.1e-06,-1.6e-05,3.1e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.8e-09,1.8e-09,1.2e-09,3.5e-06,3.5e-06,3e-07,0,0,0,0,0,0,0,0
15990000,0.7,0.0001,-0.013,0.71,0.004,-0.0039,-0.019,-0.00067,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1.9e-05,3.3e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.3e-05,0.00017,0.00017,9e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-09,1.6e-09,1.1e-09,3.4e-06,3.4e-06,2.8e-07,0,0,0,0,0,0,0,0
16090000,0.7,0.0001,-0.013,0.71,0.0057,-0.0041,-0.016,-0.0002,-0.0043,-3.7e+02,-1.2e-05,-6.1e-05,2.2e-06,-1.9e-05,3.4e-05,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,9.2e-05,0.00018,0.00018,8.9e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-09,1.6e-09,1.1e-09,3.4e-06,3.4e-06,2.7e-07,0,0,0,0,0,0,0,0
16190000,0.7,0.00013,-0.013,0.71,0.0057,-0.0033,-0.014,-0.0004,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,2.3e-06,-1.8e-05,3.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9.2e-05,0.00017,0.00017,8.9e-05,0.038,0.038,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.5e-07,0,0,0,0,0,0,0,0
16290000,0.71,0.00015,-0.013,0.71,0.0073,-0.0041,-0.016,0.00025,-0.0038,-3.7e+02,-1.2e-05,-6.1e-05,2.9e-06,-1.8e-05,3.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9.2e-05,0.00017,0.00017,8.9e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.4e-07,0,0,0,0,0,0,0,0
16390000,0.71,0.00014,-0.013,0.71,0.0062,-0.0044,-0.015,-7.1e-05,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,2.7e-06,-1.7e-05,3.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.9e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1e-09,3.4e-06,3.4e-06,2.2e-07,0,0,0,0,0,0,0,0
16490000,0.71,0.00015,-0.013,0.71,0.0054,-0.0039,-0.018,0.00049,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.9e-05,0.042,0.042,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1e-09,3.4e-06,3.4e-06,2.1e-07,0,0,0,0,0,0,0,0
16590000,0.71,0.00041,-0.013,0.71,0.0019,-0.0012,-0.018,-0.0025,-8.1e-05,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-9.7e-06,4.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9.1e-05,0.00016,0.00016,8.8e-05,0.037,0.037,0.022,0.046,0.046,0.051,1.2e-09,1.3e-09,9.9e-10,3.3e-06,3.3e-06,2e-07,0,0,0,0,0,0,0,0
16690000,0.71,0.0004,-0.013,0.71,0.0021,-0.00071,-0.015,-0.0022,-0.00018,-3.7e+02,-1.3e-05,-6e-05,2.7e-06,-1e-05,4.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9.1e-05,0.00017,0.00016,8.8e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-09,1.3e-09,9.6e-10,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0
16790000,0.71,0.00055,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-1.3e-05,-6e-05,2.8e-06,-4.5e-06,5.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9e-05,0.00016,0.00016,8.8e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-09,1.1e-09,9.4e-10,3.3e-06,3.3e-06,1.8e-07,0,0,0,0,0,0,0,0
16890000,0.71,0.00056,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-1.3e-05,-6e-05,2.7e-06,-4.9e-06,5.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9e-05,0.00016,0.00016,8.7e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-09,1.1e-09,9.2e-10,3.3e-06,3.3e-06,1.7e-07,0,0,0,0,0,0,0,0
16990000,0.71,0.0005,-0.013,0.71,-0.0015,0.00035,-0.01,-0.0052,0.00085,-3.7e+02,-1.3e-05,-6e-05,2.4e-06,-9e-06,5.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,9e-05,0.00015,0.00015,8.7e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-09,1e-09,9e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
17090000,0.71,0.00047,-0.013,0.71,-0.00074,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-1.3e-05,-6e-05,2.5e-06,-8.9e-06,5.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.7e-05,0.04,0.04,0.02,0.052,0.052,0.05,1e-09,1e-09,8.8e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
17190000,0.71,0.00045,-0.013,0.71,-0.00029,0.0013,-0.011,-0.0056,-0.00053,-3.7e+02,-1.3e-05,-6e-05,2.7e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.7e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-10,9.4e-10,8.6e-10,3.3e-06,3.3e-06,1.5e-07,0,0,0,0,0,0,0,0
17290000,0.71,0.00043,-0.013,0.71,0.0018,0.0023,-0.0066,-0.0056,-0.00037,-3.7e+02,-1.4e-05,-6e-05,2.5e-06,-1.3e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-10,9.4e-10,8.4e-10,3.3e-06,3.3e-06,1.4e-07,0,0,0,0,0,0,0,0
17390000,0.71,0.0004,-0.013,0.71,0.0025,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-1.3e-05,-6e-05,2.8e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.6e-10,8.6e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17490000,0.71,0.00039,-0.013,0.71,0.003,0.0011,-0.003,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.6e-10,8.6e-10,8.1e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17590000,0.71,0.0003,-0.013,0.71,0.0043,-9.8e-05,0.0025,-0.0037,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3e-06,-2e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.8e-05,0.00014,0.00014,8.6e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.8e-10,7.8e-10,7.9e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
17690000,0.71,0.00027,-0.012,0.71,0.0052,0.00061,0.0019,-0.0032,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.1e-06,-2e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.8e-05,0.00014,0.00014,8.5e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.8e-10,7.8e-10,7.7e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00033,0.00061,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,3.7e-06,-1.9e-05,5.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.8e-05,0.00014,0.00014,8.5e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-10,7e-10,7.6e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17890000,0.71,0.00019,-0.013,0.71,0.0093,-0.00043,0.00071,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,3.9e-06,-1.9e-05,5.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.5e-05,0.037,0.037,0.016,0.052,0.052,0.048,7e-10,7e-10,7.4e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0022,0.0019,-0.00052,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,3.9e-06,-1.9e-05,5.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.7e-05,0.00013,0.00013,8.5e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,7.3e-10,3.2e-06,3.2e-06,1e-07,0,0,0,0,0,0,0,0
18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0023,0.0043,0.00062,-0.0021,-3.7e+02,-1.3e-05,-6.1e-05,3.5e-06,-1.9e-05,5.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,7.1e-10,3.2e-06,3.2e-06,9.7e-08,0,0,0,0,0,0,0,0
18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,3.8e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.7e-05,0.00013,0.00013,8.4e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,7e-10,3.1e-06,3.1e-06,9.2e-08,0,0,0,0,0,0,0,0
18290000,0.71,4.8e-05,-0.012,0.71,0.012,-0.0018,0.0068,0.0027,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,3.6e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,6.8e-10,3.1e-06,3.1e-06,8.9e-08,0,0,0,0,0,0,0,0
18390000,0.71,6.4e-05,-0.012,0.71,0.014,-0.00017,0.008,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.8e-05,5.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.3e-10,5.3e-10,6.7e-10,3.1e-06,3.1e-06,8.4e-08,0,0,0,0,0,0,0,0
18490000,0.71,7.9e-05,-0.012,0.71,0.014,0.00024,0.0076,0.0047,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.8e-05,5.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.3e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,6.6e-10,3.1e-06,3.1e-06,8.2e-08,0,0,0,0,0,0,0,0
18590000,0.71,8.4e-05,-0.012,0.71,0.014,0.00048,0.0058,0.0036,-0.0012,-3.7e+02,-1.4e-05,-6.1e-05,4.4e-06,-1.8e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.6e-05,0.00012,0.00012,8.3e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,6.4e-10,3.1e-06,3.1e-06,7.8e-08,0,0,0,0,0,0,0,0
18690000,0.71,5.3e-05,-0.012,0.71,0.014,-0.00021,0.0039,0.0049,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.3e-06,-1.8e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.3e-10,3.1e-06,3.1e-06,7.5e-08,0,0,0,0,0,0,0,0
18790000,0.71,8.3e-05,-0.012,0.71,0.012,9.6e-05,0.0036,0.0038,-0.0009,-3.7e+02,-1.4e-05,-6.1e-05,4.2e-06,-1.8e-05,6.3e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.3e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-10,4.3e-10,6.2e-10,3.1e-06,3.1e-06,7.2e-08,0,0,0,0,0,0,0,0
18890000,0.71,0.00011,-0.012,0.71,0.013,0.00059,0.0042,0.005,-0.00083,-3.7e+02,-1.4e-05,-6.1e-05,4.6e-06,-1.8e-05,6.3e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-10,4.3e-10,6e-10,3.1e-06,3.1e-06,7e-08,0,0,0,0,0,0,0,0
18990000,0.71,9.4e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0064,-0.00069,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.8e-05,6.2e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-10,3.9e-10,5.9e-10,3.1e-06,3.1e-06,6.6e-08,0,0,0,0,0,0,0,0
19090000,0.71,7.8e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0078,-0.00049,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.8e-05,6.2e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-10,3.9e-10,5.8e-10,3.1e-06,3.1e-06,6.5e-08,0,0,0,0,0,0,0,0
19190000,0.71,8.1e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0086,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.8e-05,6.2e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,5.7e-10,3e-06,3e-06,6.2e-08,0,0,0,0,0,0,0,0
19290000,0.71,0.0001,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00025,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.8e-05,6.2e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,5.6e-10,3e-06,3e-06,6e-08,0,0,0,0,0,0,0,0
19390000,0.71,0.00012,-0.012,0.71,0.013,0.00042,0.012,0.0081,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.9e-05,6.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.4e-05,0.00011,0.00011,8.1e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-10,3.3e-10,5.5e-10,3e-06,3e-06,5.8e-08,0,0,0,0,0,0,0,0
19490000,0.71,0.00014,-0.012,0.71,0.012,-0.00029,0.0088,0.0093,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.9e-05,6.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.4e-05,0.00011,0.00011,8.1e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.4e-10,3e-06,3e-06,5.6e-08,0,0,0,0,0,0,0,0
19590000,0.71,0.00019,-0.012,0.71,0.0098,-0.0013,0.0081,0.0075,-0.00029,-3.7e+02,-1.4e-05,-6.1e-05,5.5e-06,-1.9e-05,6.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.3e-05,0.00011,0.00011,8.1e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.3e-10,3e-06,3e-06,5.4e-08,0,0,0,0,0,0,0,0
19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0096,0.0085,-0.00053,-3.7e+02,-1.4e-05,-6.1e-05,5.4e-06,-1.9e-05,6.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.2e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0
19790000,0.71,0.00026,-0.012,0.71,0.0078,-0.0043,0.01,0.0069,-0.00043,-3.7e+02,-1.4e-05,-6.1e-05,5.4e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.71,0.0002,-0.012,0.71,0.0066,-0.0046,0.011,0.0076,-0.00089,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.71,0.00019,-0.012,0.71,0.0041,-0.0053,0.014,0.0062,-0.00075,-3.7e+02,-1.4e-05,-6.1e-05,6.3e-06,-1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.71,0.00018,-0.012,0.71,0.0039,-0.0073,0.014,0.0066,-0.0014,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-10,2.5e-10,4.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.71,0.00029,-0.012,0.71,0.0015,-0.008,0.017,0.0043,-0.0011,-3.7e+02,-1.4e-05,-6e-05,6.9e-06,-1.7e-05,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.2e-05,0.0001,0.0001,7.9e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.71,0.00025,-0.012,0.71,0.00042,-0.0095,0.015,0.0044,-0.0019,-3.7e+02,-1.4e-05,-6e-05,7e-06,-1.7e-05,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,4.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.71,0.00027,-0.012,0.71,-0.002,-0.01,0.017,0.0025,-0.0015,-3.7e+02,-1.4e-05,-6e-05,7e-06,-1.5e-05,7.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.2e-05,0.0001,0.0001,7.9e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,4.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.71,0.00032,-0.012,0.71,-0.0025,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-1.4e-05,-6e-05,6.9e-06,-1.5e-05,7.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.9e-05,0.027,0.027,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,4.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.71,0.00034,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-1.4e-05,-6e-05,6.8e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.9e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-10,2e-10,4.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.71,0.00037,-0.012,0.71,-0.0021,-0.012,0.015,0.0017,-0.0032,-3.7e+02,-1.4e-05,-6e-05,6.9e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.71,0.0004,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-1.4e-05,-6e-05,6.9e-06,-1.1e-05,7.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.8e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.71,0.00038,-0.012,0.71,-0.0037,-0.014,0.014,0.001,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.2e-05,7.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,4.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.0039,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-9.4e-06,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8e-05,9.9e-05,9.9e-05,7.8e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.71,0.00039,-0.012,0.71,-0.0041,-0.017,0.015,0.0023,-0.0046,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-9.4e-06,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8e-05,9.9e-05,9.9e-05,7.8e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.71,0.00042,-0.012,0.71,-0.0033,-0.016,0.014,0.0038,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-7e-06,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8e-05,9.8e-05,9.7e-05,7.7e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.5e-10,3.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0054,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-7e-06,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,8e-05,9.8e-05,9.8e-05,7.7e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-10,1.5e-10,3.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.71,0.00051,-0.012,0.71,-0.0047,-0.017,0.016,0.0029,-0.0034,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-3.2e-06,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.9e-05,9.6e-05,9.6e-05,7.7e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,3.8e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.71,0.00052,-0.012,0.71,-0.0052,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-3.3e-06,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.9e-05,9.7e-05,9.7e-05,7.7e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,3.7e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.71,0.00054,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,1.8e-07,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.9e-05,9.5e-05,9.5e-05,7.7e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.71,0.00055,-0.012,0.71,-0.0056,-0.016,0.017,0.0014,-0.0048,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,1.7e-07,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.9e-05,9.6e-05,9.6e-05,7.7e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.71,0.00057,-0.012,0.71,-0.0062,-0.011,0.015,0.00011,-0.00075,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,5.4e-06,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.9e-05,9.4e-05,9.4e-05,7.6e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.71,0.00057,-0.012,0.71,-0.0062,-0.012,0.016,-0.00052,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,5.3e-06,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.71,0.00062,-0.012,0.71,-0.0067,-0.0091,0.016,-0.0014,0.0015,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,9.7e-06,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.8e-05,9.3e-05,9.3e-05,7.6e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.71,0.00064,-0.012,0.71,-0.0071,-0.0082,0.015,-0.0021,0.00063,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,9.6e-06,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.8e-05,9.4e-05,9.4e-05,7.6e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.71,0.00061,-0.012,0.71,-0.0069,-0.0073,0.015,-0.0018,0.00059,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.8e-05,9.3e-05,9.2e-05,7.6e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.71,0.00065,-0.012,0.71,-0.0082,-0.0081,0.015,-0.0025,-0.00019,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.8e-05,9.3e-05,9.3e-05,7.5e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.71,0.00062,-0.012,0.71,-0.0088,-0.0075,0.017,-0.0022,-0.00018,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.8e-05,9.2e-05,9.2e-05,7.5e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.71,0.00063,-0.012,0.71,-0.0094,-0.0075,0.018,-0.0031,-0.00095,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.7e-05,9.2e-05,9.2e-05,7.5e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.71,0.00061,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.00014,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.3e-05,7.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.5e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.71,0.00064,-0.012,0.71,-0.01,-0.0067,0.018,-0.0043,-0.00054,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.3e-05,7.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.5e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00044,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.7e-05,9e-05,9e-05,7.5e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0051,0.021,-0.0066,-0.00097,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.4e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.71,0.00062,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00086,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.7e-05,9e-05,8.9e-05,7.4e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0086,-0.0014,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.4e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.71,0.00065,-0.012,0.71,-0.014,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,1.5e-05,7.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.4e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.71,0.00059,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,1.4e-05,7.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.4e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.71,0.00068,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0018,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,1.5e-05,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.6e-05,8.9e-05,8.8e-05,7.4e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.5e-05,7.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.71,0.0083,-0.0017,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,1.7e-05,7.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,1.7e-05,7.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.71,0.005,0.00067,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,2e-05,6.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.5e-05,8.7e-05,8.7e-05,7.3e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.005,-3.7e+02,-1.4e-05,-5.9e-05,6.2e-06,2e-05,6.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.71,0.00097,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,2.1e-05,6.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.5e-05,8.7e-05,8.7e-05,7.3e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.71,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,2.1e-05,6.4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.5e-05,8.7e-05,8.7e-05,7.3e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.7e-11,6.7e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,2.4e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.4e-05,8.6e-05,8.6e-05,7.2e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,2.4e-05,5.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.4e-05,8.7e-05,8.6e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.4e-11,6.4e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.4e-05,8.6e-05,8.5e-05,7.2e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.71,0.0047,-0.0017,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.4e-05,8.6e-05,8.6e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.4e-05,8.5e-05,8.5e-05,7.2e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,1.9e-05,4.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.4e-05,8.5e-05,8.5e-05,7.2e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.71,0.0049,0.0015,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,2.4e-05,4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.4e-05,8.4e-05,8.4e-05,7.2e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,2.4e-05,4e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.3e-05,8.5e-05,8.4e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,5.8e-06,3.3e-05,2.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.3e-05,8.4e-05,8.3e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.4e-11,5.4e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,5.7e-06,3.3e-05,2.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.3e-05,8.4e-05,8.4e-05,7.1e-05,0.018,0.017,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,5.7e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.3e-05,8.3e-05,8.3e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-11,5.2e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,5.7e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.3e-05,8.3e-05,8.3e-05,7.1e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,5.7e-06,3.2e-05,3.5e-06,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.3e-05,8.2e-05,8.2e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,3.2e-05,3.6e-06,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.3e-05,8.2e-05,8.2e-05,7.1e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,2.9e-05,-5.9e-06,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7.1e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,2.9e-05,-5.6e-06,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.2e-05,8.2e-05,8.1e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,3.7e-05,-3.2e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,5.9e-06,3.7e-05,-3.2e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,1.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,3.3e-05,-4.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.2e-05,8e-05,8e-05,7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,5.8e-06,3.3e-05,-4.8e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.2e-05,8e-05,8e-05,7e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,1.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,5.8e-06,4.5e-05,-8.6e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.9e-05,7.9e-05,7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,1.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,5.7e-06,4.5e-05,-8.5e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.9e-05,7.9e-05,7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,5.7e-06,3.2e-05,-0.0001,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.9e-05,7.8e-05,7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,5.7e-06,3.2e-05,-9.9e-05,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.9e-05,7.9e-05,7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.3e-06,4.2e-05,-0.00014,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.8e-05,7.8e-05,7e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.4e-06,4.1e-05,-0.00014,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.8e-05,7.8e-05,7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.2e-06,1.9e-05,-0.00016,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.7e-05,7.7e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.3e-06,1.9e-05,-0.00016,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.2e-06,2.8e-05,-0.00021,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.7e-05,7.6e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.1e-06,2.7e-05,-0.00021,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7.1e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.2e-06,3.8e-05,-0.0002,-0.0013,0.21,0.0021,0.43,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.9e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.2e-06,3.8e-05,-0.0002,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.9e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.71,0.036,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.3e-06,-5.9e-05,5.3e-06,5.8e-05,-0.00022,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.2e-06,-5.9e-05,5.3e-06,5.7e-05,-0.00021,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.9e-05,7.7e-05,7.7e-05,6.8e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.3e-06,5.6e-05,-0.0002,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.9e-05,7.7e-05,7.7e-05,6.8e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.2e-06,5.6e-05,-0.00019,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.9e-05,7.7e-05,7.7e-05,6.8e-05,0.019,0.018,0.0083,0.065,0.065,0.035,3.9e-11,3.9e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.1e-06,5.7e-05,-0.00018,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.1e-06,5.5e-05,-0.00018,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.2e-06,5e-05,-0.00016,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,4.9e-06,5e-05,-0.00016,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5e-06,4.6e-05,-0.00015,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.5e-05,-0.00014,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.021,0.02,0.0086,0.092,0.092,0.036,3.8e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,4.2e-05,-0.00013,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.7e-05,7.8e-05,7.7e-05,6.6e-05,0.022,0.021,0.0087,0.1,0.099,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,3.9e-05,-0.00013,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.7e-05,7.8e-05,7.7e-05,6.6e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.71,0.00084,0.001,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,3.6e-05,-0.00012,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.7e-05,7.8e-05,7.7e-05,6.6e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.71,0.00014,8.2e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.5e-06,3.2e-05,-0.00011,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.7e-05,7.8e-05,7.8e-05,6.6e-05,0.025,0.025,0.009,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.71,-0.00015,-0.00017,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.5e-06,3.6e-07,-0.00018,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.8e-05,7.8e-05,6.6e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.71,-0.00017,5.2e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.4e-06,-4e-06,-0.00017,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.8e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.71,2.1e-05,0.0005,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.3e-06,-2.5e-05,-0.00025,-0.0012,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.9e-05,7.8e-05,6.5e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.7e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.71,0.00017,0.0009,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.3e-06,-3e-05,-0.00024,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.9e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.71,0.00039,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.3e-06,-5e-05,-0.00027,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.9e-05,7.8e-05,6.5e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.71,0.00075,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.2e-06,-5.6e-05,-0.00025,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.9e-05,7.8e-05,6.5e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.8e-05,4e-06,-7.1e-05,-0.00029,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.9e-05,7.8e-05,6.5e-05,0.024,0.025,0.009,0.16,0.15,0.036,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-7.5e-05,-0.00028,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.6e-05,7.9e-05,7.8e-05,6.5e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-9.9e-05,-0.00028,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.5e-05,0.024,0.025,0.0091,0.17,0.16,0.036,3.5e-11,3.5e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,3.8e-06,-0.0001,-0.00027,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.5e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,3.8e-06,-0.00012,-0.00029,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00013,-0.00026,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.71,0.003,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00015,-0.00026,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00016,-0.00024,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00017,-0.00025,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.2,0.19,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-1.2e-05,-5.7e-05,3.3e-06,-0.00017,-0.00024,-0.0011,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.026,0.027,0.0091,0.21,0.21,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30390000,0.71,0.003,0.0071,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.00018,-0.00023,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.21,0.2,0.036,3.3e-11,3.3e-11,1.1e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.5e-05,8.1e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.22,0.22,0.037,3.3e-11,3.3e-11,1.1e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.0002,-0.00022,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.1e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.0002,-0.00021,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.8e-05,6.3e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.1e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00021,-0.0002,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.3e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.71,0.0025,0.0055,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00021,-0.00019,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.3e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.71,0.0024,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00022,-0.00018,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.3e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00023,-0.00017,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00024,-0.00014,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31290000,0.71,0.002,0.0038,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00025,-0.00013,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31390000,0.71,0.0018,0.0033,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00025,-0.00011,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.71,0.0016,0.0027,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00026,-9.8e-05,-0.001,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.0089,0.26,0.26,0.037,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.71,0.0016,0.0024,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-8.2e-05,-0.00099,0.21,0.0021,0.43,0,0,0,0,0,6.4e-05,8.1e-05,7.6e-05,6.2e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.71,0.0013,0.0017,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00027,-6.9e-05,-0.00099,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.2e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00028,-5.1e-05,-0.00098,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.71,0.00087,0.00039,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00029,-3.8e-05,-0.00097,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.71,0.00074,-6.8e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-1.9e-05,-0.00097,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,9.8e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.71,0.00045,-0.00079,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-4.1e-06,-0.00096,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.7e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.71,0.00024,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00031,1.7e-05,-0.00096,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.5e-05,6.1e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.71,1e-05,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3.3e-05,-0.00095,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.71,-0.00017,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,4.2e-05,-0.00095,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.5e-05,6.1e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00033,5.3e-05,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,6.3e-05,8.1e-05,7.5e-05,6.1e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00033,6.1e-05,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,6.6e-05,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,7.5e-05,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2.1e-06,-0.00035,8.6e-05,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.71,-7.2e-05,-0.0033,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00035,9.9e-05,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,6.2e-05,8.1e-05,7.4e-05,6e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.71,-0.00011,-0.0033,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,0.00011,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,6.2e-05,8.1e-05,7.4e-05,6e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00036,0.00011,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,6.2e-05,8.1e-05,7.4e-05,6e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,8.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.9e-05,8e-05,7.5e-05,6.2e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.55,0.013,-0.0017,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.5e-05,7.9e-05,7.6e-05,6.6e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.41,0.0069,0.00073,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.1e-05,7.8e-05,7.7e-05,7.1e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.25,0.001,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,4.7e-05,7.6e-05,7.9e-05,7.5e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,4.4e-05,7.5e-05,8e-05,7.7e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.8e-11,2.8e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,4.4e-05,7.2e-05,8e-05,7.8e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33890000,-0.25,-0.0049,-0.0074,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,4.6e-05,7.2e-05,8.1e-05,7.7e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33990000,-0.39,-0.0031,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,4.9e-05,6.9e-05,7.8e-05,7.4e-05,0.032,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34090000,-0.5,-0.002,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.2e-05,6.9e-05,7.8e-05,7.1e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.8e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34290000,-0.61,-0.0023,-0.0086,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,6.5e-05,7.3e-05,6.6e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34390000,-0.64,-0.0024,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.6e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.5e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.4e-05,0.049,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,7.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00054,0.00027,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,5.6e-05,6.1e-05,6.3e-05,0.047,0.049,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00054,0.00027,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,5.6e-05,6.1e-05,6.3e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34790000,-0.67,-0.0021,-0.0017,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,5.1e-05,5.5e-05,6.3e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.7e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34890000,-0.68,-0.0021,-0.0016,0.74,-0.71,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,5.1e-05,5.5e-05,6.3e-05,0.059,0.061,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.7e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34990000,-0.68,-0.0084,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,4.6e-05,5e-05,6.2e-05,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,4.6e-05,5e-05,6.2e-05,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35190000,-0.68,-0.0085,-0.0045,0.73,0.45,0.34,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,4.6e-05,5e-05,6.2e-05,0.068,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35290000,-0.68,-0.0085,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,4.6e-05,5e-05,6.2e-05,0.073,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35390000,-0.68,-0.0086,-0.0045,0.73,0.5,0.4,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,4.6e-05,5e-05,6.2e-05,0.079,0.08,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35490000,-0.68,-0.0086,-0.0045,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.8e-05,4.6e-05,5e-05,6.2e-05,0.085,0.087,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35590000,-0.68,-0.0056,-0.0045,0.73,0.41,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.068,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35690000,-0.68,-0.0056,-0.0044,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35790000,-0.68,-0.0034,-0.0044,0.73,0.35,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.0008,0.00053,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,3.4e-05,3.6e-05,6.1e-05,0.061,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35890000,-0.68,-0.0035,-0.0044,0.73,0.37,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3.1e-06,-0.0008,0.00053,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,3.4e-05,3.6e-05,6.1e-05,0.066,0.068,0.0058,0.5,0.5,0.033,2.7e-11,2.7e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35990000,-0.68,-0.0016,-0.0043,0.73,0.3,0.29,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.3e-06,-0.00087,0.00059,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,3e-05,3.1e-05,6.1e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36090000,-0.68,-0.0017,-0.0043,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.4e-06,-0.00087,0.0006,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,3e-05,3.1e-05,6.1e-05,0.063,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36190000,-0.68,-0.00029,-0.0042,0.73,0.26,0.27,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00098,0.00068,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,2.6e-05,2.8e-05,6.1e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7e-11,2.4e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36290000,-0.68,-0.00042,-0.0041,0.73,0.27,0.29,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.6e-06,-0.00098,0.00068,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,2.6e-05,2.8e-05,6.1e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,6.9e-11,2.4e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36390000,-0.68,0.00061,-0.004,0.73,0.23,0.24,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.8e-06,-0.0011,0.00078,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,2.4e-05,2.5e-05,6.1e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,6.9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36490000,-0.68,0.00052,-0.004,0.73,0.24,0.26,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.1e-06,-0.0011,0.00078,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.7e-05,2.4e-05,2.5e-05,6e-05,0.059,0.061,0.0055,0.53,0.52,0.032,2.8e-11,2.8e-11,6.8e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36590000,-0.68,0.0013,-0.0039,0.73,0.2,0.22,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.2e-06,-0.0012,0.00088,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,6e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,6.8e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36690000,-0.68,0.0013,-0.0038,0.74,0.2,0.24,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.3e-06,-0.0012,0.00088,-0.00092,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,6e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36790000,-0.68,0.0018,-0.0037,0.74,0.17,0.2,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0014,0.00097,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,6e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36890000,-0.68,0.0018,-0.0037,0.74,0.17,0.21,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.6e-06,-0.0014,0.00098,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,6e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36990000,-0.68,0.0022,-0.0035,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.7e-06,-0.0015,0.0011,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.9e-05,2.1e-05,6e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.6e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37090000,-0.68,0.0021,-0.0035,0.74,0.15,0.19,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.9e-06,-0.0015,0.0011,-0.00093,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,2e-05,2.1e-05,6e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.6e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37190000,-0.68,0.0025,-0.0034,0.74,0.12,0.16,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.1e-06,-0.0016,0.0011,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,6e-05,0.05,0.052,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.5e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
37290000,-0.68,0.0024,-0.0034,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.3e-06,-0.0016,0.0011,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,6e-05,0.055,0.057,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,6.5e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
37390000,-0.68,0.0027,-0.0033,0.74,0.099,0.14,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.4e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.9e-05,6e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37490000,-0.68,0.0026,-0.0032,0.74,0.099,0.15,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.5e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.9e-05,6e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.4e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37590000,-0.68,0.0028,-0.0031,0.74,0.079,0.13,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.7e-06,-0.0018,0.0013,-0.00095,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.9e-05,6e-05,0.049,0.05,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37690000,-0.68,0.0027,-0.0032,0.74,0.078,0.13,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.8e-06,-0.0018,0.0013,-0.00095,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.9e-05,6e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.3e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37790000,-0.68,0.0028,-0.0031,0.74,0.062,0.11,-0.099,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.9e-05,6e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,6.3e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
37890000,-0.68,0.0028,-0.0031,0.74,0.06,0.12,-0.092,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.2e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.9e-05,6e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,6.3e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
37990000,-0.68,0.0029,-0.0031,0.74,0.045,0.1,-0.083,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.3e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.7e-05,1.8e-05,6e-05,0.047,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,6.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
38090000,-0.68,0.0028,-0.0031,0.74,0.042,0.1,-0.073,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.5e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.9e-05,6e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
38190000,-0.68,0.0029,-0.003,0.74,0.029,0.088,-0.065,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.6e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.7e-05,1.8e-05,6e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38290000,-0.68,0.0028,-0.003,0.74,0.026,0.089,-0.058,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.8e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.43,0,0,0,0,0,5.6e-05,1.8e-05,1.8e-05,6e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38390000,-0.68,0.0029,-0.0029,0.74,0.018,0.076,-0.051,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.9e-06,-0.0021,0.0014,-0.00098,0.21,0.0021,0.43,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38490000,-0.68,0.0028,-0.0029,0.74,0.015,0.078,-0.043,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.1e-06,-0.0021,0.0014,-0.00098,0.21,0.0021,0.43,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,6e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38590000,-0.68,0.0028,-0.0028,0.74,0.0099,0.067,-0.037,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.2e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.43,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-11,3e-11,6e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38690000,-0.68,0.0027,-0.0028,0.74,0.006,0.066,-0.03,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.43,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38790000,-0.68,0.0027,-0.0028,0.74,0.00056,0.054,-0.022,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.5e-06,-0.0022,0.0014,-0.00099,0.21,0.0021,0.43,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,5.9e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38890000,-0.68,0.0025,-0.0028,0.74,-0.0093,0.044,0.48,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.6e-06,-0.0022,0.0014,-0.001,0.21,0.0021,0.43,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,5.9e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
10000,1,-0.0094,-0.01,-9.8e-05,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,4.9e-07,0.0025,0.0025,0.0018,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
90000,1,-0.0096,-0.01,-0.02,-0.0004,0.0026,-0.026,-1.4e-05,0.00011,-0.0023,0,0,0,0,0,0,0.19,0,0.4,0,0,0,0,0,5.2e-07,0.0026,0.0026,0.0011,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
190000,1,-0.0096,-0.011,-0.02,0.0002,0.0039,-0.041,6e-06,0.00043,-0.0044,-3e-13,-2.3e-14,5.8e-15,0,0,-2e-11,0.19,0,0.4,0,0,0,0,0,5.8e-07,0.0027,0.0027,0.0008,25,25,10,1e+02,1e+02,1,1e-06,1e-06,9.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
290000,1,-0.0097,-0.011,-0.02,0.0012,0.0063,-0.053,5e-05,0.00036,-0.007,9.1e-12,9.1e-13,-1.7e-13,0,0,-4.8e-09,0.19,0,0.4,0,0,0,0,0,6.8e-07,0.0029,0.0029,0.00067,25,25,9.6,0.37,0.37,0.41,1e-06,1e-06,9.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
390000,1,-0.0089,-0.012,0.046,0.0026,0.0083,-0.059,0.00024,0.0011,-0.0094,-1.1e-10,2.8e-11,2.8e-12,0,0,-4.5e-08,0.17,0.0017,0.41,0,0,0,0,0,7e-07,0.0031,0.0031,0.00062,25,25,8.1,0.97,0.97,0.32,1e-06,1e-06,8.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
490000,0.87,-0.0023,-0.015,0.5,0.0023,0.0057,-0.06,0.0002,0.00051,-0.011,1.6e-08,-3.8e-09,-3.3e-10,0,0,-1.6e-07,0.14,0.0014,0.42,0,0,0,0,0,2.6e-06,0.0033,0.0033,0.00061,7.8,7.8,5.9,0.34,0.34,0.31,1e-06,1e-06,8.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
590000,0.76,0.00067,-0.015,0.65,0.00071,0.0084,-0.059,0.00037,0.0012,-0.012,1.6e-08,-3.5e-09,-3.2e-10,0,0,-3.4e-07,0.18,0.0018,0.43,0,0,0,0,0,1.5e-05,0.0036,0.0036,0.00061,7.9,7.9,4.2,0.67,0.67,0.32,1e-06,1e-06,7.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
690000,0.72,0.0016,-0.016,0.69,-0.00082,0.0075,-0.06,7.2e-05,0.00069,-0.013,5.4e-08,-2.4e-08,-7e-10,0,0,-6.3e-07,0.2,0.0019,0.43,0,0,0,0,0,4.1e-05,0.0039,0.0039,0.00061,2.6,2.6,2.8,0.26,0.26,0.29,1e-06,1e-06,7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
790000,0.71,0.002,-0.016,0.7,-0.0028,0.0098,-0.063,-9.3e-05,0.0015,-0.014,5.3e-08,-2.3e-08,-6.7e-10,0,0,-9.5e-07,0.2,0.002,0.43,0,0,0,0,0,7.7e-05,0.0042,0.0042,0.0006,2.7,2.7,2,0.42,0.42,0.28,1e-06,1e-06,6.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
890000,0.71,0.0021,-0.016,0.7,-0.0034,0.011,-0.077,-0.00019,0.0011,-0.021,1.7e-07,-9e-08,-1.1e-09,0,0,-9.5e-07,0.2,0.002,0.43,0,0,0,0,0,0.00012,0.0046,0.0046,0.00057,1.3,1.3,2,0.2,0.2,0.43,1e-06,1e-06,5.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
990000,0.7,0.0025,-0.016,0.71,-0.0038,0.015,-0.092,-0.00057,0.0024,-0.029,1.7e-07,-9e-08,-1.1e-09,0,0,-9.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00015,0.005,0.005,0.00054,1.4,1.4,2,0.3,0.3,0.61,1e-06,1e-06,4.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1090000,0.7,0.0025,-0.017,0.71,-0.0034,0.016,-0.11,-0.00043,0.0019,-0.039,5.5e-07,-3.7e-07,-1.6e-09,0,0,-9.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00018,0.0053,0.0053,0.00051,0.89,0.89,2,0.17,0.17,0.84,9.9e-07,9.9e-07,3.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1190000,0.7,0.0027,-0.017,0.71,-0.0037,0.02,-0.12,-0.00079,0.0037,-0.051,5.5e-07,-3.7e-07,-1.6e-09,0,0,-9.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00021,0.0058,0.0058,0.00047,1.1,1.1,2,0.24,0.24,1.1,9.9e-07,9.9e-07,3.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1290000,0.7,0.0028,-0.017,0.71,-0.0034,0.02,-0.14,-0.00055,0.0028,-0.064,1.4e-06,-1.3e-06,-2.4e-09,0,0,-9.6e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00023,0.006,0.006,0.00044,0.84,0.84,2,0.15,0.15,1.4,9.6e-07,9.6e-07,2.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1390000,0.7,0.0029,-0.017,0.71,-0.0032,0.026,-0.15,-0.0009,0.0052,-0.078,1.4e-06,-1.3e-06,-2.4e-09,0,0,-9.6e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00024,0.0066,0.0066,0.00041,1.1,1.1,2,0.21,0.21,1.7,9.6e-07,9.6e-07,2.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1490000,0.7,0.0027,-0.017,0.71,-0.0024,0.025,-0.16,-0.0006,0.0039,-0.093,2.9e-06,-3.4e-06,-5.5e-09,0,0,-9.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00025,0.0063,0.0063,0.00038,0.9,0.9,2,0.14,0.14,2.1,9e-07,9e-07,2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1590000,0.7,0.0029,-0.018,0.71,-0.0029,0.031,-0.18,-0.00087,0.0066,-0.11,2.9e-06,-3.4e-06,-5.5e-09,0,0,-9.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00026,0.0069,0.0069,0.00035,1.2,1.2,2,0.2,0.2,2.6,9e-07,9e-07,1.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1690000,0.7,0.0025,-0.018,0.71,0.00055,0.028,-0.19,-0.00048,0.0047,-0.13,5e-06,-7e-06,-1.2e-08,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.00027,0.006,0.006,0.00033,0.97,0.97,2,0.13,0.13,3,8.1e-07,8.1e-07,1.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1790000,0.7,0.0027,-0.018,0.71,0.0025,0.036,-0.2,-0.00035,0.0078,-0.15,5e-06,-7e-06,-1.2e-08,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.00027,0.0066,0.0066,0.00031,1.3,1.3,2,0.2,0.2,3.5,8.1e-07,8.1e-07,1.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1890000,0.7,0.003,-0.018,0.72,0.0039,0.044,-0.22,-2.9e-05,0.012,-0.17,5e-06,-7e-06,-1.2e-08,0,0,-1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00027,0.0073,0.0073,0.00029,1.6,1.6,2,0.3,0.3,4.1,8.1e-07,8.1e-07,1.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1990000,0.7,0.0025,-0.018,0.72,0.0056,0.037,-0.23,0.00047,0.0085,-0.19,6.8e-06,-1.2e-05,-1.6e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00027,0.0059,0.0059,0.00027,1.3,1.3,2,0.2,0.2,4.7,6.9e-07,7e-07,9.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2090000,0.7,0.0026,-0.018,0.72,0.0083,0.043,-0.24,0.0012,0.012,-0.22,6.8e-06,-1.2e-05,-1.6e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00027,0.0064,0.0064,0.00026,1.6,1.6,2.1,0.3,0.3,5.3,6.9e-07,7e-07,8.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2190000,0.7,0.0021,-0.018,0.72,0.0084,0.034,-0.26,0.0012,0.0083,-0.24,8e-06,-1.8e-05,-1.5e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00027,0.0049,0.0049,0.00024,1.2,1.2,2.1,0.19,0.19,6,5.8e-07,5.8e-07,7.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2290000,0.7,0.0021,-0.018,0.72,0.011,0.041,-0.27,0.0022,0.012,-0.27,8e-06,-1.8e-05,-1.5e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00026,0.0054,0.0054,0.00023,1.5,1.5,2.1,0.29,0.29,6.7,5.8e-07,5.8e-07,6.4e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2390000,0.7,0.0016,-0.017,0.72,0.011,0.031,-0.29,0.0019,0.0078,-0.3,8.3e-06,-2.4e-05,-4.9e-09,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00026,0.004,0.004,0.00022,1,1,2.1,0.19,0.19,7.4,4.9e-07,4.9e-07,5.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2490000,0.7,0.0017,-0.018,0.72,0.014,0.036,-0.3,0.0031,0.011,-0.32,8.3e-06,-2.4e-05,-4.9e-09,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00026,0.0044,0.0044,0.00021,1.3,1.3,2.1,0.27,0.27,8.2,4.9e-07,4.9e-07,5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2590000,0.7,0.0014,-0.017,0.72,0.012,0.027,-0.31,0.0023,0.0071,-0.36,8e-06,-2.8e-05,1.3e-08,0,0,-1.2e-06,0.21,0.002,0.43,0,0,0,0,0,0.00026,0.0033,0.0033,0.0002,0.89,0.89,2.1,0.18,0.18,9.1,4.1e-07,4.1e-07,4.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2690000,0.7,0.0014,-0.017,0.72,0.015,0.031,-0.33,0.0037,0.01,-0.39,8e-06,-2.8e-05,1.3e-08,0,0,-1.2e-06,0.21,0.002,0.43,0,0,0,0,0,0.00025,0.0036,0.0036,0.00019,1.1,1.1,2.2,0.25,0.25,10,4.1e-07,4.1e-07,4.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2790000,0.7,0.0012,-0.017,0.72,0.014,0.024,-0.34,0.0027,0.0064,-0.42,7.2e-06,-3.3e-05,3.6e-08,0,0,-1.2e-06,0.21,0.002,0.43,0,0,0,0,0,0.00025,0.0028,0.0028,0.00018,0.77,0.77,2.2,0.16,0.16,11,3.4e-07,3.4e-07,3.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2890000,0.7,0.0012,-0.017,0.72,0.016,0.027,-0.35,0.0041,0.0089,-0.46,7.2e-06,-3.3e-05,3.6e-08,0,0,-1.2e-06,0.21,0.002,0.43,0,0,0,0,0,0.00025,0.003,0.003,0.00018,0.96,0.96,2.2,0.23,0.23,12,3.4e-07,3.4e-07,3.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
2990000,0.7,0.0011,-0.017,0.72,0.014,0.022,-0.36,0.003,0.0058,-0.49,6e-06,-3.6e-05,6.5e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00024,0.0024,0.0024,0.00017,0.68,0.68,2.2,0.15,0.15,13,2.9e-07,2.9e-07,3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3090000,0.7,0.0011,-0.017,0.72,0.017,0.024,-0.38,0.0045,0.0081,-0.53,6e-06,-3.6e-05,6.5e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00024,0.0026,0.0026,0.00016,0.84,0.84,2.2,0.22,0.22,14,2.9e-07,2.9e-07,2.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3190000,0.7,0.00089,-0.017,0.72,0.014,0.019,-0.39,0.0032,0.0053,-0.57,4.6e-06,-3.9e-05,9.7e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00024,0.0021,0.0021,0.00016,0.6,0.6,2.3,0.14,0.14,15,2.5e-07,2.5e-07,2.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3290000,0.7,0.00089,-0.017,0.72,0.017,0.023,-0.4,0.0047,0.0073,-0.61,4.6e-06,-3.9e-05,9.7e-08,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00023,0.0023,0.0023,0.00015,0.74,0.74,2.3,0.2,0.2,16,2.5e-07,2.5e-07,2.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3390000,0.7,0.00084,-0.017,0.72,0.015,0.018,-0.42,0.0033,0.0049,-0.65,3.2e-06,-4.2e-05,1.3e-07,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00023,0.0018,0.0018,0.00015,0.54,0.54,2.3,0.14,0.14,17,2.1e-07,2.1e-07,2.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3490000,0.7,0.00085,-0.017,0.72,0.019,0.021,-0.43,0.005,0.0068,-0.69,3.2e-06,-4.2e-05,1.3e-07,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00023,0.002,0.002,0.00014,0.67,0.67,2.3,0.19,0.19,19,2.1e-07,2.1e-07,2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3590000,0.7,0.00079,-0.017,0.72,0.017,0.016,-0.44,0.0036,0.0045,-0.73,1.5e-06,-4.4e-05,1.7e-07,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00022,0.0016,0.0016,0.00014,0.5,0.5,2.4,0.13,0.13,20,1.8e-07,1.8e-07,1.8e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3690000,0.7,0.00079,-0.017,0.72,0.021,0.018,-0.46,0.0055,0.0063,-0.78,1.5e-06,-4.4e-05,1.7e-07,0,0,-1.1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00022,0.0018,0.0018,0.00013,0.61,0.61,2.4,0.18,0.18,21,1.8e-07,1.8e-07,1.7e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3790000,0.7,0.00073,-0.017,0.72,0.02,0.014,-0.47,0.004,0.0042,-0.83,-2.8e-07,-4.6e-05,2.1e-07,0,0,-1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00022,0.0014,0.0014,0.00013,0.46,0.46,2.4,0.12,0.12,23,1.5e-07,1.5e-07,1.6e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3890000,0.7,0.00077,-0.017,0.72,0.022,0.016,-0.48,0.0061,0.0057,-0.87,-2.8e-07,-4.6e-05,2.1e-07,0,0,-1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00021,0.0016,0.0016,0.00013,0.56,0.56,2.4,0.17,0.17,24,1.5e-07,1.5e-07,1.5e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
3990000,0.7,0.00081,-0.017,0.72,0.025,0.019,-0.5,0.0084,0.0074,-0.92,-2.8e-07,-4.6e-05,2.1e-07,0,0,-1e-06,0.21,0.002,0.43,0,0,0,0,0,0.00021,0.0017,0.0017,0.00012,0.68,0.68,2.5,0.23,0.23,26,1.5e-07,1.5e-07,1.4e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4090000,0.7,0.00078,-0.016,0.72,0.021,0.016,-0.51,0.0062,0.0053,-0.97,-2.2e-06,-4.8e-05,2.6e-07,0,0,-9.8e-07,0.21,0.002,0.43,0,0,0,0,0,0.00021,0.0014,0.0014,0.00012,0.52,0.52,2.5,0.16,0.16,27,1.2e-07,1.2e-07,1.3e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4190000,0.7,0.00076,-0.016,0.72,0.025,0.018,-0.53,0.0086,0.007,-1,-2.2e-06,-4.8e-05,2.6e-07,0,0,-9.8e-07,0.21,0.002,0.43,0,0,0,0,0,0.00021,0.0015,0.0015,0.00012,0.63,0.63,2.5,0.22,0.22,29,1.2e-07,1.2e-07,1.2e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4290000,0.7,0.0008,-0.016,0.72,0.019,0.015,-0.54,0.0063,0.005,-1.1,-4.1e-06,-5e-05,3.1e-07,0,0,-9.3e-07,0.21,0.002,0.43,0,0,0,0,0,0.0002,0.0012,0.0012,0.00011,0.48,0.48,2.6,0.15,0.15,31,1e-07,1e-07,1.1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4390000,0.7,0.00067,-0.016,0.71,0.021,0.016,-0.55,0.0083,0.0066,-1.1,-4.1e-06,-5e-05,3.1e-07,0,0,-9.3e-07,0.21,0.0021,0.43,0,0,0,0,0,0.0002,0.0014,0.0014,0.00011,0.58,0.58,2.6,0.2,0.2,33,1e-07,1e-07,1e-08,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4490000,0.7,0.00072,-0.016,0.71,0.017,0.013,-0.57,0.0058,0.0046,-1.2,-5.9e-06,-5.1e-05,3.5e-07,0,0,-8.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.0002,0.0011,0.0011,0.00011,0.44,0.44,2.6,0.14,0.14,34,8.3e-08,8.3e-08,9.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4590000,0.7,0.00068,-0.016,0.71,0.019,0.015,-0.58,0.0076,0.006,-1.2,-5.9e-06,-5.1e-05,3.5e-07,0,0,-8.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00019,0.0012,0.0012,0.00011,0.53,0.53,2.7,0.19,0.19,36,8.3e-08,8.3e-08,9.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4690000,0.7,0.00069,-0.016,0.71,0.016,0.012,-0.6,0.0054,0.0043,-1.3,-7.4e-06,-5.2e-05,3.9e-07,0,0,-8.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00019,0.00095,0.00095,0.0001,0.41,0.41,2.7,0.14,0.14,38,6.7e-08,6.7e-08,8.6e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4790000,0.7,0.00062,-0.016,0.71,0.018,0.014,-0.61,0.0071,0.0056,-1.4,-7.4e-06,-5.2e-05,3.9e-07,0,0,-8.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00019,0.001,0.001,0.0001,0.49,0.49,2.7,0.18,0.18,40,6.7e-08,6.7e-08,8.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4890000,0.7,0.00064,-0.016,0.71,0.016,0.011,-0.63,0.0051,0.0039,-1.4,-8.7e-06,-5.3e-05,4.2e-07,0,0,-7.9e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00019,0.00083,0.00083,0.0001,0.37,0.37,2.8,0.13,0.13,42,5.4e-08,5.4e-08,7.6e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
4990000,0.7,0.00068,-0.016,0.71,0.017,0.013,-0.64,0.0068,0.0051,-1.5,-8.7e-06,-5.3e-05,4.2e-07,0,0,-7.9e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00019,0.00089,0.00089,9.7e-05,0.44,0.44,2.8,0.17,0.17,44,5.4e-08,5.4e-08,7.2e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5090000,0.7,0.00068,-0.015,0.71,0.014,0.01,-0.66,0.0049,0.0037,-1.6,-9.9e-06,-5.4e-05,4.5e-07,0,0,-7.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00018,0.00071,0.00071,9.5e-05,0.34,0.34,2.8,0.13,0.13,46,4.4e-08,4.4e-08,6.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5190000,0.7,0.00067,-0.015,0.71,0.016,0.011,-0.67,0.0064,0.0047,-1.6,-9.9e-06,-5.4e-05,4.5e-07,0,0,-7.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00018,0.00077,0.00077,9.4e-05,0.4,0.4,2.9,0.16,0.16,49,4.4e-08,4.4e-08,6.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5290000,0.7,0.00074,-0.015,0.71,0.012,0.0072,-0.68,0.0046,0.0033,-1.7,-1.1e-05,-5.5e-05,4.8e-07,0,0,-7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00018,0.00062,0.00062,9.2e-05,0.31,0.31,2.9,0.12,0.12,51,3.5e-08,3.5e-08,6.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5390000,0.7,0.00083,-0.015,0.71,0.014,0.0065,-0.7,0.0058,0.0039,-1.8,-1.1e-05,-5.5e-05,4.8e-07,0,0,-7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00018,0.00066,0.00066,9e-05,0.37,0.37,2.9,0.16,0.16,53,3.5e-08,3.5e-08,5.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5490000,0.7,0.0009,-0.015,0.71,0.011,0.0042,-0.71,0.0042,0.0026,-1.8,-1.2e-05,-5.5e-05,5e-07,0,0,-6.7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00017,0.00053,0.00053,8.8e-05,0.28,0.28,3,0.11,0.11,56,2.8e-08,2.8e-08,5.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5590000,0.7,0.00091,-0.015,0.71,0.012,0.0047,-0.73,0.0053,0.003,-1.9,-1.2e-05,-5.5e-05,5e-07,0,0,-6.7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00017,0.00057,0.00057,8.7e-05,0.33,0.33,3,0.15,0.15,58,2.8e-08,2.8e-08,5.3e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5690000,0.7,0.00099,-0.015,0.71,0.0081,0.003,-0.74,0.0037,0.002,-2,-1.3e-05,-5.6e-05,5.2e-07,0,0,-6.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00017,0.00045,0.00045,8.5e-05,0.26,0.26,3.1,0.11,0.11,61,2.3e-08,2.3e-08,5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5790000,0.7,0.001,-0.015,0.71,0.0074,0.0032,-0.75,0.0045,0.0023,-2.1,-1.3e-05,-5.6e-05,5.2e-07,0,0,-6.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00017,0.00049,0.00049,8.4e-05,0.3,0.3,3.1,0.14,0.14,64,2.3e-08,2.3e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5890000,0.7,0.0011,-0.015,0.71,0.0048,0.0027,0.0028,0.003,0.0016,-3.7e+02,-1.3e-05,-5.6e-05,5.3e-07,0,0,-6.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00017,0.00039,0.00039,8.2e-05,0.23,0.23,9.8,0.11,0.11,0.52,1.8e-08,1.8e-08,4.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
5990000,0.7,0.0011,-0.015,0.71,0.0037,0.0029,0.015,0.0034,0.0018,-3.7e+02,-1.3e-05,-5.6e-05,5.3e-07,0,0,-7.3e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00017,0.00042,0.00042,8.1e-05,0.27,0.27,8.8,0.13,0.13,0.33,1.8e-08,1.8e-08,4.3e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6090000,0.7,0.0011,-0.015,0.71,0.0029,0.0038,-0.011,0.0037,0.0022,-3.7e+02,-1.3e-05,-5.6e-05,5.3e-07,0,0,-6.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00016,0.00045,0.00045,8e-05,0.32,0.32,7,0.17,0.17,0.33,1.8e-08,1.8e-08,4.1e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6190000,0.7,0.0011,-0.015,0.71,-0.00035,0.0027,-0.005,0.0022,0.0015,-3.7e+02,-1.3e-05,-5.6e-05,5.4e-07,0,0,-8.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00016,0.00036,0.00036,7.8e-05,0.25,0.25,4.9,0.13,0.13,0.32,1.5e-08,1.5e-08,3.9e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6290000,0.7,0.0011,-0.015,0.71,-6e-05,0.0039,-0.012,0.0022,0.0019,-3.7e+02,-1.3e-05,-5.6e-05,5.4e-07,0,0,-9.6e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00016,0.00038,0.00038,7.7e-05,0.29,0.29,3.2,0.16,0.16,0.3,1.5e-08,1.5e-08,3.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6390000,0.7,0.0012,-0.014,0.71,-0.0018,0.0033,-0.05,0.0012,0.0014,-3.7e+02,-1.4e-05,-5.6e-05,5.5e-07,0,0,-3.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00016,0.00031,0.00031,7.6e-05,0.23,0.23,2.3,0.12,0.12,0.29,1.2e-08,1.2e-08,3.6e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6490000,0.7,0.0012,-0.015,0.71,-0.0017,0.0039,-0.052,0.001,0.0018,-3.7e+02,-1.4e-05,-5.6e-05,5.5e-07,0,0,-8.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00016,0.00033,0.00033,7.5e-05,0.26,0.26,1.5,0.15,0.15,0.26,1.2e-08,1.2e-08,3.5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6590000,0.7,0.0012,-0.015,0.71,-0.0024,0.0029,-0.099,0.00044,0.0014,-3.7e+02,-1.4e-05,-5.7e-05,5.6e-07,0,0,9.7e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00085,0.00026,0.00026,0.00079,0.19,0.19,1.1,0.12,0.12,0.23,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6690000,0.7,0.0012,-0.015,0.71,-0.0016,0.0037,-0.076,0.00024,0.0017,-3.7e+02,-1.4e-05,-5.7e-05,5.4e-07,0,0,-2.2e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00056,0.00026,0.00026,0.00052,0.19,0.19,0.78,0.14,0.14,0.21,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6790000,0.7,0.0012,-0.014,0.71,-0.0026,0.0034,-0.11,3.5e-05,0.0021,-3.7e+02,-1.4e-05,-5.7e-05,5.7e-07,0,0,1e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00044,0.00026,0.00026,0.00041,0.2,0.2,0.6,0.17,0.17,0.2,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6890000,0.7,0.0012,-0.014,0.71,-0.0043,0.0037,-0.12,-0.00033,0.0025,-3.7e+02,-1.4e-05,-5.7e-05,5.9e-07,0,0,-4.1e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00036,0.00026,0.00026,0.00033,0.21,0.21,0.46,0.21,0.21,0.18,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6990000,0.7,0.0013,-0.014,0.71,-0.0039,0.0044,-0.12,-0.00074,0.0029,-3.7e+02,-1.4e-05,-5.7e-05,5.1e-07,0,0,-3.4e-06,0.21,0.0021,0.44,0,0,0,0,0,0.0003,0.00026,0.00026,0.00028,0.22,0.22,0.36,0.25,0.25,0.16,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7090000,0.7,0.0013,-0.014,0.71,-0.0041,0.0038,-0.13,-0.0011,0.0033,-3.7e+02,-1.4e-05,-5.7e-05,4.2e-07,0,0,-7e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00027,0.00027,0.00027,0.00025,0.23,0.23,0.29,0.29,0.29,0.16,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7190000,0.7,0.0013,-0.014,0.71,-0.0054,0.0037,-0.15,-0.0016,0.0036,-3.7e+02,-1.4e-05,-5.7e-05,3.9e-07,0,0,-4.9e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00024,0.00027,0.00027,0.00022,0.25,0.25,0.24,0.34,0.34,0.15,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7290000,0.7,0.0013,-0.014,0.71,-0.0064,0.0037,-0.15,-0.0022,0.004,-3.7e+02,-1.4e-05,-5.7e-05,4.1e-07,0,0,-1.2e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00022,0.00027,0.00027,0.0002,0.27,0.27,0.2,0.4,0.4,0.14,9.8e-09,9.8e-09,3.4e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7390000,0.7,0.0013,-0.014,0.71,-0.0061,0.005,-0.16,-0.0028,0.0044,-3.7e+02,-1.4e-05,-5.7e-05,4.5e-07,0,0,-1.3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.0002,0.00028,0.00028,0.00019,0.29,0.29,0.18,0.46,0.46,0.13,9.7e-09,9.7e-09,3.4e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7490000,0.7,0.0014,-0.014,0.71,-0.0072,0.0052,-0.16,-0.0035,0.0049,-3.7e+02,-1.4e-05,-5.7e-05,4.6e-07,0,0,-2.1e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.00028,0.00028,0.00017,0.32,0.32,0.15,0.53,0.53,0.12,9.7e-09,9.7e-09,3.4e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7590000,0.7,0.0014,-0.014,0.71,-0.0087,0.0062,-0.17,-0.0043,0.0055,-3.7e+02,-1.4e-05,-5.7e-05,5.6e-07,0,0,-3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00028,0.00028,0.00016,0.35,0.35,0.14,0.6,0.6,0.12,9.7e-09,9.7e-09,3.4e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7690000,0.7,0.0014,-0.014,0.71,-0.01,0.0068,-0.16,-0.0052,0.0061,-3.7e+02,-1.4e-05,-5.7e-05,5.7e-07,0,0,-5e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00029,0.00029,0.00016,0.38,0.38,0.13,0.69,0.69,0.11,9.7e-09,9.7e-09,3.4e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7790000,0.7,0.0015,-0.014,0.71,-0.011,0.0074,-0.16,-0.0062,0.0067,-3.7e+02,-1.4e-05,-5.7e-05,3.8e-07,0,0,-7e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.0003,0.0003,0.00015,0.41,0.41,0.12,0.78,0.78,0.11,9.7e-09,9.7e-09,3.4e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7890000,0.7,0.0015,-0.014,0.71,-0.013,0.0091,-0.16,-0.0074,0.0075,-3.7e+02,-1.4e-05,-5.7e-05,4.7e-07,0,0,-9.6e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.0003,0.0003,0.00014,0.45,0.45,0.11,0.89,0.89,0.1,9.7e-09,9.7e-09,3.4e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
7990000,0.7,0.0015,-0.014,0.71,-0.014,0.01,-0.16,-0.0087,0.0084,-3.7e+02,-1.4e-05,-5.7e-05,5.7e-07,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00031,0.00031,0.00013,0.49,0.49,0.1,1,1,0.099,9.6e-09,9.6e-09,3.4e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
8090000,0.7,0.0015,-0.014,0.71,-0.016,0.011,-0.17,-0.01,0.0095,-3.7e+02,-1.4e-05,-5.7e-05,7.3e-07,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00031,0.00031,0.00013,0.53,0.53,0.1,1.1,1.1,0.097,9.6e-09,9.6e-09,3.4e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8190000,0.7,0.0015,-0.014,0.71,-0.018,0.013,-0.18,-0.012,0.011,-3.7e+02,-1.4e-05,-5.7e-05,5.8e-07,0,0,-0.00013,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00032,0.00032,0.00013,0.58,0.58,0.099,1.3,1.3,0.094,9.6e-09,9.6e-09,3.4e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8290000,0.7,0.0015,-0.014,0.71,-0.019,0.013,-0.17,-0.014,0.012,-3.7e+02,-1.4e-05,-5.7e-05,4.8e-07,0,0,-0.00017,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00033,0.00033,0.00012,0.63,0.63,0.097,1.4,1.4,0.091,9.5e-09,9.5e-09,3.4e-09,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
8390000,0.7,0.0016,-0.014,0.71,-0.02,0.014,-0.17,-0.016,0.013,-3.7e+02,-1.4e-05,-5.7e-05,6.6e-07,0,0,-0.00021,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00034,0.00034,0.00012,0.68,0.68,0.097,1.6,1.6,0.091,9.5e-09,9.5e-09,3.3e-09,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
8490000,0.7,0.0015,-0.014,0.71,-0.021,0.015,-0.17,-0.018,0.014,-3.7e+02,-1.4e-05,-5.7e-05,5.9e-07,0,0,-0.00025,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00034,0.00034,0.00012,0.73,0.73,0.096,1.8,1.8,0.089,9.4e-09,9.4e-09,3.3e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
8590000,0.7,0.0016,-0.014,0.71,-0.023,0.017,-0.17,-0.02,0.016,-3.7e+02,-1.4e-05,-5.7e-05,4e-07,0,0,-0.00029,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00035,0.00035,0.00011,0.79,0.79,0.095,2,2,0.088,9.4e-09,9.4e-09,3.3e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
8690000,0.7,0.0016,-0.014,0.71,-0.026,0.018,-0.16,-0.022,0.017,-3.7e+02,-1.4e-05,-5.7e-05,6.7e-07,0,0,-0.00035,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00036,0.00036,0.00011,0.84,0.84,0.096,2.2,2.2,0.088,9.3e-09,9.3e-09,3.3e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
8790000,0.7,0.0016,-0.014,0.71,-0.027,0.02,-0.15,-0.025,0.019,-3.7e+02,-1.4e-05,-5.7e-05,5.5e-07,0,0,-0.00041,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00037,0.00037,0.00011,0.91,0.91,0.095,2.5,2.5,0.087,9.3e-09,9.3e-09,3.3e-09,4e-06,4e-06,3.2e-06,0,0,0,0,0,0,0,0
8890000,0.7,0.0016,-0.014,0.71,-0.029,0.02,-0.15,-0.027,0.02,-3.7e+02,-1.4e-05,-5.7e-05,4.6e-07,0,0,-0.00045,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00037,0.00037,0.00011,0.96,0.96,0.095,2.7,2.7,0.086,9.2e-09,9.2e-09,3.3e-09,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
8990000,0.7,0.0016,-0.014,0.71,-0.03,0.02,-0.14,-0.031,0.022,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-07,0,0,-0.00051,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00038,0.00038,0.00011,1,1,0.096,3,3,0.087,9.2e-09,9.2e-09,3.3e-09,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
9090000,0.7,0.0017,-0.014,0.71,-0.032,0.021,-0.14,-0.033,0.023,-3.7e+02,-1.4e-05,-5.7e-05,1.1e-07,0,0,-0.00053,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00038,0.00038,0.0001,1.1,1.1,0.095,3.3,3.3,0.086,9e-09,9e-09,3.3e-09,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
9190000,0.7,0.0017,-0.014,0.71,-0.033,0.021,-0.14,-0.036,0.025,-3.7e+02,-1.4e-05,-5.7e-05,6e-07,0,0,-0.00057,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00039,0.00039,0.0001,1.2,1.2,0.094,3.6,3.6,0.085,9e-09,9e-09,3.2e-09,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0
9290000,0.7,0.0016,-0.014,0.71,-0.033,0.022,-0.14,-0.039,0.026,-3.7e+02,-1.3e-05,-5.7e-05,6.6e-07,0,0,-0.00061,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00039,0.00039,0.0001,1.2,1.2,0.093,3.9,3.9,0.085,8.9e-09,8.9e-09,3.2e-09,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
9390000,0.7,0.0016,-0.014,0.71,-0.034,0.024,-0.14,-0.042,0.028,-3.7e+02,-1.3e-05,-5.7e-05,6.5e-07,0,0,-0.00065,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.0004,0.0004,0.0001,1.3,1.3,0.093,4.3,4.3,0.086,8.9e-09,8.9e-09,3.2e-09,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
9490000,0.7,0.0016,-0.014,0.71,-0.035,0.023,-0.13,-0.044,0.029,-3.7e+02,-1.3e-05,-5.7e-05,1e-06,0,0,-0.00068,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.0004,0.0004,9.9e-05,1.3,1.3,0.091,4.6,4.6,0.085,8.7e-09,8.7e-09,3.2e-09,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0
9590000,0.7,0.0016,-0.014,0.71,-0.037,0.025,-0.13,-0.048,0.031,-3.7e+02,-1.3e-05,-5.7e-05,1.2e-06,0,0,-0.00072,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00041,0.00041,9.8e-05,1.4,1.4,0.09,5.1,5.1,0.085,8.7e-09,8.7e-09,3.2e-09,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
9690000,0.7,0.0017,-0.014,0.71,-0.037,0.026,-0.12,-0.049,0.031,-3.7e+02,-1.3e-05,-5.7e-05,7.6e-07,0,0,-0.00077,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00041,0.00041,9.7e-05,1.4,1.4,0.089,5.3,5.3,0.086,8.4e-09,8.5e-09,3.1e-09,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
9790000,0.7,0.0017,-0.014,0.71,-0.037,0.027,-0.11,-0.053,0.034,-3.7e+02,-1.3e-05,-5.7e-05,1e-06,0,0,-0.00082,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.00042,0.00042,9.7e-05,1.5,1.5,0.087,5.9,5.9,0.085,8.4e-09,8.5e-09,3.1e-09,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
9890000,0.7,0.0016,-0.014,0.71,-0.037,0.027,-0.11,-0.054,0.034,-3.7e+02,-1.3e-05,-5.7e-05,1e-06,0,0,-0.00085,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.00041,0.00041,9.6e-05,1.5,1.5,0.084,6.1,6.1,0.085,8.2e-09,8.2e-09,3.1e-09,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0
9990000,0.7,0.0017,-0.014,0.71,-0.038,0.028,-0.1,-0.058,0.037,-3.7e+02,-1.3e-05,-5.7e-05,8.1e-07,0,0,-0.00089,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00042,0.00042,9.6e-05,1.6,1.6,0.083,6.7,6.7,0.086,8.2e-09,8.2e-09,3.1e-09,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
10090000,0.7,0.0017,-0.014,0.71,-0.037,0.026,-0.096,-0.058,0.037,-3.7e+02,-1.3e-05,-5.7e-05,9.1e-07,0,0,-0.00091,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00041,0.00041,9.5e-05,1.6,1.6,0.08,6.9,6.9,0.085,8e-09,8e-09,3e-09,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
10190000,0.7,0.0017,-0.014,0.71,-0.038,0.029,-0.096,-0.061,0.039,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-07,0,0,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00042,0.00042,9.5e-05,1.7,1.7,0.078,7.6,7.6,0.084,8e-09,8e-09,3e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10290000,0.7,0.0017,-0.014,0.71,-0.038,0.028,-0.084,-0.066,0.042,-3.7e+02,-1.3e-05,-5.7e-05,-1.8e-08,0,0,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00043,0.00043,9.5e-05,1.8,1.8,0.076,8.3,8.3,0.085,8e-09,8e-09,3e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10390000,0.7,0.0016,-0.014,0.71,0.01,-0.02,0.0096,0.0009,-0.0018,-3.7e+02,-1.3e-05,-5.7e-05,1.4e-09,-6.4e-10,5.1e-10,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00044,0.00044,9.4e-05,0.25,0.25,0.56,0.25,0.25,0.078,8e-09,8e-09,3e-09,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
10490000,0.7,0.0017,-0.014,0.71,0.0097,-0.018,0.023,0.0019,-0.0036,-3.7e+02,-1.3e-05,-5.7e-05,-3.5e-07,-1.7e-08,1.3e-08,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.4e-05,0.26,0.26,0.55,0.26,0.26,0.08,8e-09,8e-09,2.9e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10590000,0.7,0.0017,-0.014,0.71,0.0092,-0.0076,0.026,0.0018,-0.00084,-3.7e+02,-1.3e-05,-5.7e-05,-3.3e-07,-2.8e-06,7.2e-08,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00047,0.00047,9.4e-05,0.13,0.13,0.27,0.13,0.13,0.073,7.9e-09,7.9e-09,2.9e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10690000,0.7,0.0018,-0.014,0.71,0.0079,-0.0075,0.03,0.0027,-0.0016,-3.7e+02,-1.3e-05,-5.7e-05,-4.5e-07,-2.8e-06,8.4e-08,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00048,0.00048,9.4e-05,0.14,0.14,0.26,0.14,0.14,0.078,7.9e-09,7.9e-09,2.9e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10790000,0.7,0.0018,-0.014,0.71,0.0072,-0.0048,0.024,0.0028,-0.0008,-3.7e+02,-1.3e-05,-5.7e-05,-3.9e-07,-5e-06,7e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00047,0.00047,9.3e-05,0.099,0.099,0.17,0.091,0.091,0.072,7.8e-09,7.8e-09,2.8e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10890000,0.7,0.0017,-0.014,0.71,0.0067,-0.0041,0.02,0.0034,-0.0012,-3.7e+02,-1.3e-05,-5.7e-05,-4e-07,-5e-06,7e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00049,0.00049,9.3e-05,0.11,0.11,0.16,0.098,0.098,0.075,7.8e-09,7.8e-09,2.8e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10990000,0.7,0.0017,-0.014,0.71,0.0086,0.00073,0.014,0.0048,-0.0024,-3.7e+02,-1.3e-05,-5.6e-05,-2e-08,-1e-05,6.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00047,0.00047,9.3e-05,0.09,0.09,0.12,0.073,0.073,0.071,7.5e-09,7.5e-09,2.8e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11090000,0.7,0.0017,-0.014,0.71,0.0079,0.0025,0.019,0.0056,-0.0023,-3.7e+02,-1.3e-05,-5.6e-05,3.7e-07,-1e-05,6.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00048,0.00048,9.3e-05,0.11,0.11,0.11,0.079,0.079,0.074,7.5e-09,7.5e-09,2.7e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11190000,0.7,0.0017,-0.014,0.71,0.012,0.0053,0.0077,0.0067,-0.0031,-3.7e+02,-1.2e-05,-5.6e-05,7e-08,-1.3e-05,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00044,0.00044,9.3e-05,0.088,0.088,0.084,0.063,0.063,0.069,7e-09,7e-09,2.7e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11290000,0.7,0.0018,-0.014,0.71,0.012,0.0071,0.0074,0.0079,-0.0024,-3.7e+02,-1.2e-05,-5.6e-05,-4.4e-07,-1.3e-05,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00045,0.00045,9.3e-05,0.11,0.11,0.078,0.07,0.07,0.072,7e-09,7e-09,2.7e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11390000,0.7,0.0019,-0.014,0.71,0.0073,0.0067,0.0017,0.0057,-0.0022,-3.7e+02,-1.3e-05,-5.6e-05,-8.5e-07,-9.9e-06,5.2e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0004,0.0004,9.3e-05,0.089,0.089,0.063,0.057,0.057,0.068,6.5e-09,6.5e-09,2.6e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11490000,0.7,0.0019,-0.014,0.71,0.0051,0.009,0.0025,0.0063,-0.0014,-3.7e+02,-1.3e-05,-5.6e-05,-1.6e-06,-9.9e-06,5.3e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00041,0.00041,9.3e-05,0.11,0.11,0.058,0.065,0.065,0.069,6.5e-09,6.5e-09,2.6e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11590000,0.7,0.0018,-0.014,0.71,0.00046,0.0084,-0.0034,0.0047,-0.0015,-3.7e+02,-1.3e-05,-5.7e-05,-1.8e-06,-5.8e-06,2.6e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00036,0.00036,9.3e-05,0.089,0.089,0.049,0.054,0.054,0.066,6e-09,6e-09,2.6e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11690000,0.7,0.0018,-0.014,0.71,-0.002,0.011,-0.0079,0.0046,-0.0006,-3.7e+02,-1.3e-05,-5.7e-05,-2.1e-06,-5.7e-06,2.5e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00037,0.00037,9.3e-05,0.11,0.11,0.046,0.062,0.062,0.066,6e-09,6e-09,2.5e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11790000,0.7,0.0019,-0.014,0.71,-0.008,0.011,-0.0098,0.0021,0.00045,-3.7e+02,-1.3e-05,-5.7e-05,-2.2e-06,-5.2e-06,-1.2e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00032,0.00032,9.3e-05,0.087,0.087,0.039,0.052,0.052,0.063,5.5e-09,5.5e-09,2.5e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
11890000,0.7,0.0019,-0.014,0.71,-0.0092,0.012,-0.011,0.0013,0.0016,-3.7e+02,-1.3e-05,-5.7e-05,-2.6e-06,-5.2e-06,-1.2e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00033,0.00033,9.3e-05,0.1,0.1,0.037,0.06,0.06,0.063,5.5e-09,5.5e-09,2.4e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
11990000,0.7,0.002,-0.014,0.71,-0.011,0.013,-0.016,-5.7e-05,0.0022,-3.7e+02,-1.3e-05,-5.7e-05,-2.5e-06,-3.9e-06,-1.6e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00029,0.00029,9.3e-05,0.083,0.083,0.033,0.051,0.051,0.061,5.1e-09,5.1e-09,2.4e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0
12090000,0.7,0.002,-0.014,0.71,-0.013,0.015,-0.022,-0.0013,0.0036,-3.7e+02,-1.3e-05,-5.7e-05,-2.2e-06,-3.8e-06,-1.8e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00029,0.00029,9.3e-05,0.099,0.099,0.031,0.059,0.059,0.061,5.1e-09,5.1e-09,2.4e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0
12190000,0.7,0.0017,-0.014,0.71,-0.007,0.012,-0.017,0.0015,0.002,-3.7e+02,-1.3e-05,-5.7e-05,-2.1e-06,1.6e-07,5.5e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00026,0.00026,9.3e-05,0.079,0.079,0.028,0.05,0.05,0.059,4.8e-09,4.8e-09,2.3e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0
12290000,0.7,0.0016,-0.014,0.71,-0.0094,0.014,-0.016,0.00069,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-2e-06,-1.1e-07,5.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00027,0.00027,9.3e-05,0.093,0.093,0.028,0.058,0.058,0.059,4.8e-09,4.8e-09,2.3e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0
12390000,0.7,0.0014,-0.014,0.71,-0.0045,0.011,-0.015,0.0029,0.0018,-3.7e+02,-1.2e-05,-5.8e-05,-2.3e-06,2.8e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00024,0.00024,9.3e-05,0.075,0.075,0.026,0.05,0.05,0.057,4.5e-09,4.5e-09,2.3e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0
12490000,0.7,0.0013,-0.014,0.71,-0.0056,0.013,-0.018,0.0024,0.0029,-3.7e+02,-1.2e-05,-5.8e-05,-2.7e-06,2.7e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00025,0.00025,9.3e-05,0.087,0.087,0.026,0.058,0.058,0.057,4.5e-09,4.5e-09,2.2e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0
12590000,0.7,0.0014,-0.014,0.71,-0.013,0.011,-0.023,-0.0027,0.0016,-3.7e+02,-1.3e-05,-5.8e-05,-2.7e-06,5.5e-06,5.8e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00022,0.00022,9.3e-05,0.07,0.07,0.025,0.049,0.049,0.055,4.3e-09,4.3e-09,2.2e-09,3.5e-06,3.5e-06,9.9e-07,0,0,0,0,0,0,0,0
12690000,0.7,0.0015,-0.014,0.71,-0.013,0.012,-0.027,-0.0041,0.0028,-3.7e+02,-1.3e-05,-5.8e-05,-3e-06,5.7e-06,5.6e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00023,0.00023,9.3e-05,0.081,0.081,0.025,0.058,0.058,0.055,4.3e-09,4.3e-09,2.1e-09,3.5e-06,3.5e-06,9.8e-07,0,0,0,0,0,0,0,0
12790000,0.7,0.0015,-0.014,0.71,-0.019,0.0092,-0.03,-0.0075,0.0015,-3.7e+02,-1.3e-05,-5.8e-05,-2.8e-06,7.3e-06,3.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00021,0.00021,9.3e-05,0.066,0.066,0.024,0.049,0.049,0.053,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,9.7e-07,0,0,0,0,0,0,0,0
12890000,0.7,0.0015,-0.014,0.71,-0.02,0.0091,-0.029,-0.0094,0.0024,-3.7e+02,-1.3e-05,-5.8e-05,-2.8e-06,6.7e-06,4.5e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00022,0.00022,9.3e-05,0.076,0.076,0.025,0.057,0.057,0.054,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,9.6e-07,0,0,0,0,0,0,0,0
12990000,0.7,0.0012,-0.014,0.71,-0.0078,0.0067,-0.03,-0.0011,0.0013,-3.7e+02,-1.2e-05,-5.9e-05,-2.3e-06,6.8e-06,9.6e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.0002,0.0002,9.3e-05,0.062,0.062,0.025,0.049,0.049,0.052,3.8e-09,3.9e-09,2e-09,3.5e-06,3.5e-06,9.4e-07,0,0,0,0,0,0,0,0
13090000,0.7,0.0012,-0.014,0.71,-0.0084,0.0069,-0.03,-0.0019,0.002,-3.7e+02,-1.2e-05,-5.8e-05,-2.8e-06,6.4e-06,9.8e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00021,0.00021,9.3e-05,0.071,0.071,0.025,0.057,0.057,0.052,3.8e-09,3.9e-09,2e-09,3.5e-06,3.5e-06,9.4e-07,0,0,0,0,0,0,0,0
13190000,0.7,0.00095,-0.014,0.71,0.00044,0.0063,-0.027,0.0043,0.0013,-3.7e+02,-1.1e-05,-5.9e-05,-2.8e-06,5.1e-06,1.3e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.0002,0.0002,9.3e-05,0.058,0.058,0.025,0.049,0.049,0.051,3.7e-09,3.7e-09,1.9e-09,3.5e-06,3.5e-06,9.1e-07,0,0,0,0,0,0,0,0
13290000,0.7,0.00095,-0.014,0.71,0.00026,0.0072,-0.024,0.0043,0.002,-3.7e+02,-1.1e-05,-5.9e-05,-2.4e-06,3.9e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.0002,0.0002,9.3e-05,0.066,0.067,0.027,0.057,0.057,0.051,3.7e-09,3.7e-09,1.9e-09,3.5e-06,3.5e-06,9.1e-07,0,0,0,0,0,0,0,0
13390000,0.7,0.00081,-0.014,0.71,0.001,0.0062,-0.02,0.0032,0.0012,-3.7e+02,-1.1e-05,-5.9e-05,-2e-06,2.6e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.3e-05,0.055,0.055,0.026,0.048,0.048,0.05,3.5e-09,3.5e-09,1.9e-09,3.5e-06,3.5e-06,8.8e-07,0,0,0,0,0,0,0,0
13490000,0.7,0.00084,-0.014,0.71,0.0006,0.0062,-0.019,0.0033,0.0018,-3.7e+02,-1.1e-05,-5.9e-05,-1.7e-06,1.8e-06,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.0002,0.0002,9.3e-05,0.063,0.063,0.028,0.056,0.056,0.05,3.5e-09,3.5e-09,1.8e-09,3.5e-06,3.5e-06,8.7e-07,0,0,0,0,0,0,0,0
13590000,0.7,0.00078,-0.014,0.71,0.0008,0.0064,-0.021,0.0023,0.0012,-3.7e+02,-1.1e-05,-5.9e-05,-1.9e-06,1.7e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.3e-05,0.052,0.052,0.028,0.048,0.048,0.05,3.3e-09,3.4e-09,1.8e-09,3.5e-06,3.5e-06,8.4e-07,0,0,0,0,0,0,0,0
13690000,0.7,0.00076,-0.014,0.71,0.0016,0.0082,-0.025,0.0024,0.0019,-3.7e+02,-1.1e-05,-5.9e-05,-1.4e-06,2e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.0002,0.0002,9.3e-05,0.059,0.059,0.029,0.056,0.056,0.05,3.3e-09,3.4e-09,1.8e-09,3.5e-06,3.5e-06,8.3e-07,0,0,0,0,0,0,0,0
13790000,0.7,0.00065,-0.014,0.71,0.0021,0.0041,-0.027,0.0034,-0.00048,-3.7e+02,-1.1e-05,-5.9e-05,-1.5e-06,4.8e-07,1.3e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.3e-05,0.05,0.05,0.029,0.048,0.048,0.049,3.2e-09,3.2e-09,1.7e-09,3.5e-06,3.5e-06,7.9e-07,0,0,0,0,0,0,0,0
13890000,0.7,0.00062,-0.014,0.71,0.0026,0.004,-0.031,0.0037,-9.5e-05,-3.7e+02,-1.1e-05,-5.9e-05,-1.2e-06,7.8e-07,1.3e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.3e-05,0.056,0.056,0.03,0.056,0.056,0.05,3.2e-09,3.2e-09,1.7e-09,3.5e-06,3.5e-06,7.8e-07,0,0,0,0,0,0,0,0
13990000,0.7,0.00055,-0.014,0.71,0.0029,0.0016,-0.03,0.0044,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-1.1e-06,-1.5e-06,1.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9.3e-05,0.048,0.048,0.03,0.048,0.048,0.05,3e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,7.4e-07,0,0,0,0,0,0,0,0
14090000,0.7,0.00054,-0.014,0.71,0.003,0.0018,-0.031,0.0047,-0.0017,-3.7e+02,-1.1e-05,-6e-05,-5.4e-07,-1.4e-06,1.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9.3e-05,0.054,0.054,0.031,0.055,0.055,0.05,3e-09,3.1e-09,1.6e-09,3.5e-06,3.5e-06,7.3e-07,0,0,0,0,0,0,0,0
14190000,0.7,0.00044,-0.014,0.71,0.0063,0.0012,-0.033,0.0067,-0.0015,-3.7e+02,-1.1e-05,-6e-05,-2.5e-07,-1.7e-06,1.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9.3e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,6.9e-07,0,0,0,0,0,0,0,0
14290000,0.7,0.00045,-0.014,0.71,0.0071,0.002,-0.032,0.0074,-0.0014,-3.7e+02,-1.1e-05,-6e-05,-3.7e-08,-2.3e-06,1.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9.3e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,6.7e-07,0,0,0,0,0,0,0,0
14390000,0.7,0.00036,-0.014,0.71,0.0089,0.0029,-0.034,0.0087,-0.0012,-3.7e+02,-1e-05,-6e-05,5.2e-07,-2.7e-06,9.3e-06,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9.3e-05,0.044,0.044,0.031,0.047,0.047,0.05,2.8e-09,2.8e-09,1.5e-09,3.4e-06,3.4e-06,6.3e-07,0,0,0,0,0,0,0,0
14490000,0.7,0.00035,-0.014,0.71,0.0089,0.0042,-0.037,0.0096,-0.00085,-3.7e+02,-1e-05,-6e-05,6.8e-07,-2.2e-06,8.9e-06,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9.2e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-09,2.8e-09,1.5e-09,3.4e-06,3.4e-06,6.2e-07,0,0,0,0,0,0,0,0
14590000,0.7,0.00034,-0.013,0.71,0.0055,0.0026,-0.037,0.006,-0.0023,-3.7e+02,-1.1e-05,-6e-05,7.1e-07,-5.1e-06,1.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9.3e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-09,2.6e-09,1.5e-09,3.4e-06,3.4e-06,5.8e-07,0,0,0,0,0,0,0,0
14690000,0.7,0.00029,-0.013,0.71,0.0069,-0.00031,-0.034,0.0067,-0.0022,-3.7e+02,-1.1e-05,-6e-05,1.1e-06,-6.1e-06,1.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9.2e-05,0.048,0.048,0.032,0.054,0.054,0.051,2.6e-09,2.6e-09,1.4e-09,3.4e-06,3.4e-06,5.6e-07,0,0,0,0,0,0,0,0
14790000,0.7,0.00032,-0.013,0.71,0.0037,-0.0019,-0.03,0.0038,-0.0032,-3.7e+02,-1.1e-05,-6e-05,1.2e-06,-9.4e-06,1.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9.2e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-09,2.5e-09,1.4e-09,3.4e-06,3.4e-06,5.3e-07,0,0,0,0,0,0,0,0
14890000,0.7,0.00031,-0.013,0.71,0.0053,-0.00088,-0.033,0.0042,-0.0034,-3.7e+02,-1.1e-05,-6e-05,1.5e-06,-9.2e-06,1.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9.2e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-09,2.5e-09,1.4e-09,3.4e-06,3.4e-06,5.1e-07,0,0,0,0,0,0,0,0
14990000,0.7,0.00031,-0.013,0.71,0.004,-0.0011,-0.029,0.0032,-0.0027,-3.7e+02,-1.1e-05,-6e-05,1.4e-06,-9.9e-06,2.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,9.2e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-09,2.3e-09,1.4e-09,3.4e-06,3.4e-06,4.8e-07,0,0,0,0,0,0,0,0
15090000,0.7,0.00023,-0.013,0.71,0.0045,-0.0012,-0.032,0.0036,-0.0028,-3.7e+02,-1.1e-05,-6e-05,1.4e-06,-9.4e-06,2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00019,0.00019,9.2e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-09,2.3e-09,1.3e-09,3.4e-06,3.4e-06,4.6e-07,0,0,0,0,0,0,0,0
15190000,0.7,0.00025,-0.013,0.71,0.0038,-8e-05,-0.029,0.0029,-0.0023,-3.7e+02,-1.1e-05,-6e-05,1.3e-06,-9.7e-06,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,9.2e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-09,2.2e-09,1.3e-09,3.4e-06,3.4e-06,4.3e-07,0,0,0,0,0,0,0,0
15290000,0.7,0.00021,-0.013,0.71,0.0045,0.00016,-0.027,0.0033,-0.0023,-3.7e+02,-1.1e-05,-6e-05,1.6e-06,-1e-05,2.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,9.2e-05,0.045,0.045,0.03,0.053,0.053,0.052,2.2e-09,2.2e-09,1.3e-09,3.4e-06,3.4e-06,4.2e-07,0,0,0,0,0,0,0,0
15390000,0.7,0.00021,-0.013,0.71,0.0037,0.00043,-0.024,0.00066,-0.0019,-3.7e+02,-1.2e-05,-6e-05,2.2e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,9.1e-05,0.039,0.039,0.029,0.047,0.047,0.051,2e-09,2e-09,1.3e-09,3.4e-06,3.4e-06,3.9e-07,0,0,0,0,0,0,0,0
15490000,0.7,0.00023,-0.013,0.71,0.005,0.00013,-0.024,0.0011,-0.0019,-3.7e+02,-1.2e-05,-6e-05,1.9e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,9.1e-05,0.044,0.044,0.029,0.053,0.053,0.053,2e-09,2e-09,1.2e-09,3.4e-06,3.4e-06,3.7e-07,0,0,0,0,0,0,0,0
15590000,0.7,0.00025,-0.013,0.71,0.0031,5.9e-05,-0.023,-0.0012,-0.0016,-3.7e+02,-1.2e-05,-6e-05,1.7e-06,-1.1e-05,2.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,9.1e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,3.5e-07,0,0,0,0,0,0,0,0
15690000,0.7,0.00025,-0.013,0.71,0.0034,-3.7e-05,-0.023,-0.00087,-0.0015,-3.7e+02,-1.2e-05,-6e-05,1.7e-06,-1.1e-05,2.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00018,0.00018,9.1e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,3.3e-07,0,0,0,0,0,0,0,0
15790000,0.7,0.00021,-0.013,0.71,0.0039,-0.0018,-0.026,-0.00083,-0.0026,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,9.1e-05,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-09,1.7e-09,1.1e-09,3.3e-06,3.3e-06,3.1e-07,0,0,0,0,0,0,0,0
15890000,0.7,0.00016,-0.013,0.71,0.0048,-0.0022,-0.024,-0.00036,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,1.8e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00018,0.00018,9.1e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-09,1.7e-09,1.1e-09,3.3e-06,3.3e-06,3e-07,0,0,0,0,0,0,0,0
15990000,0.7,0.00011,-0.013,0.71,0.0046,-0.0031,-0.019,-0.0005,-0.0037,-3.7e+02,-1.2e-05,-6.1e-05,2.2e-06,-1.6e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,9.1e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,2.8e-07,0,0,0,0,0,0,0,0
16090000,0.71,0.00011,-0.013,0.71,0.0064,-0.0033,-0.016,3.8e-05,-0.004,-3.7e+02,-1.2e-05,-6.1e-05,2.7e-06,-1.7e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00017,0.00017,9e-05,0.042,0.042,0.025,0.053,0.053,0.052,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,2.7e-07,0,0,0,0,0,0,0,0
16190000,0.71,0.00013,-0.013,0.71,0.0064,-0.0026,-0.014,-0.00023,-0.0033,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.6e-05,3.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,9e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.1e-09,3.3e-06,3.3e-06,2.5e-07,0,0,0,0,0,0,0,0
16290000,0.71,0.00015,-0.013,0.71,0.008,-0.0033,-0.016,0.00049,-0.0036,-3.7e+02,-1.2e-05,-6.1e-05,3.3e-06,-1.6e-05,3.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00017,0.00017,9e-05,0.042,0.042,0.024,0.052,0.052,0.052,1.5e-09,1.5e-09,1e-09,3.3e-06,3.3e-06,2.4e-07,0,0,0,0,0,0,0,0
16390000,0.71,0.00014,-0.013,0.71,0.0068,-0.0036,-0.015,0.00011,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,3.2e-06,-1.5e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,9e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1e-09,3.2e-06,3.2e-06,2.2e-07,0,0,0,0,0,0,0,0
16490000,0.71,0.00015,-0.013,0.71,0.0061,-0.0031,-0.018,0.00073,-0.0032,-3.7e+02,-1.2e-05,-6.1e-05,3.3e-06,-1.4e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,9e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1e-09,3.2e-06,3.2e-06,2.1e-07,0,0,0,0,0,0,0,0
16590000,0.71,0.00041,-0.013,0.71,0.0025,-0.00049,-0.018,-0.0023,0.00012,-3.7e+02,-1.3e-05,-6e-05,3.4e-06,-7.5e-06,4.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,9e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-09,1.2e-09,9.7e-10,3.2e-06,3.2e-06,2e-07,0,0,0,0,0,0,0,0
16690000,0.71,0.0004,-0.013,0.71,0.0027,3.1e-05,-0.015,-0.002,9.8e-05,-3.7e+02,-1.3e-05,-6e-05,3.1e-06,-8e-06,4.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00016,0.00016,8.9e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-09,1.2e-09,9.5e-10,3.2e-06,3.2e-06,1.9e-07,0,0,0,0,0,0,0,0
16790000,0.71,0.00054,-0.013,0.71,-0.00072,0.0021,-0.014,-0.0044,0.0027,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-2.2e-06,5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.9e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-09,1.1e-09,9.4e-10,3.2e-06,3.2e-06,1.8e-07,0,0,0,0,0,0,0,0
16890000,0.71,0.00056,-0.013,0.71,-0.00095,0.0031,-0.011,-0.0045,0.003,-3.7e+02,-1.3e-05,-6e-05,3.1e-06,-2.6e-06,5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00016,0.00016,8.9e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-09,1.1e-09,9.2e-10,3.2e-06,3.2e-06,1.7e-07,0,0,0,0,0,0,0,0
16990000,0.71,0.0005,-0.013,0.71,-0.00098,0.00099,-0.01,-0.005,0.0011,-3.7e+02,-1.3e-05,-6e-05,2.8e-06,-6.6e-06,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.9e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-09,1e-09,9e-10,3.2e-06,3.2e-06,1.6e-07,0,0,0,0,0,0,0,0
17090000,0.71,0.00047,-0.013,0.71,-0.00014,0.002,-0.01,-0.0051,0.0012,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-6.5e-06,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.9e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-09,1e-09,8.8e-10,3.2e-06,3.2e-06,1.6e-07,0,0,0,0,0,0,0,0
17190000,0.71,0.00046,-0.013,0.71,0.00024,0.0019,-0.011,-0.0054,-0.00032,-3.7e+02,-1.3e-05,-6e-05,3e-06,-1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.8e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-10,9.4e-10,8.6e-10,3.1e-06,3.1e-06,1.5e-07,0,0,0,0,0,0,0,0
17290000,0.71,0.00043,-0.013,0.71,0.0024,0.003,-0.0066,-0.0053,-9.5e-05,-3.7e+02,-1.3e-05,-6e-05,2.8e-06,-1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.8e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-10,9.4e-10,8.4e-10,3.1e-06,3.1e-06,1.4e-07,0,0,0,0,0,0,0,0
17390000,0.71,0.0004,-0.013,0.71,0.003,0.0021,-0.0047,-0.0045,-0.0014,-3.7e+02,-1.3e-05,-6e-05,3.1e-06,-1.4e-05,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.8e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-10,8.5e-10,8.3e-10,3.1e-06,3.1e-06,1.3e-07,0,0,0,0,0,0,0,0
17490000,0.71,0.00039,-0.013,0.71,0.0035,0.0017,-0.003,-0.0042,-0.0012,-3.7e+02,-1.3e-05,-6e-05,3.1e-06,-1.4e-05,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.8e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-10,8.5e-10,8.1e-10,3.1e-06,3.1e-06,1.3e-07,0,0,0,0,0,0,0,0
17590000,0.71,0.00031,-0.013,0.71,0.0047,0.00049,0.0025,-0.0035,-0.0024,-3.7e+02,-1.3e-05,-6.1e-05,3.2e-06,-1.8e-05,5.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.8e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-10,7.7e-10,7.9e-10,3.1e-06,3.1e-06,1.2e-07,0,0,0,0,0,0,0,0
17690000,0.71,0.00028,-0.013,0.71,0.0056,0.0012,0.0019,-0.003,-0.0023,-3.7e+02,-1.3e-05,-6.1e-05,3.4e-06,-1.8e-05,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.7e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-10,7.7e-10,7.8e-10,3.1e-06,3.1e-06,1.2e-07,0,0,0,0,0,0,0,0
17790000,0.71,0.00018,-0.013,0.71,0.0082,0.0009,0.00058,-0.0019,-0.002,-3.7e+02,-1.3e-05,-6.1e-05,3.9e-06,-1.8e-05,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.7e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-10,7e-10,7.6e-10,3.1e-06,3.1e-06,1.1e-07,0,0,0,0,0,0,0,0
17890000,0.71,0.00019,-0.013,0.71,0.0097,0.00018,0.00068,-0.001,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.8e-05,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.7e-05,0.037,0.037,0.016,0.051,0.051,0.048,7e-10,7e-10,7.5e-10,3.1e-06,3.1e-06,1.1e-07,0,0,0,0,0,0,0,0
17990000,0.71,0.00014,-0.013,0.71,0.011,-0.0016,0.0019,-0.00035,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.7e-05,5.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.7e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,7.3e-10,3e-06,3e-06,1e-07,0,0,0,0,0,0,0,0
18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0018,0.0043,0.00082,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,3.8e-06,-1.7e-05,5.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.7e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,7.2e-10,3e-06,3e-06,9.7e-08,0,0,0,0,0,0,0,0
18190000,0.71,0.00011,-0.013,0.71,0.013,-0.00074,0.0056,0.0016,-0.0015,-3.7e+02,-1.3e-05,-6e-05,4e-06,-1.7e-05,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.6e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,7e-10,3e-06,3e-06,9.2e-08,0,0,0,0,0,0,0,0
18290000,0.71,5e-05,-0.012,0.71,0.013,-0.0013,0.0068,0.0029,-0.0016,-3.7e+02,-1.3e-05,-6e-05,3.8e-06,-1.7e-05,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.6e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,6.9e-10,3e-06,3e-06,8.9e-08,0,0,0,0,0,0,0,0
18390000,0.71,6.6e-05,-0.013,0.71,0.014,0.00032,0.008,0.0034,-0.0012,-3.7e+02,-1.3e-05,-6e-05,4.1e-06,-1.6e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.6e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-10,5.2e-10,6.8e-10,3e-06,3e-06,8.4e-08,0,0,0,0,0,0,0,0
18490000,0.71,8.1e-05,-0.013,0.71,0.015,0.00077,0.0076,0.0049,-0.0011,-3.7e+02,-1.3e-05,-6e-05,4.2e-06,-1.6e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.6e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-10,5.2e-10,6.6e-10,3e-06,3e-06,8.2e-08,0,0,0,0,0,0,0,0
18590000,0.71,8.6e-05,-0.012,0.71,0.014,0.00095,0.0058,0.0037,-0.00098,-3.7e+02,-1.3e-05,-6e-05,4.6e-06,-1.6e-05,5.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.6e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,6.5e-10,3e-06,3e-06,7.8e-08,0,0,0,0,0,0,0,0
18690000,0.71,5.5e-05,-0.012,0.71,0.014,0.00029,0.0039,0.0051,-0.00089,-3.7e+02,-1.3e-05,-6e-05,4.5e-06,-1.6e-05,5.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.5e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.4e-10,3e-06,3e-06,7.5e-08,0,0,0,0,0,0,0,0
18790000,0.71,8.6e-05,-0.012,0.71,0.013,0.00054,0.0035,0.0039,-0.00071,-3.7e+02,-1.4e-05,-6e-05,4.4e-06,-1.6e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.5e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-10,4.3e-10,6.3e-10,3e-06,3e-06,7.2e-08,0,0,0,0,0,0,0,0
18890000,0.71,0.00011,-0.012,0.71,0.013,0.0011,0.0042,0.0052,-0.0006,-3.7e+02,-1.4e-05,-6e-05,4.7e-06,-1.6e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.5e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-10,4.3e-10,6.2e-10,3e-06,3e-06,6.9e-08,0,0,0,0,0,0,0,0
18990000,0.71,9.6e-05,-0.012,0.71,0.014,0.0019,0.0028,0.0065,-0.00051,-3.7e+02,-1.4e-05,-6e-05,4.9e-06,-1.6e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00011,8.5e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-10,3.9e-10,6e-10,2.9e-06,2.9e-06,6.6e-08,0,0,0,0,0,0,0,0
19090000,0.71,8.1e-05,-0.012,0.71,0.015,0.0025,0.0058,0.008,-0.00026,-3.7e+02,-1.4e-05,-6e-05,4.9e-06,-1.6e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.5e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-10,3.9e-10,5.9e-10,2.9e-06,2.9e-06,6.5e-08,0,0,0,0,0,0,0,0
19190000,0.71,8.3e-05,-0.012,0.71,0.015,0.0025,0.0059,0.0087,-0.00026,-3.7e+02,-1.4e-05,-6e-05,5e-06,-1.7e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8.4e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,5.8e-10,2.9e-06,2.9e-06,6.2e-08,0,0,0,0,0,0,0,0
19290000,0.71,0.00011,-0.012,0.71,0.015,0.0018,0.0086,0.01,-2.8e-05,-3.7e+02,-1.4e-05,-6e-05,4.9e-06,-1.7e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8.4e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,5.7e-10,2.9e-06,2.9e-06,6e-08,0,0,0,0,0,0,0,0
19390000,0.71,0.00012,-0.012,0.71,0.013,0.0008,0.012,0.0082,-9e-05,-3.7e+02,-1.4e-05,-6.1e-05,5e-06,-1.7e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8.4e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-10,3.3e-10,5.6e-10,2.9e-06,2.9e-06,5.8e-08,0,0,0,0,0,0,0,0
19490000,0.71,0.00014,-0.012,0.71,0.012,0.00011,0.0088,0.0094,-4.8e-05,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.7e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8.4e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.5e-10,2.9e-06,2.9e-06,5.6e-08,0,0,0,0,0,0,0,0
19590000,0.71,0.00019,-0.012,0.71,0.01,-0.00096,0.0081,0.0076,-0.00011,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.7e-05,6.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8.4e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.4e-10,2.9e-06,2.9e-06,5.4e-08,0,0,0,0,0,0,0,0
19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0031,0.0096,0.0086,-0.00032,-3.7e+02,-1.4e-05,-6.1e-05,5.5e-06,-1.7e-05,6.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8.3e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.3e-10,2.9e-06,2.9e-06,5.2e-08,0,0,0,0,0,0,0,0
19790000,0.71,0.00026,-0.012,0.71,0.008,-0.004,0.01,0.007,-0.00026,-3.7e+02,-1.4e-05,-6e-05,5.5e-06,-1.7e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8.3e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.71,0.00021,-0.012,0.71,0.0068,-0.0043,0.011,0.0077,-0.00069,-3.7e+02,-1.4e-05,-6e-05,5.9e-06,-1.7e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8.3e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.71,0.00019,-0.012,0.71,0.0043,-0.005,0.014,0.0063,-0.00058,-3.7e+02,-1.4e-05,-6e-05,6.4e-06,-1.6e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.0001,0.0001,8.3e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.71,0.00019,-0.012,0.71,0.0041,-0.0069,0.014,0.0067,-0.0012,-3.7e+02,-1.4e-05,-6e-05,6.8e-06,-1.6e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.0001,0.0001,8.3e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-10,2.5e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.71,0.00029,-0.012,0.71,0.0017,-0.0077,0.017,0.0044,-0.00091,-3.7e+02,-1.4e-05,-6e-05,7e-06,-1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.0001,0.0001,8.2e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.71,0.00025,-0.012,0.71,0.00059,-0.0092,0.015,0.0045,-0.0018,-3.7e+02,-1.4e-05,-6e-05,7.1e-06,-1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,8.2e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.71,0.00027,-0.012,0.71,-0.0019,-0.0098,0.017,0.0026,-0.0014,-3.7e+02,-1.4e-05,-6e-05,7.1e-06,-1.3e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,8.2e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.71,0.00033,-0.012,0.71,-0.0023,-0.011,0.016,0.0023,-0.0024,-3.7e+02,-1.4e-05,-6e-05,7e-06,-1.3e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,8.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.71,0.00035,-0.012,0.71,-0.002,-0.011,0.013,0.002,-0.0019,-3.7e+02,-1.4e-05,-6e-05,6.8e-06,-1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,9.9e-05,9.9e-05,8.2e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-10,1.9e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.71,0.00037,-0.012,0.71,-0.002,-0.012,0.015,0.0018,-0.003,-3.7e+02,-1.4e-05,-6e-05,6.9e-06,-1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,9.9e-05,8.2e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-10,1.9e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.71,0.0004,-0.012,0.71,-0.0031,-0.011,0.015,0.0015,-0.0024,-3.7e+02,-1.4e-05,-6e-05,7e-06,-9.6e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.7e-05,9.7e-05,8.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.71,0.00039,-0.012,0.71,-0.0036,-0.013,0.014,0.0012,-0.0036,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-9.6e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.8e-05,9.8e-05,8.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.0038,-0.014,0.015,0.0028,-0.003,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-7.6e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.6e-05,9.6e-05,8.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.71,0.00039,-0.012,0.71,-0.004,-0.017,0.015,0.0024,-0.0045,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-7.6e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.7e-05,9.6e-05,8.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4.1e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.71,0.00042,-0.012,0.71,-0.0032,-0.015,0.014,0.0038,-0.0037,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-5.3e-06,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.5e-05,9.4e-05,8.1e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.5e-10,4.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.71,0.00046,-0.012,0.71,-0.0038,-0.018,0.016,0.0035,-0.0053,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-5.3e-06,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.5e-05,9.5e-05,8e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-10,1.5e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.71,0.00051,-0.012,0.71,-0.0046,-0.017,0.016,0.0029,-0.0033,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.6e-06,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.4e-05,9.3e-05,8e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.71,0.00052,-0.012,0.71,-0.0051,-0.018,0.015,0.0024,-0.005,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.6e-06,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.4e-05,9.4e-05,8e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.71,0.00054,-0.012,0.71,-0.0057,-0.015,0.015,0.002,-0.003,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,1.8e-06,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.2e-05,9.2e-05,8e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.71,0.00055,-0.012,0.71,-0.0055,-0.016,0.017,0.0015,-0.0046,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,1.8e-06,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.3e-05,9.3e-05,8e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.71,0.00057,-0.012,0.71,-0.0062,-0.011,0.015,0.00018,-0.00063,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,7.1e-06,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.1e-05,9.1e-05,8e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-10,1.2e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.71,0.00057,-0.012,0.71,-0.0061,-0.012,0.016,-0.00044,-0.0018,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,7e-06,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.2e-05,9.2e-05,7.9e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.2e-10,1.3e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.71,0.00062,-0.012,0.71,-0.0066,-0.0089,0.016,-0.0014,0.0016,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,1.1e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.1e-05,9e-05,7.9e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.71,0.00063,-0.012,0.71,-0.007,-0.008,0.015,-0.002,0.00076,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,1.1e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.1e-05,9.1e-05,7.9e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.71,0.0006,-0.012,0.71,-0.0068,-0.0072,0.015,-0.0017,0.0007,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,1.2e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9e-05,8.9e-05,7.9e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.71,0.00064,-0.012,0.71,-0.0081,-0.0079,0.015,-0.0024,-6.5e-05,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.2e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9e-05,9e-05,7.9e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.71,0.00062,-0.012,0.71,-0.0087,-0.0074,0.017,-0.0021,-7.3e-05,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.3e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,8.9e-05,8.9e-05,7.8e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.71,0.00062,-0.012,0.71,-0.0094,-0.0073,0.018,-0.003,-0.00083,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.3e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,8.9e-05,8.9e-05,7.8e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.71,0.0006,-0.012,0.71,-0.0091,-0.0068,0.017,-0.0033,0.00024,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.4e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.8e-05,8.8e-05,7.8e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.71,0.00064,-0.012,0.71,-0.01,-0.0066,0.018,-0.0043,-0.00043,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.4e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.9e-05,8.8e-05,7.8e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0054,0.019,-0.0054,-0.00034,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.5e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.7e-05,8.7e-05,7.8e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.005,0.021,-0.0065,-0.00086,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.8e-05,8.8e-05,7.8e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.71,0.00062,-0.012,0.71,-0.012,-0.0055,0.022,-0.0073,-0.00077,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.5e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.7e-05,8.7e-05,7.8e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.71,0.00058,-0.012,0.71,-0.013,-0.0055,0.022,-0.0086,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.5e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.7e-05,8.7e-05,7.7e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.71,0.00065,-0.012,0.71,-0.014,-0.0064,0.024,-0.012,-0.0012,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.6e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.6e-05,8.6e-05,7.7e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,2.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.71,0.00059,-0.012,0.71,-0.015,-0.0077,0.024,-0.013,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.6e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.7e-05,8.6e-05,7.7e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,2.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.71,0.00068,-0.012,0.71,-0.016,-0.0079,0.022,-0.016,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,1.7e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.6e-05,8.5e-05,7.7e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,2.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0088,-0.012,-0.018,-0.0025,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.6e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.6e-05,8.6e-05,7.7e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.71,0.0083,-0.0018,0.71,-0.033,-0.0075,-0.044,-0.017,-0.0012,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,1.8e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.5e-05,8.5e-05,7.7e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0023,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,1.9e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.5e-05,8.5e-05,7.6e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.71,0.005,0.00065,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,2.1e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.5e-05,8.4e-05,7.6e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.0049,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,2.1e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.5e-05,8.5e-05,7.6e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.039,-0.25,-0.034,-0.0081,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,2.2e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.4e-05,8.4e-05,7.6e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,2.2e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.4e-05,8.4e-05,7.6e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.7e-11,6.7e-11,2.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.4e-06,2.4e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.3e-05,8.3e-05,7.6e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.3e-06,2.4e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.4e-05,8.3e-05,7.6e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.4e-11,6.4e-11,2.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,2.1e-05,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.3e-05,8.3e-05,7.5e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,2.1e-05,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.3e-05,8.3e-05,7.5e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2e-05,4.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.2e-05,8.2e-05,7.5e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,1.9e-05,4.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.2e-05,8.2e-05,7.5e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.094,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,2.3e-05,3.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.1e-05,8.1e-05,7.5e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,2.3e-05,3.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.2e-05,8.2e-05,7.5e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3.2e-05,2.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.1e-05,8.1e-05,7.5e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.4e-11,5.4e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,5.7e-06,3.2e-05,2.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.1e-05,8.1e-05,7.4e-05,0.018,0.017,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,5.8e-06,2.8e-05,1.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8e-05,8e-05,7.4e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-11,5.2e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,5.7e-06,2.8e-05,1.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8e-05,8e-05,7.4e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,3e-05,-1.2e-07,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,7.9e-05,7.9e-05,7.4e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,3e-05,2.1e-08,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8e-05,7.9e-05,7.4e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,2.6e-05,-9.2e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,7.9e-05,7.8e-05,7.4e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,5.8e-06,2.6e-05,-8.9e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,7.9e-05,7.9e-05,7.4e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,5.9e-06,3.4e-05,-3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,7.8e-05,7.8e-05,7.4e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.3e-05,-3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,7.8e-05,7.8e-05,7.3e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,2.9e-05,-5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,7.7e-05,7.7e-05,7.3e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,5.8e-06,2.9e-05,-5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,7.7e-05,7.7e-05,7.3e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,5.8e-06,4e-05,-8.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,7.7e-05,7.6e-05,7.3e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,5.7e-06,4e-05,-8.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,7.7e-05,7.7e-05,7.3e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,5.7e-06,2.7e-05,-0.0001,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,7.6e-05,7.6e-05,7.3e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,5.7e-06,2.7e-05,-0.0001,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,7.6e-05,7.6e-05,7.3e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.4e-06,3.5e-05,-0.00014,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,7.5e-05,7.5e-05,7.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.5e-06,3.5e-05,-0.00014,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.5e-05,7.5e-05,7.3e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.3e-06,1.3e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.5e-05,7.5e-05,7.2e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.3e-06,1.2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.5e-05,7.5e-05,7.2e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.3e-06,2e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.4e-05,7.4e-05,7.2e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.2e-06,2e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.4e-05,7.4e-05,7.2e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.3e-06,3.1e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.4e-05,7.4e-05,7.2e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.3e-06,3e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.4e-05,7.4e-05,7.2e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.71,0.036,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.3e-06,-5.9e-05,5.5e-06,5.1e-05,-0.00022,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.4e-05,7.4e-05,7.1e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.3e-06,-5.9e-05,5.4e-06,5e-05,-0.00022,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.4e-05,7.4e-05,7.1e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.4e-06,4.9e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.4e-05,7.4e-05,7.1e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.3e-06,4.9e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.5e-05,7.4e-05,7.1e-05,0.019,0.018,0.0082,0.065,0.065,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.2e-06,5e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.4e-05,7.4e-05,7e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.2e-06,4.9e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.5e-05,7.4e-05,7e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.3e-06,4.4e-05,-0.00017,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.4e-05,7.4e-05,7e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,5e-06,4.3e-05,-0.00017,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.4e-05,7.4e-05,7e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5e-06,4e-05,-0.00015,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.4e-05,7.4e-05,7e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,4.9e-06,3.9e-05,-0.00015,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.4e-05,7.4e-05,7e-05,0.021,0.02,0.0085,0.092,0.092,0.036,3.8e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.6e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.5e-05,7.4e-05,6.9e-05,0.022,0.021,0.0086,0.1,0.099,0.036,3.8e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.4e-05,-0.00013,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.5e-05,7.5e-05,6.9e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.71,0.00079,0.00099,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3e-05,-0.00013,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.5e-05,7.5e-05,6.9e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.71,8.6e-05,6.9e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,2.6e-05,-0.00011,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.5e-05,7.5e-05,6.9e-05,0.025,0.025,0.0089,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.71,-0.00018,-0.00017,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.5e-06,-3.7e-06,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.6e-05,7.5e-05,6.9e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.71,-0.0002,4.7e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.5e-06,-7.9e-06,-0.00017,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.6e-05,7.5e-05,6.8e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.71,1.4e-05,0.00051,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.4e-06,-2.8e-05,-0.00025,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.6e-05,7.5e-05,6.8e-05,0.024,0.024,0.0089,0.14,0.14,0.036,3.7e-11,3.6e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.71,0.00017,0.00091,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.3e-06,-3.2e-05,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.6e-05,7.5e-05,6.8e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.71,0.0004,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.3e-06,-5.1e-05,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.6e-05,7.5e-05,6.8e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.71,0.00075,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.2e-06,-5.6e-05,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.6e-05,7.5e-05,6.8e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-7.1e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.8e-05,0.024,0.025,0.009,0.16,0.15,0.036,3.6e-11,3.5e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-7.5e-05,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.8e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-9.7e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.8e-05,0.024,0.025,0.009,0.17,0.16,0.036,3.5e-11,3.5e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,3.8e-06,-0.0001,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.7e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,3.8e-06,-0.00012,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.7e-05,0.025,0.025,0.009,0.18,0.17,0.037,3.5e-11,3.4e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00013,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.7e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.71,0.0031,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00014,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.7e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30090000,0.71,0.0031,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00015,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.7e-05,0.026,0.027,0.0091,0.2,0.2,0.036,3.4e-11,3.4e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00016,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.5e-05,6.7e-05,0.025,0.025,0.009,0.2,0.19,0.037,3.4e-11,3.3e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-1.2e-05,-5.7e-05,3.3e-06,-0.00017,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.5e-05,6.6e-05,0.026,0.027,0.0091,0.21,0.21,0.037,3.4e-11,3.3e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30390000,0.71,0.0031,0.0071,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00018,-0.00023,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.6e-05,0.025,0.025,0.009,0.21,0.2,0.036,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00018,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.6e-05,0.026,0.027,0.0091,0.22,0.22,0.037,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.71,0.0029,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.00019,-0.00021,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.6e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.2e-10,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00019,-0.0002,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.6e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.1e-10,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.71,0.0027,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.0002,-0.0002,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.6e-05,0.025,0.025,0.0089,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.71,0.0025,0.0054,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.0002,-0.00019,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.6e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.71,0.0025,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00021,-0.00018,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.5e-05,0.025,0.025,0.0089,0.23,0.23,0.036,3.2e-11,3.1e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.71,0.0023,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,2.9e-06,-0.00022,-0.00017,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.5e-05,6.5e-05,0.026,0.027,0.0089,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00023,-0.00014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.4e-05,6.5e-05,0.025,0.025,0.0088,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31290000,0.71,0.002,0.0037,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00024,-0.00013,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.4e-05,6.5e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31390000,0.71,0.0019,0.0033,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00024,-0.00011,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.4e-05,6.5e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-11,3.1e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.71,0.0017,0.0026,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00025,-9.9e-05,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.4e-05,6.5e-05,0.026,0.027,0.0088,0.26,0.26,0.037,3.1e-11,3.1e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00026,-8.3e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.4e-05,6.4e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.71,0.0014,0.0016,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00026,-7.1e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.4e-05,6.4e-05,0.026,0.027,0.0087,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.71,0.0012,0.001,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.00027,-5.3e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.4e-05,6.4e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.71,0.00091,0.00032,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.00028,-4.1e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.4e-05,6.4e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.71,0.00078,-0.00014,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.00028,-2.2e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.3e-05,6.4e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.71,0.00049,-0.00086,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00029,-7.8e-06,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.3e-05,6.4e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.71,0.00028,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.3e-06,-0.0003,1.2e-05,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.3e-05,6.3e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.9e-11,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.71,4.6e-05,-0.0024,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.3e-06,-0.00031,2.8e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.3e-05,6.3e-05,0.026,0.026,0.0086,0.3,0.3,0.036,3e-11,2.9e-11,9.8e-11,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.71,-0.00014,-0.003,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.3e-06,-0.00031,3.6e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.8e-05,7.3e-05,6.3e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.7e-11,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.71,-0.00026,-0.0033,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.3e-06,-0.00031,4.7e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,7.8e-05,7.3e-05,6.3e-05,0.026,0.026,0.0085,0.31,0.31,0.037,2.9e-11,2.9e-11,9.6e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.71,-0.00025,-0.0035,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00032,5.5e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,7.8e-05,7.2e-05,6.3e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.5e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.71,-0.0003,-0.0036,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00032,6e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,7.8e-05,7.3e-05,6.3e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.4e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.71,-0.00026,-0.0035,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00032,6.9e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,7.8e-05,7.2e-05,6.3e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.71,-0.00017,-0.0035,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2e-06,-0.00033,7.9e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,7.8e-05,7.2e-05,6.3e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9.3e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.71,-3.9e-05,-0.0034,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00033,9.2e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,7.8e-05,7.2e-05,6.2e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9.2e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.71,-7.3e-05,-0.0034,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00034,9.8e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,7.8e-05,7.2e-05,6.2e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,9.1e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.7,0.0033,-0.0025,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00034,0.0001,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,7.8e-05,7.2e-05,6.2e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.65,0.016,-0.0016,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,7.8e-05,7.2e-05,6.5e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.55,0.013,-0.0018,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,7.7e-05,7.3e-05,6.9e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.41,0.0069,0.00063,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.1e-05,7.6e-05,7.5e-05,7.4e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.25,0.00097,-0.0019,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.7e-05,7.4e-05,7.6e-05,7.8e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.087,-0.0023,-0.005,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7.3e-05,7.8e-05,8.1e-05,0.028,0.028,0.0076,0.37,0.36,0.036,2.8e-11,2.8e-11,8.7e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33790000,-0.082,-0.0038,-0.0068,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7e-05,7.7e-05,8.1e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.6e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33890000,-0.25,-0.005,-0.0075,0.97,-1,-0.66,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.7e-05,6.9e-05,7.8e-05,7.9e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.5e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
33990000,-0.39,-0.0032,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.4e-06,-0.00035,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5e-05,6.7e-05,7.5e-05,7.6e-05,0.031,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.4e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.5e-06,-0.00035,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.3e-05,6.7e-05,7.5e-05,7.2e-05,0.036,0.036,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.4e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34190000,-0.57,-0.0015,-0.011,0.82,-0.91,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00037,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,6.3e-05,7.1e-05,6.9e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.3e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34290000,-0.61,-0.0024,-0.0086,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00037,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,6.3e-05,7.1e-05,6.7e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34390000,-0.64,-0.0026,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.5e-06,-0.00042,0.00018,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,5.9e-05,6.5e-05,6.6e-05,0.041,0.042,0.0064,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34490000,-0.65,-0.0035,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.6e-06,-0.00042,0.00018,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,5.9e-05,6.5e-05,6.5e-05,0.048,0.049,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8.1e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34590000,-0.66,-0.0029,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00051,0.00026,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,5.4e-05,5.9e-05,6.4e-05,0.046,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34690000,-0.67,-0.0033,-0.002,0.74,-0.75,-0.36,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.6e-06,-0.00051,0.00026,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,5.4e-05,5.9e-05,6.4e-05,0.053,0.055,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,8e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34790000,-0.67,-0.0022,-0.0017,0.74,-0.75,-0.35,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.6e-06,-0.00062,0.00036,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.9e-05,5.3e-05,6.4e-05,0.05,0.052,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.9e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34890000,-0.68,-0.0023,-0.0016,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00062,0.00036,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.9e-05,5.4e-05,6.3e-05,0.058,0.06,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.9e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34990000,-0.68,-0.0086,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.6e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.5e-05,4.9e-05,6.3e-05,0.057,0.057,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.8e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35090000,-0.68,-0.0086,-0.0045,0.73,0.44,0.31,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.5e-05,4.9e-05,6.3e-05,0.062,0.062,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,7.8e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35190000,-0.68,-0.0087,-0.0045,0.73,0.46,0.35,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.5e-05,4.9e-05,6.3e-05,0.067,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35290000,-0.68,-0.0087,-0.0046,0.73,0.48,0.38,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.5e-05,4.9e-05,6.3e-05,0.072,0.073,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.6e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35390000,-0.68,-0.0088,-0.0045,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.6e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.5e-05,4.9e-05,6.3e-05,0.078,0.079,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,7.6e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35490000,-0.68,-0.0088,-0.0045,0.73,0.53,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.6e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,4.5e-05,4.9e-05,6.3e-05,0.084,0.085,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.5e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35590000,-0.68,-0.0058,-0.0045,0.73,0.42,0.36,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.7e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,3.8e-05,4.1e-05,6.2e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.5e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35690000,-0.68,-0.0058,-0.0045,0.73,0.44,0.39,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.8e-06,-0.00076,0.0005,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,3.8e-05,4.1e-05,6.2e-05,0.072,0.074,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.4e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35790000,-0.68,-0.0036,-0.0044,0.73,0.36,0.33,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6e-05,3.3e-05,3.5e-05,6.2e-05,0.06,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.4e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35890000,-0.68,-0.0036,-0.0044,0.73,0.38,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,3.3e-05,3.5e-05,6.2e-05,0.066,0.067,0.0058,0.5,0.5,0.033,2.7e-11,2.7e-11,7.3e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35990000,-0.68,-0.0018,-0.0043,0.73,0.31,0.3,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.2e-06,-0.00085,0.00058,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.9e-05,3.1e-05,6.2e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.7e-11,7.3e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36090000,-0.68,-0.0019,-0.0043,0.73,0.32,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.4e-06,-0.00085,0.00058,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.9e-05,3.1e-05,6.2e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.2e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36190000,-0.68,-0.00042,-0.0042,0.73,0.27,0.27,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.4e-06,-0.00095,0.00067,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.6e-05,2.7e-05,6.2e-05,0.054,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36290000,-0.68,-0.00054,-0.0041,0.73,0.28,0.29,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.6e-06,-0.00095,0.00067,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.6e-05,2.7e-05,6.2e-05,0.06,0.061,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7.1e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36390000,-0.68,0.00051,-0.004,0.73,0.23,0.25,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.8e-06,-0.0011,0.00076,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.4e-05,2.5e-05,6.2e-05,0.053,0.054,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,7e-11,2.3e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36490000,-0.68,0.00041,-0.004,0.73,0.24,0.27,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4e-06,-0.0011,0.00076,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.4e-05,2.5e-05,6.1e-05,0.058,0.06,0.0055,0.53,0.52,0.032,2.8e-11,2.8e-11,7e-11,2.3e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36590000,-0.68,0.0012,-0.0039,0.73,0.2,0.23,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.2e-06,-0.0012,0.00086,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.2e-05,2.3e-05,6.1e-05,0.052,0.053,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,6.9e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36690000,-0.68,0.0012,-0.0038,0.73,0.21,0.24,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.3e-06,-0.0012,0.00086,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2.2e-05,2.3e-05,6.1e-05,0.058,0.059,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.9e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36790000,-0.68,0.0018,-0.0037,0.74,0.17,0.21,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.4e-06,-0.0013,0.00096,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2e-05,2.1e-05,6.1e-05,0.051,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.9e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
36890000,-0.68,0.0017,-0.0037,0.74,0.18,0.22,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0013,0.00096,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,2e-05,2.1e-05,6.1e-05,0.057,0.058,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
36990000,-0.68,0.0022,-0.0036,0.74,0.15,0.19,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.7e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,1.9e-05,2e-05,6.1e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.8e-11,2.1e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37090000,-0.68,0.0021,-0.0035,0.74,0.15,0.2,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.9e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,1.9e-05,2e-05,6.1e-05,0.056,0.057,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.1e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37190000,-0.68,0.0024,-0.0034,0.74,0.13,0.17,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.1e-06,-0.0016,0.0011,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,1.8e-05,1.9e-05,6.1e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
37290000,-0.68,0.0024,-0.0034,0.74,0.13,0.18,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.3e-06,-0.0016,0.0011,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,1.8e-05,1.9e-05,6.1e-05,0.055,0.056,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,6.6e-11,2e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
37390000,-0.68,0.0026,-0.0033,0.74,0.1,0.15,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.4e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.8e-05,1.9e-05,6.1e-05,0.049,0.05,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.6e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37490000,-0.68,0.0026,-0.0032,0.74,0.1,0.16,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.5e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.8e-05,1.9e-05,6.1e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.6e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37590000,-0.68,0.0027,-0.0031,0.74,0.084,0.13,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.7e-06,-0.0018,0.0012,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6.1e-05,0.048,0.049,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
37690000,-0.68,0.0027,-0.0032,0.74,0.082,0.14,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.8e-06,-0.0018,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.8e-05,1.8e-05,6.1e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.5e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
37790000,-0.68,0.0028,-0.0031,0.74,0.066,0.12,-0.1,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6.1e-05,0.047,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,6.4e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
37890000,-0.68,0.0028,-0.0031,0.74,0.064,0.12,-0.093,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.2e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6.1e-05,0.051,0.052,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,6.4e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
37990000,-0.68,0.0029,-0.0031,0.74,0.049,0.11,-0.084,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.3e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6.1e-05,0.046,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,6.4e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
38090000,-0.68,0.0028,-0.0031,0.74,0.046,0.11,-0.074,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.5e-06,-0.0019,0.0013,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6.1e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.3e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
38190000,-0.68,0.0029,-0.003,0.74,0.032,0.092,-0.066,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.6e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6.1e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.3e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38290000,-0.68,0.0028,-0.003,0.74,0.03,0.093,-0.058,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.8e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6.1e-05,0.049,0.049,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38390000,-0.68,0.0029,-0.0029,0.74,0.021,0.081,-0.051,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7e-06,-0.0021,0.0014,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6e-05,0.044,0.044,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38490000,-0.68,0.0028,-0.0029,0.74,0.018,0.082,-0.044,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.1e-06,-0.0021,0.0014,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6e-05,0.047,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,6.2e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38590000,-0.68,0.0028,-0.0028,0.74,0.013,0.071,-0.037,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.3e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6e-05,0.043,0.043,0.0071,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38690000,-0.68,0.0028,-0.0028,0.74,0.0088,0.07,-0.03,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.8e-05,1.7e-05,1.8e-05,6e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38790000,-0.68,0.0028,-0.0028,0.74,0.0031,0.058,-0.022,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.5e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,1.7e-05,1.8e-05,6e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.4e-06,1.3e-06,5e-08,0,0,0,0,0,0,0,0
38890000,-0.68,0.0026,-0.0028,0.74,-0.0067,0.048,0.48,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.7e-06,-0.0021,0.0014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,1.7e-05,1.8e-05,6e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,6e-11,1.4e-06,1.3e-06,5e-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 10000 1 -0.011 -0.0094 -0.011 -0.01 -0.00011 -9.8e-05 0 0.00023 0 7.3e-05 0 -0.011 0 7.1e-06 0 2.2e-06 0 -0.00045 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4.9e-07 0 0.0025 0 0.0025 0 0.0018 0 25 0 25 0 10 0 1e+02 0 1e+02 0 1e+02 0 1e-06 0 1e-06 0 1e-06 0 4e-06 0 4e-06 0 4e-06 0 0 0 0 0 0 0 0
3 90000 1 -0.011 -0.0096 -0.01 -0.022 -0.02 -0.00064 -0.0004 0.00067 0.0026 -0.0094 -0.026 -3e-05 -1.4e-05 1.5e-05 0.00011 -0.0003 -0.0023 0 0 0 0 0 0 0.19 9.3e-10 0 0.4 0 0 0 0 0 1.5e-06 5.2e-07 0.0025 0.0026 0.0025 0.0026 0.0021 0.0011 25 25 10 1e+02 1e+02 1e+02 1e-06 1e-06 1e-06 9.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
4 190000 1 -0.011 -0.0096 -0.01 -0.011 -0.022 -0.02 -0.00081 0.0002 -0.00015 0.0039 -0.024 -0.041 -7.2e-05 6e-06 3.1e-05 0.00043 -0.0015 -0.0044 4.3e-15 -3e-13 -9.3e-15 -2.3e-14 -2.4e-16 5.8e-15 0 0 -2.3e-12 -2e-11 0.19 9.3e-10 0 0.4 0 0 0 0 0 1.1e-06 5.8e-07 0.0026 0.0027 0.0026 0.0027 0.0012 0.0008 25 25 10 1e+02 1e+02 1.3 1 1e-06 1e-06 9.9e-07 9.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
5 290000 1 -0.011 -0.0097 -0.011 -0.022 -0.02 -0.00054 0.0012 0.00017 0.0063 -0.037 -0.053 -3.4e-05 5e-05 -1.7e-05 0.00036 -0.0032 -0.007 1e-12 9.1e-12 1e-12 9.1e-13 -2.5e-14 -1.7e-13 0 0 -2.2e-09 -4.8e-09 0.19 9.3e-10 0 0.4 0 0 0 0 0 1e-06 6.8e-07 0.0027 0.0029 0.0027 0.0029 0.00084 0.00067 25 25 9.6 0.31 0.37 0.31 0.37 0.44 0.41 1e-06 1e-06 9.8e-07 9.4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
6 390000 1 -0.011 -0.0089 -0.011 -0.012 -0.022 0.046 0.00022 0.0026 -9.4e-05 0.0083 -0.046 -0.059 -5e-05 0.00024 8.8e-06 0.0011 -0.0052 -0.0094 1e-12 -1.1e-10 1.7e-12 2.8e-11 9.9e-14 2.8e-12 0 0 -2.7e-08 -4.5e-08 0.19 0.17 9.3e-10 0.0017 0.4 0.41 0 0 0 0 0 9.8e-07 7e-07 0.0028 0.0031 0.0028 0.0031 0.00069 0.00062 25 25 8.3 8.1 0.81 0.97 0.81 0.97 0.32 1e-06 1e-06 9.5e-07 8.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
7 490000 1 0.87 -0.011 -0.0023 -0.011 -0.015 -0.022 0.5 0.002 0.0023 -0.001 0.0057 -0.051 -0.06 6.6e-05 0.0002 -4.3e-05 0.00051 -0.0068 -0.011 -1.6e-10 1.6e-08 8.1e-12 -3.8e-09 7.2e-12 -3.3e-10 0 0 -1.1e-07 -1.6e-07 0.19 0.14 9.3e-10 0.0014 0.4 0.42 0 0 0 0 0 1e-06 2.6e-06 0.003 0.0033 0.003 0.0033 0.00062 0.00061 7.8 7.8 6.2 5.9 0.29 0.34 0.29 0.34 0.31 1e-06 1e-06 9e-07 8.3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
8 590000 1 0.76 -0.011 0.00067 -0.012 -0.015 -0.022 0.65 0.0034 0.00071 -0.00072 0.0084 -0.053 -0.059 0.00035 0.00037 -0.00013 0.0012 -0.0083 -0.012 -1.2e-10 1.6e-08 1e-10 -3.5e-09 6.8e-12 -3.2e-10 0 0 -2.5e-07 -3.4e-07 0.19 0.18 9.3e-10 0.0018 0.4 0.43 0 0 0 0 0 1.1e-06 1.5e-05 0.0033 0.0036 0.0033 0.0036 0.0006 0.00061 7.9 7.9 4.4 4.2 0.59 0.67 0.59 0.67 0.32 1e-06 1e-06 8.4e-07 7.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
9 690000 1 0.72 -0.011 0.0016 -0.012 -0.016 -0.022 0.69 0.0041 -0.00082 -0.0015 0.0075 -0.055 -0.06 0.00024 7.2e-05 -9.4e-05 0.00069 -0.0089 -0.013 -4.3e-09 5.4e-08 -1.2e-08 -2.4e-08 2.7e-10 -7e-10 0 0 -4.8e-07 -6.3e-07 0.19 0.2 9.3e-10 0.0019 0.4 0.43 0 0 0 0 0 1.2e-06 4.1e-05 0.0036 0.0039 0.0036 0.0039 0.00059 0.00061 2.6 2.6 2.9 2.8 0.23 0.26 0.23 0.26 0.3 0.29 1e-06 1e-06 7.7e-07 7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
10 790000 1 0.71 -0.011 0.002 -0.012 -0.016 -0.022 0.7 0.0056 -0.0028 -0.0016 0.0098 -0.059 -0.063 0.00071 -9.3e-05 -0.00027 0.0015 -0.01 -0.014 -4.1e-09 5.3e-08 -1.2e-08 -2.3e-08 2.7e-10 -6.7e-10 0 0 -7.6e-07 -9.5e-07 0.19 0.2 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.3e-06 7.7e-05 0.004 0.0042 0.004 0.0042 0.00059 0.0006 2.7 2.7 2 0.38 0.42 0.38 0.42 0.29 0.28 1e-06 1e-06 6.9e-07 6.2e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
11 890000 1 0.71 -0.011 0.0021 -0.012 -0.016 -0.022 0.7 0.0076 -0.0034 -0.0023 0.011 -0.074 -0.077 0.00055 -0.00019 -0.0002 0.0011 -0.017 -0.021 -2.7e-08 1.7e-07 -8.3e-08 -9e-08 1.5e-09 -1.1e-09 0 0 -7.6e-07 -9.5e-07 0.19 0.2 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.4e-06 0.00012 0.0043 0.0046 0.0043 0.0046 0.00059 0.00057 1.3 1.3 2.1 2 0.19 0.2 0.19 0.2 0.44 0.43 1e-06 1e-06 6.1e-07 5.4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
12 990000 1 0.7 -0.011 0.0025 -0.013 -0.016 -0.022 0.71 0.011 -0.0038 -0.0042 0.015 -0.089 -0.092 0.0015 -0.00057 -0.0005 0.0024 -0.025 -0.029 -2.7e-08 1.7e-07 -8.3e-08 -9e-08 1.5e-09 -1.1e-09 0 0 -7.6e-07 -9.5e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 1.6e-06 0.00015 0.0048 0.005 0.0048 0.005 0.00058 0.00054 1.4 1.4 2.1 2 0.28 0.3 0.28 0.3 0.63 0.61 1e-06 1e-06 5.3e-07 4.6e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
13 1090000 1 0.7 -0.011 0.0025 -0.013 -0.017 -0.022 0.71 0.012 -0.0034 -0.0049 0.016 -0.1 -0.11 0.0012 -0.00043 -0.00043 0.0019 -0.035 -0.039 -1.3e-07 5.5e-07 -4.1e-07 -3.7e-07 6.4e-09 -1.6e-09 0 0 -7.7e-07 -9.5e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 1.7e-06 0.00018 0.0051 0.0053 0.0051 0.0053 0.00058 0.00051 0.86 0.89 0.86 0.89 2.1 2 0.16 0.17 0.16 0.17 0.86 0.84 9.9e-07 9.9e-07 4.6e-07 3.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
14 1190000 1 0.7 -0.011 0.0027 -0.013 -0.017 -0.022 0.71 0.016 -0.0037 -0.0069 0.02 -0.12 0.0025 -0.00079 -0.001 0.0037 -0.046 -0.051 -1.3e-07 5.5e-07 -4.1e-07 -3.7e-07 6.4e-09 -1.6e-09 0 0 -7.7e-07 -9.5e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 1.9e-06 0.00021 0.0057 0.0058 0.0057 0.0058 0.00057 0.00047 1 1.1 1 1.1 2.1 2 0.22 0.24 0.22 0.24 1.1 9.9e-07 9.9e-07 4e-07 3.3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
15 1290000 1 0.7 -0.011 0.0028 -0.013 -0.017 -0.022 0.71 0.016 -0.0034 -0.0067 0.02 -0.13 -0.14 0.0019 -0.00055 -0.0008 0.0028 -0.058 -0.064 -4.7e-07 1.4e-06 -1.4e-06 -1.3e-06 2.1e-08 -2.4e-09 0 0 -7.8e-07 -9.6e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2e-06 0.00023 0.0058 0.006 0.0058 0.006 0.00056 0.00044 0.79 0.84 0.79 0.84 2.1 2 0.14 0.15 0.14 0.15 1.4 9.6e-07 9.6e-07 3.4e-07 2.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
16 1390000 1 0.7 -0.011 0.0029 -0.014 -0.017 -0.022 0.71 0.021 -0.0032 -0.009 0.026 -0.14 -0.15 0.0039 -0.0009 -0.0016 0.0052 -0.072 -0.078 -4.7e-07 1.4e-06 -1.4e-06 -1.3e-06 2.1e-08 -2.4e-09 0 0 -7.8e-07 -9.6e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.3e-06 0.00024 0.0064 0.0066 0.0064 0.0066 0.00055 0.00041 1 1.1 1 1.1 2.1 2 0.19 0.21 0.19 0.21 1.8 1.7 9.6e-07 9.6e-07 3e-07 2.3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
17 1490000 1 0.7 -0.012 0.0027 -0.014 -0.017 -0.022 0.71 0.027 -0.0024 -0.011 0.025 -0.16 0.0063 -0.0006 -0.0025 0.0039 -0.087 -0.093 -4.7e-07 2.9e-06 -1.4e-06 -3.4e-06 2.1e-08 -5.5e-09 0 0 -7.8e-07 -9.8e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.5e-06 0.00025 0.0071 0.0063 0.0071 0.0063 0.00053 0.00038 1.3 0.9 1.3 0.9 2.1 2 0.28 0.14 0.28 0.14 2.2 2.1 9.6e-07 9e-07 9.6e-07 9e-07 2.6e-07 2e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
18 1590000 1 0.7 -0.012 0.0029 -0.014 -0.018 -0.022 0.71 0.027 -0.0029 -0.0093 0.031 -0.17 -0.18 0.0052 -0.00087 -0.002 0.0066 -0.1 -0.11 -1.2e-06 2.9e-06 -3.5e-06 -3.4e-06 5.1e-08 -5.5e-09 0 0 -8.1e-07 -9.8e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.5e-06 0.00026 0.0068 0.0069 0.0068 0.0069 0.00051 0.00035 1.1 1.2 1.1 1.2 2.1 2 0.19 0.2 0.19 0.2 2.6 9.1e-07 9e-07 9.1e-07 9e-07 2.2e-07 1.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
19 1690000 1 0.7 -0.012 0.0025 -0.014 -0.018 -0.022 0.71 0.034 0.00055 -0.013 0.028 -0.18 -0.19 0.0082 -0.00048 -0.0031 0.0047 -0.12 -0.13 -1.2e-06 5e-06 -3.5e-06 -7e-06 5.1e-08 -1.2e-08 0 0 -8.1e-07 -1e-06 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.8e-06 0.00027 0.0075 0.006 0.0075 0.006 0.0005 0.00033 1.5 0.97 1.5 0.97 2.1 2 0.27 0.13 0.27 0.13 3.1 3 9.1e-07 8.1e-07 9.1e-07 8.1e-07 1.9e-07 1.4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
20 1790000 1 0.7 -0.011 0.0027 -0.014 -0.018 -0.022 0.71 0.032 0.0025 -0.013 0.036 -0.2 0.0064 -0.00035 -0.0025 0.0078 -0.14 -0.15 -2.5e-06 5e-06 -7.2e-06 -7e-06 9.8e-08 -1.2e-08 0 0 -8.6e-07 -1e-06 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.5e-06 0.00027 0.0066 0.0066 0.00048 0.00031 1.2 1.3 1.2 1.3 2.1 2 0.18 0.2 0.18 0.2 3.7 3.5 8.1e-07 8.1e-07 1.7e-07 1.2e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
21 1890000 1 0.7 -0.011 0.003 -0.014 -0.018 -0.022 0.72 0.039 0.0039 -0.015 0.044 -0.21 -0.22 0.0099 -2.9e-05 -0.0039 0.012 -0.16 -0.17 -2.5e-06 5e-06 -7.2e-06 -7e-06 9.8e-08 -1.2e-08 0 0 -8.6e-07 -1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 2.8e-06 0.00027 0.0073 0.0073 0.00046 0.00029 1.6 1.6 2.1 2 0.28 0.3 0.28 0.3 4.2 4.1 8.1e-07 8.1e-07 1.5e-07 1.1e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
22 1990000 1 0.7 -0.011 0.0025 -0.014 -0.018 -0.022 0.72 0.033 0.0056 -0.013 0.037 -0.23 0.0072 0.00047 -0.0028 0.0085 -0.18 -0.19 -4.2e-06 6.8e-06 -1.2e-05 1.6e-07 -1.6e-08 0 0 -9.1e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 2.3e-06 0.00027 0.0059 0.0059 0.00045 0.00027 1.2 1.3 1.2 1.3 2.1 2 0.18 0.2 0.18 0.2 4.8 4.7 7e-07 6.9e-07 7e-07 1.3e-07 9.3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
23 2090000 1 0.7 -0.011 0.0026 -0.014 -0.018 -0.022 0.72 0.039 0.0083 -0.016 0.043 -0.24 0.011 0.0012 -0.0042 0.012 -0.21 -0.22 -4.2e-06 6.8e-06 -1.2e-05 1.6e-07 -1.6e-08 0 0 -9.1e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 2.5e-06 0.00027 0.0064 0.0064 0.00043 0.00026 1.5 1.6 1.5 1.6 2.2 2.1 0.28 0.3 0.28 0.3 5.5 5.3 7e-07 6.9e-07 7e-07 1.1e-07 8.2e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
24 2190000 1 0.7 -0.011 0.0021 -0.013 -0.018 -0.022 0.72 0.031 0.0084 -0.011 0.034 -0.26 0.0072 0.0012 -0.0028 0.0083 -0.23 -0.24 -6.1e-06 8e-06 -1.8e-05 2.2e-07 -1.5e-08 0 0 -9.6e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 2e-06 0.00027 0.0049 0.0049 0.00042 0.00024 1.1 1.2 1.1 1.2 2.2 2.1 0.18 0.19 0.18 0.19 6.2 6 5.9e-07 5.8e-07 5.9e-07 5.8e-07 9.9e-08 7.2e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
25 2290000 1 0.7 -0.011 0.0021 -0.014 -0.018 -0.022 0.72 0.038 0.011 -0.014 0.041 -0.27 0.011 0.0022 -0.004 0.012 -0.26 -0.27 -6.1e-06 8e-06 -1.8e-05 2.2e-07 -1.5e-08 0 0 -9.6e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 2.2e-06 0.00026 0.0054 0.0054 0.0004 0.00023 1.4 1.5 1.4 1.5 2.2 2.1 0.27 0.29 0.27 0.29 6.9 6.7 5.9e-07 5.8e-07 5.9e-07 5.8e-07 8.8e-08 6.4e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
26 2390000 1 0.7 -0.011 0.0016 -0.013 -0.017 -0.022 0.72 0.029 0.011 -0.01 0.031 -0.28 -0.29 0.0068 0.0019 -0.0026 0.0078 -0.29 -0.3 -7.8e-06 8.3e-06 -2.3e-05 -2.4e-05 2.7e-07 -4.9e-09 0 0 -9.9e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.6e-06 0.00026 0.004 0.004 0.00039 0.00022 0.99 1 0.99 1 2.2 2.1 0.17 0.19 0.17 0.19 7.7 7.4 4.9e-07 4.9e-07 7.9e-08 5.6e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
27 2490000 1 0.7 -0.011 0.0017 -0.013 -0.018 -0.022 0.72 0.034 0.014 -0.012 0.036 -0.3 0.01 0.0031 -0.0037 0.011 -0.32 -7.8e-06 8.3e-06 -2.3e-05 -2.4e-05 2.7e-07 -4.9e-09 0 0 -9.9e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.8e-06 0.00026 0.0044 0.0044 0.00038 0.00021 1.2 1.3 1.2 1.3 2.2 2.1 0.25 0.27 0.25 0.27 8.6 8.2 4.9e-07 4.9e-07 7e-08 5e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
28 2590000 1 0.7 -0.011 0.0014 -0.013 -0.017 -0.022 0.72 0.026 0.012 -0.0082 0.027 -0.31 0.0063 0.0023 -0.0022 0.0071 -0.35 -0.36 -9.3e-06 8e-06 -2.8e-05 3e-07 1.3e-08 0 0 -1e-06 -1.2e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.4e-06 0.00026 0.0033 0.0033 0.00036 0.0002 0.86 0.89 0.86 0.89 2.2 2.1 0.16 0.18 0.16 0.18 9.5 9.1 4.1e-07 4.1e-07 6.3e-08 4.5e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
29 2690000 1 0.7 -0.011 0.0014 -0.013 -0.017 -0.022 0.72 0.03 0.015 -0.0091 0.031 -0.32 -0.33 0.0091 0.0037 -0.0031 0.01 -0.38 -0.39 -9.3e-06 8e-06 -2.8e-05 3e-07 1.3e-08 0 0 -1e-06 -1.2e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.5e-06 0.00025 0.0036 0.0036 0.00035 0.00019 1.1 1.1 2.3 2.2 0.24 0.25 0.24 0.25 10 4.1e-07 4.1e-07 5.7e-08 4.1e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
30 2790000 1 0.7 -0.011 0.0012 -0.013 -0.017 -0.022 0.72 0.023 0.014 -0.0067 0.024 -0.34 0.0058 0.0027 -0.0019 0.0064 -0.41 -0.42 -1e-05 7.2e-06 -3.2e-05 -3.3e-05 3.3e-07 3.6e-08 0 0 -1e-06 -1.2e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.2e-06 0.00025 0.0027 0.0028 0.0027 0.0028 0.00034 0.00018 0.74 0.77 0.74 0.77 2.3 2.2 0.15 0.16 0.15 0.16 11 3.4e-07 3.4e-07 5.1e-08 3.7e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
31 2890000 1 0.7 -0.011 0.0012 -0.013 -0.017 -0.022 0.72 0.027 0.016 -0.0077 0.027 -0.35 0.0082 0.0041 -0.0026 0.0089 -0.44 -0.46 -1e-05 7.2e-06 -3.2e-05 -3.3e-05 3.3e-07 3.6e-08 0 0 -1e-06 -1.2e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.3e-06 0.00025 0.003 0.003 0.00033 0.00018 0.93 0.96 0.93 0.96 2.3 2.2 0.22 0.23 0.22 0.23 12 3.4e-07 3.4e-07 4.6e-08 3.3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
32 2990000 1 0.7 -0.011 0.0011 -0.013 -0.017 -0.022 0.72 0.022 0.014 -0.0056 0.022 -0.36 0.0053 0.003 -0.0016 0.0058 -0.48 -0.49 -1.1e-05 6e-06 -3.5e-05 -3.6e-05 3.4e-07 6.5e-08 0 0 -1e-06 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 9.8e-07 0.00024 0.0023 0.0024 0.0023 0.0024 0.00032 0.00017 0.65 0.68 0.65 0.68 2.3 2.2 0.14 0.15 0.14 0.15 13 2.9e-07 2.9e-07 4.2e-08 3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
33 3090000 1 0.7 -0.011 0.0011 -0.013 -0.017 -0.022 0.72 0.024 0.017 -0.006 0.024 -0.37 -0.38 0.0076 0.0045 -0.0022 0.0081 -0.52 -0.53 -1.1e-05 6e-06 -3.5e-05 -3.6e-05 3.4e-07 6.5e-08 0 0 -1e-06 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 1.1e-06 0.00024 0.0026 0.0026 0.00031 0.00016 0.81 0.84 0.81 0.84 2.3 2.2 0.2 0.22 0.2 0.22 15 14 2.9e-07 2.9e-07 3.8e-08 2.8e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
34 3190000 1 0.7 -0.011 0.00089 -0.012 -0.017 -0.022 0.72 0.02 0.014 -0.0038 0.019 -0.39 0.0049 0.0032 -0.0014 0.0053 -0.56 -0.57 -1.2e-05 4.6e-06 -3.8e-05 -3.9e-05 3.6e-07 9.7e-08 0 0 -9.8e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 8.5e-07 0.00024 0.002 0.0021 0.002 0.0021 0.0003 0.00016 0.58 0.6 0.58 0.6 2.4 2.3 0.14 0.14 16 15 2.5e-07 2.5e-07 3.5e-08 2.5e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
35 3290000 1 0.7 -0.011 0.00089 -0.012 -0.017 -0.022 0.72 0.023 0.017 -0.0047 0.023 -0.4 0.007 0.0047 -0.0018 0.0073 -0.59 -0.61 -1.2e-05 4.6e-06 -3.8e-05 -3.9e-05 3.6e-07 9.7e-08 0 0 -9.8e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 9.2e-07 0.00023 0.0022 0.0023 0.0022 0.0023 0.00029 0.00015 0.72 0.74 0.72 0.74 2.4 2.3 0.19 0.2 0.19 0.2 17 16 2.5e-07 2.5e-07 3.2e-08 2.3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
36 3390000 1 0.7 -0.011 0.00084 -0.012 -0.017 -0.022 0.72 0.018 0.015 -0.0036 0.018 -0.41 -0.42 0.0046 0.0033 -0.0011 0.0049 -0.64 -0.65 -1.2e-05 3.2e-06 -4.1e-05 -4.2e-05 3.6e-07 1.3e-07 0 0 -9.6e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 7.4e-07 0.00023 0.0018 0.0018 0.00029 0.00015 0.52 0.54 0.52 0.54 2.4 2.3 0.13 0.14 0.13 0.14 18 17 2.1e-07 2.1e-07 2.9e-08 2.1e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
37 3490000 1 0.7 -0.011 0.00085 -0.012 -0.017 -0.022 0.72 0.022 0.019 -0.0052 0.021 -0.43 0.0066 0.005 -0.0015 0.0068 -0.68 -0.69 -1.2e-05 3.2e-06 -4.1e-05 -4.2e-05 3.6e-07 1.3e-07 0 0 -9.6e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 7.9e-07 0.00023 0.002 0.002 0.00028 0.00014 0.65 0.67 0.65 0.67 2.4 2.3 0.18 0.19 0.18 0.19 20 19 2.1e-07 2.1e-07 2.7e-08 2e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
38 3590000 1 0.7 -0.011 0.00079 -0.012 -0.017 -0.022 0.72 0.024 0.017 -0.0067 0.016 -0.44 0.0089 0.0036 -0.0021 0.0045 -0.72 -0.73 -1.2e-05 1.5e-06 -4.1e-05 -4.4e-05 3.6e-07 1.7e-07 0 0 -9.6e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 8.5e-07 0.00022 0.0022 0.0016 0.0022 0.0016 0.00027 0.00014 0.79 0.5 0.79 0.5 2.5 2.4 0.24 0.13 0.24 0.13 21 20 2.1e-07 1.8e-07 2.1e-07 1.8e-07 2.5e-08 1.8e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
39 3690000 1 0.7 -0.011 0.00079 -0.012 -0.017 -0.022 0.72 0.019 0.021 -0.0069 0.018 -0.45 -0.46 0.0062 0.0055 -0.0016 0.0063 -0.77 -0.78 -1.3e-05 1.5e-06 -4.3e-05 -4.4e-05 3.7e-07 1.7e-07 0 0 -9.3e-07 -1.1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 6.9e-07 0.00022 0.0017 0.0018 0.0017 0.0018 0.00026 0.00013 0.59 0.61 0.59 0.61 2.5 2.4 0.17 0.18 0.17 0.18 22 21 1.7e-07 1.8e-07 1.7e-07 1.8e-07 2.3e-08 1.7e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
40 3790000 1 0.7 -0.011 0.00073 -0.012 -0.017 -0.022 0.72 0.022 0.02 -0.0092 0.014 -0.47 0.0082 0.004 -0.0024 0.0042 -0.81 -0.83 -1.3e-05 -2.8e-07 -4.3e-05 -4.6e-05 3.7e-07 2.1e-07 0 0 -9.3e-07 -1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 7.4e-07 0.00022 0.0019 0.0014 0.0019 0.0014 0.00026 0.00013 0.72 0.46 0.72 0.46 2.5 2.4 0.23 0.12 0.23 0.12 24 23 1.7e-07 1.5e-07 1.7e-07 1.5e-07 2.1e-08 1.6e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
41 3890000 1 0.7 -0.01 0.00077 -0.012 -0.017 -0.022 0.72 0.017 0.022 -0.0072 0.016 -0.48 0.0057 0.0061 -0.0019 0.0057 -0.86 -0.87 -1.3e-05 -2.8e-07 -4.5e-05 -4.6e-05 3.8e-07 2.1e-07 0 0 -8.9e-07 -1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 6e-07 0.00021 0.0016 0.0016 0.00025 0.00013 0.54 0.56 0.54 0.56 2.5 2.4 0.16 0.17 0.16 0.17 25 24 1.5e-07 1.5e-07 2e-08 1.5e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
42 3990000 1 0.7 -0.01 0.00081 -0.012 -0.017 -0.022 0.72 0.02 0.025 -0.0079 0.019 -0.49 -0.5 0.0076 0.0084 -0.0027 0.0074 -0.91 -0.92 -1.3e-05 -2.8e-07 -4.5e-05 -4.6e-05 3.8e-07 2.1e-07 0 0 -8.9e-07 -1e-06 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 6.4e-07 0.00021 0.0017 0.0017 0.00025 0.00012 0.66 0.68 0.66 0.68 2.6 2.5 0.21 0.23 0.21 0.23 27 26 1.5e-07 1.5e-07 1.8e-08 1.4e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
43 4090000 1 0.7 -0.01 0.00078 -0.012 -0.016 -0.022 0.72 0.017 0.021 -0.0071 0.016 -0.51 0.0053 0.0062 -0.002 0.0053 -0.96 -0.97 -1.4e-05 -2.2e-06 -4.7e-05 -4.8e-05 3.9e-07 2.6e-07 0 0 -8.5e-07 -9.8e-07 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 5.2e-07 0.00021 0.0014 0.0014 0.00024 0.00012 0.5 0.52 0.5 0.52 2.6 2.5 0.15 0.16 0.15 0.16 29 27 1.2e-07 1.2e-07 1.7e-08 1.3e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
44 4190000 1 0.7 -0.01 0.00076 -0.012 -0.016 -0.022 0.72 0.02 0.025 -0.0085 0.018 -0.52 -0.53 0.0072 0.0086 -0.0027 0.007 -1 -1.4e-05 -2.2e-06 -4.7e-05 -4.8e-05 3.9e-07 2.6e-07 0 0 -8.5e-07 -9.8e-07 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 5.5e-07 0.00021 0.0015 0.0015 0.00023 0.00012 0.6 0.63 0.6 0.63 2.6 2.5 0.2 0.22 0.2 0.22 30 29 1.2e-07 1.2e-07 1.6e-08 1.2e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
45 4290000 1 0.7 -0.01 0.0008 -0.012 -0.016 -0.022 0.72 0.017 0.019 -0.0051 0.015 -0.54 0.0051 0.0063 -0.0019 0.005 -1.1 -1.5e-05 -4.1e-06 -4.9e-05 -5e-05 4e-07 3.1e-07 0 0 -8.1e-07 -9.3e-07 0.19 0.21 9.3e-10 0.002 0.4 0.43 0 0 0 0 0 4.6e-07 0.0002 0.0012 0.0012 0.00023 0.00011 0.46 0.48 0.46 0.48 2.6 0.14 0.15 0.14 0.15 32 31 1e-07 1e-07 1.5e-08 1.1e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
46 4390000 1 0.7 -0.01 0.00067 -0.012 -0.016 -0.022 0.71 0.018 0.021 -0.005 0.016 -0.55 0.0069 0.0083 -0.0025 0.0066 -1.1 -1.5e-05 -4.1e-06 -4.9e-05 -5e-05 4e-07 3.1e-07 0 0 -8.1e-07 -9.3e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 4.8e-07 0.0002 0.0013 0.0014 0.0013 0.0014 0.00022 0.00011 0.55 0.58 0.55 0.58 2.7 2.6 0.19 0.2 0.19 0.2 34 33 1e-07 1e-07 1.4e-08 1e-08 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
47 4490000 1 0.7 -0.01 0.00072 -0.012 -0.016 -0.022 0.71 0.014 0.017 -0.0034 0.013 -0.57 0.0048 0.0058 -0.0016 0.0046 -1.2 -1.5e-05 -5.9e-06 -5e-05 -5.1e-05 4e-07 3.5e-07 0 0 -7.8e-07 -8.8e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 4e-07 0.0002 0.0011 0.0011 0.00022 0.00011 0.42 0.44 0.42 0.44 2.7 2.6 0.14 0.14 36 34 8.2e-08 8.3e-08 8.2e-08 8.3e-08 1.3e-08 9.7e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
48 4590000 1 0.7 -0.01 0.00068 -0.012 -0.016 -0.022 0.71 0.017 0.019 -0.0042 0.015 -0.58 0.0064 0.0076 -0.002 0.006 -1.2 -1.5e-05 -5.9e-06 -5e-05 -5.1e-05 4e-07 3.5e-07 0 0 -7.8e-07 -8.8e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 4.2e-07 0.00019 0.0012 0.0012 0.00021 0.00011 0.51 0.53 0.51 0.53 2.7 0.18 0.19 0.18 0.19 38 36 8.2e-08 8.3e-08 8.2e-08 8.3e-08 1.2e-08 9.1e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
49 4690000 1 0.7 -0.01 0.00069 -0.011 -0.016 -0.022 0.71 0.014 0.016 -0.0037 0.012 -0.59 -0.6 0.0046 0.0054 -0.0013 0.0043 -1.3 -1.5e-05 -7.4e-06 -5.2e-05 4.1e-07 3.9e-07 0 0 -7.4e-07 -8.4e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 3.4e-07 0.00019 0.00093 0.00095 0.00093 0.00095 0.00021 0.0001 0.39 0.41 0.39 0.41 2.8 2.7 0.13 0.14 0.13 0.14 40 38 6.6e-08 6.7e-08 6.6e-08 6.7e-08 1.1e-08 8.6e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
50 4790000 1 0.7 -0.01 0.00062 -0.011 -0.016 -0.022 0.71 0.016 0.018 -0.0045 0.014 -0.61 0.006 0.0071 -0.0017 0.0056 -1.3 -1.4 -1.5e-05 -7.4e-06 -5.2e-05 4.1e-07 3.9e-07 0 0 -7.4e-07 -8.4e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 3.6e-07 0.00019 0.001 0.001 0.00021 0.0001 0.47 0.49 0.47 0.49 2.8 2.7 0.17 0.18 0.17 0.18 42 40 6.6e-08 6.7e-08 6.6e-08 6.7e-08 1.1e-08 8.1e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
51 4890000 1 0.7 -0.01 0.00064 -0.011 -0.016 -0.022 0.71 0.013 0.016 -0.0043 0.011 -0.62 -0.63 0.0043 0.0051 -0.0012 0.0039 -1.4 -1.6e-05 -8.7e-06 -5.3e-05 4.1e-07 4.2e-07 0 0 -7e-07 -7.9e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 3e-07 0.00019 0.00081 0.00083 0.00081 0.00083 0.0002 0.0001 0.36 0.37 0.36 0.37 2.9 2.8 0.12 0.13 0.12 0.13 44 42 5.4e-08 5.4e-08 1e-08 7.6e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
52 4990000 1 0.7 -0.01 0.00068 -0.011 -0.016 -0.022 0.71 0.015 0.017 -0.0044 0.013 -0.64 0.0057 0.0068 -0.0017 0.0051 -1.5 -1.6e-05 -8.7e-06 -5.3e-05 4.1e-07 4.2e-07 0 0 -7e-07 -7.9e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 3.1e-07 0.00019 0.00087 0.00089 0.00087 0.00089 0.0002 9.7e-05 0.43 0.44 0.43 0.44 2.9 2.8 0.16 0.17 0.16 0.17 46 44 5.4e-08 5.4e-08 9.5e-09 7.2e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
53 5090000 1 0.7 -0.01 0.00068 -0.011 -0.015 -0.022 0.71 0.012 0.014 -0.0033 0.01 -0.65 -0.66 0.004 0.0049 -0.0012 0.0037 -1.5 -1.6 -1.6e-05 -9.9e-06 -5.4e-05 4.2e-07 4.5e-07 0 0 -6.7e-07 -7.5e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.6e-07 0.00018 0.0007 0.00071 0.0007 0.00071 0.00019 9.5e-05 0.33 0.34 0.33 0.34 2.9 2.8 0.12 0.13 0.12 0.13 48 46 4.3e-08 4.4e-08 4.3e-08 4.4e-08 8.9e-09 6.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
54 5190000 1 0.7 -0.01 0.00067 -0.011 -0.015 -0.022 0.71 0.013 0.016 -0.0041 0.011 -0.67 0.0052 0.0064 -0.0016 0.0047 -1.6 -1.6e-05 -9.9e-06 -5.4e-05 4.2e-07 4.5e-07 0 0 -6.7e-07 -7.5e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.7e-07 0.00018 0.00075 0.00077 0.00075 0.00077 0.00019 9.4e-05 0.39 0.4 0.39 0.4 3 2.9 0.16 0.16 51 49 4.3e-08 4.4e-08 4.3e-08 4.4e-08 8.4e-09 6.5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
55 5290000 1 0.7 -0.0099 0.00074 -0.011 -0.015 -0.022 0.71 0.0089 0.012 -0.0025 0.0072 -0.68 0.0037 0.0046 -0.0011 0.0033 -1.7 -1.6e-05 -1.1e-05 -5.5e-05 4.2e-07 4.8e-07 0 0 -6.4e-07 -7e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.3e-07 0.00018 0.0006 0.00062 0.0006 0.00062 0.00019 9.2e-05 0.3 0.31 0.3 0.31 3 2.9 0.11 0.12 0.11 0.12 53 51 3.5e-08 3.5e-08 8e-09 6.1e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
56 5390000 1 0.7 -0.0099 0.00083 -0.011 -0.015 -0.022 0.71 0.0084 0.014 -0.0028 0.0065 -0.69 -0.7 0.0045 0.0058 -0.0014 0.0039 -1.7 -1.8 -1.6e-05 -1.1e-05 -5.5e-05 4.2e-07 4.8e-07 0 0 -6.4e-07 -7e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.4e-07 0.00018 0.00065 0.00066 0.00065 0.00066 0.00018 9e-05 0.35 0.37 0.35 0.37 3 2.9 0.15 0.16 0.15 0.16 56 53 3.5e-08 3.5e-08 7.5e-09 5.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
57 5490000 1 0.7 -0.0098 0.0009 -0.011 -0.015 -0.022 0.71 0.0058 0.011 -0.0019 0.0042 -0.71 0.003 0.0042 -0.00094 0.0026 -1.8 -1.6e-05 -1.2e-05 -5.5e-05 4.2e-07 5e-07 0 0 -6.2e-07 -6.7e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2e-07 0.00017 0.00052 0.00053 0.00052 0.00053 0.00018 8.8e-05 0.27 0.28 0.27 0.28 3.1 3 0.11 0.11 58 56 2.8e-08 2.8e-08 7.1e-09 5.5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
58 5590000 1 0.7 -0.0098 0.00091 -0.011 -0.015 -0.022 0.71 0.0066 0.012 -0.0018 0.0047 -0.72 -0.73 0.0036 0.0053 -0.0011 0.003 -1.9 -1.6e-05 -1.2e-05 -5.5e-05 4.2e-07 5e-07 0 0 -6.2e-07 -6.7e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.1e-07 0.00017 0.00056 0.00057 0.00056 0.00057 0.00018 8.7e-05 0.32 0.33 0.32 0.33 3.1 3 0.14 0.15 0.14 0.15 61 58 2.8e-08 2.8e-08 6.8e-09 5.3e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
59 5690000 1 0.7 -0.0097 0.00099 -0.011 -0.015 -0.022 0.71 0.007 0.0081 -0.00067 0.003 -0.74 0.0043 0.0037 -0.0012 0.002 -2 -1.6e-05 -1.3e-05 -5.5e-05 -5.6e-05 4.2e-07 5.2e-07 0 0 -6.2e-07 -6.4e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 2.1e-07 0.00017 0.00059 0.00045 0.0006 0.00045 0.00017 8.5e-05 0.37 0.26 0.37 0.26 3.2 3.1 0.18 0.11 0.18 0.11 63 61 2.8e-08 2.3e-08 2.8e-08 2.3e-08 6.4e-09 5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
60 5790000 1 0.7 -0.0096 0.001 -0.011 -0.015 -0.022 0.71 0.0051 0.0074 0.0015 0.0032 -0.75 0.0029 0.0045 -0.00065 0.0023 -2 -2.1 -1.7e-05 -1.3e-05 -5.6e-05 4.2e-07 5.2e-07 0 0 -6e-07 -6.4e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 1.8e-07 0.00017 0.00048 0.00049 0.00048 0.00049 0.00017 8.4e-05 0.29 0.3 0.29 0.3 3.2 3.1 0.13 0.14 0.13 0.14 66 64 2.3e-08 2.3e-08 6.1e-09 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
61 5890000 1 0.7 -0.0095 0.0011 -0.011 -0.015 -0.022 0.71 0.0063 0.0048 0.0022 0.0027 0.0028 0.0035 0.003 -0.0005 0.0016 -3.7e+02 -1.7e-05 -1.3e-05 -5.6e-05 4.2e-07 5.3e-07 0 0 -6.3e-07 -6.4e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 1.9e-07 0.00017 0.00051 0.00039 0.00051 0.00039 0.00017 8.2e-05 0.34 0.23 0.34 0.23 9.8 0.17 0.11 0.17 0.11 0.52 2.3e-08 1.8e-08 2.3e-08 1.8e-08 5.8e-09 4.5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
62 5990000 1 0.7 -0.0095 0.0011 -0.011 -0.015 -0.022 0.71 0.0049 0.0037 0.0042 0.0029 0.015 0.0025 0.0034 6.1e-05 0.0018 -3.7e+02 -1.7e-05 -1.3e-05 -5.6e-05 4.2e-07 5.3e-07 0 0 -7.1e-07 -7.3e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 1.6e-07 0.00017 0.00041 0.00042 0.00041 0.00042 0.00017 8.1e-05 0.26 0.27 0.26 0.27 8.8 0.13 0.13 0.33 1.8e-08 1.8e-08 5.5e-09 4.3e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
63 6090000 1 0.7 -0.0095 0.0011 -0.011 -0.015 -0.022 0.71 0.006 0.0029 0.0057 0.0038 -0.011 0.003 0.0037 0.00058 0.0022 -3.7e+02 -1.7e-05 -1.3e-05 -5.6e-05 4.2e-07 5.3e-07 0 0 -6.2e-07 -6.5e-07 0.19 0.21 9.3e-10 0.0021 0.4 0.43 0 0 0 0 0 1.7e-07 0.00016 0.00044 0.00045 0.00044 0.00045 0.00016 8e-05 0.31 0.32 0.31 0.32 7 0.16 0.17 0.16 0.17 0.33 1.8e-08 1.8e-08 5.3e-09 4.1e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
64 6190000 0.71 0.7 0.0014 0.0011 -0.014 -0.015 0.71 0.0041 -0.00035 0.0063 0.0027 -0.005 0.0022 0.0009 0.0015 -3.7e+02 -1.6e-05 -1.3e-05 -5.7e-05 -5.6e-05 4.2e-07 5.4e-07 0 0 -8.6e-07 -8.8e-07 0.21 0.0021 0.43 0 0 0 0 0 0.00081 0.00016 0.00034 0.00036 0.00034 0.00036 0.00091 7.8e-05 0.22 0.25 0.22 0.25 4.9 0.12 0.13 0.12 0.13 0.32 1.5e-08 1.5e-08 5.2e-09 3.9e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
65 6290000 0.71 0.7 0.0014 0.0011 -0.014 -0.015 0.71 0.0038 -6e-05 0.0077 0.0039 -0.012 0.0026 0.0022 0.0016 0.0019 -3.7e+02 -1.6e-05 -1.3e-05 -5.7e-05 -5.6e-05 4.2e-07 5.4e-07 0 0 -9.4e-07 -9.6e-07 0.21 0.0021 0.43 0 0 0 0 0 0.00053 0.00016 0.00034 0.00038 0.00034 0.00038 0.00059 7.7e-05 0.23 0.29 0.23 0.29 3.2 0.15 0.16 0.15 0.16 0.3 1.5e-08 1.5e-08 5.2e-09 3.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
66 6390000 0.71 0.7 0.0014 0.0012 -0.014 0.71 0.0024 -0.0018 0.0082 0.0033 -0.05 0.0029 0.0012 0.0024 0.0014 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -5.6e-05 4.6e-07 5.5e-07 0 0 -3.5e-07 0.21 0.0021 0.43 0 0 0 0 0 0.00041 0.00016 0.00034 0.00031 0.00034 0.00031 0.00046 7.6e-05 0.23 0.23 2.3 0.19 0.12 0.19 0.12 0.29 1.5e-08 1.2e-08 1.5e-08 1.2e-08 5.2e-09 3.6e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
67 6490000 0.71 0.7 0.0015 0.0012 -0.014 -0.015 0.71 0.0018 -0.0017 0.009 0.0039 -0.052 0.0031 0.001 0.0033 0.0018 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -5.6e-05 4.4e-07 5.5e-07 0 0 -8.4e-07 -8.5e-07 0.21 0.0021 0.43 0 0 0 0 0 0.00033 0.00016 0.00035 0.00033 0.00035 0.00033 0.00037 7.5e-05 0.24 0.26 0.24 0.26 1.5 0.23 0.15 0.23 0.15 0.26 1.5e-08 1.2e-08 1.5e-08 1.2e-08 5.2e-09 3.5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
68 6590000 0.71 0.7 0.0015 0.0012 -0.014 -0.015 0.71 0.00095 -0.0024 0.0091 0.0029 -0.099 0.0033 0.00044 0.0042 0.0014 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 3.4e-07 5.6e-07 0 0 9.7e-07 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00028 0.00085 0.00035 0.00026 0.00035 0.00026 0.00031 0.00079 0.25 0.19 0.25 0.19 1.1 0.27 0.12 0.27 0.12 0.23 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.2e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
69 6690000 0.71 0.7 0.0015 0.0012 -0.014 -0.015 0.71 0.00098 -0.0016 0.01 0.0037 -0.076 0.0034 0.00024 0.0051 0.0017 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 2.4e-07 5.4e-07 0 0 -2.2e-06 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00024 0.00056 0.00035 0.00026 0.00035 0.00026 0.00027 0.00052 0.26 0.19 0.26 0.19 0.78 0.32 0.14 0.32 0.14 0.21 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.2e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
70 6790000 0.71 0.7 0.0015 0.0012 -0.014 0.71 -0.00069 -0.0026 0.01 0.0034 -0.11 0.0034 3.5e-05 0.0062 0.0021 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 2.9e-07 5.7e-07 0 0 9.9e-08 1e-07 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00022 0.00044 0.00036 0.00026 0.00036 0.00026 0.00024 0.00041 0.28 0.2 0.28 0.2 0.6 0.37 0.17 0.37 0.17 0.2 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.2e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
71 6890000 0.71 0.7 0.0016 0.0012 -0.014 0.71 -0.0031 -0.0043 0.011 0.0037 -0.12 0.0032 -0.00033 0.0072 0.0025 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 2.9e-07 5.9e-07 0 0 -4.1e-07 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0002 0.00036 0.00036 0.00026 0.00036 0.00026 0.00022 0.00033 0.3 0.21 0.3 0.21 0.46 0.43 0.21 0.43 0.21 0.18 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.2e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
72 6990000 0.7 0.0016 0.0013 -0.014 0.71 -0.0035 -0.0039 0.011 0.0044 -0.12 0.0028 -0.00074 0.0083 0.0029 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 3.3e-08 5.1e-07 0 0 -3.4e-06 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00018 0.0003 0.00037 0.00026 0.00037 0.00026 0.0002 0.00028 0.32 0.22 0.32 0.22 0.36 0.5 0.25 0.5 0.25 0.16 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.2e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
73 7090000 0.7 0.0016 0.0013 -0.014 0.71 -0.0045 -0.0041 0.011 0.0038 -0.13 0.0024 -0.0011 0.0094 0.0033 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -2.6e-07 4.2e-07 0 0 -7e-06 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00017 0.00027 0.00037 0.00027 0.00037 0.00027 0.00019 0.00025 0.34 0.23 0.34 0.23 0.29 0.57 0.29 0.57 0.29 0.16 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.2e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
74 7190000 0.7 0.0016 0.0013 -0.014 0.71 -0.0066 -0.0054 0.011 0.0037 -0.15 0.0019 -0.0016 0.01 0.0036 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -4e-07 3.9e-07 0 0 -4.9e-06 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00016 0.00024 0.00038 0.00027 0.00038 0.00027 0.00018 0.00022 0.37 0.25 0.37 0.25 0.24 0.65 0.34 0.65 0.34 0.15 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.2e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
75 7290000 0.7 0.0017 0.0013 -0.014 0.71 -0.0085 -0.0064 0.011 0.0037 -0.15 0.0011 -0.0022 0.012 0.004 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -4.3e-07 4.1e-07 0 0 -1.2e-05 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00015 0.00022 0.00039 0.00027 0.00039 0.00027 0.00017 0.0002 0.4 0.27 0.4 0.27 0.2 0.74 0.4 0.74 0.4 0.14 1.5e-08 9.8e-09 1.5e-08 9.8e-09 5.1e-09 3.4e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
76 7390000 0.7 0.0017 0.0013 -0.014 0.71 -0.0091 -0.0061 0.013 0.005 -0.16 0.0002 -0.0028 0.013 0.0044 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -4.2e-07 4.5e-07 0 0 -1.3e-05 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00014 0.0002 0.0004 0.00028 0.0004 0.00028 0.00016 0.00019 0.43 0.29 0.43 0.29 0.18 0.84 0.46 0.84 0.46 0.13 1.5e-08 9.7e-09 1.5e-08 9.7e-09 5.1e-09 3.4e-09 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
77 7490000 0.7 0.0018 0.0014 -0.014 0.71 -0.011 -0.0072 0.013 0.0052 -0.16 -0.00083 -0.0035 0.014 0.0049 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -4.7e-07 4.6e-07 0 0 -2.1e-05 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00014 0.00018 0.00041 0.00028 0.00041 0.00028 0.00015 0.00017 0.47 0.32 0.47 0.32 0.15 0.95 0.53 0.95 0.53 0.12 1.5e-08 9.7e-09 1.5e-08 9.7e-09 5.1e-09 3.4e-09 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
78 7590000 0.7 0.0018 0.0014 -0.014 0.71 -0.013 -0.0087 0.015 0.0062 -0.17 -0.002 -0.0043 0.015 0.0055 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -3.2e-07 5.6e-07 0 0 -3e-05 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00013 0.00017 0.00042 0.00028 0.00042 0.00028 0.00014 0.00016 0.51 0.35 0.51 0.35 0.14 1.1 0.6 1.1 0.6 0.12 1.4e-08 9.7e-09 1.4e-08 9.7e-09 5.1e-09 3.4e-09 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
79 7690000 0.7 0.0019 0.0014 -0.014 0.71 -0.016 -0.01 0.015 0.0068 -0.16 -0.0035 -0.0052 0.017 0.0061 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -3.7e-07 5.7e-07 0 0 -5e-05 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00013 0.00016 0.00043 0.00029 0.00043 0.00029 0.00014 0.00016 0.55 0.38 0.55 0.38 0.13 1.2 0.69 1.2 0.69 0.11 1.4e-08 9.7e-09 1.4e-08 9.7e-09 5.1e-09 3.4e-09 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
80 7790000 0.7 0.0019 0.0015 -0.014 0.71 -0.018 -0.011 0.016 0.0074 -0.16 -0.0052 -0.0062 0.018 0.0067 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -7.9e-07 3.8e-07 0 0 -7e-05 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00012 0.00016 0.00044 0.0003 0.00044 0.0003 0.00013 0.00015 0.6 0.41 0.6 0.41 0.12 1.3 0.78 1.3 0.78 0.11 1.4e-08 9.7e-09 1.4e-08 9.7e-09 5.1e-09 3.4e-09 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
81 7890000 0.7 0.0019 0.0015 -0.014 0.71 -0.021 -0.013 0.018 0.0091 -0.16 -0.0071 -0.0074 0.019 0.0075 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -6.9e-07 4.7e-07 0 0 -9.6e-05 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00012 0.00015 0.00045 0.0003 0.00045 0.0003 0.00013 0.00014 0.65 0.45 0.65 0.45 0.11 1.5 0.89 1.5 0.89 0.1 1.4e-08 9.7e-09 1.4e-08 9.7e-09 5.1e-09 3.4e-09 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
82 7990000 0.7 0.0019 0.0015 -0.014 0.71 -0.023 -0.014 0.019 0.01 -0.16 -0.0093 -0.0087 0.021 0.0084 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -5.7e-07 5.7e-07 0 0 -0.00011 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00012 0.00014 0.00046 0.00031 0.00046 0.00031 0.00013 0.7 0.49 0.7 0.49 0.1 1.7 1 1.7 1 0.099 1.4e-08 9.6e-09 1.4e-08 9.6e-09 5e-09 3.4e-09 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
83 8090000 0.7 0.0019 0.0015 -0.014 0.71 -0.025 -0.016 0.02 0.011 -0.17 -0.012 -0.01 0.023 0.0095 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -3.2e-07 7.3e-07 0 0 -0.00011 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00011 0.00014 0.00047 0.00031 0.00047 0.00031 0.00012 0.00013 0.75 0.53 0.75 0.53 0.1 1.8 1.1 1.8 1.1 0.097 1.4e-08 9.6e-09 1.4e-08 9.6e-09 5e-09 3.4e-09 4e-06 4e-06 3.7e-06 0 0 0 0 0 0 0 0
84 8190000 0.7 0.0019 0.0015 -0.014 0.71 -0.029 -0.018 0.022 0.013 -0.18 -0.014 -0.012 0.025 0.011 -3.7e+02 -1.6e-05 -1.4e-05 -5.7e-05 -6.6e-07 5.8e-07 0 0 -0.00013 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00011 0.00013 0.00049 0.00032 0.00049 0.00032 0.00012 0.00013 0.81 0.58 0.81 0.58 0.099 2 1.3 2 1.3 0.094 1.4e-08 9.6e-09 1.4e-08 9.6e-09 5e-09 3.4e-09 4e-06 4e-06 3.7e-06 0 0 0 0 0 0 0 0
85 8290000 0.7 0.002 0.0015 -0.014 0.71 -0.031 -0.019 0.022 0.013 -0.17 -0.017 -0.014 0.026 0.012 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -9e-07 4.8e-07 0 0 -0.00017 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00011 0.00013 0.0005 0.00033 0.0005 0.00033 0.00012 0.87 0.63 0.87 0.63 0.097 2.2 1.4 2.2 1.4 0.091 1.4e-08 9.5e-09 1.4e-08 9.5e-09 5e-09 3.4e-09 4e-06 4e-06 3.6e-06 0 0 0 0 0 0 0 0
86 8390000 0.7 0.002 0.0016 -0.014 0.71 -0.033 -0.02 0.024 0.014 -0.17 -0.02 -0.016 0.029 0.013 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -6.3e-07 6.6e-07 0 0 -0.00021 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00011 0.00012 0.00051 0.00034 0.00051 0.00034 0.00012 0.94 0.68 0.94 0.68 0.097 2.5 1.6 2.5 1.6 0.091 1.4e-08 9.5e-09 1.4e-08 9.5e-09 4.9e-09 3.3e-09 4e-06 4e-06 3.5e-06 0 0 0 0 0 0 0 0
87 8490000 0.7 0.002 0.0015 -0.014 0.71 -0.036 -0.021 0.025 0.015 -0.17 -0.024 -0.018 0.03 0.014 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -8.2e-07 5.9e-07 0 0 -0.00025 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00011 0.00012 0.00052 0.00034 0.00052 0.00034 0.00011 0.00012 0.99 0.73 0.99 0.73 0.096 2.7 1.8 2.7 1.8 0.089 1.4e-08 9.4e-09 1.4e-08 9.4e-09 4.9e-09 3.3e-09 4e-06 4e-06 3.4e-06 0 0 0 0 0 0 0 0
88 8590000 0.7 0.0021 0.0016 -0.014 0.71 -0.039 -0.023 0.027 0.017 -0.17 -0.027 -0.02 0.032 0.016 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -1.2e-06 4e-07 0 0 -0.00029 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.00011 0.00012 0.00054 0.00035 0.00054 0.00035 0.00011 1.1 0.79 1.1 0.79 0.095 3 2 3 2 0.088 1.4e-08 9.4e-09 1.4e-08 9.4e-09 4.9e-09 3.3e-09 4e-06 4e-06 3.4e-06 0 0 0 0 0 0 0 0
89 8690000 0.7 0.0021 0.0016 -0.014 0.71 -0.042 -0.026 0.028 0.018 -0.16 -0.031 -0.022 0.034 0.017 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -7.9e-07 6.7e-07 0 0 -0.00035 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00012 0.00055 0.00036 0.00055 0.00036 0.00011 1.1 0.84 1.1 0.84 0.096 3.2 2.2 3.2 2.2 0.088 1.4e-08 9.3e-09 1.4e-08 9.3e-09 4.8e-09 3.3e-09 4e-06 4e-06 3.3e-06 0 0 0 0 0 0 0 0
90 8790000 0.7 0.0021 0.0016 -0.014 0.71 -0.045 -0.027 0.03 0.02 -0.15 -0.036 -0.025 0.036 0.019 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -1.1e-06 5.5e-07 0 0 -0.00041 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00011 0.00057 0.00037 0.00057 0.00037 0.00011 1.2 0.91 1.2 0.91 0.095 3.6 2.5 3.6 2.5 0.087 1.4e-08 9.3e-09 1.4e-08 9.3e-09 4.8e-09 3.3e-09 4e-06 4e-06 3.2e-06 0 0 0 0 0 0 0 0
91 8890000 0.7 0.0021 0.0016 -0.014 0.71 -0.047 -0.029 0.03 0.02 -0.15 -0.039 -0.027 0.038 0.02 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -1.2e-06 4.6e-07 0 0 -0.00045 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00011 0.00058 0.00037 0.00058 0.00037 0.00011 1.3 0.96 1.3 0.96 0.095 3.8 2.7 3.8 2.7 0.086 1.3e-08 9.2e-09 1.4e-08 9.2e-09 4.8e-09 3.3e-09 4e-06 4e-06 3e-06 0 0 0 0 0 0 0 0
92 8990000 0.7 0.0022 0.0016 -0.014 0.71 -0.05 -0.03 0.03 0.02 -0.14 -0.044 -0.031 0.04 0.022 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -1.6e-06 2.5e-07 0 0 -0.00051 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00011 0.0006 0.00038 0.00059 0.00038 0.00011 1.4 1 1.4 1 0.096 4.2 3 4.2 3 0.087 1.3e-08 9.2e-09 1.4e-08 9.2e-09 4.7e-09 3.3e-09 4e-06 4e-06 2.9e-06 0 0 0 0 0 0 0 0
93 9090000 0.7 0.0022 0.0017 -0.014 0.71 -0.052 -0.032 0.031 0.021 -0.14 -0.048 -0.033 0.041 0.023 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -1.9e-06 1.1e-07 0 0 -0.00053 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00011 0.0006 0.00038 0.0006 0.00038 0.00011 0.0001 1.4 1.1 1.4 1.1 0.095 4.5 3.3 4.5 3.3 0.086 1.3e-08 9e-09 1.3e-08 9e-09 4.7e-09 3.3e-09 4e-06 4e-06 2.8e-06 0 0 0 0 0 0 0 0
94 9190000 0.7 0.0022 0.0017 -0.014 0.71 -0.055 -0.033 0.032 0.021 -0.14 -0.053 -0.036 0.044 0.025 -3.7e+02 -1.6e-05 -1.4e-05 -5.6e-05 -5.7e-05 -1.2e-06 6e-07 0 0 -0.00057 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00011 0.00062 0.00039 0.00062 0.00039 0.0001 1.5 1.2 1.5 1.2 0.094 5 3.6 5 3.6 0.085 1.3e-08 9e-09 1.3e-08 9e-09 4.6e-09 3.2e-09 4e-06 4e-06 2.7e-06 0 0 0 0 0 0 0 0
95 9290000 0.7 0.0022 0.0016 -0.014 0.71 -0.055 -0.033 0.032 0.022 -0.14 -0.056 -0.039 0.045 0.026 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -1.1e-06 6.6e-07 0 0 -0.00061 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00062 0.00039 0.00062 0.00039 0.0001 1.6 1.2 1.6 1.2 0.093 5.2 3.9 5.2 3.9 0.085 1.3e-08 8.9e-09 1.3e-08 8.9e-09 4.6e-09 3.2e-09 4e-06 4e-06 2.5e-06 0 0 0 0 0 0 0 0
96 9390000 0.7 0.0022 0.0016 -0.014 0.71 -0.057 -0.034 0.034 0.024 -0.14 -0.062 -0.042 0.048 0.028 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -1.2e-06 6.5e-07 0 0 -0.00065 0.21 0.0021 0.43 0.44 0 0 0 0 0 0.0001 0.00064 0.0004 0.00064 0.0004 0.0001 1.7 1.3 1.7 1.3 0.093 5.7 4.3 5.7 4.3 0.086 1.3e-08 8.9e-09 1.3e-08 8.9e-09 4.5e-09 3.2e-09 4e-06 4e-06 2.4e-06 0 0 0 0 0 0 0 0
97 9490000 0.7 0.0022 0.0016 -0.014 0.71 -0.058 -0.035 0.034 0.023 -0.13 -0.064 -0.044 0.048 0.029 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -6.2e-07 1e-06 0 0 -0.00068 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 0.0001 0.00064 0.0004 0.00064 0.0004 0.0001 9.9e-05 1.7 1.3 1.7 1.3 0.091 5.9 4.6 5.9 4.6 0.085 1.3e-08 8.7e-09 1.3e-08 8.7e-09 4.5e-09 3.2e-09 4e-06 4e-06 2.3e-06 0 0 0 0 0 0 0 0
98 9590000 0.7 0.0022 0.0016 -0.014 0.71 -0.062 -0.037 0.035 0.025 -0.13 -0.071 -0.048 0.052 0.031 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -4.9e-07 1.2e-06 0 0 -0.00072 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 0.0001 0.00066 0.00041 0.00066 0.00041 0.0001 9.8e-05 1.8 1.4 1.8 1.4 0.09 6.5 5.1 6.5 5.1 0.085 1.3e-08 8.7e-09 1.3e-08 8.7e-09 4.4e-09 3.2e-09 4e-06 4e-06 2.1e-06 0 0 0 0 0 0 0 0
99 9690000 0.7 0.0023 0.0017 -0.014 0.71 -0.062 -0.037 0.036 0.026 -0.12 -0.072 -0.049 0.051 0.031 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -1.1e-06 7.6e-07 0 0 -0.00077 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 0.0001 0.00066 0.00041 0.00066 0.00041 0.0001 9.7e-05 1.8 1.4 1.8 1.4 0.089 6.7 5.3 6.7 5.3 0.086 1.3e-08 8.4e-09 1.3e-08 8.5e-09 4.4e-09 3.1e-09 4e-06 4e-06 2e-06 0 0 0 0 0 0 0 0
100 9790000 0.7 0.0023 0.0017 -0.014 0.71 -0.063 -0.037 0.039 0.027 -0.11 -0.079 -0.053 0.055 0.034 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -7.7e-07 1e-06 0 0 -0.00082 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 0.00068 0.00042 0.00068 0.00042 0.0001 9.7e-05 2 1.5 2 1.5 0.087 7.4 5.9 7.4 5.9 0.085 1.3e-08 8.4e-09 1.3e-08 8.5e-09 4.3e-09 3.1e-09 4e-06 4e-06 1.9e-06 0 0 0 0 0 0 0 0
101 9890000 0.7 0.0023 0.0016 -0.013 -0.014 0.71 -0.067 -0.037 0.04 0.027 -0.11 -0.086 -0.054 0.058 0.034 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -8.7e-07 1e-06 0 0 -0.00085 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.9e-05 0.0007 0.00041 0.0007 0.00041 0.0001 9.6e-05 2.1 1.5 2.1 1.5 0.084 8.1 6.1 8.1 6.1 0.085 1.3e-08 8.2e-09 1.3e-08 8.2e-09 4.3e-09 3.1e-09 4e-06 4e-06 1.8e-06 0 0 0 0 0 0 0 0
102 9990000 0.7 0.0023 0.0017 -0.014 0.71 -0.066 -0.038 0.039 0.028 -0.1 -0.086 -0.058 0.058 0.037 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -1.2e-06 8.1e-07 0 0 -0.00089 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.8e-05 0.0007 0.00042 0.0007 0.00042 0.0001 9.6e-05 2.1 1.6 2.1 1.6 0.083 8.2 6.7 8.2 6.7 0.086 1.2e-08 8.2e-09 1.2e-08 8.2e-09 4.2e-09 3.1e-09 4e-06 4e-06 1.7e-06 0 0 0 0 0 0 0 0
103 10090000 0.7 0.0024 0.0017 -0.014 0.71 -0.068 -0.037 0.04 0.026 -0.096 -0.093 -0.058 0.062 0.037 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -1.1e-06 9.1e-07 0 0 -0.00091 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.7e-05 0.00072 0.00041 0.00072 0.00041 0.0001 9.5e-05 2.2 1.6 2.2 1.6 0.08 9 6.9 9 6.9 0.085 1.2e-08 8e-09 1.2e-08 8e-09 4.2e-09 3e-09 4e-06 4e-06 1.6e-06 0 0 0 0 0 0 0 0
104 10190000 0.7 0.0023 0.0017 -0.014 0.71 -0.066 -0.038 0.041 0.029 -0.096 -0.092 -0.061 0.06 0.039 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -2e-06 3.4e-07 0 0 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.7e-05 0.00071 0.00042 0.00071 0.00042 0.0001 9.5e-05 2.2 1.7 2.2 1.7 0.078 9 7.6 9 7.6 0.084 1.2e-08 8e-09 1.2e-08 8e-09 4.1e-09 3e-09 4e-06 4e-06 1.4e-06 0 0 0 0 0 0 0 0
105 10290000 0.7 0.0023 0.0017 -0.014 0.71 -0.069 -0.038 0.041 0.028 -0.084 -0.1 -0.066 0.064 0.042 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -2.6e-06 -1.8e-08 0 0 -0.00098 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.7e-05 0.00073 0.00043 0.00073 0.00043 0.0001 9.5e-05 2.4 1.8 2.4 1.8 0.076 9.8 8.3 9.8 8.3 0.085 1.2e-08 8e-09 1.2e-08 8e-09 4e-09 3e-09 4e-06 4e-06 1.4e-06 0 0 0 0 0 0 0 0
106 10390000 0.7 0.0023 0.0016 -0.014 0.71 0.0089 0.01 -0.019 -0.02 0.0096 0.00084 0.0009 -0.0017 -0.0018 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -2.6e-06 1.4e-09 -6.6e-10 -6.4e-10 4.7e-10 5.1e-10 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.6e-05 0.00076 0.00044 0.00076 0.00044 0.0001 9.4e-05 0.25 0.25 0.56 0.25 0.25 0.078 1.2e-08 8e-09 1.2e-08 8e-09 4e-09 3e-09 4e-06 4e-06 1.3e-06 0 0 0 0 0 0 0 0
107 10490000 0.7 0.0024 0.0017 -0.014 0.71 0.007 0.0097 -0.017 -0.018 0.023 0.0016 0.0019 -0.0035 -0.0036 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -3.2e-06 -3.5e-07 -1.7e-08 1.2e-08 1.3e-08 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.6e-05 0.00078 0.00046 0.00078 0.00046 9.9e-05 9.4e-05 0.26 0.26 0.55 0.26 0.26 0.08 1.2e-08 8e-09 1.2e-08 8e-09 3.9e-09 2.9e-09 4e-06 4e-06 1.2e-06 0 0 0 0 0 0 0 0
108 10590000 0.7 0.0025 0.0017 -0.014 0.71 0.0066 0.0092 -0.0065 -0.0076 0.026 0.0018 -0.00081 -0.00084 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -3.2e-06 -3.3e-07 -2.6e-06 -2.8e-06 5.1e-07 7.2e-08 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.5e-05 0.00079 0.00047 0.00079 0.00047 9.9e-05 9.4e-05 0.14 0.13 0.14 0.13 0.27 0.13 0.13 0.073 1.2e-08 7.9e-09 1.2e-08 7.9e-09 3.8e-09 2.9e-09 4e-06 4e-06 1.2e-06 0 0 0 0 0 0 0 0
109 10690000 0.7 0.0025 0.0018 -0.014 0.71 0.0039 0.0079 -0.0058 -0.0075 0.03 0.0024 0.0027 -0.0014 -0.0016 -3.7e+02 -1.6e-05 -1.3e-05 -5.6e-05 -5.7e-05 -3.4e-06 -4.5e-07 -2.7e-06 -2.8e-06 5.2e-07 8.4e-08 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.5e-05 0.00081 0.00048 0.00081 0.00048 9.9e-05 9.4e-05 0.15 0.14 0.15 0.14 0.26 0.14 0.14 0.078 1.2e-08 7.9e-09 1.2e-08 7.9e-09 3.8e-09 2.9e-09 4e-06 4e-06 1.1e-06 0 0 0 0 0 0 0 0
110 10790000 0.7 0.0025 0.0018 -0.014 0.71 0.0035 0.0072 -0.003 -0.0048 0.024 0.0026 0.0028 -0.00072 -0.0008 -3.7e+02 -1.5e-05 -1.3e-05 -5.5e-05 -5.7e-05 -3.4e-06 -3.9e-07 -4.2e-06 -5e-06 2.3e-06 7e-07 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.5e-05 0.00078 0.00047 0.00078 0.00047 9.9e-05 9.3e-05 0.11 0.099 0.11 0.099 0.17 0.091 0.091 0.072 1.1e-08 7.8e-09 1.1e-08 7.8e-09 3.7e-09 2.8e-09 4e-06 4e-06 1.1e-06 0 0 0 0 0 0 0 0
111 10890000 0.7 0.0025 0.0017 -0.014 0.71 0.0016 0.0067 -0.0017 -0.0041 0.02 0.0029 0.0034 -0.00092 -0.0012 -3.7e+02 -1.5e-05 -1.3e-05 -5.5e-05 -5.7e-05 -3.4e-06 -4e-07 -4.2e-06 -5e-06 2.3e-06 7e-07 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.5e-05 0.00081 0.00049 0.00081 0.00049 9.9e-05 9.3e-05 0.13 0.11 0.13 0.11 0.16 0.098 0.098 0.075 1.1e-08 7.8e-09 1.1e-08 7.8e-09 3.6e-09 2.8e-09 4e-06 4e-06 1.1e-06 0 0 0 0 0 0 0 0
112 10990000 0.7 0.0024 0.0017 -0.014 0.71 0.0047 0.0086 0.0034 0.00073 0.014 0.0046 0.0048 -0.0022 -0.0024 -3.7e+02 -1.4e-05 -1.3e-05 -5.5e-05 -5.6e-05 -2.9e-06 -2e-08 -8.1e-06 -1e-05 9.2e-06 6.1e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00073 0.00047 0.00073 0.00047 9.9e-05 9.3e-05 0.1 0.09 0.1 0.09 0.12 0.073 0.073 0.071 1.1e-08 7.5e-09 1.1e-08 7.5e-09 3.6e-09 2.8e-09 3.9e-06 3.9e-06 1.1e-06 0 0 0 0 0 0 0 0
113 11090000 0.7 0.0024 0.0017 -0.014 0.71 0.003 0.0079 0.0059 0.0025 0.019 0.005 0.0056 -0.0018 -0.0023 -3.7e+02 -1.4e-05 -1.3e-05 -5.5e-05 -5.6e-05 -2.5e-06 3.7e-07 -8.2e-06 -1e-05 9.3e-06 6.1e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00076 0.00048 0.00076 0.00048 9.9e-05 9.3e-05 0.13 0.11 0.13 0.11 0.11 0.08 0.079 0.08 0.079 0.074 1.1e-08 7.5e-09 1.1e-08 7.5e-09 3.5e-09 2.7e-09 3.9e-06 3.9e-06 1.1e-06 0 0 0 0 0 0 0 0
114 11190000 0.7 0.0023 0.0017 -0.014 0.71 0.0084 0.012 0.0083 0.0053 0.0077 0.0066 0.0067 -0.0028 -0.0031 -3.7e+02 -1.3e-05 -1.2e-05 -5.5e-05 -5.6e-05 -2.9e-06 7e-08 -9.2e-06 -1.3e-05 1.6e-05 1.1e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00065 0.00044 0.00065 0.00044 9.9e-05 9.3e-05 0.1 0.088 0.1 0.088 0.084 0.063 0.063 0.069 9.4e-09 7e-09 9.4e-09 7e-09 3.4e-09 2.7e-09 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
115 11290000 0.7 0.0023 0.0018 -0.014 0.71 0.0078 0.012 0.011 0.0071 0.0074 0.0074 0.0079 -0.0018 -0.0024 -3.7e+02 -1.3e-05 -1.2e-05 -5.5e-05 -5.6e-05 -3.7e-06 -4.4e-07 -9.2e-06 -1.3e-05 1.6e-05 1.1e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00067 0.00045 0.00067 0.00045 9.9e-05 9.3e-05 0.13 0.11 0.13 0.11 0.078 0.071 0.07 0.071 0.07 0.072 9.4e-09 7e-09 9.4e-09 7e-09 3.4e-09 2.7e-09 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
116 11390000 0.7 0.0023 0.0019 -0.014 0.71 0.0034 0.0073 0.0092 0.0067 0.0017 0.0054 0.0057 -0.0019 -0.0022 -3.7e+02 -1.4e-05 -1.3e-05 -5.5e-05 -5.6e-05 -4.2e-06 -8.5e-07 -5e-06 -9.9e-06 1.3e-05 5.2e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00056 0.0004 0.00056 0.0004 9.9e-05 9.3e-05 0.1 0.089 0.1 0.089 0.063 0.058 0.057 0.058 0.057 0.068 8.2e-09 6.5e-09 8.2e-09 6.5e-09 3.3e-09 2.6e-09 3.8e-06 3.7e-06 3.8e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
117 11490000 0.7 0.0024 0.0019 -0.014 0.71 0.0005 0.0051 0.012 0.009 0.0025 0.0056 0.0063 -0.00089 -0.0014 -3.7e+02 -1.4e-05 -1.3e-05 -5.5e-05 -5.6e-05 -5.3e-06 -1.6e-06 -5e-06 -9.9e-06 1.3e-05 5.3e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00058 0.00041 0.00058 0.00041 9.8e-05 9.3e-05 0.13 0.11 0.13 0.11 0.058 0.066 0.065 0.066 0.065 0.069 8.2e-09 6.5e-09 8.2e-09 6.5e-09 3.2e-09 2.6e-09 3.8e-06 3.7e-06 3.8e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
118 11590000 0.7 0.0022 0.0018 -0.014 0.71 -0.0033 0.00046 0.01 0.0084 -0.0034 0.0043 0.0047 -0.0014 -0.0015 -3.7e+02 -1.4e-05 -1.3e-05 -5.6e-05 -5.7e-05 -5.5e-06 -1.8e-06 -8.5e-07 -5.8e-06 1.2e-05 2.6e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00047 0.00036 0.00047 0.00036 9.9e-05 9.3e-05 0.1 0.089 0.1 0.089 0.049 0.054 0.054 0.066 7.2e-09 6e-09 7.2e-09 6e-09 3.2e-09 2.6e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
119 11690000 0.7 0.0022 0.0018 -0.014 0.71 -0.0064 -0.002 0.013 0.011 -0.0079 0.0038 0.0046 -0.00027 -0.0006 -3.7e+02 -1.4e-05 -1.3e-05 -5.6e-05 -5.7e-05 -5.8e-06 -2.1e-06 -7.5e-07 -5.7e-06 1.2e-05 2.5e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00049 0.00037 0.00049 0.00037 9.8e-05 9.3e-05 0.13 0.11 0.13 0.11 0.046 0.063 0.062 0.063 0.062 0.066 7.2e-09 6e-09 7.2e-09 6e-09 3.1e-09 2.5e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
120 11790000 0.7 0.0022 0.0019 -0.014 0.71 -0.012 -0.008 0.013 0.011 -0.0098 0.0017 0.0021 0.00055 0.00045 -3.7e+02 -1.4e-05 -1.3e-05 -5.6e-05 -5.7e-05 -5.9e-06 -2.2e-06 3.1e-07 -5.2e-06 1.1e-05 -1.2e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.0004 0.00032 0.0004 0.00032 9.8e-05 9.3e-05 0.097 0.087 0.097 0.087 0.039 0.053 0.052 0.053 0.052 0.063 6.4e-09 5.5e-09 6.4e-09 5.5e-09 3e-09 2.5e-09 3.7e-06 3.6e-06 3.7e-06 3.6e-06 1e-06 0 0 0 0 0 0 0 0
121 11890000 0.7 0.0022 0.0019 -0.014 0.71 -0.013 -0.0092 0.014 0.012 -0.011 0.00046 0.0013 0.0019 0.0016 -3.7e+02 -1.4e-05 -1.3e-05 -5.6e-05 -5.7e-05 -6.4e-06 -2.6e-06 2.5e-07 -5.2e-06 1.1e-05 -1.2e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00041 0.00033 0.00041 0.00033 9.8e-05 9.3e-05 0.12 0.1 0.12 0.1 0.037 0.061 0.06 0.061 0.06 0.063 6.4e-09 5.5e-09 6.4e-09 5.5e-09 3e-09 2.4e-09 3.7e-06 3.6e-06 3.7e-06 3.6e-06 1e-06 0 0 0 0 0 0 0 0
122 11990000 0.7 0.0022 0.002 -0.014 0.71 -0.014 -0.011 0.014 0.013 -0.016 -0.00042 -5.7e-05 0.0023 0.0022 -3.7e+02 -1.4e-05 -1.3e-05 -5.6e-05 -5.7e-05 -6.2e-06 -2.5e-06 1.7e-06 -3.9e-06 1.1e-05 -1.6e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.4e-05 0.00034 0.00029 0.00034 0.00029 9.8e-05 9.3e-05 0.091 0.083 0.091 0.083 0.033 0.051 0.051 0.061 5.8e-09 5.1e-09 5.8e-09 5.1e-09 2.9e-09 2.4e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 1e-06 0 0 0 0 0 0 0 0
123 12090000 0.7 0.0022 0.002 -0.014 0.71 -0.016 -0.013 0.016 0.015 -0.022 -0.0019 -0.0013 0.0038 0.0036 -3.7e+02 -1.4e-05 -1.3e-05 -5.6e-05 -5.7e-05 -5.7e-06 -2.2e-06 1.8e-06 -3.8e-06 1.1e-05 -1.8e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00035 0.00029 0.00035 0.00029 9.8e-05 9.3e-05 0.11 0.099 0.11 0.099 0.031 0.06 0.059 0.06 0.059 0.061 5.8e-09 5.1e-09 5.8e-09 5.1e-09 2.8e-09 2.4e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 1e-06 0 0 0 0 0 0 0 0
124 12190000 0.7 0.0019 0.0017 -0.014 0.71 -0.0091 -0.007 0.013 0.012 -0.017 0.0014 0.0015 0.0019 0.002 -3.7e+02 -1.3e-05 -5.7e-05 -5.5e-06 -2.1e-06 4.3e-06 1.6e-07 1.6e-05 5.5e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.0003 0.00026 0.0003 0.00026 9.8e-05 9.3e-05 0.085 0.079 0.085 0.079 0.028 0.051 0.05 0.051 0.05 0.059 5.3e-09 4.8e-09 5.3e-09 4.8e-09 2.8e-09 2.3e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 1e-06 0 0 0 0 0 0 0 0
125 12290000 0.7 0.0018 0.0016 -0.014 0.71 -0.012 -0.0094 0.015 0.014 -0.016 0.00033 0.00069 0.0033 -3.7e+02 -1.3e-05 -5.7e-05 -5.3e-06 -2e-06 4.1e-06 -1.1e-07 1.7e-05 5.7e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00031 0.00027 0.00031 0.00027 9.8e-05 9.3e-05 0.1 0.093 0.1 0.093 0.028 0.06 0.058 0.06 0.058 0.059 5.3e-09 4.8e-09 5.3e-09 4.8e-09 2.7e-09 2.3e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 1e-06 0 0 0 0 0 0 0 0
126 12390000 0.7 0.0015 0.0014 -0.014 0.71 -0.006 -0.0045 0.011 -0.015 0.0029 0.0016 0.0018 -3.7e+02 -1.3e-05 -1.2e-05 -5.8e-05 -5.6e-06 -2.3e-06 5.7e-06 2.8e-06 2e-05 1.1e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00027 0.00024 0.00027 0.00024 9.8e-05 9.3e-05 0.079 0.075 0.079 0.075 0.026 0.05 0.05 0.057 4.9e-09 4.5e-09 4.9e-09 4.5e-09 2.7e-09 2.3e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 1e-06 0 0 0 0 0 0 0 0
127 12490000 0.7 0.0015 0.0013 -0.014 0.71 -0.0073 -0.0056 0.013 -0.018 0.0023 0.0024 0.0029 -3.7e+02 -1.3e-05 -1.2e-05 -5.8e-05 -6.1e-06 -2.7e-06 5.6e-06 2.7e-06 2e-05 1e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00028 0.00025 0.00028 0.00025 9.7e-05 9.3e-05 0.093 0.087 0.093 0.087 0.026 0.059 0.058 0.059 0.058 0.057 4.9e-09 4.5e-09 4.9e-09 4.5e-09 2.6e-09 2.2e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 1e-06 0 0 0 0 0 0 0 0
128 12590000 0.7 0.0016 0.0014 -0.014 0.71 -0.015 -0.013 0.011 -0.023 -0.0028 -0.0027 0.0014 0.0016 -3.7e+02 -1.3e-05 -5.8e-05 -6e-06 -2.7e-06 7e-06 5.5e-06 1.7e-05 5.8e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00025 0.00022 0.00025 0.00022 9.8e-05 9.3e-05 0.074 0.07 0.074 0.07 0.025 0.05 0.049 0.05 0.049 0.055 4.5e-09 4.3e-09 4.5e-09 4.3e-09 2.5e-09 2.2e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.9e-07 0 0 0 0 0 0 0 0
129 12690000 0.7 0.0016 0.0015 -0.014 0.71 -0.015 -0.013 0.012 -0.027 -0.0044 -0.0041 0.0026 0.0028 -3.7e+02 -1.3e-05 -5.8e-05 -6.2e-06 -3e-06 7.2e-06 5.7e-06 1.7e-05 5.6e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00026 0.00023 0.00026 0.00023 9.7e-05 9.3e-05 0.086 0.081 0.086 0.081 0.025 0.058 0.058 0.055 4.5e-09 4.3e-09 4.5e-09 4.3e-09 2.5e-09 2.1e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.8e-07 0 0 0 0 0 0 0 0
130 12790000 0.7 0.0016 0.0015 -0.013 -0.014 0.71 -0.02 -0.019 0.0091 0.0092 -0.03 -0.0077 -0.0075 0.0013 0.0015 -3.7e+02 -1.4e-05 -1.3e-05 -5.8e-05 -6e-06 -2.8e-06 7.6e-06 7.3e-06 1.7e-05 3.9e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00023 0.00021 0.00023 0.00021 9.7e-05 9.3e-05 0.069 0.066 0.069 0.066 0.024 0.049 0.049 0.053 4.3e-09 4e-09 4.3e-09 4e-09 2.4e-09 2.1e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.7e-07 0 0 0 0 0 0 0 0
131 12890000 0.7 0.0016 0.0015 -0.013 -0.014 0.71 -0.022 -0.02 0.0091 -0.029 -0.0098 -0.0094 0.0022 0.0024 -3.7e+02 -1.4e-05 -1.3e-05 -5.8e-05 -5.8e-06 -2.8e-06 6.9e-06 6.7e-06 1.7e-05 4.5e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00024 0.00022 0.00024 0.00022 9.7e-05 9.3e-05 0.079 0.076 0.079 0.076 0.025 0.058 0.057 0.058 0.057 0.054 4.3e-09 4e-09 4.3e-09 4e-09 2.4e-09 2.1e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.6e-07 0 0 0 0 0 0 0 0
132 12990000 0.7 0.0012 -0.014 0.71 -0.0089 -0.0078 0.0065 0.0067 -0.03 -0.0011 0.0011 0.0013 -3.7e+02 -1.3e-05 -1.2e-05 -5.9e-05 -5.1e-06 -2.3e-06 6.8e-06 1.9e-05 9.6e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00022 0.0002 0.00022 0.0002 9.7e-05 9.3e-05 0.064 0.062 0.064 0.062 0.025 0.049 0.049 0.052 4e-09 3.8e-09 4e-09 3.9e-09 2.3e-09 2e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.4e-07 0 0 0 0 0 0 0 0
133 13090000 0.7 0.0012 -0.014 0.71 -0.0097 -0.0084 0.0067 0.0069 -0.03 -0.002 -0.0019 0.0018 0.002 -3.7e+02 -1.3e-05 -1.2e-05 -5.9e-05 -5.8e-05 -5.6e-06 -2.8e-06 6.4e-06 1.9e-05 9.8e-06 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00023 0.00021 0.00023 0.00021 9.7e-05 9.3e-05 0.073 0.071 0.073 0.071 0.025 0.058 0.057 0.058 0.057 0.052 4e-09 3.8e-09 4e-09 3.9e-09 2.3e-09 2e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.4e-07 0 0 0 0 0 0 0 0
134 13190000 0.7 0.001 0.00095 -0.014 0.71 -0.00048 0.00044 0.0061 0.0063 -0.027 0.0044 0.0043 0.0011 0.0013 -3.7e+02 -1.2e-05 -1.1e-05 -5.9e-05 -5.5e-06 -2.8e-06 5e-06 5.1e-06 2e-05 1.3e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.3e-05 0.00021 0.0002 0.00021 0.0002 9.6e-05 9.3e-05 0.06 0.058 0.06 0.058 0.025 0.049 0.049 0.051 3.8e-09 3.7e-09 3.8e-09 3.7e-09 2.2e-09 1.9e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.1e-07 0 0 0 0 0 0 0 0
135 13290000 0.7 0.001 0.00095 -0.014 0.71 -0.00076 0.00026 0.0069 0.0072 -0.024 0.0043 0.0018 0.002 -3.7e+02 -1.2e-05 -1.1e-05 -5.9e-05 -4.9e-06 -2.4e-06 3.7e-06 3.9e-06 2.1e-05 1.4e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.9e-05 9.3e-05 0.00022 0.0002 0.00022 0.0002 9.6e-05 9.3e-05 0.068 0.066 0.068 0.067 0.027 0.057 0.057 0.051 3.8e-09 3.7e-09 3.8e-09 3.7e-09 2.2e-09 1.9e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 9.1e-07 0 0 0 0 0 0 0 0
136 13390000 0.7 0.00085 0.00081 -0.014 0.71 0.00016 0.001 0.0059 0.0062 -0.02 0.0033 0.0032 0.0011 0.0012 -3.7e+02 -1.2e-05 -1.1e-05 -5.9e-05 -4.4e-06 -2e-06 2e-06 2.6e-06 2.1e-05 1.4e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.3e-05 0.00021 0.00019 0.00021 0.00019 9.6e-05 9.3e-05 0.056 0.055 0.056 0.055 0.026 0.049 0.048 0.049 0.048 0.05 3.6e-09 3.5e-09 3.6e-09 3.5e-09 2.1e-09 1.9e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 8.8e-07 0 0 0 0 0 0 0 0
137 13490000 0.7 0.00088 0.00084 -0.014 0.71 -0.00036 0.0006 0.0058 0.0062 -0.019 0.0033 0.0016 0.0018 -3.7e+02 -1.2e-05 -1.1e-05 -5.9e-05 -4e-06 -1.7e-06 1.1e-06 1.8e-06 2.2e-05 1.5e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.3e-05 0.00021 0.0002 0.00021 0.0002 9.6e-05 9.3e-05 0.064 0.063 0.064 0.063 0.028 0.057 0.056 0.057 0.056 0.05 3.6e-09 3.5e-09 3.6e-09 3.5e-09 2.1e-09 1.8e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 8.7e-07 0 0 0 0 0 0 0 0
138 13590000 0.7 0.00082 0.00078 -0.014 0.71 -2.4e-05 0.0008 0.006 0.0064 -0.021 0.0024 0.0023 0.001 0.0012 -3.7e+02 -1.2e-05 -1.1e-05 -5.9e-05 -4.2e-06 -1.9e-06 8.6e-07 1.7e-06 2e-05 1.4e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.3e-05 0.0002 0.00019 0.0002 0.00019 9.6e-05 9.3e-05 0.053 0.052 0.053 0.052 0.028 0.049 0.048 0.049 0.048 0.05 3.5e-09 3.3e-09 3.5e-09 3.4e-09 2e-09 1.8e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 8.4e-07 0 0 0 0 0 0 0 0
139 13690000 0.7 0.00079 0.00076 -0.014 0.71 0.00064 0.0016 0.0078 0.0082 -0.025 0.0024 0.0017 0.0019 -3.7e+02 -1.2e-05 -1.1e-05 -5.9e-05 -3.5e-06 -1.4e-06 1.2e-06 2e-06 2e-05 1.4e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.3e-05 0.00021 0.0002 0.00021 0.0002 9.6e-05 9.3e-05 0.06 0.059 0.06 0.059 0.029 0.056 0.056 0.05 3.5e-09 3.3e-09 3.5e-09 3.4e-09 2e-09 1.8e-09 3.7e-06 3.5e-06 3.7e-06 3.5e-06 8.3e-07 0 0 0 0 0 0 0 0
140 13790000 0.7 0.00067 0.00065 -0.014 0.71 0.0013 0.0021 0.0036 0.0041 -0.027 0.0035 0.0034 -0.00064 -0.00048 -3.7e+02 -1.1e-05 -6e-05 -5.9e-05 -3.5e-06 -1.5e-06 -1e-06 4.8e-07 1.9e-05 1.3e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.3e-05 0.0002 0.00019 0.0002 0.00019 9.5e-05 9.3e-05 0.051 0.05 0.051 0.05 0.029 0.048 0.048 0.049 3.3e-09 3.2e-09 3.3e-09 3.2e-09 1.9e-09 1.7e-09 3.6e-06 3.5e-06 3.6e-06 3.5e-06 7.9e-07 0 0 0 0 0 0 0 0
141 13890000 0.7 0.00064 0.00062 -0.014 0.71 0.0018 0.0026 0.0035 0.004 -0.031 0.0036 0.0037 -0.00031 -9.5e-05 -3.7e+02 -1.1e-05 -6e-05 -5.9e-05 -3.1e-06 -1.2e-06 -7e-07 7.8e-07 1.9e-05 1.3e-05 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.8e-05 9.3e-05 0.00021 0.00019 0.00021 0.00019 9.5e-05 9.3e-05 0.057 0.056 0.057 0.056 0.03 0.056 0.056 0.05 3.3e-09 3.2e-09 3.3e-09 3.2e-09 1.9e-09 1.7e-09 3.6e-06 3.5e-06 3.6e-06 3.5e-06 7.8e-07 0 0 0 0 0 0 0 0
142 13990000 0.7 0.00057 0.00055 -0.014 0.71 0.0021 0.0029 0.001 0.0016 -0.03 0.0044 -0.002 -0.0019 -3.7e+02 -1.1e-05 -6e-05 -2.9e-06 -1.1e-06 -3.4e-06 -1.5e-06 1.8e-05 1.3e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.7e-05 9.2e-05 0.0002 0.00019 0.0002 0.00019 9.5e-05 9.3e-05 0.048 0.048 0.03 0.048 0.048 0.05 3.1e-09 3e-09 3.1e-09 1.8e-09 1.7e-09 3.6e-06 3.5e-06 3.6e-06 3.5e-06 7.4e-07 0 0 0 0 0 0 0 0
143 14090000 0.7 0.00055 0.00054 -0.014 0.71 0.0022 0.003 0.0011 0.0018 -0.031 0.0046 0.0047 -0.0019 -0.0017 -3.7e+02 -1.1e-05 -6e-05 -2.2e-06 -5.4e-07 -3.2e-06 -1.4e-06 1.8e-05 1.3e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.7e-05 9.2e-05 0.0002 0.00019 0.0002 0.00019 9.5e-05 9.3e-05 0.055 0.054 0.055 0.054 0.031 0.056 0.055 0.056 0.055 0.05 3.1e-09 3e-09 3.1e-09 1.8e-09 1.6e-09 3.6e-06 3.5e-06 3.6e-06 3.5e-06 7.3e-07 0 0 0 0 0 0 0 0
144 14190000 0.7 0.00045 0.00044 -0.014 0.71 0.0056 0.0063 0.00062 0.0012 -0.033 0.0068 0.0067 -0.0017 -0.0015 -3.7e+02 -1.1e-05 -6e-05 -1.8e-06 -2.5e-07 -3.1e-06 -1.7e-06 1.5e-05 1.1e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.7e-05 9.2e-05 0.0002 0.00019 0.0002 0.00019 9.5e-05 9.3e-05 0.046 0.046 0.031 0.048 0.048 0.05 3e-09 2.9e-09 3e-09 2.9e-09 1.7e-09 1.6e-09 3.6e-06 3.5e-06 3.6e-06 3.5e-06 6.9e-07 0 0 0 0 0 0 0 0
145 14290000 0.7 0.00045 -0.014 0.71 0.0063 0.0071 0.0014 0.002 -0.032 0.0074 -0.0016 -0.0014 -3.7e+02 -1.1e-05 -6e-05 -1.5e-06 -3.7e-08 -3.7e-06 -2.3e-06 1.5e-05 1.1e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.7e-05 9.2e-05 0.0002 0.00019 0.0002 0.00019 9.4e-05 9.3e-05 0.052 0.052 0.032 0.055 0.055 0.051 3e-09 2.9e-09 3e-09 2.9e-09 1.7e-09 1.6e-09 3.6e-06 3.5e-06 3.6e-06 3.5e-06 6.7e-07 0 0 0 0 0 0 0 0
146 14390000 0.7 0.00037 0.00036 -0.014 0.71 0.0082 0.0089 0.0023 0.0029 -0.034 0.0087 -0.0013 -0.0012 -3.7e+02 -1.1e-05 -1e-05 -6e-05 -8.6e-07 5.2e-07 -3.8e-06 -2.7e-06 1.3e-05 9.3e-06 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.6e-05 9.2e-05 0.00019 0.00018 0.00019 0.00018 9.4e-05 9.3e-05 0.045 0.044 0.045 0.044 0.031 0.048 0.047 0.048 0.047 0.05 2.8e-09 2.8e-09 1.7e-09 1.5e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 6.3e-07 0 0 0 0 0 0 0 0
147 14490000 0.7 0.00035 -0.013 -0.014 0.71 0.0082 0.0089 0.0035 0.0042 -0.037 0.0095 0.0096 -0.0011 -0.00085 -3.7e+02 -1.1e-05 -1e-05 -6e-05 -6.2e-07 6.8e-07 -3.3e-06 -2.2e-06 1.2e-05 8.9e-06 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.6e-05 9.2e-05 0.0002 0.00019 0.0002 0.00019 9.4e-05 9.2e-05 0.051 0.05 0.051 0.05 0.032 0.055 0.055 0.051 2.8e-09 2.8e-09 1.6e-09 1.5e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 6.2e-07 0 0 0 0 0 0 0 0
148 14590000 0.7 0.00034 -0.013 0.71 0.0047 0.0055 0.0019 0.0026 -0.037 0.006 -0.0025 -0.0023 -3.7e+02 -1.1e-05 -6.1e-05 -6e-05 -5.5e-07 7.1e-07 -7e-06 -5.1e-06 1.6e-05 1.3e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.6e-05 9.2e-05 0.00019 0.00018 0.00019 0.00018 9.4e-05 9.3e-05 0.043 0.043 0.031 0.047 0.047 0.051 2.7e-09 2.6e-09 2.7e-09 2.6e-09 1.6e-09 1.5e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 5.8e-07 0 0 0 0 0 0 0 0
149 14690000 0.7 0.0003 0.00029 -0.013 0.71 0.0061 0.0069 -0.0011 -0.00031 -0.034 0.0066 0.0067 -0.0024 -0.0022 -3.7e+02 -1.1e-05 -6.1e-05 -6e-05 -5.6e-08 1.1e-06 -8e-06 -6.1e-06 1.7e-05 1.4e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.6e-05 9.2e-05 0.0002 0.00019 0.0002 0.00019 9.3e-05 9.2e-05 0.049 0.048 0.049 0.048 0.032 0.054 0.054 0.051 2.7e-09 2.6e-09 2.7e-09 2.6e-09 1.5e-09 1.4e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 5.6e-07 0 0 0 0 0 0 0 0
150 14790000 0.7 0.00032 -0.013 0.71 0.0029 0.0037 -0.0026 -0.0019 -0.03 0.0037 0.0038 -0.0034 -0.0032 -3.7e+02 -1.1e-05 -6.1e-05 -6e-05 1.1e-07 1.2e-06 -1.2e-05 -9.4e-06 2.2e-05 1.8e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.5e-05 9.2e-05 0.00019 0.00018 0.00019 0.00018 9.3e-05 9.2e-05 0.042 0.042 0.031 0.047 0.047 0.051 2.5e-09 2.5e-09 1.5e-09 1.4e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 5.3e-07 0 0 0 0 0 0 0 0
151 14890000 0.7 0.00031 -0.013 0.71 0.0045 0.0053 -0.0017 -0.00088 -0.033 0.004 0.0042 -0.0036 -0.0034 -3.7e+02 -1.1e-05 -6.1e-05 -6e-05 4.4e-07 1.5e-06 -1.2e-05 -9.2e-06 2.2e-05 1.8e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.5e-05 9.2e-05 0.0002 0.00019 0.0002 0.00019 9.3e-05 9.2e-05 0.048 0.047 0.048 0.047 0.031 0.054 0.054 0.052 2.5e-09 2.5e-09 1.5e-09 1.4e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 5.1e-07 0 0 0 0 0 0 0 0
152 14990000 0.7 0.00031 -0.013 0.71 0.0033 0.004 -0.0018 -0.0011 -0.029 0.0031 0.0032 -0.0029 -0.0027 -3.7e+02 -1.2e-05 -1.1e-05 -6.1e-05 -6e-05 3.9e-07 1.4e-06 -1.2e-05 -9.9e-06 2.4e-05 2.1e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.5e-05 9.1e-05 0.00019 0.00018 0.00019 0.00018 9.2e-05 0.041 0.041 0.03 0.047 0.047 0.051 2.3e-09 2.3e-09 1.4e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 4.8e-07 0 0 0 0 0 0 0 0
153 15090000 0.7 0.00023 -0.013 0.71 0.0037 0.0045 -0.002 -0.0012 -0.032 0.0035 0.0036 -0.0031 -0.0028 -3.7e+02 -1.2e-05 -1.1e-05 -6.1e-05 -6e-05 4.4e-07 1.4e-06 -1.2e-05 -9.4e-06 2.4e-05 2e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.5e-05 9.1e-05 0.00019 0.00019 9.2e-05 0.046 0.046 0.031 0.054 0.054 0.052 2.3e-09 2.3e-09 1.4e-09 1.3e-09 3.6e-06 3.4e-06 3.6e-06 3.4e-06 4.6e-07 0 0 0 0 0 0 0 0
154 15190000 0.7 0.00025 -0.013 0.71 0.0031 0.0038 -0.0008 -8e-05 -0.029 0.0027 0.0029 -0.0024 -0.0023 -3.7e+02 -1.2e-05 -1.1e-05 -6.1e-05 -6e-05 4.1e-07 1.3e-06 -1.2e-05 -9.7e-06 2.6e-05 2.2e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.5e-05 9.1e-05 0.00019 0.00018 0.00019 0.00018 9.2e-05 0.04 0.04 0.03 0.047 0.047 0.052 2.2e-09 2.2e-09 1.4e-09 1.3e-09 3.5e-06 3.4e-06 3.5e-06 3.4e-06 4.3e-07 0 0 0 0 0 0 0 0
155 15290000 0.7 0.00021 -0.013 0.71 0.0037 0.0045 -0.00064 0.00016 -0.027 0.0031 0.0033 -0.0025 -0.0023 -3.7e+02 -1.2e-05 -1.1e-05 -6.1e-05 -6e-05 7.4e-07 1.6e-06 -1.3e-05 -1e-05 2.6e-05 2.3e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.4e-05 9.1e-05 0.00019 0.00018 0.00019 0.00018 9.2e-05 0.046 0.045 0.046 0.045 0.03 0.054 0.053 0.054 0.053 0.052 2.2e-09 2.2e-09 1.3e-09 3.5e-06 3.4e-06 3.5e-06 3.4e-06 4.2e-07 0 0 0 0 0 0 0 0
156 15390000 0.7 0.00021 -0.013 0.71 0.0029 0.0037 -0.00029 0.00043 -0.024 0.00053 0.00066 -0.002 -0.0019 -3.7e+02 -1.2e-05 -6.1e-05 -6e-05 1.4e-06 2.2e-06 -1.3e-05 -1.1e-05 2.9e-05 2.5e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.4e-05 9.1e-05 0.00018 0.00018 9.1e-05 0.04 0.039 0.04 0.039 0.029 0.047 0.047 0.051 2e-09 2e-09 1.3e-09 3.5e-06 3.4e-06 3.5e-06 3.4e-06 3.9e-07 0 0 0 0 0 0 0 0
157 15490000 0.7 0.00023 -0.013 0.71 0.0042 0.005 -0.00067 0.00013 -0.024 0.00089 0.0011 -0.0021 -0.0019 -3.7e+02 -1.2e-05 -6.1e-05 -6e-05 1.1e-06 1.9e-06 -1.3e-05 -1.1e-05 2.8e-05 2.5e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.4e-05 9.1e-05 0.00019 0.00018 0.00019 0.00018 9.1e-05 0.045 0.044 0.045 0.044 0.029 0.053 0.053 0.053 2e-09 2e-09 1.3e-09 1.2e-09 3.5e-06 3.4e-06 3.5e-06 3.4e-06 3.7e-07 0 0 0 0 0 0 0 0
158 15590000 0.7 0.00025 -0.013 0.71 0.0023 0.0031 -0.00066 5.9e-05 -0.023 -0.0013 -0.0012 -0.0017 -0.0016 -3.7e+02 -1.2e-05 -6.1e-05 -6e-05 9.1e-07 1.7e-06 -1.3e-05 -1.1e-05 3.1e-05 2.7e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.4e-05 9e-05 0.00018 0.00017 0.00018 0.00017 9.1e-05 0.039 0.039 0.028 0.046 0.046 0.052 1.9e-09 1.9e-09 1.2e-09 3.5e-06 3.3e-06 3.5e-06 3.3e-06 3.5e-07 0 0 0 0 0 0 0 0
159 15690000 0.7 0.00025 -0.013 0.71 0.0027 0.0034 -0.00084 -3.7e-05 -0.023 -0.0011 -0.00087 -0.0018 -0.0015 -3.7e+02 -1.2e-05 -6.1e-05 -6e-05 9.4e-07 1.7e-06 -1.3e-05 -1.1e-05 3.1e-05 2.7e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.3e-05 9e-05 0.00018 0.00018 9.1e-05 0.044 0.044 0.028 0.053 0.053 0.052 1.9e-09 1.9e-09 1.2e-09 3.5e-06 3.3e-06 3.5e-06 3.3e-06 3.3e-07 0 0 0 0 0 0 0 0
160 15790000 0.7 0.00021 -0.013 0.71 0.0032 0.0039 -0.0025 -0.0018 -0.026 -0.00099 -0.00083 -0.0028 -0.0026 -3.7e+02 -1.2e-05 -6.1e-05 9.9e-07 1.7e-06 -1.5e-05 -1.3e-05 3.1e-05 2.8e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.3e-05 9e-05 0.00018 0.00017 0.00018 0.00017 9e-05 9.1e-05 0.039 0.038 0.039 0.038 0.027 0.046 0.046 0.051 1.8e-09 1.7e-09 1.8e-09 1.7e-09 1.2e-09 1.1e-09 3.5e-06 3.3e-06 3.5e-06 3.3e-06 3.1e-07 0 0 0 0 0 0 0 0
161 15890000 0.7 0.00016 -0.013 0.71 0.0041 0.0048 -0.003 -0.0022 -0.024 -0.0006 -0.00036 -0.0031 -0.0029 -3.7e+02 -1.2e-05 -6.1e-05 1.1e-06 1.8e-06 -1.6e-05 -1.3e-05 3.1e-05 2.8e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.3e-05 9e-05 0.00018 0.00018 9e-05 9.1e-05 0.043 0.043 0.027 0.053 0.053 0.052 1.8e-09 1.7e-09 1.8e-09 1.7e-09 1.2e-09 1.1e-09 3.5e-06 3.3e-06 3.5e-06 3.3e-06 3e-07 0 0 0 0 0 0 0 0
162 15990000 0.7 0.0001 0.00011 -0.013 0.71 0.004 0.0046 -0.0039 -0.0031 -0.019 -0.00067 -0.0005 -0.0039 -0.0037 -3.7e+02 -1.2e-05 -6.1e-05 1.6e-06 2.2e-06 -1.9e-05 -1.6e-05 3.3e-05 3e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.3e-05 9e-05 0.00017 0.00017 9e-05 9.1e-05 0.038 0.038 0.026 0.046 0.046 0.051 1.6e-09 1.6e-09 1.1e-09 3.4e-06 3.3e-06 3.4e-06 3.3e-06 2.8e-07 0 0 0 0 0 0 0 0
163 16090000 0.7 0.71 0.0001 0.00011 -0.013 0.71 0.0057 0.0064 -0.0041 -0.0033 -0.016 -0.0002 3.8e-05 -0.0043 -0.004 -3.7e+02 -1.2e-05 -6.1e-05 2.2e-06 2.7e-06 -1.9e-05 -1.7e-05 3.4e-05 3.1e-05 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.2e-05 8.9e-05 0.00018 0.00017 0.00018 0.00017 8.9e-05 9e-05 0.043 0.042 0.043 0.042 0.025 0.053 0.053 0.052 1.6e-09 1.6e-09 1.1e-09 3.4e-06 3.3e-06 3.4e-06 3.3e-06 2.7e-07 0 0 0 0 0 0 0 0
164 16190000 0.7 0.71 0.00013 -0.013 0.71 0.0057 0.0064 -0.0033 -0.0026 -0.014 -0.0004 -0.00023 -0.0035 -0.0033 -3.7e+02 -1.2e-05 -6.1e-05 2.3e-06 2.8e-06 -1.8e-05 -1.6e-05 3.6e-05 3.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.2e-05 8.9e-05 0.00017 0.00016 0.00017 0.00016 8.9e-05 9e-05 0.038 0.037 0.038 0.037 0.025 0.046 0.046 0.051 1.5e-09 1.5e-09 1.1e-09 3.4e-06 3.3e-06 3.4e-06 3.3e-06 2.5e-07 0 0 0 0 0 0 0 0
165 16290000 0.71 0.00015 -0.013 0.71 0.0073 0.008 -0.0041 -0.0033 -0.016 0.00025 0.00049 -0.0038 -0.0036 -3.7e+02 -1.2e-05 -6.1e-05 2.9e-06 3.3e-06 -1.8e-05 -1.6e-05 3.6e-05 3.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.2e-05 8.9e-05 0.00017 0.00017 8.9e-05 9e-05 0.042 0.042 0.024 0.053 0.052 0.053 0.052 0.052 1.5e-09 1.5e-09 1.1e-09 1e-09 3.4e-06 3.3e-06 3.4e-06 3.3e-06 2.4e-07 0 0 0 0 0 0 0 0
166 16390000 0.71 0.00014 -0.013 0.71 0.0062 0.0068 -0.0044 -0.0036 -0.015 -7.1e-05 0.00011 -0.0031 -0.0029 -3.7e+02 -1.2e-05 -6.1e-05 2.7e-06 3.2e-06 -1.7e-05 -1.5e-05 3.8e-05 3.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.1e-05 8.9e-05 0.00017 0.00016 0.00017 0.00016 8.9e-05 9e-05 0.037 0.037 0.023 0.046 0.046 0.051 1.4e-09 1.4e-09 1e-09 3.4e-06 3.2e-06 3.4e-06 3.2e-06 2.2e-07 0 0 0 0 0 0 0 0
167 16490000 0.71 0.00015 -0.013 0.71 0.0054 0.0061 -0.0039 -0.0031 -0.018 0.00049 0.00073 -0.0035 -0.0032 -3.7e+02 -1.2e-05 -6.1e-05 2.8e-06 3.3e-06 -1.6e-05 -1.4e-05 3.8e-05 3.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.1e-05 8.9e-05 0.00017 0.00016 0.00017 0.00016 8.9e-05 9e-05 0.042 0.041 0.042 0.041 0.023 0.052 0.052 0.052 1.4e-09 1.4e-09 1e-09 3.4e-06 3.2e-06 3.4e-06 3.2e-06 2.1e-07 0 0 0 0 0 0 0 0
168 16590000 0.71 0.00041 -0.013 0.71 0.0019 0.0025 -0.0012 -0.00049 -0.018 -0.0025 -0.0023 -8.1e-05 0.00012 -3.7e+02 -1.3e-05 -6e-05 2.9e-06 3.4e-06 -9.7e-06 -7.5e-06 4.7e-05 4.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.1e-05 8.9e-05 0.00016 0.00016 8.8e-05 9e-05 0.037 0.036 0.037 0.036 0.022 0.046 0.046 0.051 1.2e-09 1.3e-09 1.2e-09 9.9e-10 9.7e-10 3.3e-06 3.2e-06 3.3e-06 3.2e-06 2e-07 0 0 0 0 0 0 0 0
169 16690000 0.71 0.0004 -0.013 0.71 0.0021 0.0027 -0.00071 3.1e-05 -0.015 -0.0022 -0.002 -0.00018 9.8e-05 -3.7e+02 -1.3e-05 -6e-05 2.7e-06 3.1e-06 -1e-05 -8e-06 4.7e-05 4.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9.1e-05 8.8e-05 0.00017 0.00016 0.00016 8.8e-05 8.9e-05 0.041 0.041 0.022 0.052 0.052 0.051 1.2e-09 1.3e-09 1.2e-09 9.6e-10 9.5e-10 3.3e-06 3.2e-06 3.3e-06 3.2e-06 1.9e-07 0 0 0 0 0 0 0 0
170 16790000 0.71 0.00055 0.00054 -0.013 0.71 -0.0013 -0.00072 0.0015 0.0021 -0.014 -0.0046 -0.0044 0.0025 0.0027 -3.7e+02 -1.3e-05 -6e-05 2.8e-06 3.2e-06 -4.5e-06 -2.2e-06 5.4e-05 5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9e-05 8.8e-05 0.00016 0.00015 0.00016 0.00015 8.8e-05 8.9e-05 0.036 0.036 0.021 0.046 0.046 0.05 1.1e-09 1.1e-09 9.4e-10 3.3e-06 3.2e-06 3.3e-06 3.2e-06 1.8e-07 0 0 0 0 0 0 0 0
171 16890000 0.71 0.00056 -0.013 0.71 -0.0016 -0.00095 0.0023 0.0031 -0.011 -0.0048 -0.0045 0.0027 0.003 -3.7e+02 -1.3e-05 -6e-05 2.7e-06 3.1e-06 -4.9e-06 -2.6e-06 5.5e-05 5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9e-05 8.8e-05 0.00016 0.00016 8.7e-05 8.9e-05 0.04 0.04 0.021 0.052 0.052 0.051 1.1e-09 1.1e-09 9.2e-10 3.3e-06 3.2e-06 3.3e-06 3.2e-06 1.7e-07 0 0 0 0 0 0 0 0
172 16990000 0.71 0.0005 -0.013 0.71 -0.0015 -0.00098 0.00035 0.00099 -0.01 -0.0052 -0.005 0.00085 0.0011 -3.7e+02 -1.3e-05 -6e-05 2.4e-06 2.8e-06 -9e-06 -6.6e-06 5.6e-05 5.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 9e-05 8.8e-05 0.00015 0.00015 8.7e-05 8.9e-05 0.035 0.035 0.02 0.046 0.046 0.05 1e-09 1e-09 9e-10 3.3e-06 3.2e-06 3.3e-06 3.2e-06 1.6e-07 0 0 0 0 0 0 0 0
173 17090000 0.71 0.00047 -0.013 0.71 -0.00074 -0.00014 0.0013 0.002 -0.01 -0.0053 -0.0051 0.00091 0.0012 -3.7e+02 -1.3e-05 -6e-05 2.5e-06 2.9e-06 -8.9e-06 -6.5e-06 5.6e-05 5.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.9e-05 8.8e-05 0.00016 0.00015 0.00016 0.00015 8.7e-05 8.9e-05 0.04 0.039 0.04 0.039 0.02 0.052 0.052 0.05 1e-09 1e-09 8.8e-10 3.3e-06 3.2e-06 3.3e-06 3.2e-06 1.6e-07 0 0 0 0 0 0 0 0
174 17190000 0.71 0.00045 0.00046 -0.013 0.71 -0.00029 0.00024 0.0013 0.0019 -0.011 -0.0056 -0.0054 -0.00053 -0.00032 -3.7e+02 -1.3e-05 -6e-05 2.7e-06 3e-06 -1.2e-05 -1e-05 5.8e-05 5.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.9e-05 8.8e-05 0.00015 0.00015 8.7e-05 8.8e-05 0.035 0.035 0.019 0.046 0.046 0.049 9.4e-10 9.4e-10 8.6e-10 3.3e-06 3.1e-06 3.3e-06 3.1e-06 1.5e-07 0 0 0 0 0 0 0 0
175 17290000 0.71 0.00043 -0.013 0.71 0.0018 0.0024 0.0023 0.003 -0.0066 -0.0056 -0.0053 -0.00037 -9.5e-05 -3.7e+02 -1.4e-05 -1.3e-05 -6e-05 2.5e-06 2.8e-06 -1.3e-05 -1e-05 5.9e-05 5.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.9e-05 8.7e-05 0.00015 0.00015 8.6e-05 8.8e-05 0.039 0.039 0.019 0.052 0.052 0.049 9.4e-10 9.4e-10 8.4e-10 3.3e-06 3.1e-06 3.3e-06 3.1e-06 1.4e-07 0 0 0 0 0 0 0 0
176 17390000 0.71 0.0004 -0.013 0.71 0.0025 0.003 0.0015 0.0021 -0.0047 -0.0047 -0.0045 -0.0016 -0.0014 -3.7e+02 -1.3e-05 -6e-05 2.8e-06 3.1e-06 -1.6e-05 -1.4e-05 5.8e-05 5.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.9e-05 8.7e-05 0.00015 0.00014 0.00015 0.00014 8.6e-05 8.8e-05 0.034 0.034 0.018 0.046 0.046 0.048 8.6e-10 8.5e-10 8.6e-10 8.5e-10 8.3e-10 3.2e-06 3.1e-06 3.2e-06 3.1e-06 1.3e-07 0 0 0 0 0 0 0 0
177 17490000 0.71 0.00039 -0.013 0.71 0.003 0.0035 0.0011 0.0017 -0.003 -0.0044 -0.0042 -0.0015 -0.0012 -3.7e+02 -1.3e-05 -6e-05 2.9e-06 3.1e-06 -1.7e-05 -1.4e-05 5.9e-05 5.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.9e-05 8.7e-05 0.00015 0.00014 0.00015 0.00014 8.6e-05 8.8e-05 0.038 0.038 0.018 0.052 0.052 0.049 8.6e-10 8.5e-10 8.6e-10 8.5e-10 8.1e-10 3.2e-06 3.1e-06 3.2e-06 3.1e-06 1.3e-07 0 0 0 0 0 0 0 0
178 17590000 0.71 0.0003 0.00031 -0.013 0.71 0.0043 0.0047 -9.8e-05 0.00049 0.0025 -0.0037 -0.0035 -0.0026 -0.0024 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 3e-06 3.2e-06 -2e-05 -1.8e-05 5.9e-05 5.7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.8e-05 8.7e-05 0.00014 0.00014 8.6e-05 8.8e-05 0.034 0.034 0.017 0.045 0.045 0.048 7.8e-10 7.7e-10 7.8e-10 7.7e-10 7.9e-10 3.2e-06 3.1e-06 3.2e-06 3.1e-06 1.2e-07 0 0 0 0 0 0 0 0
179 17690000 0.71 0.00027 0.00028 -0.012 -0.013 0.71 0.0052 0.0056 0.00061 0.0012 0.0019 -0.0032 -0.003 -0.0026 -0.0023 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 3.1e-06 3.4e-06 -2e-05 -1.8e-05 5.9e-05 5.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.8e-05 8.6e-05 0.00014 0.00014 8.5e-05 8.7e-05 0.037 0.037 0.017 0.052 0.052 0.048 7.8e-10 7.7e-10 7.8e-10 7.7e-10 7.7e-10 7.8e-10 3.2e-06 3.1e-06 3.2e-06 3.1e-06 1.2e-07 0 0 0 0 0 0 0 0
180 17790000 0.71 0.00018 -0.013 0.71 0.0077 0.0082 0.00033 0.0009 0.00061 0.00058 -0.0021 -0.0019 -0.0022 -0.002 -3.7e+02 -1.3e-05 -6.1e-05 3.7e-06 3.9e-06 -1.9e-05 -1.8e-05 5.6e-05 5.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.8e-05 8.6e-05 0.00014 0.00013 0.00014 0.00013 8.5e-05 8.7e-05 0.033 0.033 0.016 0.045 0.045 0.048 7e-10 7e-10 7.6e-10 3.2e-06 3.1e-06 3.2e-06 3.1e-06 1.1e-07 0 0 0 0 0 0 0 0
181 17890000 0.71 0.00019 -0.013 0.71 0.0093 0.0097 -0.00043 0.00018 0.00071 0.00068 -0.0012 -0.001 -0.0022 -0.0019 -3.7e+02 -1.3e-05 -6.1e-05 3.9e-06 4.2e-06 -1.9e-05 -1.8e-05 5.6e-05 5.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.7e-05 8.6e-05 0.00014 0.00014 8.5e-05 8.7e-05 0.037 0.037 0.016 0.052 0.051 0.052 0.051 0.048 7e-10 7e-10 7.4e-10 7.5e-10 3.2e-06 3.1e-06 3.2e-06 3.1e-06 1.1e-07 0 0 0 0 0 0 0 0
182 17990000 0.71 0.00013 0.00014 -0.013 0.71 0.011 -0.0022 -0.0016 0.0019 -0.00052 -0.00035 -0.0019 -0.0017 -3.7e+02 -1.3e-05 -6.1e-05 3.9e-06 4.1e-06 -1.9e-05 -1.7e-05 5.4e-05 5.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.7e-05 8.6e-05 0.00013 0.00013 8.5e-05 8.7e-05 0.032 0.032 0.016 0.045 0.045 0.047 6.4e-10 6.4e-10 7.3e-10 3.2e-06 3e-06 3.2e-06 3e-06 1e-07 0 0 0 0 0 0 0 0
183 18090000 0.71 0.00014 -0.013 0.71 0.012 -0.0023 -0.0018 0.0043 0.00062 0.00082 -0.0021 -0.0019 -3.7e+02 -1.3e-05 -6.1e-05 3.5e-06 3.8e-06 -1.9e-05 -1.7e-05 5.4e-05 5.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.7e-05 8.6e-05 0.00014 0.00013 0.00014 0.00013 8.4e-05 8.7e-05 0.036 0.036 0.016 0.051 0.051 0.047 6.4e-10 6.4e-10 7.1e-10 7.2e-10 3.2e-06 3e-06 3.2e-06 3e-06 9.7e-08 0 0 0 0 0 0 0 0
184 18190000 0.71 0.00011 -0.013 0.71 0.012 0.013 -0.0013 -0.00074 0.0056 0.0015 0.0016 -0.0017 -0.0015 -3.7e+02 -1.3e-05 -6.1e-05 -6e-05 3.8e-06 4e-06 -1.8e-05 -1.7e-05 5.5e-05 5.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.7e-05 8.5e-05 0.00013 0.00013 8.4e-05 8.6e-05 0.032 0.032 0.015 0.045 0.045 0.047 5.8e-10 5.8e-10 7e-10 3.1e-06 3e-06 3.1e-06 3e-06 9.2e-08 0 0 0 0 0 0 0 0
185 18290000 0.71 4.8e-05 5e-05 -0.012 0.71 0.012 0.013 -0.0018 -0.0013 0.0068 0.0027 0.0029 -0.0018 -0.0016 -3.7e+02 -1.3e-05 -6.1e-05 -6e-05 3.6e-06 3.8e-06 -1.8e-05 -1.7e-05 5.5e-05 5.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.6e-05 8.5e-05 0.00013 0.00013 8.4e-05 8.6e-05 0.035 0.035 0.015 0.051 0.051 0.046 5.8e-10 5.8e-10 6.8e-10 6.9e-10 3.1e-06 3e-06 3.1e-06 3e-06 8.9e-08 0 0 0 0 0 0 0 0
186 18390000 0.71 6.4e-05 6.6e-05 -0.012 -0.013 0.71 0.014 -0.00017 0.00032 0.008 0.0032 0.0034 -0.0014 -0.0012 -3.7e+02 -1.3e-05 -6.1e-05 -6e-05 4e-06 4.1e-06 -1.8e-05 -1.6e-05 5.6e-05 5.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.6e-05 8.5e-05 0.00013 0.00012 0.00013 0.00012 8.4e-05 8.6e-05 0.031 0.031 0.014 0.045 0.045 0.046 5.3e-10 5.2e-10 5.3e-10 5.2e-10 6.7e-10 6.8e-10 3.1e-06 3e-06 3.1e-06 3e-06 8.4e-08 0 0 0 0 0 0 0 0
187 18490000 0.71 7.9e-05 8.1e-05 -0.012 -0.013 0.71 0.014 0.015 0.00024 0.00077 0.0076 0.0047 0.0049 -0.0014 -0.0011 -3.7e+02 -1.3e-05 -6.1e-05 -6e-05 4e-06 4.2e-06 -1.8e-05 -1.6e-05 5.6e-05 5.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.6e-05 8.5e-05 0.00013 0.00013 8.3e-05 8.6e-05 0.034 0.034 0.014 0.051 0.051 0.046 5.3e-10 5.2e-10 5.3e-10 5.2e-10 6.6e-10 3.1e-06 3e-06 3.1e-06 3e-06 8.2e-08 0 0 0 0 0 0 0 0
188 18590000 0.71 8.4e-05 8.6e-05 -0.012 0.71 0.014 0.00048 0.00095 0.0058 0.0036 0.0037 -0.0012 -0.00098 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 -6e-05 4.4e-06 4.6e-06 -1.8e-05 -1.6e-05 5.9e-05 5.7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.6e-05 8.5e-05 0.00012 0.00012 8.3e-05 8.6e-05 0.03 0.03 0.014 0.045 0.045 0.045 4.8e-10 4.8e-10 6.4e-10 6.5e-10 3.1e-06 3e-06 3.1e-06 3e-06 7.8e-08 0 0 0 0 0 0 0 0
189 18690000 0.71 5.3e-05 5.5e-05 -0.012 0.71 0.014 -0.00021 0.00029 0.0039 0.0049 0.0051 -0.0011 -0.00089 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 -6e-05 4.3e-06 4.5e-06 -1.8e-05 -1.6e-05 5.9e-05 5.7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.5e-05 8.4e-05 0.00013 0.00012 0.00013 0.00012 8.3e-05 8.5e-05 0.033 0.033 0.013 0.051 0.051 0.045 4.8e-10 4.8e-10 6.3e-10 6.4e-10 3.1e-06 3e-06 3.1e-06 3e-06 7.5e-08 0 0 0 0 0 0 0 0
190 18790000 0.71 8.3e-05 8.6e-05 -0.012 0.71 0.012 0.013 9.6e-05 0.00054 0.0036 0.0035 0.0038 0.0039 -0.0009 -0.00071 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 4.2e-06 4.4e-06 -1.8e-05 -1.6e-05 6.3e-05 6.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.5e-05 8.4e-05 0.00012 0.00012 8.3e-05 8.5e-05 0.03 0.03 0.013 0.045 0.045 0.045 4.3e-10 4.3e-10 6.2e-10 6.3e-10 3.1e-06 3e-06 3.1e-06 3e-06 7.2e-08 0 0 0 0 0 0 0 0
191 18890000 0.71 0.00011 -0.012 0.71 0.013 0.00059 0.0011 0.0042 0.005 0.0052 -0.00083 -0.0006 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 4.6e-06 4.7e-06 -1.8e-05 -1.6e-05 6.3e-05 6.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.5e-05 8.4e-05 0.00012 0.00012 8.2e-05 8.5e-05 0.033 0.033 0.013 0.051 0.051 0.045 4.3e-10 4.3e-10 6e-10 6.2e-10 3.1e-06 3e-06 3.1e-06 3e-06 7e-08 6.9e-08 0 0 0 0 0 0 0 0
192 18990000 0.71 9.4e-05 9.6e-05 -0.012 0.71 0.014 0.0015 0.0019 0.0028 0.0064 0.0065 -0.00069 -0.00051 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 4.8e-06 4.9e-06 -1.8e-05 -1.6e-05 6.2e-05 6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.5e-05 8.4e-05 0.00012 0.00012 0.00011 8.2e-05 8.5e-05 0.029 0.029 0.012 0.045 0.045 0.044 3.9e-10 3.9e-10 5.9e-10 6e-10 3.1e-06 2.9e-06 3.1e-06 2.9e-06 6.6e-08 0 0 0 0 0 0 0 0
193 19090000 0.71 7.8e-05 8.1e-05 -0.012 0.71 0.015 0.0021 0.0025 0.0059 0.0058 0.0078 0.008 -0.00049 -0.00026 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 4.8e-06 4.9e-06 -1.8e-05 -1.6e-05 6.2e-05 6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.5e-05 8.4e-05 0.00012 0.00012 8.2e-05 8.5e-05 0.032 0.032 0.012 0.051 0.051 0.044 3.9e-10 3.9e-10 5.8e-10 5.9e-10 3.1e-06 2.9e-06 3.1e-06 2.9e-06 6.5e-08 0 0 0 0 0 0 0 0
194 19190000 0.71 8.1e-05 8.3e-05 -0.012 0.71 0.015 0.0021 0.0025 0.0059 0.0086 0.0087 -0.00044 -0.00026 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 4.9e-06 5e-06 -1.8e-05 -1.7e-05 6.2e-05 6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.4e-05 8.3e-05 0.00012 0.00011 0.00012 0.00011 8.2e-05 8.4e-05 0.028 0.028 0.012 0.045 0.045 0.044 3.6e-10 3.6e-10 5.7e-10 5.8e-10 3e-06 2.9e-06 3e-06 2.9e-06 6.2e-08 0 0 0 0 0 0 0 0
195 19290000 0.71 0.0001 0.00011 -0.012 0.71 0.015 0.0013 0.0018 0.0086 0.01 -0.00025 -2.8e-05 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 4.8e-06 4.9e-06 -1.8e-05 -1.7e-05 6.2e-05 6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.4e-05 8.3e-05 0.00012 0.00011 0.00012 0.00011 8.1e-05 8.4e-05 0.031 0.031 0.012 0.05 0.05 0.044 3.6e-10 3.6e-10 5.6e-10 5.7e-10 3e-06 2.9e-06 3e-06 2.9e-06 6e-08 0 0 0 0 0 0 0 0
196 19390000 0.71 0.00012 -0.012 0.71 0.013 0.00042 0.0008 0.012 0.0081 0.0082 -0.00027 -9e-05 -3.7e+02 -1.4e-05 -6.1e-05 4.9e-06 5e-06 -1.9e-05 -1.7e-05 6.6e-05 6.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.4e-05 8.3e-05 0.00011 0.00011 8.1e-05 8.4e-05 0.027 0.027 0.012 0.044 0.044 0.043 3.3e-10 3.3e-10 5.5e-10 5.6e-10 3e-06 2.9e-06 3e-06 2.9e-06 5.8e-08 0 0 0 0 0 0 0 0
197 19490000 0.71 0.00014 -0.012 0.71 0.012 -0.00029 0.00011 0.0088 0.0093 0.0094 -0.00027 -4.8e-05 -3.7e+02 -1.4e-05 -6.1e-05 5.2e-06 5.3e-06 -1.9e-05 -1.7e-05 6.6e-05 6.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.4e-05 8.3e-05 0.00011 0.00011 8.1e-05 8.4e-05 0.03 0.03 0.011 0.05 0.05 0.043 3.3e-10 3.3e-10 5.4e-10 5.5e-10 3e-06 2.9e-06 3e-06 2.9e-06 5.6e-08 0 0 0 0 0 0 0 0
198 19590000 0.71 0.00019 -0.012 0.71 0.0098 0.01 -0.0013 -0.00096 0.0081 0.0075 0.0076 -0.00029 -0.00011 -3.7e+02 -1.4e-05 -6.1e-05 5.5e-06 5.6e-06 -1.9e-05 -1.7e-05 6.9e-05 6.7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.3e-05 0.00011 0.00011 8.1e-05 8.4e-05 0.027 0.027 0.011 0.044 0.044 0.042 3e-10 3e-10 5.3e-10 5.4e-10 3e-06 2.9e-06 3e-06 2.9e-06 5.4e-08 0 0 0 0 0 0 0 0
199 19690000 0.71 0.00019 -0.012 0.71 0.01 -0.0035 -0.0031 0.0096 0.0085 0.0086 -0.00053 -0.00032 -3.7e+02 -1.4e-05 -6.1e-05 5.4e-06 5.5e-06 -1.9e-05 -1.7e-05 6.9e-05 6.7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.3e-05 8.2e-05 0.00011 0.00011 8e-05 8.3e-05 0.029 0.029 0.011 0.05 0.05 0.042 3e-10 3e-10 5.2e-10 5.3e-10 3e-06 2.9e-06 3e-06 2.9e-06 5.2e-08 0 0 0 0 0 0 0 0
200 19790000 0.71 0.00026 -0.012 0.71 0.0078 0.008 -0.0043 -0.004 0.01 0.0069 0.007 -0.00043 -0.00026 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 5.4e-06 5.5e-06 -1.8e-05 -1.7e-05 7.1e-05 7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.3e-05 8.2e-05 0.00011 0.00011 8e-05 8.3e-05 0.026 0.026 0.011 0.044 0.044 0.042 2.7e-10 2.7e-10 5.1e-10 5.2e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
201 19890000 0.71 0.0002 0.00021 -0.012 0.71 0.0066 0.0068 -0.0046 -0.0043 0.011 0.0076 0.0077 -0.00089 -0.00069 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 5.8e-06 5.9e-06 -1.8e-05 -1.7e-05 7.1e-05 7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.3e-05 8.2e-05 0.00011 0.00011 8e-05 8.3e-05 0.029 0.029 0.011 0.05 0.05 0.042 2.7e-10 2.7e-10 5e-10 5.1e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
202 19990000 0.71 0.00019 -0.012 0.71 0.0041 0.0043 -0.0053 -0.005 0.014 0.0062 0.0063 -0.00075 -0.00058 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 6.3e-06 6.4e-06 -1.8e-05 -1.6e-05 7.3e-05 7.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.2e-05 0.00011 0.0001 0.00011 0.0001 8e-05 8.3e-05 0.026 0.026 0.01 0.044 0.044 0.041 2.5e-10 2.5e-10 4.9e-10 5e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
203 20090000 0.71 0.00018 0.00019 -0.012 0.71 0.0039 0.0041 -0.0073 -0.0069 0.014 0.0066 0.0067 -0.0014 -0.0012 -3.7e+02 -1.4e-05 -6.1e-05 -6e-05 6.7e-06 6.8e-06 -1.8e-05 -1.6e-05 7.3e-05 7.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.2e-05 0.00011 0.0001 0.00011 0.0001 8e-05 8.3e-05 0.028 0.028 0.01 0.049 0.049 0.042 2.5e-10 2.5e-10 4.8e-10 4.9e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
204 20190000 0.71 0.00029 -0.012 0.71 0.0015 0.0017 -0.008 -0.0077 0.017 0.0043 0.0044 -0.0011 -0.00091 -3.7e+02 -1.4e-05 -6e-05 6.9e-06 7e-06 -1.7e-05 -1.5e-05 7.6e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.2e-05 0.0001 0.0001 7.9e-05 8.2e-05 0.025 0.025 0.01 0.044 0.044 0.041 2.3e-10 2.3e-10 4.7e-10 4.8e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
205 20290000 0.71 0.00025 -0.012 0.71 0.00042 0.00059 -0.0095 -0.0092 0.015 0.0044 0.0045 -0.0019 -0.0018 -3.7e+02 -1.4e-05 -6e-05 7e-06 7.1e-06 -1.7e-05 -1.5e-05 7.6e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.2e-05 8.1e-05 0.00011 0.0001 0.00011 0.0001 7.9e-05 8.2e-05 0.027 0.027 0.0099 0.049 0.049 0.041 2.3e-10 2.3e-10 4.6e-10 4.7e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
206 20390000 0.71 0.00027 -0.012 0.71 -0.002 -0.0019 -0.01 -0.0098 0.017 0.0025 0.0026 -0.0015 -0.0014 -3.7e+02 -1.4e-05 -6e-05 7e-06 7.1e-06 -1.5e-05 -1.3e-05 7.8e-05 7.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.2e-05 8.1e-05 0.0001 0.0001 7.9e-05 8.2e-05 0.024 0.024 0.0097 0.044 0.044 0.041 2.1e-10 2.1e-10 4.5e-10 4.7e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
207 20490000 0.71 0.00032 0.00033 -0.012 0.71 -0.0025 -0.0023 -0.011 0.016 0.0022 0.0023 -0.0026 -0.0024 -3.7e+02 -1.4e-05 -6e-05 6.9e-06 7e-06 -1.5e-05 -1.3e-05 7.8e-05 7.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.1e-05 0.0001 0.0001 7.9e-05 8.2e-05 0.027 0.026 0.027 0.026 0.0096 0.049 0.049 0.041 2.1e-10 2.1e-10 4.5e-10 4.6e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
208 20590000 0.71 0.00034 0.00035 -0.012 0.71 -0.0022 -0.002 -0.011 0.013 0.0019 0.002 -0.0021 -0.0019 -3.7e+02 -1.4e-05 -6e-05 6.8e-06 -1.3e-05 -1.1e-05 7.8e-05 7.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.1e-05 0.0001 9.9e-05 0.0001 9.9e-05 7.9e-05 8.2e-05 0.024 0.024 0.0094 0.044 0.044 0.04 1.9e-10 2e-10 1.9e-10 4.4e-10 4.5e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
209 20690000 0.71 0.00037 -0.012 0.71 -0.0021 -0.002 -0.012 0.015 0.0017 0.0018 -0.0032 -0.003 -3.7e+02 -1.4e-05 -6e-05 6.9e-06 -1.3e-05 -1.1e-05 7.8e-05 7.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.1e-05 0.0001 0.0001 9.9e-05 7.8e-05 8.2e-05 0.026 0.026 0.0093 0.049 0.049 0.04 2e-10 1.9e-10 2e-10 1.9e-10 4.3e-10 4.4e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
210 20790000 0.71 0.0004 -0.012 0.71 -0.0033 -0.0031 -0.011 0.015 0.0014 0.0015 -0.0025 -0.0024 -3.7e+02 -1.4e-05 -6e-05 6.9e-06 7e-06 -1.1e-05 -9.6e-06 7.8e-05 7.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8.1e-05 8e-05 0.0001 9.7e-05 0.0001 9.7e-05 7.8e-05 8.1e-05 0.023 0.023 0.0091 0.043 0.043 0.04 1.8e-10 1.8e-10 4.2e-10 4.3e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
211 20890000 0.71 0.00038 0.00039 -0.012 0.71 -0.0037 -0.0036 -0.014 -0.013 0.014 0.001 0.0012 -0.0038 -0.0036 -3.7e+02 -1.4e-05 -6e-05 7.2e-06 -1.2e-05 -9.6e-06 7.8e-05 7.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8e-05 0.0001 9.8e-05 0.0001 9.8e-05 7.8e-05 8.1e-05 0.025 0.025 0.0091 0.049 0.049 0.04 1.8e-10 1.8e-10 4.1e-10 4.3e-10 3e-06 2.9e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
212 20990000 0.71 0.00039 -0.012 0.71 -0.0039 -0.0038 -0.014 0.015 0.0027 0.0028 -0.0031 -0.003 -3.7e+02 -1.4e-05 -6e-05 7.2e-06 -9.4e-06 -7.6e-06 7.7e-05 7.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8e-05 9.9e-05 9.6e-05 9.9e-05 9.6e-05 7.8e-05 8.1e-05 0.023 0.023 0.0089 0.043 0.043 0.039 1.7e-10 1.7e-10 4.1e-10 4.2e-10 3e-06 2.8e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
213 21090000 0.71 0.00039 -0.012 0.71 -0.0041 -0.004 -0.017 0.015 0.0023 0.0024 -0.0046 -0.0045 -3.7e+02 -1.4e-05 -6e-05 7.3e-06 7.4e-06 -9.4e-06 -7.6e-06 7.7e-05 7.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8e-05 9.9e-05 9.7e-05 9.9e-05 9.6e-05 7.8e-05 8.1e-05 0.025 0.025 0.0089 0.048 0.048 0.039 1.7e-10 1.7e-10 4e-10 4.1e-10 3e-06 2.8e-06 3e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
214 21190000 0.71 0.00042 -0.012 0.71 -0.0033 -0.0032 -0.016 -0.015 0.014 0.0038 -0.0038 -0.0037 -3.7e+02 -1.4e-05 -6e-05 7.2e-06 7.3e-06 -7e-06 -5.3e-06 7.6e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8e-05 9.8e-05 9.5e-05 9.7e-05 9.4e-05 7.7e-05 8.1e-05 0.022 0.022 0.0087 0.043 0.043 0.039 1.5e-10 1.5e-10 3.9e-10 4.1e-10 3e-06 2.8e-06 3e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
215 21290000 0.71 0.00046 -0.012 0.71 -0.0039 -0.0038 -0.018 0.016 0.0034 0.0035 -0.0054 -0.0053 -3.7e+02 -1.4e-05 -6e-05 7.5e-06 7.6e-06 -7e-06 -5.3e-06 7.6e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 8e-05 7.9e-05 9.8e-05 9.5e-05 9.8e-05 9.5e-05 7.7e-05 8e-05 0.024 0.024 0.0086 0.048 0.048 0.039 1.5e-10 1.5e-10 3.9e-10 4e-10 3e-06 2.8e-06 3e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
216 21390000 0.71 0.00051 -0.012 0.71 -0.0047 -0.0046 -0.017 0.016 0.0029 -0.0034 -0.0033 -3.7e+02 -1.4e-05 -6e-05 7.3e-06 7.4e-06 -3.2e-06 -1.6e-06 7.6e-05 7.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.9e-05 9.6e-05 9.4e-05 9.6e-05 9.3e-05 7.7e-05 8e-05 0.022 0.022 0.0085 0.043 0.043 0.039 1.4e-10 1.4e-10 3.8e-10 3.9e-10 2.9e-06 2.8e-06 3e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
217 21490000 0.71 0.00052 -0.012 0.71 -0.0052 -0.0051 -0.018 0.015 0.0023 0.0024 -0.0052 -0.005 -3.7e+02 -1.4e-05 -6e-05 7.4e-06 7.5e-06 -3.3e-06 -1.6e-06 7.6e-05 7.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.9e-05 9.7e-05 9.4e-05 9.7e-05 9.4e-05 7.7e-05 8e-05 0.023 0.023 0.0085 0.048 0.048 0.038 1.4e-10 1.4e-10 3.7e-10 3.9e-10 2.9e-06 2.8e-06 3e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
218 21590000 0.71 0.00054 -0.012 0.71 -0.0058 -0.0057 -0.015 0.015 0.0019 0.002 -0.0032 -0.003 -3.7e+02 -1.4e-05 -6e-05 7.4e-06 1.8e-07 1.8e-06 7.6e-05 7.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.9e-05 9.5e-05 9.2e-05 9.5e-05 9.2e-05 7.7e-05 8e-05 0.021 0.021 0.0083 0.043 0.043 0.038 1.3e-10 1.3e-10 3.7e-10 3.8e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
219 21690000 0.71 0.00055 -0.012 0.71 -0.0056 -0.0055 -0.016 0.017 0.0014 0.0015 -0.0048 -0.0046 -3.7e+02 -1.4e-05 -6e-05 7.4e-06 7.5e-06 1.7e-07 1.8e-06 7.6e-05 7.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.9e-05 9.6e-05 9.3e-05 9.6e-05 9.3e-05 7.7e-05 8e-05 0.023 0.023 0.0084 0.048 0.048 0.038 1.3e-10 1.3e-10 3.6e-10 3.7e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
220 21790000 0.71 0.00057 -0.012 0.71 -0.0062 -0.011 0.015 0.00011 0.00018 -0.00075 -0.00063 -3.7e+02 -1.4e-05 -5.9e-05 7.2e-06 7.3e-06 5.4e-06 7.1e-06 7.7e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.9e-05 9.4e-05 9.1e-05 9.4e-05 9.1e-05 7.6e-05 8e-05 0.021 0.021 0.0082 0.042 0.042 0.038 1.2e-10 1.3e-10 1.2e-10 3.6e-10 3.7e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
221 21890000 0.71 0.00057 -0.012 0.71 -0.0062 -0.0061 -0.012 0.016 -0.00052 -0.00044 -0.0019 -0.0018 -3.7e+02 -1.4e-05 -5.9e-05 7.2e-06 7.3e-06 5.3e-06 7e-06 7.7e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.8e-05 9.5e-05 9.2e-05 9.5e-05 9.2e-05 7.6e-05 7.9e-05 0.022 0.022 0.0082 0.047 0.047 0.038 1.3e-10 1.2e-10 1.3e-10 3.5e-10 3.6e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
222 21990000 0.71 0.00062 -0.012 0.71 -0.0067 -0.0066 -0.0091 -0.0089 0.016 -0.0014 0.0015 0.0016 -3.7e+02 -1.4e-05 -5.9e-05 7.2e-06 9.7e-06 1.1e-05 7.7e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.8e-05 9.3e-05 9.1e-05 9.3e-05 9e-05 7.6e-05 7.9e-05 0.02 0.02 0.0081 0.042 0.042 0.038 1.2e-10 1.2e-10 3.4e-10 3.5e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
223 22090000 0.71 0.00064 0.00063 -0.012 0.71 -0.0071 -0.007 -0.0082 -0.008 0.015 -0.0021 -0.002 0.00063 0.00076 -3.7e+02 -1.4e-05 -5.9e-05 7.1e-06 7.2e-06 9.6e-06 1.1e-05 7.7e-05 7.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.8e-05 9.4e-05 9.1e-05 9.4e-05 9.1e-05 7.6e-05 7.9e-05 0.022 0.022 0.0081 0.047 0.047 0.038 1.2e-10 1.2e-10 3.4e-10 3.5e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
224 22190000 0.71 0.00061 0.0006 -0.012 0.71 -0.0069 -0.0068 -0.0073 -0.0072 0.015 -0.0018 -0.0017 0.00059 0.0007 -3.7e+02 -1.4e-05 -5.9e-05 7.1e-06 7.2e-06 1e-05 1.2e-05 7.7e-05 7.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.8e-05 9.3e-05 9e-05 9.2e-05 8.9e-05 7.6e-05 7.9e-05 0.02 0.02 0.008 0.042 0.042 0.037 1.1e-10 1.1e-10 3.3e-10 3.4e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
225 22290000 0.71 0.00065 0.00064 -0.012 0.71 -0.0082 -0.0081 -0.0081 -0.0079 0.015 -0.0025 -0.0024 -0.00019 -6.5e-05 -3.7e+02 -1.4e-05 -5.9e-05 7e-06 7.1e-06 1e-05 1.2e-05 7.7e-05 7.3e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.8e-05 9.3e-05 9e-05 9.3e-05 9e-05 7.5e-05 7.9e-05 0.021 0.021 0.008 0.047 0.047 0.037 1.1e-10 1.1e-10 3.3e-10 3.4e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
226 22390000 0.71 0.00062 -0.012 0.71 -0.0088 -0.0087 -0.0075 -0.0074 0.017 -0.0022 -0.0021 -0.00018 -7.3e-05 -3.7e+02 -1.4e-05 -5.9e-05 7.1e-06 1.1e-05 1.3e-05 7.6e-05 7.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.8e-05 9.2e-05 8.9e-05 9.2e-05 8.9e-05 7.5e-05 7.8e-05 0.019 0.019 0.0079 0.042 0.042 0.037 1e-10 1e-10 3.2e-10 3.3e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
227 22490000 0.71 0.00063 0.00062 -0.012 0.71 -0.0094 -0.0075 -0.0073 0.018 -0.0031 -0.003 -0.00095 -0.00083 -3.7e+02 -1.4e-05 -5.9e-05 7e-06 7.1e-06 1.1e-05 1.3e-05 7.6e-05 7.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.7e-05 7.8e-05 9.2e-05 8.9e-05 9.2e-05 8.9e-05 7.5e-05 7.8e-05 0.021 0.021 0.0079 0.047 0.047 0.037 1e-10 1e-10 3.2e-10 3.3e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
228 22590000 0.71 0.00061 0.0006 -0.012 0.71 -0.0092 -0.0091 -0.007 -0.0068 0.017 -0.0034 -0.0033 0.00014 0.00024 -3.7e+02 -1.4e-05 -5.9e-05 7e-06 7.1e-06 1.3e-05 1.4e-05 7.5e-05 7.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.7e-05 9.1e-05 8.8e-05 9.1e-05 8.8e-05 7.5e-05 7.8e-05 0.019 0.019 0.0078 0.042 0.042 0.036 9.7e-11 9.7e-11 3.1e-10 3.2e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
229 22690000 0.71 0.00064 -0.012 0.71 -0.01 -0.0067 -0.0066 0.018 -0.0043 -0.00054 -0.00043 -3.7e+02 -1.4e-05 -5.9e-05 7.1e-06 1.3e-05 1.4e-05 7.5e-05 7.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.7e-05 9.1e-05 8.9e-05 9.1e-05 8.8e-05 7.5e-05 7.8e-05 0.02 0.02 0.0079 0.046 0.046 0.037 9.7e-11 9.7e-11 3.1e-10 3.2e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
230 22790000 0.71 0.00063 0.00062 -0.012 0.71 -0.011 -0.0055 -0.0054 0.019 -0.0055 -0.0054 -0.00044 -0.00034 -3.7e+02 -1.4e-05 -5.9e-05 6.7e-06 6.8e-06 1.3e-05 1.5e-05 7.4e-05 7.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.7e-05 9e-05 8.7e-05 9e-05 8.7e-05 7.5e-05 7.8e-05 0.019 0.019 0.0078 0.042 0.042 0.036 9.2e-11 9.2e-11 3e-10 3.1e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
231 22890000 0.71 0.00064 0.00063 -0.012 0.71 -0.012 -0.0051 -0.005 0.021 -0.0066 -0.0065 -0.00097 -0.00086 -3.7e+02 -1.4e-05 -5.9e-05 6.6e-06 6.7e-06 1.3e-05 1.5e-05 7.4e-05 7.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.7e-05 9.1e-05 8.8e-05 9.1e-05 8.8e-05 7.4e-05 7.8e-05 0.02 0.02 0.0078 0.046 0.046 0.036 9.2e-11 9.2e-11 3e-10 3.1e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
232 22990000 0.71 0.00062 -0.012 0.71 -0.012 -0.0056 -0.0055 0.022 -0.0074 -0.0073 -0.00086 -0.00077 -3.7e+02 -1.4e-05 -5.9e-05 6.7e-06 6.8e-06 1.4e-05 1.5e-05 7.3e-05 7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.7e-05 9e-05 8.7e-05 8.9e-05 8.7e-05 7.4e-05 7.8e-05 0.018 0.018 0.0078 0.041 0.041 0.036 8.7e-11 8.7e-11 2.9e-10 3e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
233 23090000 0.71 0.00059 0.00058 -0.012 0.71 -0.013 -0.0056 -0.0055 0.022 -0.0086 -0.0014 -0.0013 -3.7e+02 -1.4e-05 -5.9e-05 6.5e-06 1.4e-05 1.5e-05 7.3e-05 7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.6e-05 7.7e-05 9e-05 8.7e-05 9e-05 8.7e-05 7.4e-05 7.7e-05 0.02 0.02 0.0078 0.046 0.046 0.036 8.7e-11 8.7e-11 2.9e-10 3e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
234 23190000 0.71 0.00065 -0.012 0.71 -0.014 -0.0066 -0.0064 0.024 -0.012 -0.0013 -0.0012 -3.7e+02 -1.4e-05 -5.9e-05 6.4e-06 6.5e-06 1.5e-05 1.6e-05 7.5e-05 7.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.6e-05 8.9e-05 8.6e-05 8.9e-05 8.6e-05 7.4e-05 7.7e-05 0.018 0.018 0.0077 0.041 0.041 0.036 8.2e-11 8.2e-11 2.8e-10 2.9e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
235 23290000 0.71 0.00059 -0.012 0.71 -0.015 -0.0078 -0.0077 0.024 -0.013 -0.002 -0.0019 -3.7e+02 -1.4e-05 -5.9e-05 6.4e-06 6.5e-06 1.4e-05 1.6e-05 7.5e-05 7.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.6e-05 8.9e-05 8.7e-05 8.9e-05 8.6e-05 7.4e-05 7.7e-05 0.019 0.019 0.0078 0.046 0.046 0.036 8.2e-11 8.2e-11 2.8e-10 2.9e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
236 23390000 0.71 0.00068 -0.012 0.71 -0.016 -0.008 -0.0079 0.022 -0.016 -0.0018 -0.0017 -3.7e+02 -1.4e-05 -5.9e-05 6.4e-06 1.5e-05 1.7e-05 7.6e-05 7.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.6e-05 8.9e-05 8.6e-05 8.8e-05 8.5e-05 7.4e-05 7.7e-05 0.018 0.018 0.0077 0.041 0.041 0.036 7.8e-11 7.8e-11 2.8e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
237 23490000 0.71 0.0031 -0.0096 0.71 -0.023 -0.0089 -0.0088 -0.012 -0.018 -0.0026 -0.0025 -3.7e+02 -1.4e-05 -5.9e-05 6.5e-06 1.5e-05 1.6e-05 7.6e-05 7.2e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.6e-05 8.9e-05 8.6e-05 8.9e-05 8.6e-05 7.3e-05 7.7e-05 0.019 0.019 0.0078 0.045 0.045 0.036 7.8e-11 7.8e-11 2.7e-10 2.8e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
238 23590000 0.71 0.0083 -0.0017 -0.0018 0.71 -0.034 -0.033 -0.0076 -0.0075 -0.044 -0.017 -0.0013 -0.0012 -3.7e+02 -1.4e-05 -5.9e-05 6.3e-06 6.4e-06 1.7e-05 1.8e-05 7.4e-05 7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.5e-05 7.6e-05 8.8e-05 8.5e-05 8.8e-05 8.5e-05 7.3e-05 7.7e-05 0.017 0.017 0.0077 0.041 0.041 0.035 7.4e-11 7.4e-11 2.7e-10 2.8e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
239 23690000 0.71 0.0079 0.004 0.71 -0.065 -0.016 -0.094 -0.021 -0.0024 -0.0023 -3.7e+02 -1.4e-05 -5.9e-05 6.3e-06 1.7e-05 1.9e-05 7.4e-05 7e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.5e-05 7.6e-05 8.8e-05 8.5e-05 8.8e-05 8.5e-05 7.3e-05 7.6e-05 0.019 0.019 0.0078 0.045 0.045 0.036 7.4e-11 7.4e-11 2.6e-10 2.7e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
240 23790000 0.71 0.005 0.00067 0.00065 0.71 -0.089 -0.027 -0.15 -0.021 -0.0017 -3.7e+02 -1.4e-05 -5.9e-05 6.3e-06 2e-05 2.1e-05 6.8e-05 6.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.5e-05 8.7e-05 8.5e-05 8.7e-05 8.4e-05 7.3e-05 7.6e-05 0.017 0.017 0.0077 0.041 0.041 0.035 7.1e-11 7.1e-11 2.6e-10 2.7e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
241 23890000 0.71 0.0024 -0.0054 0.71 -0.11 -0.036 -0.2 -0.03 -0.005 -0.0049 -3.7e+02 -1.4e-05 -5.9e-05 6.2e-06 6.3e-06 2e-05 2.1e-05 6.8e-05 6.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.5e-05 8.8e-05 8.5e-05 8.8e-05 8.5e-05 7.3e-05 7.6e-05 0.019 0.019 0.0078 0.045 0.045 0.035 7.1e-11 7.1e-11 2.5e-10 2.6e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
242 23990000 0.71 0.00097 0.00096 -0.01 0.71 -0.11 -0.04 -0.039 -0.25 -0.034 -0.0082 -0.0081 -3.7e+02 -1.4e-05 -5.9e-05 6.3e-06 2.1e-05 2.2e-05 6.4e-05 6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.5e-05 8.7e-05 8.4e-05 8.7e-05 8.4e-05 7.3e-05 7.6e-05 0.017 0.017 0.0077 0.041 0.041 0.035 6.7e-11 6.7e-11 2.5e-10 2.6e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
243 24090000 0.71 0.0023 0.0022 -0.0088 0.71 -0.11 -0.04 -0.3 -0.045 -0.012 -3.7e+02 -1.4e-05 -5.9e-05 6.4e-06 2.1e-05 2.2e-05 6.4e-05 6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.5e-05 8.7e-05 8.4e-05 8.7e-05 8.4e-05 7.3e-05 7.6e-05 0.018 0.018 0.0078 0.045 0.045 0.035 6.7e-11 6.7e-11 2.5e-10 2.6e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
244 24190000 0.71 0.0033 -0.0065 0.71 -0.11 -0.041 -0.35 -0.046 -0.014 -3.7e+02 -1.4e-05 -5.9e-05 6.4e-06 2.4e-05 5.9e-05 5.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.4e-05 7.5e-05 8.6e-05 8.3e-05 8.6e-05 8.3e-05 7.2e-05 7.6e-05 0.017 0.017 0.0077 0.04 0.04 0.035 6.4e-11 6.4e-11 2.4e-10 2.5e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
245 24290000 0.71 0.0038 -0.0057 0.71 -0.12 -0.045 -0.41 -0.058 -0.018 -3.7e+02 -1.4e-05 -5.9e-05 6.3e-06 2.4e-05 5.9e-05 5.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.4e-05 7.5e-05 8.7e-05 8.4e-05 8.6e-05 8.3e-05 7.2e-05 7.6e-05 0.018 0.018 0.0078 0.045 0.045 0.036 6.4e-11 6.4e-11 2.4e-10 2.5e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
246 24390000 0.71 0.0039 -0.0059 0.71 -0.13 -0.052 -0.46 -0.064 -0.03 -3.7e+02 -1.3e-05 -5.9e-05 6.1e-06 2.1e-05 5.5e-05 5.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.4e-05 7.5e-05 8.6e-05 8.3e-05 8.5e-05 8.3e-05 7.2e-05 7.5e-05 0.017 0.017 0.0078 0.04 0.04 0.035 6.2e-11 6.2e-11 2.4e-10 2.5e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
247 24490000 0.71 0.0047 -0.0017 -0.0018 0.71 -0.14 -0.057 -0.51 -0.077 -0.035 -3.7e+02 -1.3e-05 -5.9e-05 6.1e-06 2.1e-05 5.5e-05 5.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.4e-05 8.6e-05 8.3e-05 8.6e-05 8.3e-05 7.2e-05 7.5e-05 0.018 0.018 0.0078 0.045 0.045 0.035 6.2e-11 6.2e-11 2.3e-10 2.4e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
248 24590000 0.71 0.0052 0.0019 0.71 -0.16 -0.068 -0.56 -0.081 -0.045 -3.7e+02 -1.3e-05 -5.9e-05 6.2e-06 2e-05 4.8e-05 4.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.4e-05 8.5e-05 8.2e-05 8.5e-05 8.2e-05 7.2e-05 7.5e-05 0.017 0.017 0.0078 0.04 0.04 0.035 5.9e-11 5.9e-11 2.3e-10 2.4e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
249 24690000 0.71 0.0052 0.0028 0.71 -0.18 -0.082 -0.64 -0.098 -0.052 -3.7e+02 -1.3e-05 -5.9e-05 6.3e-06 1.9e-05 4.8e-05 4.4e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.4e-05 8.5e-05 8.2e-05 8.5e-05 8.2e-05 7.2e-05 7.5e-05 0.018 0.018 0.0078 0.044 0.044 0.035 5.9e-11 5.9e-11 2.3e-10 2.4e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
250 24790000 0.71 0.0049 0.0015 0.0014 0.71 -0.2 -0.095 -0.094 -0.72 -0.1 -0.063 -3.7e+02 -1.3e-05 -5.9e-05 6.1e-06 2.4e-05 2.3e-05 4e-05 3.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.4e-05 8.4e-05 8.1e-05 8.4e-05 8.1e-05 7.2e-05 7.5e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.7e-11 5.7e-11 2.2e-10 2.3e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
251 24890000 0.71 0.0067 0.0031 0.71 -0.22 -0.11 -0.75 -0.13 -0.073 -3.7e+02 -1.3e-05 -5.9e-05 6e-06 2.4e-05 2.3e-05 4e-05 3.6e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.5e-05 8.2e-05 8.4e-05 8.2e-05 7.1e-05 7.5e-05 0.018 0.018 0.0078 0.044 0.044 0.035 5.7e-11 5.7e-11 2.2e-10 2.3e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
252 24990000 0.71 0.0085 0.0047 0.71 -0.24 -0.11 -0.81 -0.13 -0.081 -3.7e+02 -1.3e-05 -5.9e-05 5.8e-06 5.9e-06 3.3e-05 3.2e-05 2.5e-05 2.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.4e-05 8.1e-05 8.3e-05 8.1e-05 7.1e-05 7.5e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.4e-11 5.4e-11 2.2e-10 2.3e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
253 25090000 0.71 0.0088 0.0041 0.71 -0.27 -0.12 -0.85 -0.15 -0.093 -3.7e+02 -1.3e-05 -5.9e-05 5.7e-06 3.3e-05 3.2e-05 2.5e-05 2.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.4e-05 8.1e-05 8.4e-05 8.1e-05 7.1e-05 7.4e-05 0.018 0.017 0.0079 0.044 0.044 0.035 5.5e-11 5.5e-11 2.1e-10 2.2e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
254 25190000 0.71 0.0082 0.0027 0.71 -0.29 -0.14 -0.91 -0.17 -0.12 -3.7e+02 -1.3e-05 -5.9e-05 5.7e-06 5.8e-06 3e-05 2.8e-05 1.9e-05 1.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.3e-05 8.3e-05 8e-05 8.3e-05 8e-05 7.1e-05 7.4e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.2e-11 5.2e-11 2.1e-10 2.2e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
255 25290000 0.71 0.01 0.0095 0.71 -0.32 -0.15 -0.96 -0.2 -0.13 -3.7e+02 -1.3e-05 -5.9e-05 5.7e-06 3e-05 2.8e-05 1.9e-05 1.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.3e-05 8.3e-05 8e-05 8.3e-05 8e-05 7.1e-05 7.4e-05 0.017 0.017 0.0079 0.044 0.044 0.035 5.3e-11 5.3e-11 2.1e-10 2.2e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
256 25390000 0.71 0.011 0.016 0.71 -0.35 -0.17 -1 -0.22 -0.15 -3.7e+02 -1.2e-05 -5.9e-05 5.7e-06 5.8e-06 3.2e-05 3e-05 3.5e-06 -1.2e-07 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.3e-05 8.2e-05 7.9e-05 8.2e-05 7.9e-05 7.1e-05 7.4e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.1e-11 5.1e-11 2.1e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
257 25490000 0.71 0.012 0.017 0.71 -0.4 -0.19 -1.1 -0.25 -0.17 -3.7e+02 -1.2e-05 -5.9e-05 5.8e-06 3.2e-05 3e-05 3.6e-06 2.1e-08 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.3e-05 8.2e-05 8e-05 8.2e-05 7.9e-05 7.1e-05 7.4e-05 0.017 0.017 0.0079 0.044 0.044 0.035 5.1e-11 5.1e-11 2e-10 2.1e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
258 25590000 0.71 0.011 0.015 0.71 -0.44 -0.22 -1.1 -0.28 -0.21 -3.7e+02 -1.2e-05 -5.9e-05 5.8e-06 2.9e-05 2.6e-05 -5.9e-06 -9.2e-06 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.1e-05 7.9e-05 8.1e-05 7.8e-05 7.1e-05 7.4e-05 0.016 0.016 0.0079 0.04 0.04 0.035 4.9e-11 4.9e-11 2e-10 2.1e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
259 25690000 0.71 0.015 0.022 0.71 -0.49 -0.24 -1.2 -0.33 -0.23 -3.7e+02 -1.2e-05 -5.9e-05 5.8e-06 2.9e-05 2.6e-05 -5.6e-06 -8.9e-06 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.2e-05 7.9e-05 8.1e-05 7.9e-05 7e-05 7.4e-05 0.017 0.017 0.0079 0.044 0.044 0.035 4.9e-11 4.9e-11 2e-10 2.9e-06 2.8e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
260 25790000 0.71 0.017 0.028 0.71 -0.53 -0.27 -1.2 -0.34 -0.26 -3.7e+02 -1.2e-05 -5.9e-05 5.8e-06 5.9e-06 3.7e-05 3.4e-05 -3.2e-05 -3.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.1e-05 7.8e-05 8.1e-05 7.8e-05 7e-05 7.4e-05 0.016 0.016 0.0079 0.04 0.04 0.035 4.7e-11 4.7e-11 2e-10 2.9e-06 2.7e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
261 25890000 0.71 0.017 0.028 0.71 -0.6 -0.3 -1.3 -0.4 -0.29 -3.7e+02 -1.2e-05 -5.9e-05 5.9e-06 6e-06 3.7e-05 3.3e-05 -3.2e-05 -3.5e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.1e-05 7.8e-05 8.1e-05 7.8e-05 7e-05 7.3e-05 0.017 0.017 0.008 0.044 0.044 0.035 4.7e-11 4.7e-11 1.9e-10 2e-10 2.9e-06 2.7e-06 2.9e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
262 25990000 0.71 0.016 0.025 0.71 -0.66 -0.33 -1.3 -0.44 -0.34 -3.7e+02 -1.1e-05 -5.9e-05 5.9e-06 6e-06 3.3e-05 2.9e-05 -4.9e-05 -5.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.2e-05 8e-05 7.7e-05 8e-05 7.7e-05 7e-05 7.3e-05 0.015 0.015 0.0079 0.039 0.039 0.035 4.6e-11 4.6e-11 1.9e-10 2e-10 2.9e-06 2.7e-06 2.9e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
263 26090000 0.7 0.021 0.035 0.71 -0.72 -0.36 -1.3 -0.51 -0.38 -3.7e+02 -1.1e-05 -5.9e-05 5.8e-06 3.3e-05 2.9e-05 -4.8e-05 -5.1e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.2e-05 8e-05 7.7e-05 8e-05 7.7e-05 7e-05 7.3e-05 0.017 0.016 0.008 0.043 0.043 0.035 4.6e-11 4.6e-11 1.9e-10 2.9e-06 2.7e-06 2.9e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
264 26190000 0.7 0.023 0.045 0.71 -0.78 -0.39 -1.3 -0.53 -0.42 -3.7e+02 -1.1e-05 -5.9e-05 5.8e-06 4.5e-05 4e-05 -8.6e-05 -8.9e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.2e-05 7.9e-05 7.7e-05 7.9e-05 7.6e-05 7e-05 7.3e-05 0.015 0.015 0.0079 0.039 0.039 0.035 4.4e-11 4.4e-11 1.9e-10 2.9e-06 2.7e-06 2.9e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
265 26290000 0.7 0.024 0.047 0.71 -0.87 -0.44 -1.3 -0.62 -0.46 -3.7e+02 -1.1e-05 -5.9e-05 5.7e-06 4.5e-05 4e-05 -8.5e-05 -8.8e-05 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.2e-05 7.9e-05 7.7e-05 7.9e-05 7.7e-05 7e-05 7.3e-05 0.016 0.016 0.008 0.043 0.043 0.035 4.5e-11 4.5e-11 1.8e-10 1.9e-10 2.9e-06 2.7e-06 2.9e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
266 26390000 0.7 0.023 0.043 0.71 -0.95 -0.49 -1.3 -0.68 -0.55 -3.7e+02 -1e-05 -5.9e-05 5.7e-06 3.2e-05 2.7e-05 -0.0001 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.2e-05 7.9e-05 7.6e-05 7.8e-05 7.6e-05 7e-05 7.3e-05 0.015 0.015 0.0079 0.039 0.039 0.035 4.3e-11 4.3e-11 1.8e-10 1.9e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
267 26490000 0.7 0.031 0.059 0.71 -1 -0.53 -1.3 -0.78 -0.6 -3.7e+02 -1e-05 -5.9e-05 5.7e-06 3.2e-05 2.7e-05 -9.9e-05 -0.0001 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.2e-05 7.9e-05 7.6e-05 7.9e-05 7.6e-05 7e-05 7.3e-05 0.016 0.016 0.008 0.043 0.043 0.035 4.3e-11 4.3e-11 1.8e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
268 26590000 0.7 0.037 0.075 0.71 -1.1 -0.59 -1.3 -0.82 -0.67 -3.7e+02 -9.5e-06 -5.9e-05 5.3e-06 5.4e-06 4.2e-05 3.5e-05 -0.00014 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.2e-05 7.8e-05 7.5e-05 7.8e-05 7.5e-05 7e-05 7.3e-05 0.015 0.015 0.008 0.039 0.039 0.035 4.2e-11 4.2e-11 1.8e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
269 26690000 0.7 0.038 0.078 0.71 -1.3 -0.65 -1.3 -0.94 -0.73 -3.7e+02 -9.5e-06 -5.9e-05 5.4e-06 5.5e-06 4.1e-05 3.5e-05 -0.00014 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.8e-05 7.5e-05 7.8e-05 7.5e-05 7e-05 7.3e-05 0.016 0.016 0.008 0.043 0.043 0.035 4.2e-11 4.2e-11 1.7e-10 1.8e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
270 26790000 0.7 0.036 0.072 0.71 -1.4 -0.73 -1.3 -1 -0.85 -3.7e+02 -9e-06 -6e-05 5.2e-06 5.3e-06 1.9e-05 1.3e-05 -0.00016 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.7e-05 7.5e-05 7.7e-05 7.5e-05 6.9e-05 7.2e-05 0.015 0.014 0.008 0.039 0.039 0.035 4.1e-11 4.1e-11 1.7e-10 1.8e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
271 26890000 0.7 0.045 0.094 0.7 -1.5 -0.79 -1.3 -1.2 -0.93 -3.7e+02 -9e-06 -6e-05 5.3e-06 1.9e-05 1.2e-05 -0.00016 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.7e-05 7.5e-05 7.7e-05 7.5e-05 6.9e-05 7.2e-05 0.016 0.015 0.0081 0.043 0.043 0.035 4.1e-11 4.1e-11 1.7e-10 1.8e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
272 26990000 0.7 0.051 0.12 0.7 -1.7 -0.87 -1.3 -1.2 -1 -3.7e+02 -7.9e-06 -6e-05 5.2e-06 5.3e-06 2.8e-05 2e-05 -0.00021 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.7e-05 7.4e-05 7.6e-05 7.4e-05 6.9e-05 7.2e-05 0.015 0.014 0.008 0.039 0.039 0.035 4e-11 4e-11 1.7e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
273 27090000 0.7 0.052 0.12 0.7 -1.9 -0.96 -1.3 -1.4 -1.1 -3.7e+02 -7.9e-06 -6e-05 5.1e-06 5.2e-06 2.7e-05 2e-05 -0.00021 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7.1e-05 7.7e-05 7.4e-05 7.7e-05 7.4e-05 6.9e-05 7.2e-05 0.016 0.015 0.0081 0.043 0.043 0.035 4e-11 4e-11 1.7e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
274 27190000 0.71 0.048 0.11 0.7 -2.1 -1 -1.2 -1.6 -1.2 -3.7e+02 -7.8e-06 -5.9e-05 5.2e-06 5.3e-06 3.8e-05 3.1e-05 -0.0002 -0.00021 -0.0013 0.21 0.0021 0.43 0.44 0 0 0 0 0 7e-05 7.1e-05 7.7e-05 7.4e-05 7.6e-05 7.4e-05 6.9e-05 7.2e-05 0.016 0.015 0.0081 0.045 0.045 0.035 4e-11 4e-11 1.6e-10 1.7e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
275 27290000 0.71 0.043 0.094 0.7 -2.2 -1.1 -1.2 -1.8 -1.3 -3.7e+02 -7.8e-06 -5.9e-05 5.2e-06 5.3e-06 3.8e-05 3e-05 -0.0002 -0.00021 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 7e-05 7.1e-05 7.7e-05 7.4e-05 7.7e-05 7.4e-05 6.9e-05 7.2e-05 0.017 0.016 0.0081 0.05 0.049 0.035 4e-11 4e-11 1.6e-10 1.7e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
276 27390000 0.71 0.036 0.078 0.7 -2.3 -1.1 -1.2 -2 -1.4 -3.7e+02 -7.3e-06 -5.9e-05 5.3e-06 5.5e-06 5.8e-05 5.1e-05 -0.00022 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 7e-05 7.7e-05 7.4e-05 7.6e-05 7.4e-05 6.8e-05 7.1e-05 0.017 0.016 0.0081 0.052 0.052 0.035 3.9e-11 3.9e-11 1.6e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
277 27490000 0.71 0.031 0.063 0.7 -2.4 -1.2 -1.2 -2.3 -1.5 -3.7e+02 -7.2e-06 -7.3e-06 -5.9e-05 5.3e-06 5.4e-06 5.7e-05 5e-05 -0.00021 -0.00022 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.9e-05 7e-05 7.7e-05 7.4e-05 7.7e-05 7.4e-05 6.8e-05 7.1e-05 0.018 0.018 0.0082 0.057 0.057 0.035 3.9e-11 3.9e-11 1.6e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
278 27590000 0.71 0.026 0.05 0.7 -2.5 -1.2 -1.2 -2.5 -1.6 -3.7e+02 -7.5e-06 -5.9e-05 5.3e-06 5.4e-06 5.6e-05 4.9e-05 -0.0002 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.9e-05 7e-05 7.7e-05 7.4e-05 7.7e-05 7.4e-05 6.8e-05 7.1e-05 0.018 0.017 0.0082 0.06 0.059 0.035 3.9e-11 3.9e-11 1.6e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
279 27690000 0.71 0.025 0.048 0.7 -2.5 -1.2 -1.2 -2.8 -1.7 -3.7e+02 -7.5e-06 -5.9e-05 5.2e-06 5.3e-06 5.6e-05 4.9e-05 -0.00019 -0.0002 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.9e-05 7.7e-05 7.5e-05 7.7e-05 7.4e-05 6.8e-05 7.1e-05 0.019 0.018 0.0083 0.0082 0.065 0.065 0.035 3.9e-11 3.9e-11 1.5e-10 1.6e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
280 27790000 0.71 0.026 0.05 0.7 -2.6 -1.2 -1.2 -3 -1.8 -3.7e+02 -7.6e-06 -5.8e-05 5.1e-06 5.2e-06 5.7e-05 5e-05 -0.00018 -0.00019 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.8e-05 6.9e-05 7.7e-05 7.4e-05 7.7e-05 7.4e-05 6.7e-05 7e-05 0.019 0.018 0.0082 0.068 0.067 0.035 3.8e-11 3.8e-11 1.5e-10 1.6e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
281 27890000 0.71 0.025 0.048 0.7 -2.6 -1.2 -1.2 -3.3 -2 -3.7e+02 -7.6e-06 -5.8e-05 5.1e-06 5.2e-06 5.5e-05 4.9e-05 -0.00018 -0.00019 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.8e-05 6.9e-05 7.7e-05 7.5e-05 7.7e-05 7.4e-05 6.7e-05 7e-05 0.02 0.019 0.0083 0.074 0.073 0.035 3.9e-11 3.8e-11 1.5e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
282 27990000 0.71 0.024 0.045 0.7 -2.7 -1.2 -1.2 -3.6 -2.1 -3.7e+02 -8e-06 -5.8e-05 5.2e-06 5.3e-06 5e-05 4.4e-05 -0.00016 -0.00017 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.8e-05 6.9e-05 7.7e-05 7.4e-05 7.6e-05 7.4e-05 6.7e-05 7e-05 0.02 0.019 0.0083 0.076 0.076 0.035 3.8e-11 3.8e-11 1.5e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
283 28090000 0.71 0.03 0.058 0.7 -2.7 -1.3 -1.2 -3.9 -2.2 -3.7e+02 -8e-06 -5.8e-05 4.9e-06 5e-06 5e-05 4.3e-05 -0.00016 -0.00017 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.8e-05 6.9e-05 7.7e-05 7.4e-05 7.6e-05 7.4e-05 6.7e-05 7e-05 0.021 0.02 0.0084 0.083 0.082 0.035 3.8e-11 3.8e-11 1.5e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
284 28190000 0.71 0.035 0.071 0.7 -2.8 -1.3 -0.95 -4.2 -2.3 -3.7e+02 -8.2e-06 -5.8e-05 5e-06 4.6e-05 4e-05 -0.00015 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.8e-05 7.7e-05 7.4e-05 7.6e-05 7.4e-05 6.7e-05 7e-05 0.02 0.02 0.0084 0.085 0.085 0.035 3.8e-11 3.7e-11 1.4e-10 1.5e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
285 28290000 0.71 0.028 0.054 0.7 -2.8 -1.3 -0.09 -4.4 -2.4 -3.7e+02 -8.2e-06 -5.8e-05 4.8e-06 4.9e-06 4.5e-05 3.9e-05 -0.00014 -0.00015 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.8e-05 7.7e-05 7.4e-05 7.6e-05 7.4e-05 6.7e-05 7e-05 0.021 0.02 0.0086 0.0085 0.092 0.092 0.036 3.8e-11 3.7e-11 1.4e-10 1.5e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
286 28390000 0.71 0.011 0.023 0.7 -2.8 -1.3 0.77 -4.7 -2.6 -3.7e+02 -8.2e-06 -5.8e-05 4.6e-06 4.7e-06 4.2e-05 3.6e-05 -0.00013 -0.00014 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.7e-05 6.8e-05 7.8e-05 7.5e-05 7.7e-05 7.4e-05 6.6e-05 6.9e-05 0.022 0.021 0.0087 0.0086 0.1 0.099 0.036 3.8e-11 3.8e-11 1.4e-10 1.5e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
287 28490000 0.71 0.0026 0.0045 0.7 -2.7 -1.3 1.1 -5 -2.7 -3.7e+02 -8.2e-06 -5.8e-05 4.6e-06 4.7e-06 3.9e-05 3.4e-05 -0.00013 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.7e-05 6.8e-05 7.8e-05 7.5e-05 7.7e-05 7.5e-05 6.6e-05 6.9e-05 0.023 0.022 0.0088 0.11 0.11 0.036 3.8e-11 3.8e-11 1.4e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
288 28590000 0.71 0.00084 0.00079 0.001 0.00099 0.7 -2.6 -1.3 0.96 -5.3 -2.8 -3.7e+02 -8.2e-06 -5.8e-05 4.6e-06 4.7e-06 3.6e-05 3e-05 -0.00012 -0.00013 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.7e-05 6.8e-05 7.8e-05 7.5e-05 7.7e-05 7.5e-05 6.6e-05 6.9e-05 0.024 0.023 0.0089 0.12 0.12 0.036 3.8e-11 3.8e-11 1.4e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
289 28690000 0.71 0.00014 8.6e-05 8.2e-05 6.9e-05 0.7 -2.6 -1.2 0.96 -5.5 -2.9 -3.7e+02 -8.2e-06 -5.8e-05 4.5e-06 4.6e-06 3.2e-05 2.6e-05 -0.00011 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.7e-05 7.8e-05 7.5e-05 7.8e-05 7.5e-05 6.6e-05 6.9e-05 0.025 0.025 0.009 0.0089 0.13 0.12 0.036 3.8e-11 3.8e-11 1.4e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
290 28790000 0.71 -0.00015 -0.00018 -0.00017 0.71 -2.5 -1.2 0.97 -5.8 -3 -3.7e+02 -8.9e-06 -5.8e-05 4.5e-06 3.6e-07 -3.7e-06 -0.00018 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 6.7e-05 7.8e-05 7.6e-05 7.8e-05 7.5e-05 6.6e-05 6.9e-05 0.024 0.024 0.0089 0.13 0.13 0.036 3.7e-11 3.7e-11 1.4e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
291 28890000 0.71 -0.00017 -0.0002 5.2e-05 4.7e-05 0.71 -2.5 -1.2 0.96 -6.1 -3.2 -3.7e+02 -8.9e-06 -5.8e-05 4.4e-06 4.5e-06 -4e-06 -7.9e-06 -0.00017 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 6.7e-05 7.8e-05 7.6e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.025 0.025 0.009 0.14 0.13 0.036 3.7e-11 3.7e-11 1.3e-10 1.4e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
292 28990000 0.71 2.1e-05 1.4e-05 0.0005 0.00051 0.71 -2.4 -1.2 0.95 -6.4 -3.3 -3.7e+02 -9.8e-06 -5.8e-05 4.3e-06 4.4e-06 -2.5e-05 -2.8e-05 -0.00025 -0.0012 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 6.7e-05 7.9e-05 7.6e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.024 0.024 0.009 0.0089 0.14 0.14 0.036 3.7e-11 3.6e-11 1.3e-10 1.4e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
293 29090000 0.71 0.00017 0.0009 0.00091 0.71 -2.4 -1.2 0.94 -6.7 -3.4 -3.7e+02 -9.8e-06 -5.8e-05 4.3e-06 -3e-05 -3.2e-05 -0.00024 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 6.7e-05 7.9e-05 7.6e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.025 0.025 0.009 0.15 0.15 0.036 3.7e-11 3.7e-11 1.3e-10 1.4e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
294 29190000 0.71 0.00039 0.0004 0.0013 0.71 -2.3 -1.1 0.93 -7 -3.5 -3.7e+02 -1e-05 -5.8e-05 4.3e-06 -5e-05 -5.1e-05 -0.00027 -0.00026 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 6.7e-05 7.9e-05 7.6e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.024 0.024 0.009 0.15 0.15 0.036 3.6e-11 3.6e-11 1.3e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
295 29290000 0.71 0.00075 0.0022 0.71 -2.3 -1.1 0.96 -7.2 -3.6 -3.7e+02 -1e-05 -5.8e-05 4.2e-06 -5.6e-05 -0.00025 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 7.9e-05 7.6e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.025 0.026 0.0091 0.16 0.16 0.036 3.6e-11 3.6e-11 1.3e-10 2.8e-06 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
296 29390000 0.71 0.0013 0.0037 0.71 -2.3 -1.1 0.97 -7.5 -3.7 -3.7e+02 -1.1e-05 -5.8e-05 -5.7e-05 4e-06 -7.1e-05 -0.00029 -0.00028 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 7.9e-05 7.7e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.024 0.025 0.009 0.16 0.15 0.036 3.6e-11 3.5e-11 1.3e-10 2.8e-06 2.7e-06 2.8e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
297 29490000 0.71 0.0018 0.0048 0.71 -2.2 -1.1 0.97 -7.7 -3.8 -3.7e+02 -1.1e-05 -5.7e-05 3.9e-06 4e-06 -7.5e-05 -0.00028 -0.00027 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.6e-05 7.9e-05 7.7e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.026 0.026 0.0091 0.17 0.17 0.037 3.6e-11 3.5e-11 1.3e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
298 29590000 0.71 0.0022 0.0059 0.71 -2.2 -1.1 0.96 -8 -3.9 -3.7e+02 -1.1e-05 -5.7e-05 3.9e-06 -9.9e-05 -9.7e-05 -0.00028 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 7.9e-05 7.7e-05 7.8e-05 7.5e-05 6.5e-05 6.8e-05 0.024 0.025 0.0091 0.009 0.17 0.16 0.036 3.5e-11 3.5e-11 1.2e-10 1.3e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
299 29690000 0.71 0.0025 0.0066 0.71 -2.2 -1.1 0.95 -8.2 -4 -3.7e+02 -1.1e-05 -5.7e-05 3.8e-06 -0.0001 -0.00027 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 8e-05 7.7e-05 7.8e-05 7.5e-05 6.5e-05 6.7e-05 0.026 0.026 0.0091 0.18 0.18 0.036 3.5e-11 3.5e-11 1.2e-10 1.3e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
300 29790000 0.71 0.0028 0.0071 0.71 -2.1 -1.1 0.93 -8.5 -4.1 -3.7e+02 -1.2e-05 -5.7e-05 3.8e-06 -0.00012 -0.00029 -0.00028 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 8e-05 7.7e-05 7.8e-05 7.5e-05 6.4e-05 6.7e-05 0.025 0.025 0.0091 0.009 0.18 0.17 0.037 3.5e-11 3.4e-11 1.2e-10 1.3e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
301 29890000 0.71 0.0029 0.0074 0.71 -2.1 -1.1 0.92 -8.7 -4.2 -3.7e+02 -1.2e-05 -5.7e-05 3.6e-06 -0.00013 -0.00026 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 8e-05 7.7e-05 7.8e-05 7.5e-05 6.4e-05 6.7e-05 0.026 0.026 0.0091 0.19 0.19 0.037 3.5e-11 3.4e-11 1.2e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
302 29990000 0.71 0.003 0.0031 0.0076 0.71 -2.1 -1.1 0.9 -9 -4.3 -3.7e+02 -1.2e-05 -5.7e-05 3.5e-06 -0.00015 -0.00014 -0.00026 -0.00025 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 8e-05 7.7e-05 7.8e-05 7.5e-05 6.4e-05 6.7e-05 0.025 0.025 0.009 0.19 0.18 0.036 3.4e-11 3.4e-11 1.2e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
303 30090000 0.71 0.003 0.0031 0.0075 0.71 -2.1 -1 0.89 -9.2 -4.4 -3.7e+02 -1.2e-05 -5.7e-05 3.4e-06 -0.00016 -0.00015 -0.00024 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 8e-05 7.7e-05 7.8e-05 7.5e-05 6.4e-05 6.7e-05 0.026 0.026 0.027 0.0091 0.2 0.2 0.036 3.4e-11 3.4e-11 1.2e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
304 30190000 0.71 0.0031 0.0074 0.71 -2 -1 0.88 -9.4 -4.5 -3.7e+02 -1.2e-05 -5.7e-05 3.4e-06 -0.00017 -0.00016 -0.00025 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 8e-05 7.7e-05 7.8e-05 7.5e-05 6.4e-05 6.7e-05 0.025 0.025 0.009 0.2 0.19 0.037 3.4e-11 3.3e-11 1.2e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
305 30290000 0.71 0.003 0.0072 0.71 -2 -1 0.86 -9.6 -4.6 -3.7e+02 -1.2e-05 -5.7e-05 3.3e-06 -0.00017 -0.00024 -0.0011 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 6.6e-05 8e-05 7.8e-05 7.8e-05 7.5e-05 6.4e-05 6.6e-05 0.026 0.027 0.0091 0.21 0.21 0.037 3.4e-11 3.3e-11 1.2e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
306 30390000 0.71 0.003 0.0031 0.0071 0.71 -2 -1 0.85 -9.9 -4.7 -3.7e+02 -1.3e-05 -5.7e-05 3.3e-06 3.2e-06 -0.00018 -0.00023 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 8e-05 7.8e-05 7.8e-05 7.5e-05 6.3e-05 6.6e-05 0.025 0.025 0.009 0.21 0.2 0.036 3.3e-11 3.3e-11 1.1e-10 1.2e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
307 30490000 0.71 0.0029 0.0068 0.71 -2 -1 0.83 -10 -4.8 -3.7e+02 -1.3e-05 -5.7e-05 3.3e-06 3.2e-06 -0.00019 -0.00018 -0.00022 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.5e-05 8.1e-05 7.8e-05 7.8e-05 7.5e-05 6.3e-05 6.6e-05 0.026 0.027 0.0091 0.22 0.22 0.037 3.3e-11 3.3e-11 1.1e-10 1.2e-10 2.8e-06 2.7e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
308 30590000 0.71 0.0028 0.0029 0.0065 0.71 -1.9 -1 0.79 -10 -4.9 -3.7e+02 -1.3e-05 -5.7e-05 3.3e-06 -0.0002 -0.00019 -0.00022 -0.00021 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.8e-05 7.5e-05 6.3e-05 6.6e-05 0.025 0.025 0.009 0.21 0.21 0.037 3.3e-11 3.2e-11 1.1e-10 1.2e-10 2.8e-06 2.6e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
309 30690000 0.71 0.0027 0.0062 0.71 -1.9 -0.99 0.79 -11 -5 -3.7e+02 -1.3e-05 -5.7e-05 3.2e-06 -0.0002 -0.00019 -0.00021 -0.0002 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.8e-05 7.5e-05 6.3e-05 6.6e-05 0.026 0.027 0.009 0.23 0.23 0.037 3.3e-11 3.2e-11 1.1e-10 2.8e-06 2.6e-06 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
310 30790000 0.71 0.0026 0.0027 0.0059 0.71 -1.9 -0.98 0.78 -11 -5.1 -3.7e+02 -1.3e-05 -5.7e-05 3.1e-06 -0.00021 -0.0002 -0.0002 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.7e-05 7.5e-05 6.3e-05 6.6e-05 0.025 0.025 0.009 0.0089 0.22 0.22 0.037 3.2e-11 3.2e-11 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
311 30890000 0.71 0.0025 0.0055 0.0054 0.71 -1.9 -0.97 0.76 -11 -5.2 -3.7e+02 -1.3e-05 -5.7e-05 3.1e-06 -0.00021 -0.0002 -0.00019 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.7e-05 7.5e-05 6.3e-05 6.6e-05 0.026 0.027 0.009 0.24 0.24 0.037 3.2e-11 3.2e-11 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
312 30990000 0.71 0.0024 0.0025 0.005 0.71 -1.8 -0.96 0.76 -11 -5.3 -3.7e+02 -1.3e-05 -5.7e-05 3e-06 -0.00022 -0.00021 -0.00018 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.7e-05 7.5e-05 6.3e-05 6.5e-05 0.025 0.025 0.0089 0.23 0.23 0.037 0.036 3.2e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
313 31090000 0.71 0.0022 0.0023 0.0045 0.71 -1.8 -0.96 0.74 -11 -5.4 -3.7e+02 -1.3e-05 -5.7e-05 3e-06 2.9e-06 -0.00023 -0.00022 -0.00017 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.7e-05 7.5e-05 6.2e-05 6.5e-05 0.026 0.027 0.009 0.0089 0.25 0.24 0.037 3.2e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
314 31190000 0.71 0.0022 0.0043 0.71 -1.8 -0.95 0.73 -12 -5.5 -3.7e+02 -1.4e-05 -5.7e-05 2.9e-06 -0.00024 -0.00023 -0.00014 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.7e-05 7.4e-05 6.2e-05 6.5e-05 0.025 0.025 0.0089 0.0088 0.24 0.24 0.037 3.1e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
315 31290000 0.71 0.002 0.0038 0.0037 0.71 -1.8 -0.94 0.73 -12 -5.6 -3.7e+02 -1.4e-05 -5.7e-05 2.9e-06 -0.00025 -0.00024 -0.00013 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8.1e-05 7.8e-05 7.7e-05 7.4e-05 6.2e-05 6.5e-05 0.026 0.027 0.0089 0.26 0.25 0.037 3.1e-11 3.1e-11 1e-10 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
316 31390000 0.71 0.0018 0.0019 0.0033 0.71 -1.8 -0.93 0.73 -12 -5.7 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00025 -0.00024 -0.00011 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 8.1e-05 7.8e-05 7.7e-05 7.4e-05 6.2e-05 6.5e-05 0.025 0.025 0.0088 0.25 0.25 0.036 3.1e-11 3.1e-11 1e-10 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
317 31490000 0.71 0.0016 0.0017 0.0027 0.0026 0.71 -1.7 -0.92 0.72 -12 -5.8 -3.7e+02 -1.4e-05 -5.7e-05 2.7e-06 -0.00026 -0.00025 -9.8e-05 -9.9e-05 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 8.1e-05 7.8e-05 7.7e-05 7.4e-05 6.2e-05 6.5e-05 0.026 0.027 0.0089 0.0088 0.26 0.26 0.037 3.1e-11 3.1e-11 1e-10 1.1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
318 31590000 0.71 0.0016 0.0024 0.0023 0.71 -1.7 -0.91 0.72 -12 -5.9 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 2.7e-06 -0.00027 -0.00026 -8.2e-05 -8.3e-05 -0.00099 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.4e-05 8.1e-05 7.8e-05 7.6e-05 7.4e-05 6.2e-05 6.4e-05 0.025 0.025 0.0087 0.26 0.26 0.037 3.1e-11 3e-11 1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
319 31690000 0.71 0.0013 0.0014 0.0017 0.0016 0.71 -1.7 -0.9 0.72 -12 -5.9 -3.7e+02 -1.4e-05 -5.7e-05 2.7e-06 -0.00027 -0.00026 -6.9e-05 -7.1e-05 -0.00099 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.6e-05 7.4e-05 6.2e-05 6.4e-05 0.026 0.026 0.027 0.0088 0.0087 0.27 0.27 0.037 3.1e-11 3e-11 1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
320 31790000 0.71 0.0011 0.0012 0.0011 0.001 0.71 -1.7 -0.89 0.72 -13 -6 -3.7e+02 -1.4e-05 -5.7e-05 2.7e-06 -0.00028 -0.00027 -5.1e-05 -5.3e-05 -0.00098 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.6e-05 7.4e-05 6.1e-05 6.4e-05 0.025 0.025 0.0087 0.27 0.27 0.037 3e-11 3e-11 1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
321 31890000 0.71 0.00087 0.00091 0.00039 0.00032 0.71 -1.6 -0.88 0.72 -13 -6.1 -3.7e+02 -1.4e-05 -5.7e-05 2.7e-06 2.6e-06 -0.00029 -0.00028 -3.8e-05 -4.1e-05 -0.00097 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.6e-05 7.4e-05 6.1e-05 6.4e-05 0.026 0.026 0.0087 0.28 0.28 0.037 3e-11 3e-11 9.9e-11 1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
322 31990000 0.71 0.00074 0.00078 -6.8e-05 -0.00014 0.71 -1.6 -0.87 0.71 -13 -6.2 -3.7e+02 -1.4e-05 -5.7e-05 2.6e-06 -0.0003 -0.00028 -1.9e-05 -2.2e-05 -0.00097 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.6e-05 7.3e-05 6.1e-05 6.4e-05 0.025 0.025 0.0086 0.28 0.28 0.036 3e-11 3e-11 9.8e-11 1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
323 32090000 0.71 0.00045 0.00049 -0.00079 -0.00086 0.71 -1.6 -0.86 0.72 -13 -6.3 -3.7e+02 -1.4e-05 -5.7e-05 2.6e-06 2.5e-06 -0.0003 -0.00029 -4.1e-06 -7.8e-06 -0.00096 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.6e-05 7.3e-05 6.1e-05 6.4e-05 0.026 0.026 0.0087 0.29 0.29 0.037 3e-11 3e-11 9.7e-11 1e-10 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
324 32190000 0.71 0.00024 0.00028 -0.0016 0.71 -1.5 -0.85 0.72 -13 -6.4 -3.7e+02 -1.4e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00031 -0.0003 1.7e-05 1.2e-05 -0.00096 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.5e-05 7.3e-05 6.1e-05 6.3e-05 0.025 0.025 0.0086 0.29 0.29 0.036 2.9e-11 2.9e-11 9.6e-11 9.9e-11 2.7e-06 2.6e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
325 32290000 0.71 1e-05 4.6e-05 -0.0023 -0.0024 0.71 -1.5 -0.84 0.71 -13 -6.4 -3.7e+02 -1.4e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00032 -0.00031 3.3e-05 2.8e-05 -0.00095 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.6e-05 7.3e-05 6.1e-05 6.3e-05 0.026 0.026 0.0086 0.3 0.3 0.037 0.036 3e-11 2.9e-11 9.5e-11 9.8e-11 2.7e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
326 32390000 0.71 -0.00017 -0.00014 -0.0029 -0.003 0.71 -1.5 -0.83 0.71 -14 -6.5 -3.7e+02 -1.4e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00032 -0.00031 4.2e-05 3.6e-05 -0.00095 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.8e-05 7.5e-05 7.3e-05 6.1e-05 6.3e-05 0.025 0.025 0.0085 0.3 0.3 0.037 2.9e-11 2.9e-11 9.5e-11 9.7e-11 2.7e-06 2.6e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
327 32490000 0.71 -0.00029 -0.00026 -0.0032 -0.0033 0.71 -1.4 -0.81 0.72 -14 -6.6 -3.7e+02 -1.4e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00033 -0.00031 5.3e-05 4.7e-05 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.3e-05 8.1e-05 7.8e-05 7.5e-05 7.3e-05 6.1e-05 6.3e-05 0.026 0.026 0.0086 0.0085 0.31 0.31 0.037 2.9e-11 2.9e-11 9.4e-11 9.6e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
328 32590000 0.71 -0.00029 -0.00025 -0.0034 -0.0035 0.71 -1.4 -0.8 0.71 -14 -6.7 -3.7e+02 -1.5e-05 -5.7e-05 2.3e-06 2.2e-06 -0.00033 -0.00032 6.1e-05 5.5e-05 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.8e-05 7.5e-05 7.2e-05 6e-05 6.3e-05 0.025 0.025 0.0084 0.31 0.31 0.036 2.9e-11 2.9e-11 9.3e-11 9.5e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
329 32690000 0.71 -0.00033 -0.0003 -0.0035 -0.0036 0.71 -1.4 -0.79 0.71 -14 -6.8 -3.7e+02 -1.5e-05 -5.7e-05 2.3e-06 2.2e-06 -0.00034 -0.00032 6.6e-05 6e-05 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.8e-05 7.5e-05 7.3e-05 6e-05 6.3e-05 0.026 0.026 0.0085 0.32 0.32 0.036 2.9e-11 2.9e-11 9.2e-11 9.4e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
330 32790000 0.71 -0.00029 -0.00026 -0.0034 -0.0035 0.71 -1.4 -0.78 0.71 -14 -6.8 -3.7e+02 -1.5e-05 -5.7e-05 2.3e-06 2.2e-06 -0.00034 -0.00032 7.5e-05 6.9e-05 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.8e-05 7.5e-05 7.2e-05 6e-05 6.3e-05 0.025 0.025 0.0084 0.32 0.31 0.036 2.9e-11 2.9e-11 9.1e-11 9.4e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
331 32890000 0.71 -0.0002 -0.00017 -0.0034 -0.0035 0.71 -1.3 -0.77 0.71 -14 -6.9 -3.7e+02 -1.5e-05 -5.7e-05 2.1e-06 2e-06 -0.00035 -0.00033 8.6e-05 7.9e-05 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.8e-05 7.5e-05 7.2e-05 6e-05 6.3e-05 0.026 0.026 0.0084 0.33 0.33 0.036 2.9e-11 2.9e-11 9e-11 9.3e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
332 32990000 0.71 -7.2e-05 -3.9e-05 -0.0033 -0.0034 0.71 -1.3 -0.76 0.7 -15 -7 -3.7e+02 -1.5e-05 -5.7e-05 2.2e-06 -0.00035 -0.00033 9.9e-05 9.2e-05 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.8e-05 7.4e-05 7.2e-05 6e-05 6.2e-05 0.025 0.025 0.0083 0.32 0.32 0.036 2.8e-11 2.8e-11 9e-11 9.2e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
333 33090000 0.71 -0.00011 -7.3e-05 -0.0033 -0.0034 0.71 -1.3 -0.76 0.69 -15 -7.1 -3.7e+02 -1.5e-05 -5.7e-05 2.3e-06 2.2e-06 -0.00035 -0.00034 0.00011 9.8e-05 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.8e-05 7.4e-05 7.2e-05 6e-05 6.2e-05 0.026 0.026 0.0084 0.34 0.34 0.036 2.8e-11 2.8e-11 8.9e-11 9.1e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
334 33190000 0.7 0.0033 -0.0024 -0.0025 0.71 -1.3 -0.75 0.64 -15 -7.1 -3.7e+02 -1.5e-05 -5.7e-05 2.3e-06 2.2e-06 -0.00036 -0.00034 0.00011 0.0001 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.8e-05 7.4e-05 7.2e-05 6e-05 6.2e-05 0.025 0.025 0.0083 0.33 0.33 0.036 2.8e-11 2.8e-11 8.8e-11 9e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
335 33290000 0.65 0.015 0.016 -0.0015 -0.0016 0.76 -1.3 -0.73 0.62 -15 -7.2 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00036 -0.00034 0.00012 0.00011 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.9e-05 6e-05 8e-05 7.8e-05 7.5e-05 7.2e-05 6.2e-05 6.5e-05 0.026 0.026 0.0083 0.35 0.35 0.036 2.8e-11 2.8e-11 8.7e-11 9e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
336 33390000 0.55 0.013 -0.0017 -0.0018 0.84 -1.3 -0.72 0.81 -15 -7.3 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00036 -0.00034 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.5e-05 7.9e-05 7.7e-05 7.6e-05 7.3e-05 6.6e-05 6.9e-05 0.024 0.024 0.0083 0.34 0.34 0.036 2.8e-11 2.8e-11 8.7e-11 8.9e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
337 33490000 0.41 0.0069 0.00073 0.00063 0.91 -1.2 -0.71 0.83 -15 -7.4 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00036 -0.00035 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.1e-05 7.8e-05 7.6e-05 7.7e-05 7.5e-05 7.1e-05 7.4e-05 0.026 0.026 0.0081 0.36 0.35 0.036 2.8e-11 2.8e-11 8.6e-11 8.8e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
338 33590000 0.25 0.001 0.00097 -0.0018 -0.0019 0.97 -1.2 -0.71 0.79 -15 -7.4 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 2.3e-06 -0.00036 -0.00035 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 4.7e-05 7.6e-05 7.4e-05 7.9e-05 7.6e-05 7.5e-05 7.8e-05 0.025 0.025 0.0078 0.35 0.35 0.036 2.8e-11 2.8e-11 8.5e-11 8.7e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
339 33690000 0.087 -0.0023 -0.0049 -0.005 1 -1.2 -0.71 0.8 -15 -7.5 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 2.4e-06 -0.00036 -0.00035 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 4.4e-05 4.5e-05 7.5e-05 7.3e-05 8e-05 7.8e-05 7.7e-05 8.1e-05 0.028 0.028 0.0076 0.36 0.37 0.36 0.036 2.8e-11 2.8e-11 8.5e-11 8.7e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
340 33790000 -0.082 -0.0038 -0.0067 -0.0068 1 -1.1 -0.69 0.78 -16 -7.6 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 2.4e-06 -0.00036 -0.00035 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 4.4e-05 4.5e-05 7.2e-05 7e-05 8e-05 7.7e-05 7.8e-05 8.1e-05 0.028 0.028 0.0074 0.36 0.36 0.036 2.7e-11 2.7e-11 8.4e-11 8.6e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
341 33890000 -0.25 -0.0049 -0.005 -0.0074 -0.0075 0.97 -1 -0.67 -0.66 0.77 -16 -7.6 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 2.4e-06 -0.00036 -0.00035 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 4.6e-05 4.7e-05 7.2e-05 6.9e-05 8.1e-05 7.8e-05 7.7e-05 7.9e-05 0.031 0.032 0.0072 0.37 0.37 0.036 2.7e-11 2.8e-11 8.3e-11 8.5e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
342 33990000 -0.39 -0.0031 -0.0032 -0.011 0.92 -0.98 -0.63 0.74 -16 -7.7 -3.7e+02 -1.5e-05 -5.6e-05 2.5e-06 2.4e-06 -0.00036 -0.00035 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 4.9e-05 5e-05 6.9e-05 6.7e-05 7.8e-05 7.5e-05 7.4e-05 7.6e-05 0.032 0.031 0.032 0.007 0.37 0.37 0.035 2.7e-11 2.7e-11 8.2e-11 8.4e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
343 34090000 -0.5 -0.002 -0.0021 -0.013 0.87 -0.93 -0.58 0.74 -16 -7.7 -3.7e+02 -1.5e-05 -5.6e-05 2.6e-06 2.5e-06 -0.00036 -0.00035 0.00013 0.00012 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.2e-05 5.3e-05 6.9e-05 6.7e-05 7.8e-05 7.5e-05 7.1e-05 7.2e-05 0.036 0.037 0.036 0.0069 0.38 0.38 0.036 2.7e-11 2.7e-11 8.2e-11 8.4e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
344 34190000 -0.57 -0.0014 -0.0015 -0.011 0.82 -0.92 -0.91 -0.54 0.74 -16 -7.8 -3.7e+02 -1.5e-05 -5.7e-05 2.6e-06 2.5e-06 -0.00039 -0.00037 0.00014 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.4e-05 5.6e-05 6.5e-05 6.3e-05 7.3e-05 7.1e-05 6.8e-05 6.9e-05 0.036 0.037 0.0067 0.38 0.38 0.035 2.7e-11 2.7e-11 8.1e-11 8.3e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
345 34290000 -0.61 -0.0023 -0.0024 -0.0086 0.79 -0.87 -0.49 0.74 -16 -7.9 -3.7e+02 -1.5e-05 -5.7e-05 2.6e-06 2.5e-06 -0.00039 -0.00037 0.00014 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 6.5e-05 6.3e-05 7.3e-05 7.1e-05 6.6e-05 6.7e-05 0.042 0.043 0.0066 0.39 0.39 0.035 2.7e-11 2.7e-11 8e-11 8.2e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
346 34390000 -0.64 -0.0024 -0.0026 -0.006 0.77 -0.85 -0.46 0.73 -16 -7.9 -3.7e+02 -1.6e-05 -5.7e-05 2.6e-06 2.5e-06 -0.00044 -0.00042 0.00019 0.00018 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 6.1e-05 5.9e-05 6.7e-05 6.5e-05 6.5e-05 6.6e-05 0.042 0.041 0.043 0.042 0.0065 0.0064 0.39 0.39 0.035 2.7e-11 2.7e-11 8e-11 8.2e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
347 34490000 -0.65 -0.0034 -0.0035 -0.0039 0.76 -0.8 -0.42 0.73 -16 -8 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 2.6e-06 -0.00044 -0.00042 0.00019 0.00018 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 6e-05 6.1e-05 5.9e-05 6.7e-05 6.5e-05 6.4e-05 6.5e-05 0.049 0.048 0.05 0.049 0.0064 0.4 0.4 0.035 2.7e-11 2.7e-11 7.9e-11 8.1e-11 2.7e-06 2.6e-06 2.5e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
348 34590000 -0.66 -0.0028 -0.0029 -0.0028 0.75 -0.8 -0.4 0.73 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00054 -0.00051 0.00027 0.00026 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 5.6e-05 5.4e-05 6.1e-05 5.9e-05 6.3e-05 6.4e-05 0.047 0.046 0.049 0.048 0.0063 0.4 0.4 0.034 2.6e-11 2.7e-11 7.9e-11 8e-11 2.6e-06 2.5e-06 2.4e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
349 34690000 -0.67 -0.0032 -0.0033 -0.002 0.74 -0.75 -0.37 -0.36 0.73 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 2.6e-06 -0.00054 -0.00051 0.00027 0.00026 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 5.6e-05 5.4e-05 6.1e-05 5.9e-05 6.3e-05 6.4e-05 0.054 0.053 0.056 0.055 0.0063 0.41 0.41 0.034 2.7e-11 2.7e-11 7.8e-11 8e-11 2.6e-06 2.5e-06 2.4e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
350 34790000 -0.67 -0.0021 -0.0022 -0.0017 0.74 -0.75 -0.36 -0.35 0.72 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 2.6e-06 -0.00064 -0.00062 0.00038 0.00036 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 5.1e-05 4.9e-05 5.5e-05 5.3e-05 6.3e-05 6.4e-05 0.051 0.05 0.053 0.052 0.0062 0.41 0.41 0.034 2.6e-11 2.7e-11 7.7e-11 7.9e-11 2.6e-06 2.5e-06 2.4e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
351 34890000 -0.68 -0.0021 -0.0023 -0.0016 0.74 -0.71 -0.7 -0.32 0.72 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00064 -0.00062 0.00038 0.00036 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 5.1e-05 4.9e-05 5.5e-05 5.4e-05 6.3e-05 0.059 0.058 0.061 0.06 0.0062 0.42 0.42 0.034 2.6e-11 2.7e-11 7.7e-11 7.9e-11 2.6e-06 2.5e-06 2.4e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
352 34990000 -0.68 -0.0084 -0.0086 -0.0044 0.73 0.31 0.29 -0.13 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 2.6e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 4.6e-05 4.5e-05 5e-05 4.9e-05 6.2e-05 6.3e-05 0.058 0.057 0.058 0.057 0.0068 0.42 0.42 0.034 2.6e-11 2.7e-11 7.6e-11 7.8e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
353 35090000 -0.68 -0.0085 -0.0086 -0.0045 0.73 0.43 0.44 0.31 -0.19 -0.18 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 4.6e-05 4.5e-05 5e-05 4.9e-05 6.2e-05 6.3e-05 0.063 0.062 0.063 0.062 0.0068 0.43 0.43 0.034 2.7e-11 2.7e-11 7.6e-11 7.8e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
354 35190000 -0.68 -0.0085 -0.0087 -0.0045 0.73 0.45 0.46 0.34 0.35 -0.18 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 2.7e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 4.6e-05 4.5e-05 5e-05 4.9e-05 6.2e-05 6.3e-05 0.068 0.067 0.068 0.0067 0.44 0.44 0.034 2.7e-11 2.7e-11 7.5e-11 7.7e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
355 35290000 -0.68 -0.0085 -0.0087 -0.0046 0.73 0.48 0.37 0.38 -0.18 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 2.7e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 4.6e-05 4.5e-05 5e-05 4.9e-05 6.2e-05 6.3e-05 0.073 0.072 0.074 0.073 0.0066 0.46 0.45 0.033 2.7e-11 2.7e-11 7.5e-11 7.6e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
356 35390000 -0.68 -0.0086 -0.0088 -0.0045 0.73 0.5 0.4 0.41 -0.18 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 2.6e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 4.6e-05 4.5e-05 5e-05 4.9e-05 6.2e-05 6.3e-05 0.079 0.078 0.08 0.079 0.0066 0.47 0.47 0.034 2.7e-11 2.7e-11 7.4e-11 7.6e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
357 35490000 -0.68 -0.0086 -0.0088 -0.0045 0.73 0.52 0.53 0.44 -0.18 -17 -8 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 2.6e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.8e-05 6e-05 4.6e-05 4.5e-05 5e-05 4.9e-05 6.2e-05 6.3e-05 0.085 0.084 0.087 0.085 0.0065 0.49 0.49 0.034 2.7e-11 2.7e-11 7.3e-11 7.5e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
358 35590000 -0.68 -0.0056 -0.0058 -0.0045 0.73 0.41 0.42 0.35 0.36 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 2.8e-06 2.7e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 6e-05 3.9e-05 3.8e-05 4.2e-05 4.1e-05 6.1e-05 6.2e-05 0.068 0.067 0.069 0.0062 0.48 0.48 0.033 2.7e-11 2.7e-11 7.3e-11 7.5e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
359 35690000 -0.68 -0.0056 -0.0058 -0.0044 -0.0045 0.73 0.43 0.44 0.38 0.39 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 2.8e-06 -0.00078 -0.00076 0.00051 0.0005 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 6e-05 3.9e-05 3.8e-05 4.2e-05 4.1e-05 6.1e-05 6.2e-05 0.073 0.072 0.075 0.074 0.0061 0.49 0.49 0.033 2.7e-11 2.7e-11 7.2e-11 7.4e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
360 35790000 -0.68 -0.0034 -0.0036 -0.0044 0.73 0.35 0.36 0.32 0.33 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3e-06 2.9e-06 -0.0008 -0.00077 0.00053 0.00052 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 6e-05 3.4e-05 3.3e-05 3.6e-05 3.5e-05 6.1e-05 6.2e-05 0.061 0.06 0.062 0.0059 0.49 0.48 0.033 2.7e-11 2.7e-11 7.2e-11 7.4e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
361 35890000 -0.68 -0.0035 -0.0036 -0.0044 0.73 0.37 0.38 0.35 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 3.1e-06 3e-06 -0.0008 -0.00077 0.00053 0.00052 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 3.4e-05 3.3e-05 3.6e-05 3.5e-05 6.1e-05 6.2e-05 0.066 0.068 0.067 0.0058 0.5 0.5 0.033 2.7e-11 2.7e-11 7.1e-11 7.3e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
362 35990000 -0.68 -0.0016 -0.0018 -0.0043 0.73 0.3 0.31 0.29 0.3 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.3e-06 3.2e-06 -0.00087 -0.00085 0.00059 0.00058 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 3e-05 2.9e-05 3.1e-05 6.1e-05 6.2e-05 0.057 0.058 0.0057 0.49 0.49 0.033 2.7e-11 2.8e-11 2.7e-11 7.1e-11 7.3e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
363 36090000 -0.68 -0.0017 -0.0019 -0.0043 0.73 0.32 0.31 0.32 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.4e-06 -0.00087 -0.00085 0.0006 0.00058 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 3e-05 2.9e-05 3.1e-05 6.1e-05 6.2e-05 0.063 0.062 0.064 0.0057 0.51 0.51 0.032 2.7e-11 2.8e-11 7e-11 7.2e-11 2.5e-06 2.4e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
364 36190000 -0.68 -0.00029 -0.00042 -0.0042 0.73 0.26 0.27 0.27 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.5e-06 3.4e-06 -0.00098 -0.00095 0.00068 0.00067 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 2.6e-05 2.8e-05 2.7e-05 6.1e-05 6.2e-05 0.055 0.054 0.056 0.0055 0.5 0.5 0.032 2.7e-11 2.8e-11 7e-11 7.1e-11 2.4e-06 2.3e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
365 36290000 -0.68 -0.00042 -0.00054 -0.0041 0.73 0.27 0.28 0.29 -0.18 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.6e-06 -0.00098 -0.00095 0.00068 0.00067 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 2.6e-05 2.8e-05 2.7e-05 6.1e-05 6.2e-05 0.06 0.062 0.061 0.0056 0.52 0.52 0.032 2.7e-11 2.8e-11 6.9e-11 7.1e-11 2.4e-06 2.3e-06 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
366 36390000 -0.68 0.00061 0.00051 -0.004 0.73 0.23 0.24 0.25 -0.18 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.8e-06 -0.0011 0.00078 0.00076 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 2.4e-05 2.5e-05 6.1e-05 6.2e-05 0.053 0.055 0.054 0.0055 0.51 0.51 0.032 2.8e-11 2.8e-11 6.9e-11 7e-11 2.4e-06 2.3e-06 2.2e-06 2.1e-06 5e-08 0 0 0 0 0 0 0 0
367 36490000 -0.68 0.00052 0.00041 -0.004 0.73 0.24 0.26 0.27 -0.18 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.1e-06 4e-06 -0.0011 0.00078 0.00076 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.7e-05 5.9e-05 2.4e-05 2.5e-05 6e-05 6.1e-05 0.059 0.058 0.061 0.06 0.0055 0.53 0.52 0.032 2.8e-11 2.8e-11 6.8e-11 7e-11 2.4e-06 2.3e-06 2.2e-06 2.1e-06 5e-08 0 0 0 0 0 0 0 0
368 36590000 -0.68 0.0013 0.0012 -0.0039 0.73 0.2 0.22 0.23 -0.17 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.2e-06 -0.0012 0.00088 0.00086 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 2.2e-05 2.3e-05 6e-05 6.1e-05 0.053 0.052 0.054 0.053 0.0055 0.52 0.52 0.031 2.8e-11 2.8e-11 6.8e-11 6.9e-11 2.3e-06 2.2e-06 2.2e-06 2.1e-06 5e-08 0 0 0 0 0 0 0 0
369 36690000 -0.68 0.0013 0.0012 -0.0038 0.74 0.73 0.2 0.21 0.24 -0.17 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.3e-06 -0.0012 0.00088 0.00086 -0.00092 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 2.2e-05 2.3e-05 6e-05 6.1e-05 0.058 0.06 0.059 0.0055 0.53 0.53 0.031 2.8e-11 2.8e-11 6.8e-11 6.9e-11 2.3e-06 2.2e-06 2.2e-06 2.1e-06 5e-08 0 0 0 0 0 0 0 0
370 36790000 -0.68 0.0018 -0.0037 0.74 0.17 0.2 0.21 -0.16 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.5e-06 4.4e-06 -0.0014 -0.0013 0.00097 0.00096 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 2.1e-05 2e-05 2.2e-05 2.1e-05 6e-05 6.1e-05 0.052 0.051 0.053 0.0055 0.53 0.53 0.031 2.8e-11 2.8e-11 6.7e-11 6.9e-11 2.2e-06 2.1e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
371 36890000 -0.68 0.0018 0.0017 -0.0037 0.74 0.17 0.18 0.21 0.22 -0.16 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.6e-06 4.5e-06 -0.0014 -0.0013 0.00098 0.00096 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 2.1e-05 2e-05 2.2e-05 2.1e-05 6e-05 6.1e-05 0.057 0.059 0.058 0.0056 0.54 0.54 0.031 2.8e-11 2.8e-11 6.7e-11 6.8e-11 2.2e-06 2.1e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
372 36990000 -0.68 0.0022 -0.0035 -0.0036 0.74 0.14 0.15 0.19 -0.16 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.7e-06 -0.0015 0.0011 0.001 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 1.9e-05 2.1e-05 2e-05 6e-05 6.1e-05 0.051 0.052 0.0056 0.54 0.54 0.031 2.8e-11 2.8e-11 6.6e-11 6.8e-11 2.2e-06 2.1e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
373 37090000 -0.68 0.0021 -0.0035 0.74 0.15 0.19 0.2 -0.15 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.9e-06 -0.0015 0.0011 0.001 -0.00093 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 2e-05 1.9e-05 2.1e-05 2e-05 6e-05 6.1e-05 0.056 0.058 0.057 0.0057 0.55 0.55 0.031 2.8e-11 2.9e-11 6.6e-11 6.7e-11 2.2e-06 2.1e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
374 37190000 -0.68 0.0025 0.0024 -0.0034 0.74 0.12 0.13 0.16 0.17 -0.14 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.1e-06 -0.0016 0.0011 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 1.9e-05 1.8e-05 2e-05 1.9e-05 6e-05 6.1e-05 0.05 0.052 0.051 0.0057 0.55 0.55 0.031 2.8e-11 2.9e-11 6.5e-11 6.7e-11 2.1e-06 2e-06 1.9e-06 5e-08 0 0 0 0 0 0 0 0
375 37290000 -0.68 0.0024 -0.0034 0.74 0.12 0.13 0.17 0.18 -0.14 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.3e-06 -0.0016 0.0011 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.9e-05 1.9e-05 1.8e-05 2e-05 1.9e-05 6e-05 6.1e-05 0.055 0.057 0.056 0.0059 0.56 0.56 0.031 2.8e-11 2.9e-11 6.5e-11 6.6e-11 2.1e-06 2e-06 1.9e-06 5e-08 0 0 0 0 0 0 0 0
376 37390000 -0.68 0.0027 0.0026 -0.0033 0.74 0.099 0.1 0.14 0.15 -0.13 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.4e-06 -0.0017 0.0012 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.9e-05 6e-05 6.1e-05 0.05 0.049 0.051 0.05 0.0059 0.56 0.56 0.031 2.9e-11 2.9e-11 6.5e-11 6.6e-11 2e-06 1.9e-06 1.8e-06 5e-08 0 0 0 0 0 0 0 0
377 37490000 -0.68 0.0026 -0.0032 0.74 0.099 0.1 0.15 0.16 -0.12 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.5e-06 -0.0017 0.0012 -0.00094 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.9e-05 6e-05 6.1e-05 0.054 0.055 0.006 0.57 0.57 0.031 2.9e-11 2.9e-11 6.4e-11 6.6e-11 2e-06 1.9e-06 1.8e-06 5e-08 0 0 0 0 0 0 0 0
378 37590000 -0.68 0.0028 0.0027 -0.0031 0.74 0.079 0.084 0.13 -0.12 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.7e-06 -0.0018 0.0013 0.0012 -0.00095 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 6e-05 6.1e-05 0.049 0.048 0.05 0.049 0.0061 0.57 0.57 0.031 2.9e-11 2.9e-11 6.4e-11 6.5e-11 1.9e-06 1.8e-06 1.8e-06 1.7e-06 5e-08 0 0 0 0 0 0 0 0
379 37690000 -0.68 0.0027 -0.0032 0.74 0.078 0.082 0.13 0.14 -0.11 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.8e-06 -0.0018 0.0013 -0.00095 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.9e-05 1.8e-05 6e-05 6.1e-05 0.053 0.054 0.0062 0.58 0.58 0.031 2.9e-11 2.9e-11 6.3e-11 6.5e-11 1.9e-06 1.8e-06 1.8e-06 1.7e-06 5e-08 0 0 0 0 0 0 0 0
380 37790000 -0.68 0.0028 -0.0031 0.74 0.062 0.066 0.11 0.12 -0.099 -0.1 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6e-06 -0.0019 0.0013 -0.00096 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 6e-05 6.1e-05 0.048 0.047 0.048 0.0063 0.58 0.58 0.03 2.9e-11 2.9e-11 6.3e-11 6.4e-11 1.8e-06 1.7e-06 1.7e-06 1.6e-06 5e-08 0 0 0 0 0 0 0 0
381 37890000 -0.68 0.0028 -0.0031 0.74 0.06 0.064 0.12 -0.092 -0.093 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.2e-06 -0.0019 0.0013 -0.00096 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 6e-05 6.1e-05 0.052 0.051 0.053 0.052 0.0064 0.59 0.59 0.03 2.9e-11 2.9e-11 6.3e-11 6.4e-11 1.8e-06 1.7e-06 1.7e-06 1.6e-06 5e-08 0 0 0 0 0 0 0 0
382 37990000 -0.68 0.0029 -0.0031 0.74 0.045 0.049 0.1 0.11 -0.083 -0.084 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.3e-06 -0.002 -0.0019 0.0013 -0.00096 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.7e-05 1.8e-05 6e-05 6.1e-05 0.047 0.046 0.047 0.0065 0.59 0.59 0.031 2.9e-11 2.9e-11 6.2e-11 6.4e-11 1.7e-06 1.6e-06 5e-08 0 0 0 0 0 0 0 0
383 38090000 -0.68 0.0028 -0.0031 0.74 0.042 0.046 0.1 0.11 -0.073 -0.074 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.5e-06 -0.002 -0.0019 0.0014 0.0013 -0.00097 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 6e-05 6.1e-05 0.05 0.051 0.0066 0.6 0.6 0.031 2.9e-11 3e-11 6.2e-11 6.3e-11 1.7e-06 1.6e-06 5e-08 0 0 0 0 0 0 0 0
384 38190000 -0.68 0.0029 -0.003 0.74 0.029 0.032 0.088 0.092 -0.065 -0.066 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.6e-06 -0.002 0.0014 -0.00097 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.7e-05 1.8e-05 6e-05 6.1e-05 0.045 0.046 0.0067 0.6 0.6 0.031 2.9e-11 3e-11 6.1e-11 6.3e-11 1.6e-06 1.5e-06 5e-08 0 0 0 0 0 0 0 0
385 38290000 -0.68 0.0028 -0.003 0.74 0.026 0.03 0.089 0.093 -0.058 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.8e-06 -0.002 0.0014 -0.00097 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.6e-05 5.8e-05 1.8e-05 1.7e-05 1.8e-05 6e-05 6.1e-05 0.049 0.05 0.049 0.0068 0.61 0.61 0.031 2.9e-11 3e-11 6.1e-11 6.2e-11 1.6e-06 1.5e-06 5e-08 0 0 0 0 0 0 0 0
386 38390000 -0.68 0.0029 -0.0029 0.74 0.018 0.021 0.076 0.081 -0.051 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.9e-06 7e-06 -0.0021 0.0014 -0.00098 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.5e-05 5.8e-05 1.7e-05 1.8e-05 5.9e-05 6e-05 0.044 0.045 0.044 0.0069 0.61 0.61 0.031 2.9e-11 3e-11 6.1e-11 6.2e-11 1.6e-06 1.5e-06 1.5e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
387 38490000 -0.68 0.0028 -0.0029 0.74 0.015 0.018 0.078 0.082 -0.043 -0.044 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.1e-06 -0.0021 0.0014 -0.00098 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.5e-05 5.8e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 5.9e-05 6e-05 0.048 0.047 0.048 0.007 0.62 0.62 0.031 3e-11 3e-11 6e-11 6.2e-11 1.6e-06 1.5e-06 1.5e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
388 38590000 -0.68 0.0028 -0.0028 0.74 0.0099 0.013 0.067 0.071 -0.037 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.2e-06 7.3e-06 -0.0021 0.0014 -0.00099 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.5e-05 5.8e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 5.9e-05 6e-05 0.043 0.044 0.043 0.0071 0.62 0.62 0.031 3e-11 3e-11 6e-11 6.1e-11 1.5e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
389 38690000 -0.68 0.0027 0.0028 -0.0028 0.74 0.006 0.0088 0.066 0.07 -0.03 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.4e-06 -0.0021 0.0014 -0.00099 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.5e-05 5.8e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 5.9e-05 6e-05 0.046 0.047 0.0072 0.63 0.63 0.031 3e-11 3e-11 6e-11 6.1e-11 1.5e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
390 38790000 -0.68 0.0027 0.0028 -0.0028 0.74 0.00056 0.0031 0.054 0.058 -0.022 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.5e-06 -0.0022 -0.0021 0.0014 -0.00099 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.5e-05 5.7e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 5.9e-05 6e-05 0.042 0.042 0.0073 0.63 0.63 0.031 3e-11 3e-11 5.9e-11 6e-11 1.4e-06 1.4e-06 1.3e-06 5e-08 0 0 0 0 0 0 0 0
391 38890000 -0.68 0.0025 0.0026 -0.0028 0.74 -0.0093 -0.0067 0.044 0.048 0.48 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.6e-06 7.7e-06 -0.0022 -0.0021 0.0014 -0.001 0.21 0.0021 0.43 0.44 0 0 0 0 0 5.5e-05 5.7e-05 1.8e-05 1.7e-05 1.9e-05 1.8e-05 5.9e-05 6e-05 0.045 0.045 0.0075 0.64 0.64 0.032 3e-11 3e-11 5.9e-11 6e-11 1.4e-06 1.4e-06 1.3e-06 5e-08 0 0 0 0 0 0 0 0

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]
10000,1,-0.0099,-0.011,-0.0001,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
90000,0.98,-0.0093,-0.012,0.18,1.9e-05,-0.0025,-0.0087,-1.3e-05,-9.5e-05,-0.00027,0,0,0,0,0,0,0.2,-6.1e-09,0.43,0,0,0,0,0,6.5e-05,0.0025,0.0025,0.002,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
190000,0.98,-0.0093,-0.012,0.18,-0.0017,-0.0025,-0.021,-7.1e-05,-0.00033,0.034,8e-13,-3.2e-12,-6.8e-14,0,0,-2.7e-10,0.2,-6.1e-09,0.43,0,0,0,0,0,3.7e-05,0.0025,0.0025,0.0011,25,25,10,1e+02,1e+02,1.3,1e-06,1e-06,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
290000,0.98,-0.0094,-0.013,0.18,-0.0026,-0.0038,-0.029,-0.00015,-0.00018,0.037,1.1e-11,-3.9e-11,-9.2e-13,0,0,-2.7e-08,0.2,-6.1e-09,0.43,0,0,0,0,0,2.7e-05,0.0027,0.0027,0.00081,25,25,9.6,0.31,0.31,0.44,1e-06,1e-06,9.8e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
390000,0.98,-0.0094,-0.013,0.18,-0.0018,-0.0047,-0.049,-0.00041,-0.00057,0.044,-2.7e-11,-4.6e-12,-2.8e-13,0,0,1e-07,0.2,-6.1e-09,0.43,0,0,0,0,0,2.2e-05,0.0028,0.0028,0.00067,25,25,8.3,0.81,0.81,0.32,1e-06,1e-06,9.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
490000,0.98,-0.0094,-0.013,0.18,0.00035,-0.0048,-0.06,-7.5e-05,-0.00031,0.046,-4.7e-09,5.3e-09,1.4e-10,0,0,2e-07,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.003,0.003,0.00061,7.8,7.8,6.2,0.29,0.29,0.31,1e-06,1e-06,9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
590000,0.98,-0.0095,-0.014,0.18,-0.00033,-0.0075,-0.11,-6.5e-05,-0.00095,0.027,-5.5e-09,5.5e-09,1.6e-10,0,0,7e-07,0.2,-6.1e-09,0.43,0,0,0,0,0,1.9e-05,0.0033,0.0033,0.00058,7.9,7.9,4.4,0.59,0.59,0.32,1e-06,1e-06,8.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
690000,0.98,-0.0095,-0.014,0.18,0.0017,-0.0068,-0.045,4e-05,-0.00052,0.048,-3.2e-08,1.6e-08,6.6e-10,0,0,-8.1e-07,0.2,-6.1e-09,0.43,0,0,0,0,0,1.9e-05,0.0036,0.0036,0.00057,2.6,2.6,2.9,0.23,0.23,0.3,1e-06,1e-06,7.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
790000,0.98,-0.0095,-0.014,0.18,0.0039,-0.0073,-0.05,0.00025,-0.0012,0.045,-3.1e-08,1.6e-08,6.3e-10,0,0,-1.1e-06,0.2,-6.1e-09,0.43,0,0,0,0,0,1.9e-05,0.0039,0.0039,0.00057,2.7,2.7,2,0.38,0.38,0.27,1e-06,1e-06,6.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
890000,0.98,-0.0095,-0.014,0.18,0.0041,-0.0053,-0.091,0.00025,-0.00067,0.025,-1.4e-07,2.2e-08,4.5e-09,0,0,-1.3e-07,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.0043,0.0043,0.00057,1.3,1.3,1.4,0.19,0.19,0.26,1e-06,1e-06,6.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
990000,0.98,-0.0095,-0.015,0.18,0.0067,-0.0053,-0.11,0.00082,-0.0012,0.0098,-1.4e-07,2.2e-08,4.6e-09,0,0,3.6e-07,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.0047,0.0047,0.00057,1.4,1.4,0.99,0.28,0.28,0.23,1e-06,1e-06,5.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1090000,0.98,-0.0096,-0.015,0.18,0.013,-0.0068,-0.13,0.00079,-0.00077,-0.0066,-4.1e-07,-9.4e-08,1.8e-08,0,0,7e-07,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.0051,0.0051,0.00056,0.85,0.86,0.72,0.16,0.16,0.21,9.9e-07,9.9e-07,4.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1190000,0.98,-0.0095,-0.015,0.18,0.018,-0.0095,-0.1,0.0023,-0.0016,0.0096,-4e-07,-8.1e-08,1.7e-08,0,0,-4.4e-06,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.0056,0.0056,0.00055,1,1,0.56,0.22,0.22,0.2,9.9e-07,9.9e-07,4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1290000,0.98,-0.0093,-0.015,0.18,0.021,-0.0083,-0.11,0.002,-0.0012,0.0086,-1.3e-06,-7.9e-07,6.7e-08,0,0,-7e-06,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.0058,0.0058,0.00054,0.79,0.79,0.43,0.14,0.14,0.18,9.6e-07,9.6e-07,3.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1390000,0.98,-0.0093,-0.016,0.18,0.03,-0.011,-0.095,0.0046,-0.0021,0.018,-1.2e-06,-7.5e-07,6.6e-08,0,0,-1.3e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.0064,0.0064,0.00053,1,1,0.34,0.19,0.19,0.16,9.6e-07,9.6e-07,3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1490000,0.98,-0.0093,-0.016,0.18,0.035,-0.013,-0.11,0.0079,-0.0032,0.0027,-1.2e-06,-7.6e-07,6.6e-08,0,0,-1.1e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,2e-05,0.0071,0.0071,0.00051,1.3,1.3,0.27,0.28,0.28,0.15,9.6e-07,9.6e-07,2.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1590000,0.98,-0.0092,-0.016,0.18,0.035,-0.011,-0.13,0.0067,-0.0025,-0.007,-3.2e-06,-2.9e-06,1.8e-07,0,0,-1.3e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.9e-05,0.0068,0.0068,0.0005,1.1,1.1,0.23,0.19,0.19,0.14,9.1e-07,9.1e-07,2.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1690000,0.98,-0.0092,-0.016,0.18,0.043,-0.012,-0.13,0.011,-0.0036,-0.012,-3.1e-06,-2.8e-06,1.8e-07,0,0,-1.7e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.9e-05,0.0075,0.0075,0.00048,1.5,1.5,0.19,0.27,0.27,0.13,9.1e-07,9.1e-07,1.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1790000,0.98,-0.009,-0.016,0.18,0.04,-0.0094,-0.13,0.0082,-0.0025,-0.011,-6.2e-06,-6.6e-06,3.4e-07,0,0,-2.7e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.8e-05,0.0066,0.0066,0.00046,1.2,1.2,0.17,0.18,0.18,0.13,8.1e-07,8.1e-07,1.7e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
1890000,0.98,-0.009,-0.016,0.18,0.047,-0.0081,-0.14,0.013,-0.0033,-0.019,-6.2e-06,-6.6e-06,3.4e-07,0,0,-3.1e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.8e-05,0.0073,0.0072,0.00045,1.6,1.6,0.15,0.28,0.28,0.12,8.1e-07,8.1e-07,1.5e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
1990000,0.98,-0.0087,-0.016,0.18,0.038,-0.0042,-0.14,0.0088,-0.002,-0.018,-9.8e-06,-1.2e-05,5.3e-07,0,0,-4.4e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.7e-05,0.0059,0.0059,0.00043,1.2,1.2,0.13,0.18,0.18,0.11,7e-07,7e-07,1.3e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
2090000,0.98,-0.0087,-0.016,0.18,0.045,-0.0043,-0.14,0.013,-0.0024,-0.015,-9.7e-06,-1.2e-05,5.2e-07,0,0,-6.3e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.7e-05,0.0064,0.0064,0.00042,1.5,1.5,0.12,0.28,0.28,0.11,7e-07,7e-07,1.1e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
2190000,0.98,-0.0083,-0.015,0.18,0.035,-0.0017,-0.14,0.0085,-0.0012,-0.021,-1.3e-05,-1.7e-05,6.8e-07,0,0,-7.3e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.5e-05,0.0049,0.0049,0.0004,1.1,1.1,0.12,0.18,0.18,0.11,5.9e-07,5.9e-07,9.9e-08,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
2290000,0.98,-0.0084,-0.016,0.18,0.04,-0.00055,-0.14,0.012,-0.0013,-0.019,-1.3e-05,-1.7e-05,6.7e-07,0,0,-9.5e-05,0.2,-6.1e-09,0.43,0,0,0,0,0,1.5e-05,0.0054,0.0054,0.00039,1.4,1.4,0.11,0.27,0.27,0.1,5.9e-07,5.9e-07,8.8e-08,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
2390000,0.98,-0.0082,-0.015,0.18,0.031,0.00032,-0.14,0.0077,-0.00055,-0.016,-1.5e-05,-2.2e-05,7.7e-07,0,0,-0.00012,0.2,-6.1e-09,0.43,0,0,0,0,0,1.4e-05,0.004,0.004,0.00038,0.99,0.99,0.1,0.17,0.17,0.098,4.9e-07,4.9e-07,7.9e-08,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
2490000,0.98,-0.0081,-0.015,0.18,0.033,0.0022,-0.14,0.011,-0.00044,-0.023,-1.5e-05,-2.2e-05,7.7e-07,0,0,-0.00013,0.2,-6.1e-09,0.43,0,0,0,0,0,1.4e-05,0.0044,0.0044,0.00036,1.2,1.2,0.1,0.25,0.25,0.097,4.9e-07,4.9e-07,7e-08,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
2590000,0.98,-0.008,-0.015,0.18,0.023,0.0014,-0.15,0.0066,-7.8e-05,-0.028,-1.7e-05,-2.7e-05,8.3e-07,0,0,-0.00015,0.2,-6.1e-09,0.43,0,0,0,0,0,1.3e-05,0.0033,0.0033,0.00035,0.86,0.86,0.099,0.16,0.16,0.094,4.1e-07,4.1e-07,6.3e-08,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
2690000,0.98,-0.008,-0.015,0.18,0.027,0.0034,-0.15,0.0092,0.00016,-0.028,-1.7e-05,-2.7e-05,8.3e-07,0,0,-0.00018,0.2,-6.1e-09,0.43,0,0,0,0,0,1.3e-05,0.0036,0.0036,0.00034,1.1,1.1,0.097,0.24,0.24,0.091,4.1e-07,4.1e-07,5.7e-08,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
2790000,0.98,-0.0079,-0.015,0.18,0.021,0.0037,-0.14,0.0057,0.0003,-0.025,-1.8e-05,-3e-05,8.6e-07,0,0,-0.00022,0.2,-6.1e-09,0.43,0,0,0,0,0,1.2e-05,0.0027,0.0027,0.00033,0.74,0.74,0.096,0.15,0.15,0.089,3.4e-07,3.4e-07,5.1e-08,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
2890000,0.98,-0.0079,-0.015,0.18,0.025,0.0032,-0.14,0.0081,0.0006,-0.025,-1.8e-05,-3e-05,8.6e-07,0,0,-0.00025,0.2,-6.1e-09,0.43,0,0,0,0,0,1.2e-05,0.003,0.003,0.00032,0.92,0.92,0.096,0.22,0.22,0.089,3.4e-07,3.4e-07,4.6e-08,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
2990000,0.98,-0.0078,-0.014,0.18,0.019,0.0023,-0.15,0.0052,0.00045,-0.03,-1.9e-05,-3.3e-05,8.8e-07,0,0,-0.00027,0.2,-6.1e-09,0.43,0,0,0,0,0,1.1e-05,0.0023,0.0023,0.00031,0.65,0.65,0.095,0.14,0.14,0.088,2.9e-07,2.9e-07,4.2e-08,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
3090000,0.98,-0.0078,-0.015,0.18,0.025,0.0012,-0.15,0.0075,0.00057,-0.032,-1.9e-05,-3.3e-05,8.7e-07,0,0,-0.00031,0.2,-6.1e-09,0.43,0,0,0,0,0,1.1e-05,0.0026,0.0026,0.0003,0.81,0.81,0.095,0.2,0.2,0.086,2.9e-07,2.9e-07,3.8e-08,4e-06,4e-06,3.2e-06,0,0,0,0,0,0,0,0
3190000,0.98,-0.0078,-0.014,0.18,0.021,1.8e-05,-0.15,0.0049,0.00029,-0.042,-2e-05,-3.6e-05,8.9e-07,0,0,-0.00032,0.2,-6.1e-09,0.43,0,0,0,0,0,1e-05,0.002,0.002,0.00029,0.58,0.58,0.096,0.14,0.14,0.087,2.4e-07,2.4e-07,3.5e-08,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0
3290000,0.98,-0.0077,-0.015,0.18,0.024,0.0007,-0.15,0.0072,0.00026,-0.05,-2e-05,-3.6e-05,8.8e-07,0,0,-0.00034,0.2,-6.1e-09,0.43,0,0,0,0,0,1e-05,0.0022,0.0022,0.00028,0.71,0.72,0.095,0.19,0.19,0.086,2.4e-07,2.4e-07,3.2e-08,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
3390000,0.98,-0.0075,-0.014,0.18,0.019,0.0021,-0.15,0.0048,0.00019,-0.048,-2e-05,-3.8e-05,8.9e-07,0,0,-0.00039,0.2,-6.1e-09,0.43,0,0,0,0,0,9.6e-06,0.0018,0.0018,0.00028,0.52,0.52,0.095,0.13,0.13,0.085,2.1e-07,2.1e-07,2.9e-08,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
3490000,0.98,-0.0074,-0.014,0.18,0.024,0.0052,-0.15,0.007,0.00055,-0.048,-2e-05,-3.8e-05,8.9e-07,0,0,-0.00043,0.2,-6.1e-09,0.43,0,0,0,0,0,9.5e-06,0.002,0.002,0.00027,0.64,0.64,0.095,0.18,0.18,0.086,2.1e-07,2.1e-07,2.7e-08,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
3590000,0.98,-0.0073,-0.014,0.18,0.028,0.0054,-0.15,0.0097,0.0011,-0.055,-2e-05,-3.8e-05,8.9e-07,0,0,-0.00046,0.2,-6.1e-09,0.43,0,0,0,0,0,9.3e-06,0.0022,0.0022,0.00026,0.79,0.79,0.094,0.24,0.24,0.086,2.1e-07,2.1e-07,2.5e-08,4e-06,4e-06,2.6e-06,0,0,0,0,0,0,0,0
3690000,0.98,-0.0073,-0.014,0.18,0.022,0.0058,-0.15,0.007,0.00099,-0.052,-2.1e-05,-4e-05,8.9e-07,0,0,-0.00051,0.2,-6.1e-09,0.43,0,0,0,0,0,8.9e-06,0.0017,0.0017,0.00026,0.58,0.58,0.093,0.17,0.17,0.085,1.7e-07,1.7e-07,2.3e-08,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
3790000,0.98,-0.0072,-0.014,0.18,0.024,0.01,-0.15,0.0094,0.0019,-0.057,-2.1e-05,-4e-05,8.9e-07,0,0,-0.00054,0.2,-6.1e-09,0.43,0,0,0,0,0,8.8e-06,0.0019,0.0019,0.00025,0.71,0.71,0.093,0.23,0.23,0.086,1.7e-07,1.7e-07,2.1e-08,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
3890000,0.98,-0.0072,-0.014,0.18,0.018,0.01,-0.14,0.0065,0.0018,-0.058,-2.1e-05,-4.3e-05,8.8e-07,0,0,-0.00058,0.2,-6.1e-09,0.43,0,0,0,0,0,8.4e-06,0.0015,0.0015,0.00024,0.54,0.54,0.091,0.16,0.16,0.086,1.5e-07,1.5e-07,2e-08,4e-06,4e-06,2.2e-06,0,0,0,0,0,0,0,0
3990000,0.98,-0.0071,-0.014,0.18,0.023,0.011,-0.14,0.0087,0.0028,-0.056,-2.1e-05,-4.2e-05,8.8e-07,0,0,-0.00063,0.2,-6.1e-09,0.43,0,0,0,0,0,8.3e-06,0.0017,0.0017,0.00024,0.65,0.65,0.089,0.21,0.21,0.085,1.5e-07,1.5e-07,1.8e-08,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
4090000,0.98,-0.0071,-0.014,0.18,0.019,0.0093,-0.12,0.0063,0.0023,-0.042,-2.1e-05,-4.5e-05,8.7e-07,0,0,-0.00071,0.2,-6.1e-09,0.43,0,0,0,0,0,8e-06,0.0014,0.0014,0.00023,0.49,0.49,0.087,0.15,0.15,0.085,1.2e-07,1.2e-07,1.7e-08,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
4190000,0.98,-0.0072,-0.014,0.18,0.022,0.0097,-0.12,0.0083,0.0032,-0.045,-2.1e-05,-4.4e-05,8.7e-07,0,0,-0.00074,0.2,-6.1e-09,0.43,0,0,0,0,0,7.8e-06,0.0015,0.0015,0.00023,0.6,0.6,0.086,0.2,0.2,0.086,1.2e-07,1.2e-07,1.6e-08,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
4290000,0.98,-0.0073,-0.014,0.18,0.019,0.0088,-0.13,0.006,0.0024,-0.05,-2.1e-05,-4.7e-05,8.6e-07,0,0,-0.00076,0.2,-6.1e-09,0.43,0,0,0,0,0,7.5e-06,0.0012,0.0012,0.00022,0.45,0.46,0.084,0.14,0.14,0.085,1e-07,1e-07,1.5e-08,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
4390000,0.98,-0.0072,-0.014,0.18,0.023,0.0084,-0.11,0.0082,0.0032,-0.039,-2.1e-05,-4.6e-05,8.5e-07,0,0,-0.00083,0.2,-6.1e-09,0.43,0,0,0,0,0,7.4e-06,0.0013,0.0013,0.00022,0.55,0.55,0.081,0.19,0.19,0.084,1e-07,1e-07,1.4e-08,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
4490000,0.98,-0.0073,-0.013,0.18,0.019,0.0089,-0.11,0.006,0.0024,-0.04,-2.1e-05,-4.8e-05,8.4e-07,0,0,-0.00086,0.2,-6.1e-09,0.43,0,0,0,0,0,7.2e-06,0.0011,0.0011,0.00021,0.42,0.42,0.08,0.14,0.14,0.085,8.2e-08,8.2e-08,1.3e-08,4e-06,4e-06,1.5e-06,0,0,0,0,0,0,0,0
4590000,0.98,-0.0073,-0.013,0.18,0.022,0.0085,-0.11,0.008,0.0033,-0.042,-2.1e-05,-4.8e-05,8.4e-07,0,0,-0.00088,0.2,-6.1e-09,0.43,0,0,0,0,0,7.1e-06,0.0012,0.0012,0.00021,0.5,0.5,0.077,0.18,0.18,0.084,8.2e-08,8.2e-08,1.2e-08,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
4690000,0.98,-0.0073,-0.013,0.18,0.016,0.007,-0.1,0.0058,0.0023,-0.035,-2.1e-05,-5e-05,8.3e-07,0,0,-0.00093,0.2,-6.1e-09,0.43,0,0,0,0,0,6.8e-06,0.00093,0.00093,0.0002,0.39,0.39,0.075,0.13,0.13,0.083,6.6e-08,6.6e-08,1.1e-08,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
4790000,0.98,-0.0072,-0.013,0.18,0.014,0.0081,-0.1,0.0072,0.0031,-0.037,-2.1e-05,-5e-05,8.3e-07,0,0,-0.00095,0.2,-6.1e-09,0.43,0,0,0,0,0,6.7e-06,0.001,0.001,0.0002,0.46,0.46,0.073,0.17,0.17,0.084,6.6e-08,6.6e-08,1.1e-08,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
4890000,0.98,-0.0072,-0.013,0.18,0.0097,0.0043,-0.094,0.0048,0.0021,-0.033,-2.1e-05,-5.2e-05,8.2e-07,0,0,-0.00098,0.2,-6.1e-09,0.43,0,0,0,0,0,6.5e-06,0.00081,0.00081,0.0002,0.35,0.35,0.07,0.12,0.12,0.083,5.4e-08,5.4e-08,1e-08,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
4990000,0.98,-0.0071,-0.013,0.18,0.013,0.006,-0.086,0.0059,0.0027,-0.028,-2.1e-05,-5.1e-05,8.2e-07,0,0,-0.001,0.2,-6.1e-09,0.43,0,0,0,0,0,6.4e-06,0.00087,0.00087,0.00019,0.42,0.42,0.067,0.16,0.16,0.082,5.4e-08,5.4e-08,9.5e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
5090000,0.98,-0.007,-0.013,0.18,0.0096,0.0054,-0.083,0.0041,0.0018,-0.026,-2.1e-05,-5.3e-05,8.1e-07,0,0,-0.001,0.2,-6.1e-09,0.43,0,0,0,0,0,6.3e-06,0.0007,0.0007,0.00019,0.32,0.32,0.066,0.12,0.12,0.082,4.3e-08,4.3e-08,8.9e-09,4e-06,4e-06,9.9e-07,0,0,0,0,0,0,0,0
5190000,0.98,-0.0069,-0.013,0.18,0.0083,0.0085,-0.08,0.005,0.0025,-0.024,-2.1e-05,-5.3e-05,8.1e-07,0,0,-0.0011,0.2,-6.1e-09,0.43,0,0,0,0,0,6.2e-06,0.00075,0.00075,0.00018,0.38,0.38,0.063,0.16,0.16,0.081,4.3e-08,4.3e-08,8.4e-09,4e-06,4e-06,9.2e-07,0,0,0,0,0,0,0,0
5290000,0.98,-0.0068,-0.013,0.18,0.0066,0.0083,-0.069,0.0034,0.002,-0.017,-2.1e-05,-5.4e-05,8e-07,0,0,-0.0011,0.2,-6.1e-09,0.43,0,0,0,0,0,6e-06,0.0006,0.0006,0.00018,0.3,0.3,0.06,0.11,0.11,0.08,3.5e-08,3.5e-08,8e-09,4e-06,4e-06,8.5e-07,0,0,0,0,0,0,0,0
5390000,0.98,-0.0067,-0.013,0.18,0.005,0.011,-0.065,0.004,0.0029,-0.012,-2.1e-05,-5.3e-05,8e-07,0,0,-0.0011,0.2,-6.1e-09,0.43,0,0,0,0,0,5.9e-06,0.00065,0.00065,0.00018,0.35,0.35,0.058,0.15,0.15,0.079,3.5e-08,3.5e-08,7.5e-09,4e-06,4e-06,7.9e-07,0,0,0,0,0,0,0,0
5490000,0.98,-0.0068,-0.013,0.18,0.004,0.012,-0.061,0.0026,0.0024,-0.0099,-2e-05,-5.4e-05,7.9e-07,0,0,-0.0011,0.2,-6.1e-09,0.43,0,0,0,0,0,5.8e-06,0.00052,0.00052,0.00017,0.27,0.27,0.056,0.11,0.11,0.079,2.8e-08,2.8e-08,7.1e-09,4e-06,4e-06,7.3e-07,0,0,0,0,0,0,0,0
5590000,0.98,-0.0068,-0.013,0.18,0.0041,0.016,-0.054,0.0031,0.0038,-0.0031,-2e-05,-5.4e-05,7.9e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.7e-06,0.00056,0.00056,0.00017,0.32,0.32,0.054,0.14,0.14,0.078,2.8e-08,2.8e-08,6.8e-09,4e-06,4e-06,6.8e-07,0,0,0,0,0,0,0,0
5690000,0.98,-0.0067,-0.013,0.18,0.0051,0.019,-0.053,0.0035,0.0056,-0.00026,-2e-05,-5.4e-05,7.9e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.6e-06,0.0006,0.0006,0.00017,0.37,0.37,0.051,0.18,0.18,0.077,2.8e-08,2.8e-08,6.4e-09,4e-06,4e-06,6.3e-07,0,0,0,0,0,0,0,0
5790000,0.98,-0.0067,-0.013,0.18,0.0038,0.019,-0.05,0.0024,0.0049,0.0021,-2e-05,-5.5e-05,7.8e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.5e-06,0.00048,0.00048,0.00017,0.29,0.29,0.05,0.13,0.13,0.077,2.3e-08,2.3e-08,6.1e-09,4e-06,4e-06,5.9e-07,0,0,0,0,0,0,0,0
5890000,0.98,-0.0066,-0.013,0.18,0.0064,0.02,-0.048,0.0029,0.0068,-0.00038,-2e-05,-5.5e-05,7.8e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.4e-06,0.00051,0.00051,0.00016,0.34,0.34,0.048,0.17,0.17,0.075,2.3e-08,2.3e-08,5.8e-09,4e-06,4e-06,5.5e-07,0,0,0,0,0,0,0,0
5990000,0.98,-0.0067,-0.013,0.18,0.006,0.018,-0.042,0.0022,0.0056,0.0052,-1.9e-05,-5.5e-05,7.6e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.3e-06,0.00041,0.00041,0.00016,0.26,0.26,0.046,0.13,0.13,0.074,1.8e-08,1.8e-08,5.5e-09,4e-06,4e-06,5.1e-07,0,0,0,0,0,0,0,0
6090000,0.98,-0.0067,-0.013,0.18,0.0057,0.02,-0.039,0.0028,0.0075,0.0078,-1.9e-05,-5.5e-05,7.6e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.2e-06,0.00044,0.00044,0.00016,0.3,0.3,0.044,0.16,0.16,0.074,1.8e-08,1.8e-08,5.3e-09,4e-06,4e-06,4.8e-07,0,0,0,0,0,0,0,0
6190000,0.98,-0.0068,-0.013,0.18,0.0036,0.018,-0.038,0.0021,0.006,0.0086,-1.9e-05,-5.6e-05,7.5e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.1e-06,0.00036,0.00036,0.00016,0.24,0.24,0.042,0.12,0.12,0.073,1.5e-08,1.5e-08,5e-09,4e-06,4e-06,4.4e-07,0,0,0,0,0,0,0,0
6290000,0.98,-0.0068,-0.013,0.18,0.0022,0.02,-0.041,0.0024,0.0078,0.002,-1.9e-05,-5.6e-05,7.5e-07,0,0,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5e-06,0.00038,0.00038,0.00015,0.27,0.27,0.041,0.15,0.15,0.072,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,4.1e-07,0,0,0,0,0,0,0,0
6390000,0.98,-0.0067,-0.013,0.19,0.0032,0.017,-0.042,0.0016,0.0062,-0.00048,-1.8e-05,-5.6e-05,7.3e-07,0,0,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.2e-05,0.0003,0.0003,0.0017,0.2,0.2,0.039,0.12,0.12,0.072,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,3.9e-07,0,0,0,0,0,0,0,0
6490000,0.98,-0.0066,-0.013,0.19,0.00094,0.016,-0.039,0.0019,0.0078,0.002,-1.8e-05,-5.6e-05,7.1e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.8e-05,0.0003,0.0003,0.0011,0.21,0.21,0.038,0.14,0.14,0.071,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,3.6e-07,0,0,0,0,0,0,0,0
6590000,0.98,-0.0066,-0.013,0.19,0.00022,0.019,-0.042,0.002,0.0095,-0.0009,-1.8e-05,-5.6e-05,6.9e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-05,0.0003,0.0003,0.00076,0.21,0.21,0.036,0.18,0.18,0.069,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,3.4e-07,0,0,0,0,0,0,0,0
6690000,0.98,-0.0065,-0.013,0.19,-0.0024,0.021,-0.044,0.0018,0.012,-0.0016,-1.8e-05,-5.6e-05,6.5e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.1e-05,0.0003,0.0003,0.0006,0.22,0.22,0.035,0.21,0.21,0.068,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,3.1e-07,0,0,0,0,0,0,0,0
6790000,0.98,-0.0065,-0.013,0.19,-0.0007,0.023,-0.042,0.0016,0.014,-0.0023,-1.8e-05,-5.6e-05,6.2e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.8e-05,0.0003,0.0003,0.0005,0.23,0.23,0.034,0.25,0.25,0.068,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,2.9e-07,0,0,0,0,0,0,0,0
6890000,0.98,-0.0063,-0.013,0.19,-0.0012,0.023,-0.039,0.0015,0.016,0.00034,-1.8e-05,-5.6e-05,6e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.5e-05,0.00031,0.00031,0.00042,0.25,0.25,0.032,0.3,0.3,0.067,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,2.8e-07,0,0,0,0,0,0,0,0
6990000,0.98,-0.0062,-0.013,0.19,-0.0013,0.025,-0.037,0.0014,0.018,0.00071,-1.8e-05,-5.6e-05,5.9e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00031,0.00031,0.00037,0.27,0.27,0.031,0.35,0.35,0.066,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0
7090000,0.98,-0.0061,-0.012,0.19,-0.0022,0.03,-0.038,0.0012,0.021,-0.00035,-1.8e-05,-5.6e-05,6e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00031,0.00031,0.00033,0.29,0.29,0.03,0.41,0.41,0.066,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,2.4e-07,0,0,0,0,0,0,0,0
7190000,0.98,-0.006,-0.013,0.19,-0.0027,0.032,-0.037,0.00089,0.024,-0.003,-1.8e-05,-5.6e-05,5.3e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00032,0.00032,0.00029,0.32,0.32,0.029,0.47,0.47,0.065,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,2.3e-07,0,0,0,0,0,0,0,0
7290000,0.98,-0.006,-0.013,0.19,-0.002,0.037,-0.034,0.00061,0.028,0.00094,-1.8e-05,-5.6e-05,5.4e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,9.6e-06,0.00032,0.00032,0.00027,0.34,0.34,0.028,0.55,0.55,0.064,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0
7390000,0.98,-0.0059,-0.013,0.19,-0.0037,0.04,-0.032,0.00034,0.031,0.0032,-1.8e-05,-5.6e-05,5.6e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8.9e-06,0.00033,0.00033,0.00025,0.38,0.38,0.027,0.63,0.63,0.064,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0
7490000,0.98,-0.0059,-0.013,0.19,-0.0015,0.043,-0.026,0.00013,0.036,0.0095,-1.8e-05,-5.6e-05,6.7e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00034,0.00034,0.00023,0.41,0.41,0.026,0.72,0.72,0.063,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,1.9e-07,0,0,0,0,0,0,0,0
7590000,0.98,-0.006,-0.013,0.19,-0.00051,0.046,-0.023,4.1e-05,0.04,0.015,-1.8e-05,-5.6e-05,6.9e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00034,0.00034,0.00021,0.45,0.45,0.025,0.81,0.82,0.062,1.2e-08,1.2e-08,4.7e-09,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0
7690000,0.98,-0.006,-0.013,0.19,-0.00089,0.05,-0.022,-2.6e-05,0.045,0.019,-1.8e-05,-5.6e-05,6.6e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,0.00035,0.00035,0.0002,0.49,0.49,0.025,0.93,0.93,0.062,1.2e-08,1.2e-08,4.6e-09,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0
7790000,0.98,-0.0058,-0.013,0.19,0.00066,0.053,-0.025,-4.8e-05,0.05,0.014,-1.8e-05,-5.6e-05,5.8e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,0.00036,0.00036,0.00019,0.54,0.54,0.024,1.1,1.1,0.061,1.2e-08,1.2e-08,4.6e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
7890000,0.98,-0.0059,-0.013,0.19,-0.00072,0.057,-0.025,-0.00014,0.055,0.011,-1.8e-05,-5.6e-05,5.3e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,0.00037,0.00037,0.00018,0.58,0.58,0.023,1.2,1.2,0.06,1.2e-08,1.2e-08,4.6e-09,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0
7990000,0.98,-0.0058,-0.013,0.19,-0.0005,0.06,-0.022,-0.0002,0.06,0.014,-1.8e-05,-5.6e-05,5.4e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.1e-06,0.00038,0.00038,0.00017,0.64,0.64,0.022,1.4,1.4,0.059,1.2e-08,1.2e-08,4.6e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
8090000,0.98,-0.0056,-0.013,0.19,0.00093,0.065,-0.022,-0.00015,0.066,0.012,-1.8e-05,-5.6e-05,2.8e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.9e-06,0.00038,0.00038,0.00016,0.69,0.69,0.022,1.5,1.5,0.059,1.2e-08,1.2e-08,4.6e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
8190000,0.98,-0.0057,-0.013,0.19,0.0015,0.071,-0.018,-5.7e-05,0.073,0.018,-1.8e-05,-5.6e-05,7.1e-08,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.6e-06,0.00039,0.00039,0.00015,0.75,0.75,0.021,1.7,1.7,0.058,1.2e-08,1.2e-08,4.6e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
8290000,0.98,-0.0057,-0.013,0.19,0.0036,0.075,-0.017,0.00018,0.079,0.018,-1.8e-05,-5.6e-05,-6.3e-09,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.4e-06,0.0004,0.0004,0.00015,0.8,0.81,0.02,1.9,1.9,0.057,1.2e-08,1.2e-08,4.6e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
8390000,0.98,-0.0056,-0.013,0.19,0.0014,0.077,-0.016,0.00043,0.086,0.019,-1.8e-05,-5.6e-05,-8.2e-08,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.2e-06,0.00041,0.00041,0.00014,0.87,0.87,0.02,2.1,2.1,0.057,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
8490000,0.98,-0.0055,-0.013,0.19,0.0011,0.081,-0.017,0.00057,0.092,0.015,-1.8e-05,-5.6e-05,7.5e-08,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.1e-06,0.00042,0.00042,0.00014,0.93,0.93,0.019,2.4,2.4,0.056,1.1e-08,1.1e-08,4.5e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8590000,0.98,-0.0055,-0.013,0.19,0.0021,0.085,-0.012,0.00069,0.1,0.019,-1.8e-05,-5.6e-05,-4.7e-08,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.9e-06,0.00043,0.00043,0.00013,1,1,0.019,2.6,2.6,0.055,1.1e-08,1.1e-08,4.5e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8690000,0.98,-0.0055,-0.013,0.19,0.0021,0.086,-0.014,0.00084,0.11,0.018,-1.8e-05,-5.6e-05,-1.7e-08,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.8e-06,0.00043,0.00043,0.00013,1.1,1.1,0.018,2.9,2.9,0.055,1.1e-08,1.1e-08,4.5e-09,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0
8790000,0.98,-0.0055,-0.013,0.19,0.0034,0.09,-0.014,0.00098,0.12,0.021,-1.8e-05,-5.6e-05,-2.5e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.7e-06,0.00045,0.00045,0.00013,1.1,1.1,0.018,3.2,3.2,0.055,1.1e-08,1.1e-08,4.4e-09,4e-06,4e-06,9.6e-08,0,0,0,0,0,0,0,0
8890000,0.98,-0.0056,-0.013,0.19,0.0034,0.093,-0.0092,0.0013,0.12,0.027,-1.8e-05,-5.6e-05,-6.5e-08,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.6e-06,0.00045,0.00045,0.00012,1.2,1.2,0.017,3.5,3.5,0.054,1.1e-08,1.1e-08,4.4e-09,4e-06,4e-06,9.2e-08,0,0,0,0,0,0,0,0
8990000,0.98,-0.0055,-0.013,0.19,0.0025,0.098,-0.0084,0.0016,0.13,0.024,-1.7e-05,-5.6e-05,2.1e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00046,0.00046,0.00012,1.3,1.3,0.017,3.9,3.9,0.054,1.1e-08,1.1e-08,4.4e-09,4e-06,4e-06,8.8e-08,0,0,0,0,0,0,0,0
9090000,0.98,-0.0055,-0.013,0.19,0.0028,0.1,-0.0094,0.0019,0.13,0.024,-1.7e-05,-5.6e-05,5.2e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.4e-06,0.00046,0.00046,0.00012,1.3,1.3,0.016,4.2,4.2,0.053,1.1e-08,1.1e-08,4.4e-09,4e-06,4e-06,8.4e-08,0,0,0,0,0,0,0,0
9190000,0.98,-0.0055,-0.013,0.19,0.0064,0.1,-0.0089,0.0024,0.14,0.023,-1.7e-05,-5.6e-05,8e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.4e-06,0.00047,0.00047,0.00012,1.4,1.4,0.016,4.6,4.6,0.052,1.1e-08,1.1e-08,4.3e-09,4e-06,4e-06,8e-08,0,0,0,0,0,0,0,0
9290000,0.98,-0.0054,-0.013,0.19,0.0086,0.1,-0.0073,0.0031,0.15,0.026,-1.7e-05,-5.7e-05,8.8e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00047,0.00047,0.00012,1.5,1.5,0.015,4.9,4.9,0.052,1.1e-08,1.1e-08,4.3e-09,4e-06,4e-06,7.7e-08,0,0,0,0,0,0,0,0
9390000,0.98,-0.0053,-0.013,0.19,0.0086,0.11,-0.0062,0.0039,0.16,0.025,-1.7e-05,-5.7e-05,5.6e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00048,0.00048,0.00012,1.6,1.6,0.015,5.4,5.5,0.052,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,7.4e-08,0,0,0,0,0,0,0,0
9490000,0.98,-0.0054,-0.013,0.19,0.0084,0.11,-0.0045,0.0045,0.16,0.028,-1.7e-05,-5.7e-05,6.8e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00047,0.00047,0.00011,1.6,1.6,0.015,5.7,5.7,0.051,1e-08,1e-08,4.2e-09,4e-06,4e-06,7.1e-08,0,0,0,0,0,0,0,0
9590000,0.98,-0.0054,-0.013,0.19,0.0082,0.11,-0.0044,0.0052,0.17,0.027,-1.7e-05,-5.7e-05,4e-08,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00049,0.00049,0.00011,1.7,1.7,0.014,6.3,6.3,0.05,1e-08,1e-08,4.2e-09,4e-06,4e-06,6.8e-08,0,0,0,0,0,0,0,0
9690000,0.98,-0.0055,-0.013,0.19,0.0079,0.11,-0.0015,0.0056,0.17,0.028,-1.7e-05,-5.7e-05,-1.5e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00047,0.00047,0.00011,1.7,1.7,0.014,6.5,6.5,0.05,1e-08,1e-08,4.1e-09,4e-06,4e-06,6.5e-08,0,0,0,0,0,0,0,0
9790000,0.98,-0.0054,-0.013,0.19,0.0092,0.11,-0.0028,0.0063,0.18,0.027,-1.7e-05,-5.7e-05,-7.8e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00049,0.00049,0.00011,1.8,1.8,0.014,7.2,7.2,0.05,1e-08,1e-08,4.1e-09,4e-06,4e-06,6.3e-08,0,0,0,0,0,0,0,0
9890000,0.98,-0.0054,-0.013,0.19,0.011,0.11,-0.0015,0.0074,0.19,0.027,-1.7e-05,-5.7e-05,-6.5e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.0005,0.0005,0.00011,1.9,1.9,0.013,7.9,7.9,0.049,1e-08,1e-08,4e-09,4e-06,4e-06,6e-08,0,0,0,0,0,0,0,0
9990000,0.98,-0.0055,-0.013,0.19,0.013,0.11,-0.00082,0.0079,0.19,0.025,-1.6e-05,-5.7e-05,-1.2e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00049,0.00049,0.00011,1.9,1.9,0.013,8.1,8.1,0.049,9.7e-09,9.7e-09,4e-09,4e-06,4e-06,5.8e-08,0,0,0,0,0,0,0,0
10090000,0.98,-0.0054,-0.013,0.19,0.011,0.11,0.0004,0.009,0.2,0.027,-1.6e-05,-5.7e-05,-1.8e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.0005,0.0005,0.00011,2,2,0.013,8.9,8.9,0.049,9.7e-09,9.7e-09,3.9e-09,4e-06,4e-06,5.6e-08,0,0,0,0,0,0,0,0
10190000,0.98,-0.0055,-0.013,0.19,0.009,0.11,0.0013,0.0091,0.19,0.025,-1.6e-05,-5.7e-05,-2.5e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00048,0.00048,0.00011,2,2,0.013,8.9,8.9,0.048,9.4e-09,9.4e-09,3.9e-09,4e-06,4e-06,5.4e-08,0,0,0,0,0,0,0,0
10290000,0.98,-0.0055,-0.013,0.19,0.0095,0.11,0.00021,0.01,0.2,0.026,-1.6e-05,-5.7e-05,-2.2e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00049,0.00049,0.00011,2.1,2.1,0.012,9.8,9.8,0.048,9.4e-09,9.4e-09,3.8e-09,4e-06,4e-06,5.2e-08,0,0,0,0,0,0,0,0
10390000,0.98,-0.0055,-0.012,0.19,0.0069,0.005,-0.0025,0.00075,0.00014,0.027,-1.6e-05,-5.7e-05,-2e-06,-3.6e-10,2.5e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00051,0.00051,0.00011,0.25,0.25,0.56,0.25,0.25,0.048,9.4e-09,9.4e-09,3.8e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10490000,0.98,-0.0054,-0.012,0.19,0.0082,0.0072,0.007,0.0015,0.00071,0.033,-1.6e-05,-5.7e-05,-2.6e-06,-1.2e-08,8.4e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00053,0.00053,0.00011,0.26,0.26,0.55,0.26,0.26,0.057,9.4e-09,9.4e-09,3.7e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10590000,0.98,-0.0054,-0.012,0.19,-0.0014,0.0051,0.013,-0.0012,-0.0054,0.035,-1.6e-05,-5.7e-05,-2.2e-06,3.2e-06,3.8e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00053,0.00053,0.00011,0.13,0.13,0.27,0.13,0.13,0.055,9.3e-09,9.3e-09,3.7e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10690000,0.98,-0.0053,-0.012,0.19,-0.00043,0.0061,0.016,-0.0013,-0.0049,0.038,-1.6e-05,-5.7e-05,-2.4e-06,3.2e-06,4.5e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00055,0.00055,0.00011,0.14,0.14,0.26,0.14,0.14,0.065,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10790000,0.98,-0.0054,-0.012,0.19,0.0014,0.0026,0.014,-0.00079,-0.0047,0.04,-1.6e-05,-5.7e-05,-2.4e-06,5e-06,4.6e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00054,0.00054,0.00011,0.1,0.1,0.17,0.091,0.091,0.062,9.1e-09,9.1e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10890000,0.98,-0.0054,-0.012,0.19,0.0014,0.0059,0.01,-0.00064,-0.0043,0.038,-1.6e-05,-5.7e-05,-1.8e-06,5e-06,4.6e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00056,0.00056,0.00011,0.12,0.12,0.16,0.098,0.098,0.068,9.1e-09,9.1e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10990000,0.98,-0.0055,-0.013,0.19,0.00094,0.012,0.016,-0.00047,-0.0031,0.044,-1.5e-05,-5.7e-05,-2e-06,6.3e-06,6.9e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00053,0.00053,0.00011,0.092,0.092,0.12,0.073,0.073,0.065,8.7e-09,8.7e-09,3.5e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11090000,0.98,-0.0056,-0.013,0.19,0.0018,0.017,0.02,-0.00037,-0.0017,0.048,-1.5e-05,-5.7e-05,-2.7e-06,6.3e-06,6.9e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00054,0.00054,0.00011,0.11,0.11,0.11,0.08,0.08,0.069,8.7e-09,8.7e-09,3.4e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11190000,0.98,-0.0058,-0.013,0.19,0.0035,0.016,0.026,0.001,-0.0018,0.055,-1.5e-05,-5.7e-05,-3e-06,5.8e-06,1.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00049,0.00049,0.00011,0.092,0.092,0.083,0.063,0.063,0.066,8.1e-09,8.1e-09,3.3e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11290000,0.98,-0.0058,-0.013,0.19,0.0036,0.018,0.026,0.0013,-5.3e-05,0.055,-1.5e-05,-5.7e-05,-3.2e-06,5.9e-06,1.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00051,0.00051,0.00011,0.11,0.11,0.077,0.07,0.07,0.069,8.1e-09,8.1e-09,3.3e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11390000,0.98,-0.006,-0.013,0.19,0.0021,0.015,0.016,0.00084,-0.00083,0.047,-1.4e-05,-5.8e-05,-3.1e-06,1.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00044,0.00044,0.00011,0.093,0.093,0.062,0.057,0.057,0.066,7.4e-09,7.4e-09,3.2e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11490000,0.98,-0.0059,-0.013,0.19,0.0011,0.016,0.02,0.00093,0.00076,0.053,-1.4e-05,-5.8e-05,-3e-06,1.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00046,0.00046,0.00011,0.11,0.11,0.057,0.065,0.065,0.067,7.4e-09,7.4e-09,3.2e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11590000,0.98,-0.0062,-0.012,0.19,0.003,0.013,0.018,0.0008,-0.00027,0.052,-1.3e-05,-5.8e-05,-3e-06,1.4e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00039,0.00039,0.00011,0.092,0.092,0.048,0.054,0.054,0.065,6.8e-09,6.8e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11690000,0.98,-0.0062,-0.012,0.19,0.0034,0.017,0.018,0.0011,0.0012,0.051,-1.3e-05,-5.8e-05,-2.7e-06,1.5e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.0004,0.0004,0.00011,0.11,0.11,0.044,0.062,0.062,0.066,6.8e-09,6.8e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11790000,0.98,-0.0066,-0.012,0.19,0.0022,0.011,0.019,0.00067,-0.0016,0.054,-1.2e-05,-5.9e-05,-2e-06,2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00034,0.00034,0.00011,0.089,0.089,0.037,0.052,0.052,0.063,6.2e-09,6.2e-09,3e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11890000,0.98,-0.0067,-0.012,0.19,0.0048,0.013,0.017,0.00096,-0.00049,0.054,-1.2e-05,-5.9e-05,-2.1e-06,2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00035,0.00035,0.00011,0.11,0.11,0.034,0.06,0.06,0.063,6.2e-09,6.2e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11990000,0.98,-0.0068,-0.012,0.19,0.0078,0.012,0.015,0.0021,-0.0017,0.051,-1.2e-05,-5.9e-05,-1.8e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.0003,0.0003,0.00011,0.086,0.086,0.03,0.051,0.051,0.061,5.7e-09,5.7e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12090000,0.98,-0.0067,-0.012,0.19,0.0094,0.012,0.018,0.0029,-0.00044,0.057,-1.2e-05,-5.9e-05,-1.8e-06,1.9e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00031,0.00031,0.00011,0.1,0.1,0.027,0.059,0.059,0.06,5.7e-09,5.7e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12190000,0.98,-0.0066,-0.012,0.19,0.0076,0.012,0.017,0.0018,0.00052,0.058,-1.2e-05,-5.9e-05,-2e-06,2.2e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00027,0.00027,0.00011,0.081,0.081,0.024,0.05,0.05,0.058,5.3e-09,5.3e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12290000,0.98,-0.0067,-0.012,0.19,0.0053,0.011,0.016,0.0024,0.0017,0.059,-1.2e-05,-5.9e-05,-2.2e-06,2.2e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00028,0.00028,0.00011,0.096,0.096,0.022,0.059,0.059,0.058,5.3e-09,5.3e-09,2.7e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12390000,0.98,-0.0068,-0.012,0.19,0.0039,0.0076,0.014,0.0017,0.00062,0.053,-1.2e-05,-5.9e-05,-2.1e-06,2.5e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00025,0.00025,0.00011,0.076,0.076,0.02,0.05,0.05,0.056,5e-09,5e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12490000,0.98,-0.0068,-0.012,0.19,0.0039,0.0087,0.018,0.0021,0.0014,0.055,-1.2e-05,-5.9e-05,-2.1e-06,2.5e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00026,0.00026,0.00011,0.089,0.089,0.018,0.058,0.058,0.055,5e-09,5e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12590000,0.98,-0.007,-0.012,0.19,0.0077,0.002,0.02,0.0033,-0.0012,0.057,-1.1e-05,-5.9e-05,-2.1e-06,2.5e-05,4.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00023,0.00023,0.00011,0.071,0.071,0.017,0.049,0.049,0.054,4.7e-09,4.7e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12690000,0.98,-0.007,-0.012,0.19,0.0082,-0.00012,0.019,0.004,-0.0011,0.059,-1.1e-05,-5.9e-05,-2e-06,2.5e-05,4.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00024,0.00024,0.00011,0.083,0.083,0.016,0.058,0.058,0.053,4.7e-09,4.7e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12790000,0.98,-0.0072,-0.012,0.19,0.0098,-0.0036,0.021,0.0041,-0.0043,0.061,-1.1e-05,-5.9e-05,-1.1e-06,2.6e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00022,0.00022,0.00011,0.067,0.067,0.014,0.049,0.049,0.052,4.5e-09,4.5e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12890000,0.98,-0.0072,-0.012,0.19,0.01,-0.0044,0.022,0.0051,-0.0047,0.064,-1.1e-05,-5.9e-05,-5.5e-07,2.6e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00023,0.00023,0.00011,0.077,0.077,0.013,0.058,0.058,0.051,4.5e-09,4.5e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12990000,0.98,-0.0072,-0.012,0.19,0.0079,-0.0025,0.022,0.0036,-0.0035,0.065,-1.1e-05,-6e-05,-7.6e-10,2.7e-05,4.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00021,0.00021,0.00011,0.063,0.063,0.012,0.049,0.049,0.05,4.2e-09,4.2e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13090000,0.98,-0.0072,-0.012,0.19,0.0088,-0.0023,0.02,0.0044,-0.0036,0.064,-1.1e-05,-6e-05,7e-07,2.7e-05,4.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00022,0.00022,0.00011,0.072,0.072,0.012,0.057,0.057,0.049,4.2e-09,4.2e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13190000,0.98,-0.0072,-0.012,0.19,0.0039,-0.0041,0.019,0.00095,-0.0045,0.065,-1.1e-05,-6e-05,1.2e-06,2.8e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.00011,0.059,0.059,0.011,0.049,0.049,0.047,4e-09,4e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13290000,0.98,-0.0073,-0.012,0.19,0.0035,-0.005,0.016,0.0013,-0.0049,0.064,-1.1e-05,-6e-05,1.3e-06,2.8e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.00011,0.067,0.067,0.01,0.057,0.057,0.047,4e-09,4e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13390000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0031,0.016,0.00085,-0.0036,0.065,-1.1e-05,-6e-05,1.1e-06,2.9e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.056,0.056,0.0097,0.049,0.049,0.046,3.8e-09,3.8e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13490000,0.98,-0.0072,-0.012,0.19,0.0031,-0.0014,0.015,0.0011,-0.0038,0.061,-1.1e-05,-6e-05,1.3e-06,3e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.0001,0.063,0.063,0.0093,0.056,0.056,0.045,3.8e-09,3.8e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13590000,0.98,-0.0072,-0.012,0.19,0.0076,-0.0016,0.017,0.004,-0.0031,0.059,-1.1e-05,-6e-05,1.2e-06,3.1e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0088,0.048,0.048,0.044,3.7e-09,3.7e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13690000,0.98,-0.0071,-0.012,0.19,0.0076,-0.003,0.017,0.0047,-0.0033,0.062,-1.1e-05,-6e-05,1.6e-06,3.1e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.06,0.06,0.0085,0.056,0.056,0.044,3.7e-09,3.7e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13790000,0.98,-0.0071,-0.012,0.19,0.015,0.0011,0.017,0.0083,-0.00087,0.061,-1.1e-05,-5.9e-05,1.5e-06,3.5e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.05,0.05,0.0082,0.048,0.048,0.043,3.5e-09,3.5e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13890000,0.98,-0.007,-0.012,0.19,0.016,0.0018,0.018,0.0098,-0.00072,0.064,-1.1e-05,-5.9e-05,2e-06,3.5e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.057,0.057,0.008,0.056,0.056,0.042,3.5e-09,3.5e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0019,0.017,0.0074,-0.0022,0.062,-1.1e-05,-5.9e-05,2.5e-06,3.3e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00019,0.00019,0.0001,0.048,0.048,0.0077,0.048,0.048,0.041,3.3e-09,3.3e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0025,0.018,0.0088,-0.0023,0.059,-1.1e-05,-5.9e-05,1.5e-06,3.4e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.055,0.055,0.0075,0.055,0.055,0.041,3.3e-09,3.3e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14190000,0.98,-0.007,-0.012,0.19,0.01,-0.0012,0.018,0.008,-0.0017,0.059,-1.1e-05,-5.9e-05,1.1e-06,3.5e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00019,0.00019,0.0001,0.046,0.046,0.0074,0.048,0.048,0.04,3.1e-09,3.1e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0013,0.016,0.009,-0.0019,0.063,-1.1e-05,-6e-05,1.2e-06,3.5e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0073,0.055,0.055,0.04,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0043,0.017,0.0084,-0.003,0.068,-1.1e-05,-6e-05,1.5e-06,3.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.045,0.045,0.0071,0.048,0.048,0.039,3e-09,3e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.004,0.021,0.0095,-0.0034,0.07,-1.1e-05,-6e-05,1.1e-06,3.3e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0071,0.055,0.055,0.038,3e-09,3e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14590000,0.98,-0.0073,-0.011,0.19,0.0081,-0.0042,0.019,0.0059,-0.0041,0.066,-1.1e-05,-6e-05,1e-06,3.1e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.044,0.044,0.007,0.047,0.047,0.038,2.8e-09,2.8e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14690000,0.98,-0.0073,-0.011,0.19,0.0073,-0.0041,0.019,0.0067,-0.0045,0.066,-1.1e-05,-6e-05,1.2e-06,3.2e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.00019,0.0001,0.049,0.049,0.007,0.054,0.054,0.037,2.8e-09,2.8e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14790000,0.98,-0.0072,-0.011,0.19,0.009,0.0028,0.019,0.0053,0.00084,0.069,-1.2e-05,-6e-05,1.8e-06,3.2e-05,4.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.043,0.043,0.0069,0.047,0.047,0.037,2.6e-09,2.6e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14890000,0.98,-0.0071,-0.011,0.19,0.0077,0.00041,0.023,0.0061,0.001,0.07,-1.2e-05,-6e-05,2.3e-06,3.3e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.048,0.048,0.007,0.054,0.054,0.037,2.6e-09,2.6e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14990000,0.98,-0.0072,-0.011,0.19,0.0064,-0.0012,0.026,0.0048,-0.00062,0.072,-1.2e-05,-6e-05,2.5e-06,3.1e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.042,0.042,0.0069,0.047,0.047,0.036,2.5e-09,2.5e-09,1.5e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15090000,0.98,-0.0072,-0.011,0.19,0.0065,-0.00014,0.03,0.0054,-0.00073,0.074,-1.2e-05,-6e-05,2.5e-06,3.1e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.047,0.047,0.007,0.054,0.054,0.036,2.5e-09,2.5e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15190000,0.98,-0.0073,-0.011,0.19,0.0046,-0.0012,0.03,0.0043,-0.00069,0.076,-1.2e-05,-6.1e-05,2.4e-06,3.1e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00018,0.00018,9.9e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.3e-09,2.3e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15290000,0.98,-0.0074,-0.011,0.19,0.0052,-0.0023,0.03,0.0048,-0.00084,0.073,-1.2e-05,-6e-05,2.8e-06,3.3e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.8e-05,0.046,0.046,0.0071,0.054,0.054,0.035,2.3e-09,2.3e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15390000,0.98,-0.0075,-0.011,0.19,0.0054,6.3e-05,0.029,0.0038,-0.00057,0.073,-1.2e-05,-6.1e-05,2.8e-06,3.4e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00018,0.00018,9.8e-05,0.04,0.04,0.007,0.047,0.047,0.035,2.2e-09,2.2e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15490000,0.98,-0.0075,-0.011,0.19,0.0049,-0.0025,0.029,0.0043,-0.00066,0.074,-1.2e-05,-6.1e-05,2.8e-06,3.5e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.8e-05,0.045,0.045,0.0072,0.053,0.053,0.035,2.2e-09,2.2e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.0063,0.029,0.0063,-0.0046,0.073,-1.1e-05,-6.1e-05,3.1e-06,3.8e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.7e-05,0.04,0.04,0.0072,0.046,0.046,0.035,2e-09,2e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15690000,0.98,-0.0077,-0.011,0.19,0.01,-0.0094,0.029,0.0072,-0.0054,0.074,-1.1e-05,-6.1e-05,3.5e-06,3.9e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.045,0.045,0.0073,0.053,0.053,0.034,2e-09,2e-09,1.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15790000,0.98,-0.0077,-0.011,0.19,0.0067,-0.0087,0.029,0.0055,-0.0042,0.076,-1.1e-05,-6.1e-05,4e-06,3.7e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00017,9.6e-05,0.039,0.039,0.0073,0.046,0.046,0.034,1.8e-09,1.8e-09,1.2e-09,3.3e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15890000,0.98,-0.0078,-0.011,0.19,0.0056,-0.0071,0.03,0.0061,-0.005,0.075,-1.1e-05,-6.1e-05,3.6e-06,4e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.044,0.044,0.0074,0.053,0.053,0.034,1.8e-09,1.8e-09,1.2e-09,3.3e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15990000,0.98,-0.0076,-0.011,0.19,0.0035,-0.0057,0.027,0.0048,-0.0038,0.074,-1.2e-05,-6.1e-05,3.6e-06,4.1e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00017,0.00017,9.5e-05,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-09,1.7e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16090000,0.98,-0.0075,-0.011,0.19,0.0029,-0.0069,0.024,0.0051,-0.0045,0.074,-1.2e-05,-6.1e-05,3.4e-06,4.3e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.4e-05,0.043,0.043,0.0076,0.053,0.053,0.034,1.7e-09,1.7e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16190000,0.98,-0.0074,-0.011,0.19,-0.001,-0.0046,0.023,0.0028,-0.0033,0.071,-1.2e-05,-6.1e-05,3.1e-06,4.4e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.4e-05,0.038,0.038,0.0076,0.046,0.046,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16290000,0.98,-0.0075,-0.011,0.19,-0.0007,-0.0061,0.023,0.0026,-0.0039,0.072,-1.2e-05,-6.1e-05,3.3e-06,4.4e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.4e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16390000,0.98,-0.0074,-0.011,0.19,0.0017,-0.0054,0.023,0.0037,-0.0029,0.072,-1.2e-05,-6.1e-05,3.6e-06,5e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00016,0.00016,9.3e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.4e-09,1.4e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16490000,0.98,-0.0075,-0.011,0.19,0.0037,-0.007,0.026,0.0039,-0.0036,0.077,-1.2e-05,-6.1e-05,3.5e-06,4.9e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.3e-05,0.042,0.042,0.0079,0.053,0.053,0.034,1.4e-09,1.4e-09,1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16590000,0.98,-0.0075,-0.011,0.19,0.0078,-0.0071,0.029,0.0034,-0.0028,0.077,-1.2e-05,-6.1e-05,3.5e-06,5e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16690000,0.98,-0.0076,-0.011,0.19,0.0092,-0.012,0.029,0.0043,-0.0037,0.077,-1.2e-05,-6.1e-05,3.7e-06,5.1e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.041,0.042,0.008,0.052,0.052,0.034,1.3e-09,1.3e-09,9.9e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16790000,0.98,-0.0074,-0.011,0.19,0.01,-0.011,0.028,0.0033,-0.0027,0.077,-1.2e-05,-6.1e-05,3.8e-06,5.2e-05,3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00015,9.1e-05,0.036,0.037,0.008,0.046,0.046,0.034,1.2e-09,1.2e-09,9.7e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16890000,0.98,-0.0074,-0.011,0.19,0.0091,-0.011,0.029,0.0043,-0.0037,0.076,-1.2e-05,-6.1e-05,4.2e-06,5.5e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.1e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-09,1.2e-09,9.5e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16990000,0.98,-0.0074,-0.011,0.19,0.0088,-0.01,0.029,0.0041,-0.0028,0.074,-1.3e-05,-6.1e-05,4.3e-06,6.1e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00015,0.00015,9e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-09,1.1e-09,9.3e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.0051,-0.004,0.074,-1.3e-05,-6.1e-05,4.2e-06,6.3e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,9e-05,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-09,1.1e-09,9.1e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17190000,0.98,-0.0076,-0.011,0.19,0.0092,-0.018,0.03,0.0034,-0.0075,0.077,-1.2e-05,-6.1e-05,3.8e-06,6.1e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.035,0.035,0.0083,0.046,0.046,0.034,9.7e-10,9.7e-10,8.9e-10,3.1e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17290000,0.98,-0.0076,-0.011,0.19,0.01,-0.019,0.03,0.0044,-0.0093,0.077,-1.2e-05,-6.1e-05,3.5e-06,6.4e-05,2.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.039,0.039,0.0084,0.052,0.052,0.034,9.7e-10,9.7e-10,8.7e-10,3.1e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17390000,0.98,-0.0074,-0.011,0.19,0.0069,-0.018,0.029,0.0058,-0.0059,0.076,-1.3e-05,-6e-05,3.8e-06,7.2e-05,2.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00014,0.00014,8.8e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.8e-10,8.8e-10,8.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17490000,0.98,-0.0075,-0.011,0.19,0.005,-0.019,0.029,0.0063,-0.0077,0.078,-1.3e-05,-6e-05,3.6e-06,7.2e-05,2.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00014,8.8e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.8e-10,8.8e-10,8.3e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17590000,0.98,-0.0074,-0.011,0.19,0.0011,-0.015,0.028,0.0025,-0.0058,0.076,-1.3e-05,-6.1e-05,3.6e-06,7.1e-05,3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8e-10,8e-10,8.2e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17690000,0.98,-0.0075,-0.011,0.19,0.00019,-0.016,0.029,0.0026,-0.0073,0.078,-1.3e-05,-6.1e-05,3.6e-06,7.2e-05,3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.038,0.038,0.0086,0.052,0.052,0.034,8e-10,8e-10,8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17790000,0.98,-0.0074,-0.011,0.19,0.0028,-0.014,0.029,0.0035,-0.0062,0.083,-1.4e-05,-6e-05,3.7e-06,7.5e-05,3.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00013,8.7e-05,0.033,0.033,0.0086,0.045,0.045,0.034,7.2e-10,7.2e-10,7.8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17890000,0.98,-0.0073,-0.011,0.19,0.0049,-0.016,0.029,0.004,-0.0077,0.088,-1.4e-05,-6e-05,3.8e-06,7.4e-05,3.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.6e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.2e-10,7.2e-10,7.7e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17990000,0.98,-0.0071,-0.011,0.19,0.0043,-0.0092,0.029,0.0031,-0.0019,0.088,-1.4e-05,-6e-05,3.7e-06,7.8e-05,4.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00013,0.00013,8.5e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.5e-10,6.5e-10,7.5e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
18090000,0.98,-0.0072,-0.011,0.19,0.0038,-0.0097,0.028,0.0036,-0.0029,0.086,-1.4e-05,-6e-05,3.7e-06,8.1e-05,4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.5e-10,6.5e-10,7.3e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
18190000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0087,0.028,0.0042,-0.0022,0.084,-1.4e-05,-6e-05,4.1e-06,8.7e-05,4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.032,0.032,0.0086,0.045,0.045,0.035,5.9e-10,5.9e-10,7.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18290000,0.98,-0.0072,-0.011,0.19,0.0048,-0.0092,0.027,0.0046,-0.003,0.083,-1.4e-05,-6e-05,4.1e-06,8.9e-05,4.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.4e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.9e-10,5.9e-10,7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18390000,0.98,-0.0072,-0.011,0.19,0.0056,-0.0079,0.027,0.0062,-0.0023,0.082,-1.4e-05,-6e-05,3.9e-06,9.5e-05,4.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00012,0.00012,8.3e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.3e-10,5.3e-10,6.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18490000,0.98,-0.0072,-0.011,0.19,0.0084,-0.0079,0.026,0.007,-0.0031,0.083,-1.4e-05,-6e-05,4.1e-06,9.5e-05,4.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.3e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.3e-10,5.3e-10,6.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18590000,0.98,-0.007,-0.011,0.19,0.0068,-0.0073,0.026,0.0056,-0.0024,0.086,-1.5e-05,-6e-05,3.8e-06,9.4e-05,4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00012,0.00012,8.3e-05,0.03,0.031,0.0087,0.045,0.045,0.035,4.8e-10,4.8e-10,6.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18690000,0.98,-0.007,-0.011,0.19,0.0068,-0.0063,0.024,0.0063,-0.0031,0.085,-1.5e-05,-6e-05,4e-06,9.6e-05,4.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.8e-10,4.8e-10,6.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18790000,0.98,-0.007,-0.011,0.19,0.0058,-0.0059,0.023,0.0063,-0.0025,0.082,-1.5e-05,-6e-05,3.9e-06,0.0001,4.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-10,4.4e-10,6.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18890000,0.98,-0.0069,-0.011,0.19,0.0045,-0.0056,0.021,0.0068,-0.0031,0.078,-1.5e-05,-6e-05,3.8e-06,0.0001,4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-10,4.4e-10,6.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18990000,0.98,-0.0069,-0.011,0.19,0.0028,-0.0057,0.022,0.0056,-0.0025,0.082,-1.5e-05,-6e-05,3.7e-06,0.0001,4.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00011,8.1e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-10,4e-10,6.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19090000,0.98,-0.007,-0.011,0.19,0.00086,-0.0062,0.023,0.0059,-0.003,0.078,-1.5e-05,-6e-05,3.9e-06,0.00011,3.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-10,4e-10,6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19190000,0.98,-0.0069,-0.011,0.19,-0.00065,-0.0058,0.022,0.0049,-0.0025,0.077,-1.5e-05,-6e-05,3.5e-06,0.00011,4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00011,0.00011,8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.6e-10,3.6e-10,5.9e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19290000,0.98,-0.0068,-0.011,0.19,-0.0015,-0.0057,0.023,0.0048,-0.003,0.076,-1.5e-05,-6e-05,3.4e-06,0.00011,3.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.6e-10,3.6e-10,5.8e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19390000,0.98,-0.0069,-0.011,0.19,-0.002,-0.0022,0.024,0.0041,-0.0011,0.075,-1.5e-05,-6e-05,3.3e-06,0.00011,4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-10,3.3e-10,5.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19490000,0.98,-0.007,-0.011,0.19,-0.0028,-0.0022,0.023,0.0039,-0.0014,0.074,-1.5e-05,-6e-05,3e-06,0.00011,3.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-10,3.3e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19590000,0.98,-0.0069,-0.011,0.19,-0.0039,-0.0051,0.025,0.0044,-0.0024,0.075,-1.5e-05,-6e-05,2.9e-06,0.00011,3.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.8e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-10,3e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19690000,0.98,-0.0069,-0.011,0.19,-0.0056,-0.0036,0.023,0.004,-0.0028,0.074,-1.5e-05,-6e-05,3e-06,0.00012,3.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.8e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-10,3e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19790000,0.98,-0.007,-0.011,0.19,-0.0056,-0.0022,0.022,0.0064,-0.0023,0.07,-1.5e-05,-6e-05,2.8e-06,0.00012,3.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.0001,7.8e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-10,2.8e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.98,-0.0071,-0.011,0.19,-0.0056,-0.0019,0.022,0.0058,-0.0025,0.068,-1.5e-05,-6e-05,2.7e-06,0.00012,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.00011,7.7e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.98,-0.0071,-0.011,0.19,-0.0053,-0.0019,0.019,0.0062,-0.00088,0.065,-1.5e-05,-5.9e-05,2.7e-06,0.00013,2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-10,2.5e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.98,-0.0071,-0.011,0.19,-0.0048,-0.0041,0.019,0.0056,-0.0012,0.068,-1.5e-05,-5.9e-05,2.7e-06,0.00013,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.0001,7.6e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-10,2.5e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.98,-0.0071,-0.011,0.19,-0.0038,-0.0015,0.02,0.0066,-0.00088,0.068,-1.5e-05,-5.9e-05,2.4e-06,0.00013,2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.98,-0.0071,-0.011,0.19,-0.007,-0.0026,0.02,0.0061,-0.001,0.069,-1.5e-05,-5.9e-05,2.3e-06,0.00013,2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.98,-0.007,-0.011,0.19,-0.0077,-0.0014,0.02,0.0069,-0.00075,0.07,-1.5e-05,-5.9e-05,2.5e-06,0.00013,2.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,9.9e-05,7.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-10,2.1e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.0059,-0.00092,0.068,-1.5e-05,-5.9e-05,2.4e-06,0.00014,2.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-10,2.1e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0033,0.02,0.007,-0.00076,0.066,-1.5e-05,-5.9e-05,2.6e-06,0.00014,2.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.9e-05,9.8e-05,7.4e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0021,0.021,0.0058,-0.00099,0.067,-1.5e-05,-5.9e-05,2.4e-06,0.00014,2.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,9.9e-05,7.4e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00046,0.0055,0.0049,-0.00078,0.065,-1.5e-05,-5.9e-05,2.5e-06,0.00014,2.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.6e-05,7.3e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-10,1.8e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.98,0.0028,-0.0073,0.19,-0.021,0.012,-0.11,0.003,-9.5e-05,0.059,-1.5e-05,-5.9e-05,2.5e-06,0.00014,2.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.7e-05,7.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0023,0.00055,0.044,-1.5e-05,-5.9e-05,2.4e-06,0.00014,2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.6e-05,9.5e-05,7.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0016,0.0044,0.014,-1.5e-05,-5.9e-05,2.4e-06,0.00014,2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.7e-05,9.6e-05,7.2e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-10,1.7e-10,4.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.98,0.0017,-0.0058,0.19,-0.049,0.05,-0.5,-0.0012,0.0035,-0.022,-1.4e-05,-5.9e-05,2.5e-06,0.00014,1.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.5e-05,9.3e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.5e-10,1.5e-10,4.1e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.98,-0.0005,-0.0072,0.19,-0.049,0.054,-0.63,-0.0061,0.0088,-0.081,-1.4e-05,-5.9e-05,2.2e-06,0.00014,1.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.5e-05,9.4e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.5e-10,1.5e-10,4e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.15,-1.4e-05,-5.9e-05,2.2e-06,0.00015,1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.2e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0092,0.016,-0.23,-1.4e-05,-5.9e-05,2.3e-06,0.00015,9.7e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.2e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.0079,0.017,-0.32,-1.4e-05,-5.9e-05,2.4e-06,0.00015,9.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.43,-1.4e-05,-5.9e-05,2.5e-06,0.00015,7.3e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0037,0.018,-0.55,-1.4e-05,-5.8e-05,2.7e-06,0.00015,5.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.9e-05,8.8e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.69,-1.4e-05,-5.8e-05,2.6e-06,0.00016,3.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.9e-05,8.8e-05,6.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00032,0.017,-0.83,-1.4e-05,-5.8e-05,2.6e-06,0.00015,6.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.7e-05,8.6e-05,6.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-10,1.1e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0016,0.019,-0.97,-1.4e-05,-5.8e-05,2.8e-06,0.00015,4.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.7e-05,8.6e-05,6.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-10,1.1e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.0061,0.013,-1.1,-1.4e-05,-5.8e-05,2.9e-06,0.00015,5.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.5e-05,8.4e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.98,-0.0069,-0.01,0.19,0.0017,0.0078,-1.4,0.006,0.014,-1.3,-1.4e-05,-5.8e-05,2.8e-06,0.00016,4.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.6e-05,8.5e-05,6.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.98,-0.0072,-0.01,0.19,0.0067,-0.0017,-1.4,0.013,0.0042,-1.4,-1.4e-05,-5.8e-05,2.7e-06,0.00015,3.7e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.4e-05,8.3e-05,6.8e-05,0.021,0.021,0.0081,0.042,0.043,0.036,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0037,-1.5,-1.4e-05,-5.8e-05,2.5e-06,0.00016,-3.3e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.4e-05,8.3e-05,6.7e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-2.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.2e-05,8.1e-05,6.7e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.8,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-2.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.3e-05,8.2e-05,6.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.4e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.4e-06,0.00016,-3.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.1e-05,8e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-11,8.9e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.1,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-4.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.2e-05,8e-05,6.6e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-6.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.4,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-6.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.5e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-11,8.4e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.5e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-11,7.9e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.7,-1.4e-05,-5.8e-05,2.7e-06,0.00017,-8.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.8e-05,6.5e-05,0.02,0.02,0.0081,0.046,0.046,0.036,7.9e-11,7.9e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.8,-1.4e-05,-5.8e-05,2.5e-06,0.00017,-5.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-11,7.5e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.98,-0.0079,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-1.4e-05,-5.8e-05,2.6e-06,0.00017,-6.3e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.9e-05,7.8e-05,6.4e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.5e-11,7.5e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.1,-1.4e-05,-5.8e-05,2.7e-06,0.00017,-7.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-11,7.2e-11,2.7e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-1.4e-05,-5.8e-05,2.8e-06,0.00017,-7.7e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.3e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-11,7.2e-11,2.7e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-1.4e-05,-5.8e-05,2.9e-06,0.00017,-7.7e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.8e-11,6.9e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.98,-0.014,-0.021,0.18,0.053,-0.059,-0.52,0.12,-0.087,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00017,-7.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-11,6.9e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.13,-0.089,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00018,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.98,-0.016,-0.023,0.18,0.061,-0.066,0.09,0.13,-0.095,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00018,-1.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-11,6.6e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.98,-0.013,-0.019,0.18,0.072,-0.071,0.077,0.14,-0.1,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00019,-2.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-11,6.3e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00019,-2.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,3.1e-06,0.00019,-2.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.3e-06,0.00019,-2.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-11,6.1e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.3e-06,0.00019,-3.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.98,-0.011,-0.014,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.5,-1.4e-05,-5.8e-05,3.3e-06,0.00019,-3.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-4.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.4e-06,0.00019,-4.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00018,-4.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-4.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00018,-5.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3e-06,0.00018,-5.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,3e-06,0.00018,-6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-11,5.1e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00018,-6.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-11,5.1e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.98,-0.011,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00018,-6.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00018,-6.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.5,-1.6e-05,-5.8e-05,2.8e-06,0.00018,-6.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.98,-0.011,-0.011,0.18,-0.0036,-0.029,0.019,0.17,-0.096,-3.5,-1.6e-05,-5.8e-05,2.6e-06,0.00018,-6.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.7e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-7.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.021,0.011,0.16,-0.088,-3.5,-1.6e-05,-5.8e-05,2.6e-06,0.00019,-7.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.5,-1.6e-05,-5.8e-05,2.6e-06,0.00019,-7.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.014,0.00051,0.15,-0.083,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-7.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.98,-0.0098,-0.012,0.18,-0.031,-0.0064,0.0045,0.13,-0.075,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00019,-7.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0033,0.014,0.13,-0.075,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00019,-7.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-11,4.5e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0046,0.014,0.12,-0.068,-3.5,-1.6e-05,-5.8e-05,2.2e-06,0.00019,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0097,0.013,0.12,-0.067,-3.5,-1.6e-05,-5.8e-05,2e-06,0.00019,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00019,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.98,-0.008,-0.011,0.18,-0.051,0.017,0.007,0.1,-0.06,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00019,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-11,4.2e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00019,-8.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-11,4.1e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00019,-8.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.4e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-11,4.1e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.036,0.011,0.071,-0.046,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.0002,-8.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.4e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.98,-0.0075,-0.013,0.18,-0.073,0.041,0.12,0.064,-0.042,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.0002,-8.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.8e-05,5.4e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.98,-0.0089,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.0002,-9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.03,-3.4,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-9.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.8e-05,5.4e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-9.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.8e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.98,-0.0089,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-9.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.05,0.75,0.025,-0.018,-3.2,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-8.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.98,-0.0072,-0.012,0.18,-0.078,0.057,0.79,0.018,-0.012,-3.1,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-8.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00019,-8.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0047,-3,-1.6e-05,-5.8e-05,1.3e-06,0.00019,-8.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0022,-0.0043,-2.9,-1.6e-05,-5.8e-05,1.3e-06,0.00019,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0014,-2.8,-1.6e-05,-5.8e-05,1.3e-06,0.00019,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.061,0.79,-0.015,0.0044,-2.8,-1.5e-05,-5.8e-05,1.4e-06,0.00019,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.7,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-11,3.6e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0084,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.98,-0.007,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-8.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.4,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.3,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.0002,-8.4e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.6e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.98,-0.006,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.033,-2.1,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.7e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.8e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-8.9e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,5e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-1.5e-05,-5.8e-05,1.6e-06,0.0002,-9.1e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.98,-0.0064,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.8,-1.5e-05,-5.8e-05,1.7e-06,0.0002,-9.2e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.98,-0.0063,-0.013,0.18,-0.074,0.056,0.78,-0.065,0.044,-1.7,-1.4e-05,-5.8e-05,1.8e-06,0.0002,-9.5e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.98,-0.0058,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-1.4e-05,-5.8e-05,1.9e-06,0.0002,-9.6e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-1.4e-05,-5.8e-05,1.9e-06,0.0002,-0.0001,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30090000,0.98,-0.006,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.5,-1.4e-05,-5.8e-05,1.7e-06,0.0002,-0.0001,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.4,-1.4e-05,-5.7e-05,1.6e-06,0.00021,-0.0001,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30290000,0.98,-0.006,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-1.4e-05,-5.7e-05,1.6e-06,0.00021,-0.00011,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.3,-1.4e-05,-5.7e-05,1.7e-06,0.00021,-0.00011,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.2,-1.4e-05,-5.7e-05,1.8e-06,0.00021,-0.00011,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-0.95,-1.4e-05,-5.7e-05,1.8e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.88,-1.4e-05,-5.7e-05,1.8e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.98,-0.0062,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.81,-1.4e-05,-5.7e-05,1.8e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.98,-0.0063,-0.013,0.19,-0.031,0.021,0.76,-0.052,0.046,-0.74,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.67,-1.4e-05,-5.7e-05,2e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31390000,0.98,-0.0064,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.59,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.6e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.52,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0067,0.76,-0.038,0.039,-0.45,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.98,-0.0059,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.38,-1.4e-05,-5.7e-05,2e-06,0.00024,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.0031,0.76,-0.028,0.037,-0.31,-1.4e-05,-5.7e-05,2.1e-06,0.00024,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.00081,0.76,-0.029,0.038,-0.24,-1.4e-05,-5.7e-05,2.2e-06,0.00024,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.98,-0.0062,-0.015,0.18,-0.00011,0.00015,0.75,-0.017,0.034,-0.17,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.5e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.98,-0.0065,-0.014,0.18,-0.00064,-0.0033,0.76,-0.017,0.034,-0.1,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.98,-0.0067,-0.015,0.18,0.0047,-0.0065,0.76,-0.006,0.033,-0.037,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0092,0.75,-0.0055,0.032,0.032,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.98,-0.0067,-0.015,0.18,0.013,-0.01,0.75,0.0057,0.03,0.11,-1.3e-05,-5.7e-05,2.1e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.8e-05,4.5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-11,2.7e-11,9.7e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.11,-1.3e-05,-5.7e-05,2.1e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-11,2.8e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.075,-0.12,0.021,0.02,0.09,-1.4e-05,-5.7e-05,2.1e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.7e-05,4.5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-11,2.7e-11,9.5e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.075,-1.4e-05,-5.7e-05,2.1e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.8e-05,4.4e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-11,2.7e-11,9.4e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.06,-1.4e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.6e-05,7.5e-05,4.4e-05,0.019,0.019,0.0071,0.037,0.037,0.035,2.7e-11,2.7e-11,9.3e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.98,-0.0092,-0.013,0.18,0.033,-0.084,-0.13,0.038,0.0021,0.044,-1.4e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.6e-05,7.5e-05,4.4e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-11,2.7e-11,9.3e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0011,0.031,-1.4e-05,-5.6e-05,2.3e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.2e-05,7.1e-05,4.4e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-11,2.7e-11,9.2e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0092,0.024,-1.4e-05,-5.6e-05,2.3e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.2e-05,7.1e-05,4.4e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-11,2.7e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,0.018,-1.4e-05,-5.6e-05,2.2e-06,0.00025,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6.7e-05,6.6e-05,4.4e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-11,2.6e-11,9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,0.011,-1.4e-05,-5.6e-05,2.3e-06,0.00025,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6.7e-05,6.6e-05,4.4e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-11,2.6e-11,8.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,0.0022,-1.4e-05,-5.6e-05,2.3e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.3e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-11,2.6e-11,8.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.0071,-1.4e-05,-5.6e-05,2.3e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.3e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-11,2.6e-11,8.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.014,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00019,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.3e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-11,2.6e-11,8.7e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.98,-0.0077,-0.013,0.18,0.00084,-0.058,-0.11,0.063,-0.023,-0.022,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00019,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.3e-05,4.3e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-11,2.6e-11,8.7e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33790000,0.98,-0.0075,-0.013,0.18,-0.0023,-0.048,-0.11,0.067,-0.018,-0.028,-1.4e-05,-5.6e-05,2.3e-06,0.00023,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,4.7e-05,4.6e-05,4.3e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33890000,0.98,-0.0075,-0.013,0.18,-0.0065,-0.046,-0.11,0.066,-0.023,-0.034,-1.4e-05,-5.6e-05,2.4e-06,0.00023,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.7e-05,4.6e-05,4.3e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-11,2.6e-11,8.5e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.037,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00024,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.1e-05,4.1e-05,4.3e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-11,2.6e-11,8.4e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.041,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00024,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.1e-05,4.1e-05,4.3e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-11,2.6e-11,8.4e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.021,-0.098,0.072,-0.013,-0.043,-1.4e-05,-5.6e-05,2.3e-06,0.00019,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.2e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-11,2.6e-11,8.3e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.049,-1.4e-05,-5.6e-05,2.3e-06,0.00019,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.2e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-11,2.6e-11,8.2e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.073,-0.01,-0.052,-1.4e-05,-5.6e-05,2.3e-06,0.00017,-0.00027,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.2e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-11,2.6e-11,8.2e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0095,-0.09,0.071,-0.011,-0.055,-1.4e-05,-5.6e-05,2.3e-06,0.00017,-0.00027,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.2e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-11,2.6e-11,8.1e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0052,0.71,0.073,-0.0089,-0.025,-1.4e-05,-5.6e-05,2.3e-06,0.00016,-0.00028,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-11,2.6e-11,8e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0031,1.7,0.071,-0.0093,0.093,-1.4e-05,-5.6e-05,2.2e-06,0.00016,-0.00028,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-11,2.6e-11,8e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34790000,0.98,-0.0068,-0.012,0.18,-0.018,0.0016,2.7,0.072,-0.0069,0.27,-1.4e-05,-5.6e-05,2.2e-06,0.00017,-0.00029,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,2.9e-05,2.9e-05,4.2e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-11,2.6e-11,7.9e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.004,3.6,0.07,-0.0065,0.56,-1.4e-05,-5.6e-05,2.2e-06,0.00018,-0.00029,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3e-05,2.9e-05,4.2e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-11,2.6e-11,7.9e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
10000,1,-0.011,-0.01,0.00012,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.8e-07,0.0025,0.0025,0.0018,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
90000,0.98,-0.0095,-0.012,0.18,-5.5e-05,-0.0032,-0.024,-3.6e-06,-0.00014,-0.0021,0,0,0,0,0,0,0.2,9.3e-09,0.43,0,0,0,0,0,8.9e-07,0.0026,0.0026,0.0011,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
190000,0.98,-0.0092,-0.013,0.2,-0.0013,-0.0036,-0.037,-4.4e-05,-0.00046,-0.017,5.2e-12,-4.3e-12,-1.5e-13,0,0,-6.8e-10,0.2,0.011,0.43,0,0,0,0,0,2.8e-06,0.0027,0.0027,0.00081,25,25,10,1e+02,1e+02,1,1e-06,1e-06,9.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
290000,0.98,-0.0092,-0.013,0.2,-0.0016,-0.0053,-0.046,-0.00015,-0.00032,-0.018,4.4e-11,-5.4e-11,-2.6e-12,0,0,-2.9e-08,0.2,0.011,0.43,0,0,0,0,0,6.6e-06,0.0029,0.0029,0.00068,25,25,9.6,0.37,0.37,0.41,1e-06,1e-06,9.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
390000,0.98,-0.0095,-0.013,0.19,-0.00033,-0.0065,-0.063,-0.00029,-0.00087,-0.013,-6.7e-11,-6.3e-11,3e-12,0,0,8.8e-08,0.2,0.002,0.44,0,0,0,0,0,1.1e-05,0.0031,0.0031,0.00062,25,25,8.1,0.97,0.97,0.32,1e-06,1e-06,8.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
490000,0.98,-0.0095,-0.014,0.19,0.0016,-0.0061,-0.069,2.4e-05,-0.00049,-0.011,-1.2e-08,6.5e-09,2.1e-10,0,0,1.6e-07,0.2,0.002,0.44,0,0,0,0,0,1.7e-05,0.0034,0.0033,0.00059,7.8,7.8,5.9,0.34,0.34,0.31,1e-06,1e-06,8.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
590000,0.98,-0.0095,-0.014,0.19,0.0014,-0.0091,-0.12,0.00018,-0.0013,-0.03,-1.4e-08,6.7e-09,2.5e-10,0,0,6.4e-07,0.2,0.002,0.44,0,0,0,0,0,2.2e-05,0.0037,0.0037,0.00058,7.9,7.9,4.2,0.67,0.67,0.32,1e-06,1e-06,7.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
690000,0.98,-0.0096,-0.014,0.19,0.0032,-0.0083,-0.05,0.00021,-0.00076,-0.0089,-5.6e-08,1.3e-08,3.3e-10,0,0,-9.5e-07,0.2,0.002,0.44,0,0,0,0,0,2.7e-05,0.004,0.004,0.00057,2.7,2.7,2.8,0.26,0.26,0.29,1e-06,1e-06,6.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
790000,0.98,-0.0096,-0.014,0.19,0.0059,-0.009,-0.054,0.0006,-0.0016,-0.011,-5.5e-08,1.3e-08,2.7e-10,0,0,-1.3e-06,0.2,0.002,0.44,0,0,0,0,0,3.2e-05,0.0044,0.0044,0.00057,2.8,2.8,1.9,0.42,0.42,0.27,1e-06,1e-06,5.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
890000,0.98,-0.0096,-0.015,0.19,0.006,-0.0068,-0.093,0.00052,-0.00095,-0.031,-2.2e-07,1.8e-09,4.8e-09,0,0,-3.3e-07,0.2,0.002,0.44,0,0,0,0,0,3.5e-05,0.0048,0.0048,0.00056,1.3,1.3,1.3,0.2,0.2,0.25,9.9e-07,1e-06,5.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
990000,0.98,-0.0096,-0.015,0.19,0.0091,-0.0071,-0.12,0.0013,-0.0017,-0.046,-2.2e-07,1.4e-09,4.9e-09,0,0,1.3e-07,0.2,0.002,0.44,0,0,0,0,0,3.8e-05,0.0053,0.0053,0.00055,1.5,1.5,0.95,0.3,0.3,0.23,9.9e-07,9.9e-07,4.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1090000,0.98,-0.0096,-0.015,0.19,0.015,-0.0083,-0.13,0.0012,-0.0011,-0.063,-6.1e-07,-1.7e-07,2.1e-08,0,0,4.4e-07,0.2,0.002,0.44,0,0,0,0,0,4.1e-05,0.0057,0.0057,0.00054,0.92,0.92,0.69,0.17,0.17,0.2,9.8e-07,9.8e-07,3.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1190000,0.98,-0.0096,-0.015,0.19,0.021,-0.011,-0.11,0.003,-0.0021,-0.047,-5.8e-07,-1.5e-07,2e-08,0,0,-4.8e-06,0.2,0.002,0.44,0,0,0,0,0,4.2e-05,0.0063,0.0063,0.00053,1.1,1.1,0.54,0.24,0.24,0.19,9.8e-07,9.8e-07,3.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1290000,0.98,-0.0093,-0.016,0.19,0.024,-0.0097,-0.11,0.0027,-0.0016,-0.048,-1.7e-06,-1e-06,7.6e-08,0,0,-7.5e-06,0.2,0.002,0.44,0,0,0,0,0,4.3e-05,0.0064,0.0064,0.00052,0.88,0.88,0.41,0.15,0.15,0.18,9.5e-07,9.5e-07,2.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1390000,0.98,-0.0093,-0.016,0.19,0.033,-0.012,-0.097,0.0056,-0.0027,-0.038,-1.6e-06,-9.6e-07,7.3e-08,0,0,-1.4e-05,0.2,0.002,0.44,0,0,0,0,0,4.3e-05,0.0071,0.0071,0.0005,1.1,1.1,0.33,0.21,0.21,0.16,9.5e-07,9.5e-07,2.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1490000,0.98,-0.009,-0.016,0.19,0.03,-0.01,-0.12,0.0044,-0.0018,-0.053,-3.9e-06,-3.4e-06,2e-07,0,0,-1.2e-05,0.2,0.002,0.44,0,0,0,0,0,4.3e-05,0.0067,0.0067,0.00048,0.95,0.95,0.27,0.14,0.14,0.15,8.8e-07,8.8e-07,2.1e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1590000,0.98,-0.0091,-0.016,0.19,0.038,-0.012,-0.13,0.0077,-0.003,-0.063,-3.9e-06,-3.4e-06,2e-07,0,0,-1.4e-05,0.2,0.002,0.44,0,0,0,0,0,4.3e-05,0.0074,0.0074,0.00047,1.3,1.3,0.23,0.2,0.2,0.14,8.8e-07,8.8e-07,1.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1690000,0.98,-0.0088,-0.016,0.19,0.033,-0.0083,-0.13,0.0054,-0.0019,-0.068,-7.3e-06,-7.5e-06,3.8e-07,0,0,-1.8e-05,0.2,0.002,0.44,0,0,0,0,0,4.2e-05,0.0064,0.0064,0.00045,1,1,0.19,0.14,0.14,0.13,7.8e-07,7.8e-07,1.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
1790000,0.98,-0.009,-0.016,0.19,0.042,-0.0099,-0.13,0.0092,-0.0029,-0.067,-7.2e-06,-7.4e-06,3.8e-07,0,0,-2.8e-05,0.2,0.002,0.44,0,0,0,0,0,4.2e-05,0.007,0.007,0.00043,1.3,1.3,0.16,0.2,0.2,0.12,7.8e-07,7.8e-07,1.4e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
1890000,0.98,-0.0089,-0.016,0.19,0.049,-0.0086,-0.14,0.014,-0.0037,-0.076,-7.2e-06,-7.4e-06,3.7e-07,0,0,-3.2e-05,0.2,0.002,0.44,0,0,0,0,0,4.1e-05,0.0076,0.0076,0.00042,1.7,1.7,0.15,0.31,0.31,0.12,7.8e-07,7.8e-07,1.2e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
1990000,0.98,-0.0085,-0.016,0.19,0.039,-0.0042,-0.14,0.0096,-0.0021,-0.074,-1.1e-05,-1.3e-05,5.7e-07,0,0,-4.6e-05,0.2,0.002,0.44,0,0,0,0,0,4e-05,0.0061,0.0061,0.0004,1.3,1.3,0.13,0.2,0.2,0.11,6.6e-07,6.6e-07,1.1e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
2090000,0.98,-0.0086,-0.016,0.19,0.047,-0.0042,-0.14,0.014,-0.0026,-0.071,-1.1e-05,-1.3e-05,5.6e-07,0,0,-6.5e-05,0.2,0.002,0.44,0,0,0,0,0,3.9e-05,0.0066,0.0066,0.00039,1.7,1.7,0.12,0.31,0.31,0.11,6.6e-07,6.6e-07,9.7e-08,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
2190000,0.98,-0.0082,-0.015,0.19,0.035,-0.0012,-0.14,0.0091,-0.0012,-0.077,-1.4e-05,-1.8e-05,7.2e-07,0,0,-7.5e-05,0.2,0.002,0.44,0,0,0,0,0,3.7e-05,0.005,0.005,0.00038,1.2,1.2,0.11,0.2,0.2,0.11,5.5e-07,5.5e-07,8.6e-08,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
2290000,0.98,-0.0082,-0.016,0.19,0.04,6.6e-05,-0.14,0.013,-0.0012,-0.075,-1.4e-05,-1.8e-05,7.1e-07,0,0,-9.8e-05,0.2,0.002,0.44,0,0,0,0,0,3.7e-05,0.0054,0.0054,0.00036,1.5,1.5,0.11,0.29,0.3,0.1,5.5e-07,5.5e-07,7.6e-08,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
2390000,0.98,-0.008,-0.015,0.19,0.031,0.001,-0.14,0.0082,-0.00047,-0.072,-1.7e-05,-2.3e-05,8.1e-07,0,0,-0.00012,0.2,0.002,0.44,0,0,0,0,0,3.5e-05,0.004,0.004,0.00035,1,1,0.1,0.19,0.19,0.098,4.5e-07,4.5e-07,6.8e-08,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
2490000,0.98,-0.0079,-0.015,0.19,0.033,0.0031,-0.14,0.011,-0.00027,-0.079,-1.7e-05,-2.3e-05,8.1e-07,0,0,-0.00013,0.2,0.002,0.44,0,0,0,0,0,3.4e-05,0.0044,0.0044,0.00034,1.3,1.3,0.1,0.28,0.28,0.097,4.5e-07,4.5e-07,6.1e-08,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
2590000,0.98,-0.0078,-0.015,0.19,0.023,0.0022,-0.15,0.0069,8.2e-05,-0.085,-1.8e-05,-2.7e-05,8.7e-07,0,0,-0.00015,0.2,0.002,0.44,0,0,0,0,0,3.3e-05,0.0032,0.0032,0.00033,0.89,0.89,0.099,0.18,0.18,0.094,3.8e-07,3.8e-07,5.5e-08,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
2690000,0.98,-0.0078,-0.015,0.19,0.027,0.0043,-0.15,0.0095,0.00041,-0.084,-1.8e-05,-2.7e-05,8.7e-07,0,0,-0.00018,0.2,0.002,0.44,0,0,0,0,0,3.2e-05,0.0035,0.0035,0.00032,1.1,1.1,0.097,0.25,0.25,0.091,3.8e-07,3.8e-07,5e-08,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
2790000,0.98,-0.0077,-0.015,0.19,0.021,0.0046,-0.14,0.006,0.00051,-0.081,-1.9e-05,-3e-05,8.9e-07,0,0,-0.00022,0.2,0.002,0.44,0,0,0,0,0,3.1e-05,0.0027,0.0027,0.00031,0.77,0.77,0.096,0.16,0.16,0.089,3.2e-07,3.2e-07,4.5e-08,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
2890000,0.98,-0.0077,-0.015,0.19,0.025,0.0043,-0.14,0.0084,0.00092,-0.082,-1.9e-05,-3e-05,8.9e-07,0,0,-0.00025,0.2,0.002,0.44,0,0,0,0,0,3e-05,0.0029,0.0029,0.0003,0.95,0.95,0.096,0.23,0.23,0.089,3.2e-07,3.2e-07,4.1e-08,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
2990000,0.98,-0.0076,-0.015,0.19,0.019,0.0032,-0.15,0.0055,0.00069,-0.086,-2e-05,-3.3e-05,9.1e-07,0,0,-0.00028,0.2,0.002,0.44,0,0,0,0,0,2.9e-05,0.0023,0.0023,0.00029,0.67,0.67,0.095,0.15,0.15,0.088,2.7e-07,2.7e-07,3.7e-08,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
3090000,0.98,-0.0076,-0.015,0.19,0.026,0.0024,-0.15,0.0077,0.00092,-0.088,-2e-05,-3.3e-05,9e-07,0,0,-0.00031,0.2,0.002,0.44,0,0,0,0,0,2.9e-05,0.0025,0.0025,0.00028,0.82,0.82,0.095,0.22,0.22,0.086,2.7e-07,2.7e-07,3.4e-08,4e-06,4e-06,3.2e-06,0,0,0,0,0,0,0,0
3190000,0.98,-0.0076,-0.015,0.19,0.021,0.0011,-0.15,0.0052,0.00052,-0.098,-2e-05,-3.6e-05,9.1e-07,0,0,-0.00033,0.2,0.002,0.44,0,0,0,0,0,2.8e-05,0.002,0.002,0.00027,0.59,0.59,0.096,0.14,0.14,0.087,2.3e-07,2.3e-07,3.1e-08,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0
3290000,0.98,-0.0075,-0.015,0.19,0.024,0.0019,-0.15,0.0075,0.00061,-0.11,-2e-05,-3.6e-05,9.1e-07,0,0,-0.00034,0.2,0.002,0.44,0,0,0,0,0,2.7e-05,0.0022,0.0022,0.00027,0.73,0.73,0.095,0.2,0.2,0.086,2.3e-07,2.3e-07,2.9e-08,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
3390000,0.98,-0.0073,-0.014,0.19,0.019,0.0032,-0.15,0.0051,0.00045,-0.1,-2.1e-05,-3.8e-05,9.1e-07,0,0,-0.0004,0.2,0.002,0.44,0,0,0,0,0,2.6e-05,0.0017,0.0017,0.00026,0.53,0.53,0.095,0.14,0.14,0.085,1.9e-07,1.9e-07,2.6e-08,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
3490000,0.98,-0.0072,-0.014,0.19,0.024,0.0064,-0.15,0.0073,0.00092,-0.1,-2.1e-05,-3.8e-05,9.1e-07,0,0,-0.00044,0.2,0.002,0.44,0,0,0,0,0,2.6e-05,0.0019,0.0019,0.00025,0.65,0.65,0.095,0.19,0.19,0.086,1.9e-07,1.9e-07,2.4e-08,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
3590000,0.98,-0.0071,-0.014,0.19,0.021,0.0056,-0.15,0.0051,0.00082,-0.11,-2.2e-05,-4e-05,9.1e-07,0,0,-0.00047,0.2,0.002,0.44,0,0,0,0,0,2.5e-05,0.0015,0.0015,0.00025,0.48,0.48,0.094,0.13,0.13,0.086,1.6e-07,1.6e-07,2.2e-08,4e-06,4e-06,2.6e-06,0,0,0,0,0,0,0,0
3690000,0.98,-0.0071,-0.014,0.19,0.023,0.0071,-0.15,0.0074,0.0014,-0.11,-2.1e-05,-4e-05,9.1e-07,0,0,-0.00052,0.2,0.002,0.44,0,0,0,0,0,2.5e-05,0.0017,0.0017,0.00024,0.59,0.59,0.093,0.18,0.18,0.085,1.6e-07,1.6e-07,2.1e-08,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
3790000,0.98,-0.007,-0.014,0.19,0.018,0.0098,-0.15,0.005,0.0012,-0.11,-2.2e-05,-4.2e-05,9e-07,0,0,-0.00055,0.2,0.002,0.44,0,0,0,0,0,2.4e-05,0.0014,0.0014,0.00023,0.44,0.44,0.093,0.12,0.12,0.086,1.4e-07,1.4e-07,1.9e-08,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
3890000,0.98,-0.007,-0.014,0.19,0.019,0.011,-0.14,0.0069,0.0023,-0.11,-2.2e-05,-4.2e-05,9e-07,0,0,-0.00059,0.2,0.002,0.44,0,0,0,0,0,2.4e-05,0.0015,0.0015,0.00023,0.54,0.54,0.091,0.17,0.17,0.086,1.4e-07,1.4e-07,1.8e-08,4e-06,4e-06,2.2e-06,0,0,0,0,0,0,0,0
3990000,0.98,-0.007,-0.014,0.19,0.023,0.013,-0.14,0.0091,0.0035,-0.11,-2.2e-05,-4.2e-05,9e-07,0,0,-0.00064,0.2,0.002,0.44,0,0,0,0,0,2.3e-05,0.0017,0.0017,0.00022,0.66,0.66,0.089,0.22,0.22,0.085,1.4e-07,1.4e-07,1.7e-08,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
4090000,0.98,-0.0069,-0.014,0.19,0.02,0.011,-0.12,0.0067,0.0028,-0.098,-2.2e-05,-4.4e-05,8.8e-07,0,0,-0.00072,0.2,0.002,0.44,0,0,0,0,0,2.3e-05,0.0013,0.0013,0.00022,0.5,0.5,0.087,0.16,0.16,0.085,1.2e-07,1.2e-07,1.6e-08,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
4190000,0.98,-0.007,-0.014,0.19,0.023,0.011,-0.12,0.0088,0.0039,-0.1,-2.2e-05,-4.4e-05,8.8e-07,0,0,-0.00074,0.2,0.002,0.44,0,0,0,0,0,2.2e-05,0.0015,0.0015,0.00021,0.6,0.6,0.086,0.21,0.21,0.086,1.2e-07,1.2e-07,1.5e-08,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
4290000,0.98,-0.0072,-0.014,0.19,0.02,0.01,-0.12,0.0064,0.0029,-0.11,-2.2e-05,-4.6e-05,8.7e-07,0,0,-0.00077,0.2,0.002,0.44,0,0,0,0,0,2.2e-05,0.0012,0.0012,0.00021,0.46,0.46,0.084,0.15,0.15,0.085,9.6e-08,9.6e-08,1.4e-08,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
4390000,0.98,-0.0071,-0.014,0.19,0.024,0.01,-0.11,0.0087,0.0039,-0.095,-2.2e-05,-4.6e-05,8.7e-07,0,0,-0.00083,0.2,0.002,0.44,0,0,0,0,0,2.1e-05,0.0013,0.0013,0.0002,0.56,0.56,0.081,0.2,0.2,0.084,9.6e-08,9.6e-08,1.3e-08,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
4490000,0.98,-0.0072,-0.014,0.19,0.019,0.01,-0.11,0.0064,0.0029,-0.095,-2.1e-05,-4.8e-05,8.5e-07,0,0,-0.00086,0.2,0.002,0.44,0,0,0,0,0,2.1e-05,0.001,0.001,0.0002,0.43,0.43,0.08,0.14,0.14,0.085,7.9e-08,7.9e-08,1.2e-08,4e-06,4e-06,1.5e-06,0,0,0,0,0,0,0,0
4590000,0.98,-0.0071,-0.014,0.19,0.023,0.01,-0.11,0.0085,0.0039,-0.098,-2.1e-05,-4.8e-05,8.5e-07,0,0,-0.00089,0.2,0.002,0.44,0,0,0,0,0,2e-05,0.0011,0.0011,0.0002,0.51,0.51,0.077,0.19,0.19,0.084,7.9e-08,7.9e-08,1.1e-08,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
4690000,0.98,-0.0071,-0.013,0.19,0.017,0.0083,-0.1,0.0062,0.0029,-0.09,-2.1e-05,-5e-05,8.4e-07,0,0,-0.00093,0.2,0.002,0.44,0,0,0,0,0,2e-05,0.00092,0.00092,0.00019,0.39,0.39,0.074,0.14,0.14,0.083,6.4e-08,6.4e-08,1.1e-08,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
4790000,0.98,-0.007,-0.013,0.19,0.014,0.0094,-0.099,0.0078,0.0038,-0.093,-2.1e-05,-5e-05,8.4e-07,0,0,-0.00095,0.2,0.002,0.44,0,0,0,0,0,2e-05,0.001,0.001,0.00019,0.47,0.47,0.073,0.18,0.18,0.084,6.4e-08,6.4e-08,9.9e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
4890000,0.98,-0.007,-0.013,0.19,0.01,0.0054,-0.093,0.0052,0.0026,-0.088,-2.1e-05,-5.1e-05,8.2e-07,0,0,-0.00099,0.2,0.002,0.44,0,0,0,0,0,1.9e-05,0.0008,0.0008,0.00018,0.36,0.36,0.07,0.13,0.13,0.083,5.2e-08,5.2e-08,9.3e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
4990000,0.98,-0.007,-0.013,0.19,0.014,0.0072,-0.085,0.0064,0.0033,-0.083,-2.1e-05,-5.1e-05,8.2e-07,0,0,-0.001,0.2,0.002,0.44,0,0,0,0,0,1.9e-05,0.00087,0.00087,0.00018,0.43,0.43,0.067,0.17,0.17,0.082,5.2e-08,5.2e-08,8.8e-09,4e-06,4e-06,1e-06,0,0,0,0,0,0,0,0
5090000,0.98,-0.0069,-0.013,0.19,0.01,0.0064,-0.082,0.0045,0.0023,-0.082,-2.1e-05,-5.2e-05,8.1e-07,0,0,-0.001,0.2,0.002,0.44,0,0,0,0,0,1.9e-05,0.0007,0.0007,0.00018,0.33,0.33,0.065,0.12,0.12,0.082,4.2e-08,4.2e-08,8.3e-09,4e-06,4e-06,9.8e-07,0,0,0,0,0,0,0,0
5190000,0.98,-0.0067,-0.013,0.19,0.0089,0.0096,-0.08,0.0054,0.0031,-0.079,-2.1e-05,-5.2e-05,8.1e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,1.8e-05,0.00075,0.00075,0.00017,0.39,0.39,0.063,0.16,0.16,0.081,4.2e-08,4.2e-08,7.9e-09,4e-06,4e-06,9.1e-07,0,0,0,0,0,0,0,0
5290000,0.98,-0.0066,-0.013,0.19,0.0071,0.0092,-0.068,0.0037,0.0024,-0.072,-2.1e-05,-5.3e-05,8e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,1.8e-05,0.0006,0.0006,0.00017,0.3,0.3,0.06,0.12,0.12,0.08,3.4e-08,3.4e-08,7.4e-09,4e-06,4e-06,8.4e-07,0,0,0,0,0,0,0,0
5390000,0.98,-0.0066,-0.013,0.19,0.0055,0.012,-0.065,0.0044,0.0034,-0.067,-2.1e-05,-5.3e-05,8e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,1.8e-05,0.00065,0.00065,0.00017,0.36,0.36,0.057,0.15,0.15,0.079,3.4e-08,3.4e-08,7.1e-09,4e-06,4e-06,7.8e-07,0,0,0,0,0,0,0,0
5490000,0.98,-0.0066,-0.013,0.19,0.0043,0.013,-0.06,0.0028,0.0028,-0.065,-2.1e-05,-5.4e-05,7.9e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,1.7e-05,0.00052,0.00052,0.00016,0.28,0.28,0.056,0.11,0.11,0.079,2.8e-08,2.8e-08,6.7e-09,4e-06,4e-06,7.3e-07,0,0,0,0,0,0,0,0
5590000,0.98,-0.0066,-0.013,0.19,0.0043,0.017,-0.053,0.0033,0.0044,-0.058,-2.1e-05,-5.4e-05,7.9e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.7e-05,0.00056,0.00056,0.00016,0.32,0.32,0.053,0.15,0.15,0.078,2.8e-08,2.8e-08,6.3e-09,4e-06,4e-06,6.7e-07,0,0,0,0,0,0,0,0
5690000,0.98,-0.0067,-0.013,0.19,0.0034,0.017,-0.052,0.0022,0.0036,-0.056,-2e-05,-5.5e-05,7.8e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.7e-05,0.00045,0.00045,0.00016,0.25,0.25,0.051,0.11,0.11,0.076,2.2e-08,2.2e-08,6e-09,4e-06,4e-06,6.2e-07,0,0,0,0,0,0,0,0
5790000,0.98,-0.0065,-0.013,0.19,0.004,0.02,-0.049,0.0026,0.0054,-0.053,-2e-05,-5.5e-05,7.8e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.6e-05,0.00048,0.00048,0.00016,0.29,0.29,0.05,0.14,0.14,0.077,2.2e-08,2.2e-08,5.7e-09,4e-06,4e-06,5.8e-07,0,0,0,0,0,0,0,0
5890000,0.98,-0.0066,-0.013,0.19,0.005,0.018,-0.048,0.0018,0.0044,-0.056,-1.9e-05,-5.5e-05,7.6e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.6e-05,0.00039,0.00039,0.00015,0.23,0.23,0.048,0.1,0.1,0.075,1.8e-08,1.8e-08,5.5e-09,4e-06,4e-06,5.4e-07,0,0,0,0,0,0,0,0
5990000,0.98,-0.0065,-0.013,0.19,0.0061,0.019,-0.041,0.0024,0.0062,-0.05,-1.9e-05,-5.5e-05,7.6e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.6e-05,0.00041,0.00041,0.00015,0.27,0.27,0.045,0.13,0.13,0.074,1.8e-08,1.8e-08,5.2e-09,4e-06,4e-06,5e-07,0,0,0,0,0,0,0,0
6090000,0.98,-0.0065,-0.013,0.19,0.0058,0.021,-0.039,0.003,0.0082,-0.048,-1.9e-05,-5.5e-05,7.6e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.6e-05,0.00044,0.00044,0.00015,0.31,0.31,0.044,0.17,0.17,0.074,1.8e-08,1.8e-08,5e-09,4e-06,4e-06,4.7e-07,0,0,0,0,0,0,0,0
6190000,0.98,-0.0067,-0.013,0.19,0.0037,0.019,-0.037,0.0022,0.0066,-0.047,-1.9e-05,-5.6e-05,7.5e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.5e-05,0.00036,0.00036,0.00015,0.24,0.24,0.042,0.13,0.13,0.073,1.5e-08,1.5e-08,4.7e-09,4e-06,4e-06,4.4e-07,0,0,0,0,0,0,0,0
6290000,0.98,-0.0066,-0.013,0.19,0.0022,0.021,-0.041,0.0026,0.0085,-0.053,-1.9e-05,-5.6e-05,7.5e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,1.5e-05,0.00038,0.00038,0.00014,0.28,0.28,0.04,0.16,0.16,0.072,1.5e-08,1.5e-08,4.5e-09,4e-06,4e-06,4.1e-07,0,0,0,0,0,0,0,0
6390000,0.98,-0.0066,-0.013,0.19,0.0032,0.018,-0.042,0.0017,0.0068,-0.056,-1.8e-05,-5.6e-05,7.3e-07,0,0,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.2e-05,0.0003,0.0003,0.0015,0.2,0.2,0.039,0.12,0.12,0.072,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,3.8e-07,0,0,0,0,0,0,0,0
6490000,0.98,-0.0066,-0.013,0.19,0.00098,0.017,-0.039,0.0019,0.0085,-0.053,-1.8e-05,-5.6e-05,7.1e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,4.2e-05,0.0003,0.0003,0.00096,0.2,0.21,0.038,0.15,0.15,0.07,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,3.6e-07,0,0,0,0,0,0,0,0
6590000,0.98,-0.0065,-0.013,0.19,0.00028,0.02,-0.042,0.002,0.01,-0.056,-1.8e-05,-5.6e-05,6.8e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-05,0.0003,0.0003,0.00071,0.21,0.21,0.036,0.18,0.18,0.069,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,3.3e-07,0,0,0,0,0,0,0,0
6690000,0.98,-0.0064,-0.013,0.19,-0.0024,0.022,-0.044,0.0019,0.012,-0.057,-1.8e-05,-5.6e-05,6.4e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-05,0.0003,0.0003,0.00056,0.22,0.22,0.035,0.22,0.22,0.068,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,3.1e-07,0,0,0,0,0,0,0,0
6790000,0.98,-0.0064,-0.013,0.19,-0.00059,0.024,-0.042,0.0017,0.015,-0.058,-1.8e-05,-5.6e-05,6e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.0003,0.0003,0.00048,0.23,0.23,0.034,0.26,0.26,0.068,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,2.9e-07,0,0,0,0,0,0,0,0
6890000,0.98,-0.0062,-0.013,0.19,-0.0011,0.024,-0.038,0.0016,0.017,-0.055,-1.8e-05,-5.6e-05,5.8e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2e-05,0.00031,0.00031,0.00041,0.25,0.25,0.032,0.31,0.31,0.067,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,2.7e-07,0,0,0,0,0,0,0,0
6990000,0.98,-0.0062,-0.013,0.19,-0.0011,0.026,-0.037,0.0015,0.02,-0.055,-1.8e-05,-5.6e-05,5.7e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.8e-05,0.00031,0.00031,0.00035,0.27,0.27,0.031,0.36,0.36,0.066,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0
7090000,0.98,-0.0061,-0.012,0.19,-0.002,0.031,-0.037,0.0013,0.023,-0.056,-1.8e-05,-5.6e-05,5.7e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.7e-05,0.00031,0.00031,0.00032,0.29,0.29,0.03,0.42,0.42,0.066,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,2.4e-07,0,0,0,0,0,0,0,0
7190000,0.98,-0.006,-0.013,0.19,-0.0025,0.034,-0.036,0.0011,0.026,-0.058,-1.8e-05,-5.6e-05,5e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.6e-05,0.00032,0.00032,0.00029,0.32,0.32,0.029,0.49,0.49,0.065,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,2.3e-07,0,0,0,0,0,0,0,0
7290000,0.98,-0.006,-0.013,0.19,-0.0017,0.038,-0.034,0.0008,0.029,-0.054,-1.8e-05,-5.6e-05,5e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.5e-05,0.00032,0.00032,0.00026,0.35,0.35,0.028,0.56,0.56,0.064,1.2e-08,1.2e-08,4.5e-09,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0
7390000,0.98,-0.0059,-0.013,0.19,-0.0035,0.041,-0.032,0.00056,0.033,-0.052,-1.8e-05,-5.6e-05,5.1e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.4e-05,0.00033,0.00033,0.00024,0.38,0.38,0.027,0.64,0.64,0.064,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0
7490000,0.98,-0.0058,-0.013,0.19,-0.0012,0.045,-0.026,0.00037,0.038,-0.046,-1.8e-05,-5.6e-05,6.2e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00034,0.00034,0.00022,0.42,0.42,0.026,0.73,0.73,0.063,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.9e-07,0,0,0,0,0,0,0,0
7590000,0.98,-0.0059,-0.013,0.19,-0.00017,0.048,-0.023,0.00032,0.042,-0.041,-1.8e-05,-5.6e-05,6.3e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00034,0.00034,0.00021,0.45,0.45,0.025,0.83,0.83,0.062,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0
7690000,0.98,-0.0059,-0.013,0.19,-0.00052,0.052,-0.022,0.00028,0.047,-0.036,-1.8e-05,-5.6e-05,5.9e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00035,0.00035,0.0002,0.5,0.5,0.025,0.95,0.95,0.062,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0
7790000,0.98,-0.0058,-0.013,0.19,0.0011,0.054,-0.024,0.00029,0.052,-0.041,-1.8e-05,-5.6e-05,5.1e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00036,0.00036,0.00018,0.54,0.54,0.024,1.1,1.1,0.061,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
7890000,0.98,-0.0058,-0.013,0.19,-0.00028,0.059,-0.025,0.00024,0.057,-0.045,-1.8e-05,-5.6e-05,4.6e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00037,0.00037,0.00017,0.59,0.59,0.023,1.2,1.2,0.06,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0
7990000,0.98,-0.0057,-0.013,0.19,-3.6e-05,0.062,-0.021,0.00022,0.063,-0.042,-1.8e-05,-5.6e-05,4.6e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00037,0.00037,0.00017,0.64,0.64,0.022,1.4,1.4,0.059,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
8090000,0.98,-0.0056,-0.013,0.19,0.0014,0.067,-0.022,0.00031,0.069,-0.044,-1.8e-05,-5.6e-05,2e-07,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00038,0.00038,0.00016,0.7,0.7,0.022,1.5,1.5,0.059,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
8190000,0.98,-0.0056,-0.013,0.19,0.002,0.073,-0.018,0.00045,0.076,-0.038,-1.8e-05,-5.6e-05,-1.9e-09,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00039,0.00039,0.00015,0.76,0.76,0.021,1.7,1.7,0.058,1.2e-08,1.2e-08,4.4e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
8290000,0.98,-0.0056,-0.013,0.19,0.0042,0.077,-0.016,0.00073,0.082,-0.038,-1.8e-05,-5.6e-05,-8.3e-08,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1e-05,0.0004,0.0004,0.00015,0.81,0.81,0.02,1.9,1.9,0.057,1.1e-08,1.1e-08,4.3e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
8390000,0.98,-0.0056,-0.013,0.19,0.002,0.08,-0.015,0.001,0.09,-0.036,-1.8e-05,-5.6e-05,-1.6e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,1e-05,0.00041,0.00041,0.00014,0.88,0.88,0.02,2.2,2.2,0.057,1.1e-08,1.1e-08,4.3e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
8490000,0.98,-0.0055,-0.013,0.19,0.0018,0.084,-0.017,0.0012,0.096,-0.041,-1.8e-05,-5.6e-05,-1.7e-08,0,0,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1e-05,0.00042,0.00042,0.00014,0.94,0.94,0.019,2.4,2.4,0.056,1.1e-08,1.1e-08,4.3e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8590000,0.98,-0.0054,-0.013,0.19,0.0028,0.088,-0.012,0.0014,0.1,-0.036,-1.8e-05,-5.6e-05,-1.4e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.9e-06,0.00043,0.00043,0.00013,1,1,0.018,2.7,2.7,0.055,1.1e-08,1.1e-08,4.3e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8690000,0.98,-0.0055,-0.013,0.19,0.0028,0.089,-0.014,0.0016,0.11,-0.037,-1.8e-05,-5.6e-05,-1.2e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.8e-06,0.00043,0.00043,0.00013,1.1,1.1,0.018,2.9,2.9,0.055,1.1e-08,1.1e-08,4.3e-09,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0
8790000,0.98,-0.0054,-0.013,0.19,0.0042,0.093,-0.013,0.0018,0.12,-0.035,-1.8e-05,-5.6e-05,-3.5e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.7e-06,0.00045,0.00045,0.00013,1.2,1.2,0.018,3.3,3.3,0.055,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,9.6e-08,0,0,0,0,0,0,0,0
8890000,0.98,-0.0055,-0.013,0.19,0.0042,0.095,-0.0091,0.0022,0.13,-0.029,-1.8e-05,-5.6e-05,-1.8e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.5e-06,0.00045,0.00045,0.00012,1.2,1.2,0.017,3.5,3.6,0.054,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,9.1e-08,0,0,0,0,0,0,0,0
8990000,0.98,-0.0054,-0.013,0.19,0.0033,0.1,-0.0083,0.0026,0.14,-0.032,-1.8e-05,-5.6e-05,8.4e-08,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.5e-06,0.00046,0.00046,0.00012,1.3,1.3,0.017,4,4,0.054,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,8.8e-08,0,0,0,0,0,0,0,0
9090000,0.98,-0.0055,-0.013,0.19,0.0036,0.1,-0.0093,0.0029,0.14,-0.032,-1.7e-05,-5.6e-05,3.8e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.4e-06,0.00046,0.00046,0.00012,1.3,1.3,0.016,4.2,4.2,0.053,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,8.4e-08,0,0,0,0,0,0,0,0
9190000,0.98,-0.0054,-0.013,0.19,0.0072,0.11,-0.0088,0.0035,0.15,-0.032,-1.7e-05,-5.6e-05,6.4e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.3e-06,0.00047,0.00047,0.00012,1.4,1.4,0.016,4.7,4.7,0.052,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,8e-08,0,0,0,0,0,0,0,0
9290000,0.98,-0.0053,-0.013,0.19,0.0094,0.11,-0.0072,0.0042,0.15,-0.03,-1.7e-05,-5.6e-05,7.2e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.2e-06,0.00047,0.00047,0.00011,1.5,1.5,0.015,5,5,0.052,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,7.6e-08,0,0,0,0,0,0,0,0
9390000,0.98,-0.0052,-0.013,0.19,0.0095,0.11,-0.0061,0.0051,0.16,-0.03,-1.7e-05,-5.6e-05,4e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.2e-06,0.00048,0.00048,0.00011,1.6,1.6,0.015,5.5,5.5,0.052,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,7.3e-08,0,0,0,0,0,0,0,0
9490000,0.98,-0.0053,-0.013,0.19,0.0092,0.11,-0.0044,0.0058,0.17,-0.027,-1.7e-05,-5.7e-05,5.1e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.1e-06,0.00047,0.00047,0.00011,1.6,1.6,0.015,5.8,5.8,0.051,1e-08,1e-08,4e-09,4e-06,4e-06,7e-08,0,0,0,0,0,0,0,0
9590000,0.98,-0.0054,-0.013,0.19,0.0091,0.11,-0.0043,0.0065,0.18,-0.029,-1.7e-05,-5.6e-05,-1.1e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.1e-06,0.00049,0.00049,0.00011,1.7,1.7,0.014,6.4,6.4,0.05,1e-08,1e-08,4e-09,4e-06,4e-06,6.7e-08,0,0,0,0,0,0,0,0
9690000,0.98,-0.0054,-0.013,0.19,0.0088,0.11,-0.0014,0.0069,0.18,-0.027,-1.7e-05,-5.7e-05,-2.9e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9e-06,0.00047,0.00047,0.00011,1.7,1.7,0.014,6.6,6.6,0.05,9.9e-09,9.9e-09,3.9e-09,4e-06,4e-06,6.5e-08,0,0,0,0,0,0,0,0
9790000,0.98,-0.0054,-0.013,0.19,0.01,0.11,-0.0027,0.0077,0.19,-0.028,-1.7e-05,-5.7e-05,-9.1e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9e-06,0.00049,0.00049,0.00011,1.8,1.8,0.014,7.3,7.3,0.05,9.9e-09,9.9e-09,3.9e-09,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0
9890000,0.98,-0.0055,-0.013,0.19,0.012,0.11,-0.0014,0.0082,0.18,-0.029,-1.6e-05,-5.7e-05,-8e-07,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.9e-06,0.00047,0.00047,0.00011,1.8,1.8,0.013,7.4,7.4,0.049,9.6e-09,9.6e-09,3.9e-09,4e-06,4e-06,6e-08,0,0,0,0,0,0,0,0
9990000,0.98,-0.0054,-0.013,0.19,0.014,0.11,-0.00073,0.0093,0.2,-0.031,-1.6e-05,-5.7e-05,-1.3e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.9e-06,0.00049,0.00049,0.00011,1.9,1.9,0.013,8.2,8.2,0.049,9.6e-09,9.6e-09,3.8e-09,4e-06,4e-06,5.8e-08,0,0,0,0,0,0,0,0
10090000,0.98,-0.0055,-0.013,0.19,0.012,0.11,0.00048,0.0096,0.19,-0.029,-1.6e-05,-5.7e-05,-1.9e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.9e-06,0.00046,0.00046,0.00011,1.9,1.9,0.013,8.2,8.2,0.048,9.3e-09,9.3e-09,3.8e-09,4e-06,4e-06,5.6e-08,0,0,0,0,0,0,0,0
10190000,0.98,-0.0055,-0.013,0.19,0.0099,0.11,0.0014,0.011,0.2,-0.03,-1.6e-05,-5.7e-05,-2.6e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.9e-06,0.00048,0.00048,0.00011,2,2,0.012,9,9,0.048,9.3e-09,9.3e-09,3.7e-09,4e-06,4e-06,5.4e-08,0,0,0,0,0,0,0,0
10290000,0.98,-0.0055,-0.013,0.19,0.01,0.11,0.00029,0.012,0.21,-0.029,-1.6e-05,-5.7e-05,-2.3e-06,0,0,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.9e-06,0.00049,0.00049,0.00011,2.1,2.1,0.012,9.9,9.9,0.048,9.3e-09,9.3e-09,3.7e-09,4e-06,4e-06,5.2e-08,0,0,0,0,0,0,0,0
10390000,0.98,-0.0055,-0.012,0.19,0.007,0.0051,-0.0025,0.00075,0.00014,-0.028,-1.6e-05,-5.7e-05,-2.1e-06,-3.6e-10,2.5e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00051,0.00051,0.00011,0.25,0.25,0.56,0.25,0.25,0.048,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10490000,0.98,-0.0054,-0.012,0.19,0.0083,0.0074,0.007,0.0015,0.00073,-0.023,-1.6e-05,-5.7e-05,-2.7e-06,-1.2e-08,8.3e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00053,0.00053,0.00011,0.26,0.26,0.55,0.26,0.26,0.057,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10590000,0.98,-0.0053,-0.012,0.19,-0.0014,0.0053,0.013,-0.0012,-0.0054,-0.021,-1.6e-05,-5.7e-05,-2.3e-06,3.2e-06,6.7e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00053,0.00053,0.00011,0.13,0.13,0.27,0.13,0.13,0.055,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10690000,0.98,-0.0053,-0.012,0.19,-0.00034,0.0064,0.016,-0.0013,-0.0049,-0.017,-1.6e-05,-5.7e-05,-2.5e-06,3.2e-06,7.5e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00055,0.00055,0.00011,0.14,0.14,0.26,0.14,0.14,0.065,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10790000,0.98,-0.0054,-0.012,0.19,0.0015,0.0029,0.014,-0.00078,-0.0047,-0.015,-1.6e-05,-5.7e-05,-2.6e-06,5.1e-06,4.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00054,0.00054,0.00011,0.1,0.1,0.17,0.091,0.091,0.062,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10890000,0.98,-0.0053,-0.013,0.19,0.0015,0.0064,0.01,-0.00063,-0.0043,-0.018,-1.6e-05,-5.7e-05,-1.9e-06,5.1e-06,4.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00056,0.00056,0.00011,0.12,0.12,0.16,0.098,0.098,0.068,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10990000,0.98,-0.0054,-0.013,0.19,0.001,0.012,0.016,-0.00046,-0.003,-0.012,-1.6e-05,-5.7e-05,-2.1e-06,6.5e-06,7.2e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00053,0.00053,0.00011,0.092,0.092,0.12,0.073,0.073,0.065,8.6e-09,8.6e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11090000,0.98,-0.0055,-0.013,0.19,0.0019,0.017,0.02,-0.00036,-0.0016,-0.0075,-1.6e-05,-5.7e-05,-2.8e-06,6.5e-06,7.2e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00054,0.00054,0.00011,0.11,0.11,0.11,0.08,0.08,0.069,8.6e-09,8.6e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11190000,0.98,-0.0058,-0.013,0.19,0.0036,0.017,0.026,0.001,-0.0018,-0.00047,-1.5e-05,-5.7e-05,-3.1e-06,6.2e-06,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00049,0.00049,0.00011,0.092,0.092,0.083,0.063,0.063,0.066,8e-09,8e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11290000,0.98,-0.0058,-0.013,0.19,0.0037,0.018,0.026,0.0014,2.7e-05,-0.00024,-1.5e-05,-5.7e-05,-3.3e-06,6.2e-06,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00051,0.00051,0.00011,0.11,0.11,0.077,0.07,0.07,0.069,8e-09,8e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11390000,0.98,-0.0059,-0.013,0.19,0.0022,0.016,0.016,0.00085,-0.00079,-0.0087,-1.4e-05,-5.8e-05,-3.2e-06,1.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00044,0.00044,0.00011,0.093,0.093,0.062,0.057,0.057,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11490000,0.98,-0.0059,-0.013,0.19,0.0012,0.017,0.02,0.00095,0.00085,-0.0026,-1.4e-05,-5.8e-05,-3.1e-06,1.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00046,0.00046,0.00011,0.11,0.11,0.057,0.065,0.065,0.067,7.4e-09,7.4e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11590000,0.98,-0.0062,-0.012,0.19,0.0031,0.013,0.018,0.00081,-0.00023,-0.0037,-1.3e-05,-5.8e-05,-3.1e-06,1.5e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00039,0.00039,0.00011,0.092,0.092,0.048,0.054,0.054,0.065,6.7e-09,6.7e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11690000,0.98,-0.0061,-0.012,0.19,0.0035,0.017,0.018,0.0012,0.0013,-0.0051,-1.3e-05,-5.8e-05,-2.8e-06,1.5e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.0004,0.0004,0.00011,0.11,0.11,0.044,0.062,0.062,0.066,6.7e-09,6.7e-09,2.9e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11790000,0.98,-0.0065,-0.012,0.19,0.0023,0.011,0.019,0.00068,-0.0016,-0.0021,-1.2e-05,-5.9e-05,-2.2e-06,2e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00034,0.00034,0.00011,0.089,0.09,0.037,0.052,0.052,0.063,6.2e-09,6.2e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11890000,0.98,-0.0066,-0.012,0.19,0.0049,0.013,0.017,0.00098,-0.00042,-0.0014,-1.2e-05,-5.9e-05,-2.2e-06,2e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00035,0.00035,0.0001,0.11,0.11,0.034,0.06,0.06,0.063,6.2e-09,6.2e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11990000,0.98,-0.0068,-0.012,0.19,0.0079,0.013,0.015,0.0021,-0.0016,-0.0051,-1.2e-05,-5.9e-05,-2e-06,2e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.0003,0.0003,0.00011,0.086,0.086,0.03,0.051,0.051,0.061,5.7e-09,5.7e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12090000,0.98,-0.0067,-0.012,0.19,0.0095,0.013,0.018,0.003,-0.00037,0.00096,-1.2e-05,-5.9e-05,-1.9e-06,2e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00031,0.00031,0.00011,0.1,0.1,0.027,0.059,0.059,0.06,5.7e-09,5.7e-09,2.7e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12190000,0.98,-0.0066,-0.012,0.19,0.0077,0.012,0.017,0.0018,0.00055,0.0028,-1.2e-05,-5.9e-05,-2.1e-06,2.3e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00027,0.00027,0.0001,0.081,0.081,0.024,0.05,0.05,0.058,5.3e-09,5.3e-09,2.7e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12290000,0.98,-0.0067,-0.012,0.19,0.0054,0.011,0.016,0.0024,0.0017,0.0038,-1.2e-05,-5.9e-05,-2.3e-06,2.3e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00028,0.00028,0.00011,0.096,0.096,0.022,0.059,0.059,0.058,5.3e-09,5.3e-09,2.6e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12390000,0.98,-0.0068,-0.012,0.19,0.004,0.0078,0.014,0.0017,0.00064,-0.0022,-1.2e-05,-5.9e-05,-2.2e-06,2.6e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00025,0.00025,0.00011,0.076,0.076,0.02,0.05,0.05,0.056,4.9e-09,4.9e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12490000,0.98,-0.0068,-0.012,0.19,0.004,0.0089,0.018,0.0021,0.0015,-0.00019,-1.2e-05,-5.9e-05,-2.2e-06,2.6e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00026,0.00026,0.0001,0.089,0.089,0.018,0.058,0.058,0.055,4.9e-09,4.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12590000,0.98,-0.007,-0.012,0.19,0.0078,0.0022,0.02,0.0033,-0.0012,0.0016,-1.1e-05,-5.9e-05,-2.2e-06,2.6e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00023,0.00023,0.00011,0.071,0.071,0.017,0.049,0.049,0.054,4.7e-09,4.7e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12690000,0.98,-0.007,-0.012,0.19,0.0083,9.1e-05,0.019,0.004,-0.0011,0.0032,-1.1e-05,-5.9e-05,-2.1e-06,2.6e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00024,0.00024,0.0001,0.083,0.083,0.016,0.058,0.058,0.053,4.7e-09,4.7e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12790000,0.98,-0.0072,-0.012,0.19,0.0099,-0.0034,0.021,0.0041,-0.0043,0.0053,-1.1e-05,-5.9e-05,-1.2e-06,2.7e-05,4.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00022,0.00022,0.0001,0.067,0.067,0.014,0.049,0.049,0.052,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12890000,0.98,-0.0072,-0.012,0.19,0.01,-0.0042,0.022,0.0051,-0.0046,0.0083,-1.1e-05,-5.9e-05,-6.7e-07,2.7e-05,4.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00023,0.00023,0.0001,0.077,0.077,0.013,0.058,0.058,0.051,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12990000,0.98,-0.0072,-0.012,0.19,0.008,-0.0023,0.022,0.0036,-0.0034,0.0095,-1.1e-05,-6e-05,-1.2e-07,2.7e-05,4.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.00021,0.00021,0.0001,0.063,0.063,0.012,0.049,0.049,0.05,4.2e-09,4.2e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13090000,0.98,-0.0072,-0.012,0.19,0.0089,-0.0022,0.02,0.0044,-0.0036,0.0084,-1.1e-05,-6e-05,5.7e-07,2.8e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.00022,0.00022,0.0001,0.072,0.072,0.012,0.057,0.057,0.049,4.2e-09,4.2e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13190000,0.98,-0.0072,-0.012,0.19,0.0039,-0.0039,0.019,0.00096,-0.0044,0.009,-1.1e-05,-6e-05,1e-06,2.9e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.00021,0.00021,0.0001,0.059,0.059,0.011,0.049,0.049,0.047,4e-09,4e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13290000,0.98,-0.0073,-0.012,0.19,0.0036,-0.0048,0.016,0.0013,-0.0048,0.0083,-1.1e-05,-6e-05,1.1e-06,2.9e-05,4.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.00021,0.00021,0.0001,0.067,0.067,0.01,0.057,0.057,0.047,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13390000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0029,0.016,0.00085,-0.0036,0.009,-1.1e-05,-6e-05,9.8e-07,3e-05,4.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.0002,0.0002,0.0001,0.056,0.056,0.0097,0.049,0.049,0.046,3.8e-09,3.8e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13490000,0.98,-0.0072,-0.012,0.19,0.0032,-0.0012,0.015,0.0012,-0.0038,0.0051,-1.1e-05,-6e-05,1.2e-06,3.1e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.00021,0.00021,0.0001,0.063,0.063,0.0093,0.056,0.056,0.045,3.8e-09,3.8e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13590000,0.98,-0.0072,-0.012,0.19,0.0076,-0.0015,0.017,0.004,-0.0031,0.0036,-1.1e-05,-6e-05,1.1e-06,3.2e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0088,0.048,0.048,0.044,3.6e-09,3.6e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13690000,0.98,-0.0071,-0.012,0.19,0.0076,-0.0029,0.017,0.0048,-0.0033,0.0063,-1.1e-05,-6e-05,1.5e-06,3.2e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.0002,0.0002,0.0001,0.06,0.06,0.0085,0.056,0.056,0.044,3.6e-09,3.6e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13790000,0.98,-0.0071,-0.012,0.19,0.015,0.0011,0.017,0.0083,-0.00086,0.0058,-1.1e-05,-5.9e-05,1.4e-06,3.6e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.0002,0.0002,0.0001,0.05,0.05,0.0082,0.048,0.048,0.043,3.5e-09,3.5e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13890000,0.98,-0.007,-0.012,0.19,0.016,0.0019,0.018,0.0098,-0.0007,0.008,-1.1e-05,-5.9e-05,1.9e-06,3.6e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.6e-06,0.0002,0.0002,0.0001,0.057,0.057,0.008,0.056,0.056,0.042,3.5e-09,3.5e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13990000,0.98,-0.007,-0.012,0.19,0.015,0.002,0.017,0.0074,-0.0022,0.0069,-1.1e-05,-5.9e-05,2.4e-06,3.4e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.00019,0.00019,0.0001,0.048,0.048,0.0077,0.048,0.048,0.041,3.3e-09,3.3e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0024,0.018,0.0088,-0.0023,0.0033,-1.1e-05,-5.9e-05,1.5e-06,3.5e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.0002,0.0002,0.0001,0.055,0.055,0.0076,0.055,0.055,0.041,3.3e-09,3.3e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14190000,0.98,-0.007,-0.012,0.19,0.01,-0.0012,0.018,0.008,-0.0017,0.0035,-1.1e-05,-5.9e-05,1e-06,3.6e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.00019,0.00019,0.0001,0.046,0.046,0.0074,0.048,0.048,0.04,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0012,0.016,0.009,-0.0018,0.0078,-1.1e-05,-6e-05,1.1e-06,3.6e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.0002,0.0002,0.0001,0.052,0.052,0.0073,0.055,0.055,0.04,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0042,0.017,0.0084,-0.003,0.012,-1.1e-05,-6e-05,1.5e-06,3.4e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.00019,0.00019,0.0001,0.045,0.045,0.0071,0.048,0.048,0.039,3e-09,3e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.004,0.021,0.0095,-0.0034,0.014,-1.1e-05,-6e-05,1e-06,3.4e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0071,0.055,0.055,0.038,3e-09,3e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14590000,0.98,-0.0072,-0.011,0.19,0.0081,-0.0041,0.019,0.0059,-0.0041,0.01,-1.1e-05,-6e-05,9.8e-07,3.2e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.00019,0.00019,0.0001,0.044,0.044,0.007,0.047,0.047,0.038,2.8e-09,2.8e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14690000,0.98,-0.0072,-0.011,0.19,0.0073,-0.0041,0.019,0.0067,-0.0045,0.011,-1.1e-05,-6e-05,1.2e-06,3.3e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.5e-06,0.00019,0.00019,0.0001,0.049,0.049,0.007,0.054,0.054,0.037,2.8e-09,2.8e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14790000,0.98,-0.0072,-0.011,0.19,0.009,0.0028,0.019,0.0053,0.00085,0.013,-1.2e-05,-6e-05,1.8e-06,3.3e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.4e-06,0.00019,0.00019,9.9e-05,0.042,0.042,0.0069,0.047,0.047,0.037,2.6e-09,2.6e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14890000,0.98,-0.0071,-0.011,0.19,0.0077,0.00044,0.023,0.0061,0.001,0.014,-1.2e-05,-6e-05,2.2e-06,3.4e-05,4.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.4e-06,0.00019,0.00019,9.9e-05,0.048,0.048,0.007,0.054,0.054,0.037,2.6e-09,2.6e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14990000,0.98,-0.0072,-0.011,0.19,0.0065,-0.0012,0.026,0.0048,-0.00061,0.016,-1.2e-05,-6e-05,2.5e-06,3.2e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.4e-06,0.00019,0.00019,9.9e-05,0.042,0.042,0.0069,0.047,0.047,0.036,2.5e-09,2.5e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15090000,0.98,-0.0072,-0.011,0.19,0.0065,-0.00012,0.03,0.0054,-0.00072,0.019,-1.2e-05,-6e-05,2.5e-06,3.2e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.4e-06,0.00019,0.00019,9.8e-05,0.047,0.047,0.007,0.054,0.054,0.036,2.5e-09,2.5e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15190000,0.98,-0.0073,-0.011,0.19,0.0046,-0.0012,0.03,0.0043,-0.00068,0.021,-1.2e-05,-6.1e-05,2.4e-06,3.2e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.4e-06,0.00018,0.00018,9.8e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.3e-09,2.3e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15290000,0.98,-0.0074,-0.011,0.19,0.0053,-0.0023,0.03,0.0048,-0.00083,0.017,-1.2e-05,-6e-05,2.8e-06,3.4e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.4e-06,0.00019,0.00019,9.8e-05,0.046,0.046,0.0071,0.054,0.054,0.035,2.3e-09,2.3e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15390000,0.98,-0.0075,-0.011,0.19,0.0055,7e-05,0.029,0.0038,-0.00056,0.018,-1.2e-05,-6.1e-05,2.8e-06,3.5e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.3e-06,0.00018,0.00018,9.7e-05,0.04,0.04,0.007,0.047,0.047,0.035,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15490000,0.98,-0.0075,-0.011,0.19,0.0049,-0.0024,0.029,0.0043,-0.00065,0.019,-1.2e-05,-6.1e-05,2.8e-06,3.6e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.3e-06,0.00019,0.00019,9.7e-05,0.045,0.045,0.0072,0.053,0.053,0.035,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.0063,0.029,0.0063,-0.0046,0.017,-1.1e-05,-6.1e-05,3.1e-06,3.9e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.3e-06,0.00018,0.00018,9.6e-05,0.04,0.04,0.0072,0.046,0.046,0.035,2e-09,2e-09,1.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15690000,0.98,-0.0077,-0.011,0.19,0.01,-0.0093,0.029,0.0072,-0.0054,0.018,-1.1e-05,-6.1e-05,3.4e-06,4e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.3e-06,0.00018,0.00018,9.6e-05,0.044,0.045,0.0073,0.053,0.053,0.034,2e-09,2e-09,1.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15790000,0.98,-0.0077,-0.011,0.19,0.0067,-0.0087,0.029,0.0055,-0.0042,0.02,-1.1e-05,-6.1e-05,4e-06,3.8e-05,3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.3e-06,0.00018,0.00017,9.5e-05,0.039,0.039,0.0073,0.046,0.046,0.034,1.8e-09,1.8e-09,1.2e-09,3.3e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15890000,0.98,-0.0077,-0.011,0.19,0.0056,-0.0071,0.03,0.0062,-0.005,0.02,-1.1e-05,-6.1e-05,3.6e-06,4.1e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.3e-06,0.00018,0.00018,9.5e-05,0.044,0.044,0.0074,0.053,0.053,0.034,1.8e-09,1.8e-09,1.2e-09,3.3e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15990000,0.98,-0.0075,-0.011,0.19,0.0035,-0.0057,0.027,0.0049,-0.0038,0.019,-1.2e-05,-6.1e-05,3.6e-06,4.2e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00017,0.00017,9.4e-05,0.038,0.038,0.0074,0.046,0.046,0.034,1.7e-09,1.7e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16090000,0.98,-0.0075,-0.011,0.19,0.0029,-0.0069,0.024,0.0051,-0.0045,0.019,-1.2e-05,-6.1e-05,3.4e-06,4.4e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00018,0.00017,9.4e-05,0.043,0.043,0.0076,0.053,0.053,0.034,1.7e-09,1.7e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16190000,0.98,-0.0074,-0.011,0.19,-0.001,-0.0046,0.023,0.0028,-0.0033,0.016,-1.2e-05,-6.1e-05,3.1e-06,4.5e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00017,0.00017,9.4e-05,0.038,0.038,0.0076,0.046,0.046,0.034,1.5e-09,1.5e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16290000,0.98,-0.0075,-0.011,0.19,-0.00067,-0.0061,0.023,0.0027,-0.0039,0.017,-1.2e-05,-6.1e-05,3.3e-06,4.5e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.5e-09,1.5e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16390000,0.98,-0.0074,-0.011,0.19,0.0018,-0.0055,0.023,0.0037,-0.0029,0.017,-1.2e-05,-6.1e-05,3.6e-06,5.1e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00016,0.00016,9.2e-05,0.037,0.038,0.0077,0.046,0.046,0.034,1.4e-09,1.4e-09,1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16490000,0.98,-0.0075,-0.011,0.19,0.0037,-0.007,0.026,0.0039,-0.0036,0.021,-1.2e-05,-6.1e-05,3.5e-06,5e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00017,0.00017,9.2e-05,0.042,0.042,0.0079,0.052,0.053,0.034,1.4e-09,1.4e-09,1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16590000,0.98,-0.0075,-0.011,0.19,0.0078,-0.0071,0.029,0.0034,-0.0028,0.021,-1.2e-05,-6.1e-05,3.5e-06,5.1e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.1e-06,0.00016,0.00016,9.2e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16690000,0.98,-0.0076,-0.011,0.19,0.0093,-0.012,0.029,0.0043,-0.0037,0.022,-1.2e-05,-6.1e-05,3.7e-06,5.2e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.1e-06,0.00016,0.00016,9.1e-05,0.041,0.041,0.008,0.052,0.052,0.034,1.3e-09,1.3e-09,9.8e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16790000,0.98,-0.0074,-0.011,0.19,0.01,-0.011,0.028,0.0033,-0.0027,0.022,-1.2e-05,-6.1e-05,3.8e-06,5.3e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.1e-06,0.00016,0.00015,9.1e-05,0.036,0.036,0.008,0.046,0.046,0.034,1.2e-09,1.2e-09,9.6e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16890000,0.98,-0.0074,-0.011,0.19,0.0092,-0.011,0.029,0.0043,-0.0037,0.02,-1.2e-05,-6.1e-05,4.2e-06,5.6e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.1e-06,0.00016,0.00016,9e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-09,1.2e-09,9.3e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16990000,0.98,-0.0074,-0.011,0.19,0.0088,-0.01,0.029,0.0041,-0.0028,0.019,-1.3e-05,-6.1e-05,4.3e-06,6.2e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8e-06,0.00015,0.00015,9e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-09,1.1e-09,9.1e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.0051,-0.004,0.018,-1.2e-05,-6.1e-05,4.2e-06,6.4e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8e-06,0.00015,0.00015,8.9e-05,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-09,1.1e-09,8.9e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17190000,0.98,-0.0076,-0.011,0.19,0.0092,-0.018,0.03,0.0034,-0.0075,0.021,-1.2e-05,-6.1e-05,3.8e-06,6.2e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8e-06,0.00015,0.00015,8.9e-05,0.035,0.035,0.0083,0.046,0.046,0.034,9.7e-10,9.7e-10,8.8e-10,3.1e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17290000,0.98,-0.0076,-0.011,0.19,0.01,-0.019,0.03,0.0044,-0.0093,0.021,-1.2e-05,-6.1e-05,3.5e-06,6.5e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8e-06,0.00015,0.00015,8.8e-05,0.039,0.039,0.0084,0.052,0.052,0.034,9.7e-10,9.7e-10,8.6e-10,3.1e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17390000,0.98,-0.0074,-0.011,0.19,0.0069,-0.018,0.029,0.0058,-0.0059,0.021,-1.3e-05,-6e-05,3.8e-06,7.3e-05,2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8e-06,0.00014,0.00014,8.8e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.8e-10,8.8e-10,8.4e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17490000,0.98,-0.0075,-0.011,0.19,0.005,-0.019,0.029,0.0063,-0.0077,0.022,-1.3e-05,-6e-05,3.6e-06,7.3e-05,2.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8e-06,0.00015,0.00014,8.8e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.8e-10,8.8e-10,8.2e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17590000,0.98,-0.0073,-0.011,0.19,0.0011,-0.015,0.028,0.0025,-0.0058,0.02,-1.3e-05,-6.1e-05,3.6e-06,7.2e-05,3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.9e-06,0.00014,0.00014,8.7e-05,0.034,0.034,0.0085,0.046,0.046,0.034,7.9e-10,7.9e-10,8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17690000,0.98,-0.0074,-0.011,0.19,0.00022,-0.016,0.029,0.0026,-0.0073,0.022,-1.3e-05,-6.1e-05,3.7e-06,7.3e-05,3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.9e-06,0.00014,0.00014,8.6e-05,0.038,0.038,0.0086,0.052,0.052,0.034,7.9e-10,7.9e-10,7.9e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17790000,0.98,-0.0074,-0.011,0.19,0.0028,-0.014,0.029,0.0036,-0.0062,0.028,-1.4e-05,-6e-05,3.7e-06,7.6e-05,3.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.9e-06,0.00014,0.00013,8.6e-05,0.033,0.033,0.0086,0.045,0.045,0.034,7.2e-10,7.2e-10,7.7e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17890000,0.98,-0.0073,-0.011,0.19,0.005,-0.016,0.029,0.004,-0.0077,0.032,-1.4e-05,-6e-05,3.8e-06,7.5e-05,4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.9e-06,0.00014,0.00014,8.6e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.2e-10,7.2e-10,7.6e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17990000,0.98,-0.0071,-0.011,0.19,0.0043,-0.0093,0.029,0.0032,-0.002,0.033,-1.4e-05,-6e-05,3.8e-06,7.9e-05,5.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.9e-06,0.00013,0.00013,8.5e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.5e-10,6.5e-10,7.4e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
18090000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0098,0.028,0.0037,-0.003,0.031,-1.4e-05,-6e-05,3.7e-06,8.2e-05,4.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.8e-06,0.00013,0.00013,8.5e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6.5e-10,6.5e-10,7.3e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
18190000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0088,0.028,0.0042,-0.0022,0.029,-1.4e-05,-6e-05,4.1e-06,8.8e-05,4.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.8e-06,0.00013,0.00013,8.4e-05,0.032,0.032,0.0086,0.045,0.045,0.035,5.9e-10,5.9e-10,7.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18290000,0.98,-0.0072,-0.011,0.19,0.0048,-0.0093,0.027,0.0046,-0.0031,0.027,-1.4e-05,-6e-05,4.1e-06,9e-05,4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.8e-06,0.00013,0.00013,8.4e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.9e-10,5.9e-10,6.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18390000,0.98,-0.0071,-0.011,0.19,0.0057,-0.008,0.027,0.0062,-0.0023,0.026,-1.4e-05,-6e-05,4e-06,9.6e-05,4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.8e-06,0.00012,0.00012,8.3e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.3e-10,5.3e-10,6.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18490000,0.98,-0.0072,-0.011,0.19,0.0084,-0.008,0.026,0.007,-0.0031,0.028,-1.4e-05,-6e-05,4.1e-06,9.7e-05,4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.8e-06,0.00013,0.00013,8.3e-05,0.034,0.034,0.0087,0.051,0.051,0.035,5.3e-10,5.3e-10,6.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18590000,0.98,-0.007,-0.011,0.19,0.0068,-0.0074,0.026,0.0056,-0.0024,0.03,-1.5e-05,-6e-05,3.9e-06,9.5e-05,4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.8e-06,0.00012,0.00012,8.2e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.8e-10,4.8e-10,6.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18690000,0.98,-0.007,-0.011,0.19,0.0069,-0.0063,0.024,0.0063,-0.0031,0.029,-1.5e-05,-6e-05,4e-06,9.8e-05,4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00012,0.00012,8.2e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.8e-10,4.8e-10,6.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18790000,0.98,-0.007,-0.011,0.19,0.0058,-0.006,0.024,0.0063,-0.0025,0.027,-1.5e-05,-6e-05,4e-06,0.0001,4.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00012,0.00012,8.2e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-10,4.4e-10,6.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18890000,0.98,-0.0069,-0.011,0.19,0.0045,-0.0056,0.021,0.0068,-0.0032,0.023,-1.5e-05,-6e-05,3.8e-06,0.0001,4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00012,0.00012,8.1e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-10,4.4e-10,6.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18990000,0.98,-0.0069,-0.011,0.19,0.0029,-0.0057,0.022,0.0056,-0.0025,0.026,-1.5e-05,-6e-05,3.8e-06,0.0001,4.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00012,0.00011,8.1e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-10,4e-10,6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19090000,0.98,-0.007,-0.011,0.19,0.00087,-0.0062,0.023,0.0059,-0.0031,0.022,-1.5e-05,-6e-05,3.9e-06,0.00011,4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00012,0.00012,8e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-10,4e-10,5.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19190000,0.98,-0.0069,-0.011,0.19,-0.00064,-0.0059,0.022,0.0049,-0.0025,0.021,-1.5e-05,-6e-05,3.5e-06,0.00011,4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00011,0.00011,8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.6e-10,3.6e-10,5.8e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19290000,0.98,-0.0068,-0.011,0.19,-0.0015,-0.0057,0.023,0.0048,-0.0031,0.02,-1.5e-05,-6e-05,3.4e-06,0.00011,4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00011,0.00011,7.9e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.6e-10,3.6e-10,5.7e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19390000,0.98,-0.0069,-0.011,0.19,-0.002,-0.0022,0.024,0.0041,-0.0012,0.019,-1.5e-05,-6e-05,3.3e-06,0.00011,4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00011,0.00011,7.9e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-10,3.3e-10,5.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19490000,0.98,-0.0069,-0.011,0.19,-0.0028,-0.0022,0.023,0.0039,-0.0014,0.019,-1.5e-05,-6e-05,3e-06,0.00011,4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00011,0.00011,7.9e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-10,3.3e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19590000,0.98,-0.0069,-0.011,0.19,-0.0039,-0.0051,0.025,0.0044,-0.0024,0.019,-1.5e-05,-6e-05,2.9e-06,0.00012,3.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00011,0.00011,7.8e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-10,3e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19690000,0.98,-0.0069,-0.011,0.19,-0.0055,-0.0037,0.023,0.004,-0.0028,0.018,-1.5e-05,-6e-05,3.1e-06,0.00012,3.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00011,0.00011,7.8e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-10,3e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19790000,0.98,-0.007,-0.011,0.19,-0.0056,-0.0022,0.022,0.0064,-0.0023,0.014,-1.5e-05,-6e-05,2.8e-06,0.00012,3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00011,0.0001,7.7e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-10,2.8e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.98,-0.007,-0.011,0.19,-0.0056,-0.002,0.022,0.0058,-0.0025,0.013,-1.5e-05,-6e-05,2.7e-06,0.00013,3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.00011,0.00011,7.7e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.98,-0.0071,-0.011,0.19,-0.0053,-0.0019,0.019,0.0062,-0.00091,0.0096,-1.5e-05,-5.9e-05,2.8e-06,0.00013,3.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.0001,0.0001,7.6e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-10,2.5e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.98,-0.0071,-0.011,0.19,-0.0048,-0.0041,0.019,0.0056,-0.0012,0.013,-1.5e-05,-5.9e-05,2.7e-06,0.00013,3.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.00011,0.0001,7.6e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-10,2.5e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.98,-0.0071,-0.011,0.19,-0.0038,-0.0016,0.02,0.0066,-0.0009,0.013,-1.5e-05,-5.9e-05,2.5e-06,0.00013,3.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.0001,0.0001,7.6e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.98,-0.007,-0.011,0.19,-0.007,-0.0027,0.02,0.0061,-0.0011,0.013,-1.5e-05,-5.9e-05,2.4e-06,0.00013,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.98,-0.007,-0.011,0.19,-0.0077,-0.0015,0.021,0.0069,-0.00077,0.014,-1.5e-05,-5.9e-05,2.5e-06,0.00014,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.0001,9.9e-05,7.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-10,2.1e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.006,-0.00095,0.012,-1.5e-05,-5.9e-05,2.5e-06,0.00014,2.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.0001,0.0001,7.4e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-10,2.1e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.007,-0.00079,0.011,-1.5e-05,-5.9e-05,2.7e-06,0.00014,2.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,9.9e-05,9.8e-05,7.4e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0022,0.021,0.0058,-0.001,0.011,-1.5e-05,-5.9e-05,2.5e-06,0.00014,2.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,0.0001,9.9e-05,7.4e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00041,0.0055,0.0049,-0.00081,0.0096,-1.5e-05,-5.9e-05,2.6e-06,0.00014,2.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,9.8e-05,9.6e-05,7.3e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-10,1.8e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.98,0.0028,-0.0073,0.19,-0.021,0.012,-0.11,0.003,-0.00013,0.0033,-1.5e-05,-5.9e-05,2.5e-06,0.00015,2.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,9.8e-05,9.7e-05,7.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0023,0.00052,-0.011,-1.5e-05,-5.9e-05,2.5e-06,0.00015,2.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,9.6e-05,9.5e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0016,0.0044,-0.042,-1.5e-05,-5.9e-05,2.5e-06,0.00014,2.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,9.7e-05,9.5e-05,7.2e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-10,1.7e-10,4.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.98,0.0017,-0.0058,0.19,-0.049,0.05,-0.5,-0.0012,0.0035,-0.078,-1.4e-05,-5.9e-05,2.5e-06,0.00014,1.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,9.5e-05,9.3e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.5e-10,1.5e-10,4e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.98,-0.00049,-0.0072,0.19,-0.049,0.054,-0.63,-0.0061,0.0087,-0.14,-1.4e-05,-5.9e-05,2.2e-06,0.00015,1.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,9.5e-05,9.4e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.5e-10,1.5e-10,3.9e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-1.4e-05,-5.9e-05,2.2e-06,0.00015,1.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,9.3e-05,9.1e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0092,0.016,-0.29,-1.4e-05,-5.9e-05,2.3e-06,0.00015,1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,9.3e-05,9.2e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.0079,0.016,-0.38,-1.4e-05,-5.9e-05,2.4e-06,0.00015,1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,9.1e-05,9e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-1.4e-05,-5.9e-05,2.6e-06,0.00015,9.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,9.1e-05,9e-05,7e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0037,0.018,-0.61,-1.4e-05,-5.8e-05,2.7e-06,0.00016,6.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,8.9e-05,8.8e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.75,-1.4e-05,-5.8e-05,2.6e-06,0.00016,5.6e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,8.9e-05,8.8e-05,6.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00032,0.017,-0.89,-1.4e-05,-5.8e-05,2.7e-06,0.00015,7.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,8.7e-05,8.6e-05,6.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-10,1.1e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0016,0.019,-1,-1.4e-05,-5.8e-05,2.9e-06,0.00016,6.6e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,8.7e-05,8.6e-05,6.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-10,1.1e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.0061,0.013,-1.2,-1.4e-05,-5.8e-05,3e-06,0.00016,6.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.5e-05,8.4e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.98,-0.0069,-0.01,0.19,0.0017,0.0078,-1.4,0.006,0.014,-1.3,-1.4e-05,-5.8e-05,2.9e-06,0.00016,5.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.6e-05,8.4e-05,6.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-10,1.1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.98,-0.0072,-0.01,0.19,0.0067,-0.0018,-1.4,0.013,0.0042,-1.5,-1.4e-05,-5.8e-05,2.7e-06,0.00016,2.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.4e-05,8.3e-05,6.8e-05,0.021,0.021,0.0081,0.042,0.043,0.036,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0036,-1.6,-1.4e-05,-5.8e-05,2.6e-06,0.00016,1.4e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.4e-05,8.3e-05,6.7e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-10,1e-10,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-3.6e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.2e-05,8.1e-05,6.7e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-1.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.3e-05,8.2e-05,6.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.4e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.5e-06,0.00016,-2.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.1e-05,8e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.8e-11,8.9e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-3.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,8.1e-05,8e-05,6.6e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,2.8e-06,0.00016,-4.4e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,8e-05,7.9e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-1.4e-05,-5.8e-05,2.8e-06,0.00016,-4.7e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,8e-05,7.9e-05,6.5e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-11,8.4e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-1.4e-05,-5.8e-05,2.7e-06,0.00017,-6.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,7.9e-05,7.8e-05,6.5e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-11,7.9e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-1.4e-05,-5.8e-05,2.7e-06,0.00017,-6.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,7.9e-05,7.8e-05,6.5e-05,0.019,0.02,0.0081,0.046,0.046,0.036,7.9e-11,7.9e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-1.4e-05,-5.8e-05,2.5e-06,0.00017,-4.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,7.8e-05,7.7e-05,6.4e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-11,7.5e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.98,-0.0079,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-1.4e-05,-5.8e-05,2.7e-06,0.00017,-4.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,7.9e-05,7.7e-05,6.4e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.5e-11,7.5e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-1.4e-05,-5.8e-05,2.7e-06,0.00017,-5.7e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.8e-05,7.7e-05,6.4e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-11,7.2e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-1.4e-05,-5.8e-05,2.8e-06,0.00017,-5.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.8e-05,7.7e-05,6.3e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-11,7.2e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-1.4e-05,-5.8e-05,3e-06,0.00017,-5.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.8e-11,6.8e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.98,-0.014,-0.021,0.18,0.053,-0.059,-0.52,0.12,-0.087,-3.5,-1.4e-05,-5.8e-05,3e-06,0.00017,-6e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.3e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-11,6.9e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.13,-0.089,-3.6,-1.4e-05,-5.8e-05,3e-06,0.00018,-1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.3e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.98,-0.016,-0.023,0.18,0.061,-0.066,0.09,0.13,-0.095,-3.6,-1.4e-05,-5.8e-05,2.9e-06,0.00018,-1.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-11,6.6e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.98,-0.013,-0.019,0.18,0.072,-0.071,0.077,0.14,-0.1,-3.6,-1.4e-05,-5.8e-05,2.9e-06,0.00019,-1.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-11,6.3e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-1.4e-05,-5.8e-05,2.9e-06,0.00019,-1.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-1.4e-05,-5.8e-05,3.1e-06,0.00019,-2.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-1.4e-05,-5.8e-05,3.3e-06,0.00019,-2.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,7e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.035,6.1e-11,6.1e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-1.4e-05,-5.8e-05,3.3e-06,0.00019,-3.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.98,-0.011,-0.014,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-1.4e-05,-5.8e-05,3.3e-06,0.00019,-3.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-3.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.7e-05,7.6e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-1.5e-05,-5.8e-05,3.4e-06,0.00019,-3.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.7e-05,7.6e-05,6e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3.4e-06,0.00019,-4.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.7e-05,7.6e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-4.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.8e-05,7.6e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3.2e-06,0.00019,-5.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.8e-05,7.6e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3.1e-06,0.00019,-5.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-1.5e-05,-5.8e-05,3.1e-06,0.00018,-5.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.8e-05,7.7e-05,5.9e-05,0.014,0.015,0.008,0.039,0.039,0.035,5.1e-11,5.1e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3e-06,0.00019,-5.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.8e-05,7.7e-05,5.8e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-11,5.1e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.98,-0.011,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-1.5e-05,-5.8e-05,2.9e-06,0.00018,-6.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-1.5e-05,-5.8e-05,2.9e-06,0.00018,-6.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.8e-05,7.7e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-1.6e-05,-5.8e-05,2.8e-06,0.00018,-6.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.98,-0.011,-0.011,0.19,-0.0036,-0.029,0.019,0.17,-0.096,-3.6,-1.6e-05,-5.8e-05,2.6e-06,0.00019,-6.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.8e-05,7.7e-05,5.7e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-7.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.8e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.022,0.011,0.16,-0.088,-3.6,-1.6e-05,-5.8e-05,2.6e-06,0.00019,-7.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.9e-05,7.7e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-1.6e-05,-5.8e-05,2.6e-06,0.00019,-7.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.8e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.014,0.00052,0.15,-0.083,-3.6,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-7.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.9e-05,7.7e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.98,-0.0098,-0.012,0.18,-0.031,-0.0065,0.0045,0.13,-0.075,-3.6,-1.6e-05,-5.8e-05,2.4e-06,0.00019,-7.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.9e-05,7.7e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0033,0.014,0.13,-0.075,-3.6,-1.6e-05,-5.8e-05,2.3e-06,0.00019,-7.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-11,4.5e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0046,0.014,0.12,-0.068,-3.6,-1.6e-05,-5.8e-05,2.2e-06,0.00019,-7.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,7.9e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0097,0.013,0.12,-0.067,-3.6,-1.6e-05,-5.8e-05,2e-06,0.00019,-7.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.6,-1.6e-05,-5.8e-05,1.9e-06,0.00019,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.98,-0.008,-0.011,0.18,-0.051,0.016,0.007,0.1,-0.06,-3.6,-1.6e-05,-5.8e-05,1.9e-06,0.00019,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-11,4.2e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-1.6e-05,-5.8e-05,1.8e-06,0.00019,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-11,4.1e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-1.6e-05,-5.8e-05,1.8e-06,0.0002,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-11,4.1e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.035,0.011,0.071,-0.046,-3.6,-1.6e-05,-5.8e-05,1.7e-06,0.0002,-8.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.4e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.98,-0.0075,-0.013,0.18,-0.073,0.041,0.12,0.064,-0.042,-3.6,-1.6e-05,-5.8e-05,1.7e-06,0.0002,-8.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.4e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-11,4e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.98,-0.0089,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.0002,-8.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,7.9e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.03,-3.5,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-8.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,8e-05,7.8e-05,5.4e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,8e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.98,-0.0089,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-9.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.05,0.75,0.025,-0.018,-3.3,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-8.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.98,-0.0072,-0.012,0.18,-0.078,0.057,0.79,0.018,-0.012,-3.2,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-8.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0048,-3,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0022,-0.0043,-3,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-7.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0014,-2.9,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.061,0.79,-0.015,0.0044,-2.8,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-7.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.8,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-11,3.6e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.98,-0.0072,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0084,-2.7,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-7.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.98,-0.007,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.0002,-7.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-7.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.5,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.4,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.2e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.4e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.98,-0.006,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.033,-2.2,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-8.4e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-8.6e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-1.5e-05,-5.8e-05,1.6e-06,0.0002,-8.6e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-1.5e-05,-5.8e-05,1.7e-06,0.0002,-8.8e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.98,-0.0064,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-1.5e-05,-5.8e-05,1.7e-06,0.0002,-9e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.98,-0.0063,-0.013,0.18,-0.074,0.056,0.78,-0.065,0.044,-1.8,-1.4e-05,-5.8e-05,1.8e-06,0.0002,-9.2e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.98,-0.0057,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-1.4e-05,-5.8e-05,1.9e-06,0.0002,-9.4e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-1.4e-05,-5.8e-05,1.9e-06,0.00021,-9.8e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30090000,0.98,-0.006,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-1.4e-05,-5.8e-05,1.8e-06,0.00021,-9.9e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-1.4e-05,-5.7e-05,1.6e-06,0.00021,-0.0001,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30290000,0.98,-0.006,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-1.4e-05,-5.7e-05,1.7e-06,0.00021,-0.0001,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-1.4e-05,-5.7e-05,1.8e-06,0.00021,-0.00011,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30490000,0.98,-0.006,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-1.4e-05,-5.7e-05,1.8e-06,0.00021,-0.00011,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00011,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00011,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.98,-0.0064,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.98,-0.0061,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.86,-1.4e-05,-5.7e-05,1.8e-06,0.00023,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.98,-0.0063,-0.013,0.19,-0.031,0.021,0.76,-0.052,0.046,-0.79,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-1.4e-05,-5.7e-05,2e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31390000,0.98,-0.0063,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8.1e-05,7.9e-05,4.6e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.58,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8.1e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.98,-0.0059,-0.014,0.18,-0.018,0.0068,0.76,-0.038,0.039,-0.51,-1.4e-05,-5.7e-05,2e-06,0.00024,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.98,-0.0059,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.44,-1.4e-05,-5.7e-05,2.1e-06,0.00024,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8.1e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.0031,0.76,-0.028,0.037,-0.36,-1.4e-05,-5.7e-05,2.1e-06,0.00024,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.00082,0.76,-0.029,0.038,-0.3,-1.4e-05,-5.7e-05,2.2e-06,0.00024,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.98,-0.0061,-0.015,0.18,-0.0001,0.00016,0.75,-0.017,0.034,-0.23,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.98,-0.0065,-0.014,0.18,-0.00064,-0.0032,0.76,-0.017,0.034,-0.16,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.98,-0.0067,-0.015,0.18,0.0047,-0.0065,0.76,-0.006,0.033,-0.092,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.5e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0091,0.75,-0.0055,0.032,-0.024,-1.3e-05,-5.7e-05,2.2e-06,0.00025,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,9.7e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.98,-0.0067,-0.015,0.18,0.013,-0.01,0.75,0.0057,0.03,0.051,-1.3e-05,-5.7e-05,2.1e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.8e-05,4.5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-11,2.7e-11,9.7e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.054,-1.3e-05,-5.7e-05,2.1e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,8e-05,7.9e-05,4.5e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-11,2.8e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.074,-0.12,0.021,0.02,0.035,-1.4e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,7.9e-05,7.7e-05,4.5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-11,2.7e-11,9.5e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-1.4e-05,-5.7e-05,2.1e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,7.9e-05,7.8e-05,4.5e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-11,2.7e-11,9.4e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.0042,-1.4e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,7.6e-05,7.5e-05,4.4e-05,0.019,0.019,0.0071,0.037,0.037,0.035,2.7e-11,2.7e-11,9.3e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.98,-0.0091,-0.013,0.18,0.033,-0.084,-0.13,0.038,0.0021,-0.011,-1.4e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,7.6e-05,7.5e-05,4.4e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-11,2.7e-11,9.2e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0011,-0.024,-1.4e-05,-5.6e-05,2.3e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,7.2e-05,7.1e-05,4.4e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-11,2.7e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0092,-0.031,-1.4e-05,-5.6e-05,2.3e-06,0.00026,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,7.2e-05,7.1e-05,4.4e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-11,2.7e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-1.4e-05,-5.6e-05,2.2e-06,0.00026,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,6.6e-05,6.6e-05,4.4e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-11,2.6e-11,9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-1.4e-05,-5.6e-05,2.3e-06,0.00026,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,6.7e-05,6.6e-05,4.4e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-11,2.6e-11,8.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-1.4e-05,-5.6e-05,2.3e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,6e-05,5.9e-05,4.4e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-11,2.6e-11,8.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-1.4e-05,-5.6e-05,2.3e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,6e-05,5.9e-05,4.3e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-11,2.6e-11,8.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.069,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,5.3e-05,5.2e-05,4.3e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-11,2.6e-11,8.7e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.98,-0.0077,-0.013,0.18,0.00085,-0.058,-0.11,0.063,-0.023,-0.077,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,5.3e-05,5.2e-05,4.3e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-11,2.6e-11,8.6e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33790000,0.98,-0.0075,-0.013,0.18,-0.0023,-0.048,-0.11,0.067,-0.018,-0.083,-1.4e-05,-5.6e-05,2.3e-06,0.00023,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,4.6e-05,4.6e-05,4.3e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33890000,0.98,-0.0075,-0.013,0.18,-0.0065,-0.046,-0.11,0.066,-0.023,-0.09,-1.4e-05,-5.6e-05,2.4e-06,0.00023,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,4.7e-05,4.6e-05,4.3e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-11,2.6e-11,8.5e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00024,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,4.1e-05,4.1e-05,4.3e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-11,2.6e-11,8.4e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00024,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,4.1e-05,4.1e-05,4.3e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-11,2.6e-11,8.4e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.021,-0.098,0.072,-0.013,-0.099,-1.4e-05,-5.6e-05,2.3e-06,0.00019,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,3.7e-05,3.6e-05,4.3e-05,0.047,0.048,0.0058,0.043,0.043,0.033,2.6e-11,2.6e-11,8.3e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-1.4e-05,-5.6e-05,2.3e-06,0.00019,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,3.7e-05,3.6e-05,4.2e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-11,2.6e-11,8.2e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.073,-0.01,-0.11,-1.4e-05,-5.6e-05,2.3e-06,0.00018,-0.00027,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,3.3e-05,3.3e-05,4.2e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-11,2.6e-11,8.2e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0096,-0.09,0.071,-0.011,-0.11,-1.4e-05,-5.6e-05,2.3e-06,0.00017,-0.00027,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,3.3e-05,3.3e-05,4.2e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-11,2.6e-11,8.1e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0053,0.71,0.073,-0.0089,-0.081,-1.4e-05,-5.6e-05,2.3e-06,0.00016,-0.00027,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,3.1e-05,3e-05,4.2e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-11,2.6e-11,8e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0032,1.7,0.071,-0.0093,0.037,-1.4e-05,-5.6e-05,2.3e-06,0.00016,-0.00027,-0.0011,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,3.1e-05,3.1e-05,4.2e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-11,2.6e-11,8e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34790000,0.98,-0.0068,-0.012,0.18,-0.018,0.0015,2.7,0.072,-0.0069,0.21,-1.4e-05,-5.6e-05,2.2e-06,0.00018,-0.00029,-0.001,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,2.9e-05,2.9e-05,4.2e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-11,2.6e-11,7.9e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0039,3.6,0.07,-0.0065,0.5,-1.4e-05,-5.6e-05,2.2e-06,0.00018,-0.00029,-0.001,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,2.9e-05,2.9e-05,4.2e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-11,2.6e-11,7.8e-11,2e-06,2e-06,5e-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 10000 1 -0.0099 -0.011 -0.011 -0.01 -0.0001 0.00012 0 0.00033 0 -0.00013 0 -0.01 0 1e-05 0 -3.9e-06 0 -0.00042 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5.8e-07 0 0.0025 0 0.0025 0 0.0018 0 25 0 25 0 10 0 1e+02 0 1e+02 0 1e+02 0 1e-06 0 1e-06 0 1e-06 0 4e-06 0 4e-06 0 4e-06 0 0 0 0 0 0 0 0
3 90000 0.98 -0.0093 -0.0095 -0.012 0.18 1.9e-05 -5.5e-05 -0.0025 -0.0032 -0.0087 -0.024 -1.3e-05 -3.6e-06 -9.5e-05 -0.00014 -0.00027 -0.0021 0 0 0 0 0 0 0.2 -6.1e-09 9.3e-09 0.43 0 0 0 0 0 6.5e-05 8.9e-07 0.0025 0.0026 0.0025 0.0026 0.002 0.0011 25 25 10 1e+02 1e+02 1e+02 1e-06 1e-06 1e-06 9.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
4 190000 0.98 -0.0093 -0.0092 -0.012 -0.013 0.18 0.2 -0.0017 -0.0013 -0.0025 -0.0036 -0.021 -0.037 -7.1e-05 -4.4e-05 -0.00033 -0.00046 0.034 -0.017 8e-13 5.2e-12 -3.2e-12 -4.3e-12 -6.8e-14 -1.5e-13 0 0 -2.7e-10 -6.8e-10 0.2 -6.1e-09 0.011 0.43 0 0 0 0 0 3.7e-05 2.8e-06 0.0025 0.0027 0.0025 0.0027 0.0011 0.00081 25 25 10 1e+02 1e+02 1.3 1 1e-06 1e-06 9.9e-07 9.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
5 290000 0.98 -0.0094 -0.0092 -0.013 0.18 0.2 -0.0026 -0.0016 -0.0038 -0.0053 -0.029 -0.046 -0.00015 -0.00018 -0.00032 0.037 -0.018 1.1e-11 4.4e-11 -3.9e-11 -5.4e-11 -9.2e-13 -2.6e-12 0 0 -2.7e-08 -2.9e-08 0.2 -6.1e-09 0.011 0.43 0 0 0 0 0 2.7e-05 6.6e-06 0.0027 0.0029 0.0027 0.0029 0.00081 0.00068 25 25 9.6 0.31 0.37 0.31 0.37 0.44 0.41 1e-06 1e-06 9.8e-07 9.4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
6 390000 0.98 -0.0094 -0.0095 -0.013 0.18 0.19 -0.0018 -0.00033 -0.0047 -0.0065 -0.049 -0.063 -0.00041 -0.00029 -0.00057 -0.00087 0.044 -0.013 -2.7e-11 -6.7e-11 -4.6e-12 -6.3e-11 -2.8e-13 3e-12 0 0 1e-07 8.8e-08 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2.2e-05 1.1e-05 0.0028 0.0031 0.0028 0.0031 0.00067 0.00062 25 25 8.3 8.1 0.81 0.97 0.81 0.97 0.32 1e-06 1e-06 9.5e-07 8.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
7 490000 0.98 -0.0094 -0.0095 -0.013 -0.014 0.18 0.19 0.00035 0.0016 -0.0048 -0.0061 -0.06 -0.069 -7.5e-05 2.4e-05 -0.00031 -0.00049 0.046 -0.011 -4.7e-09 -1.2e-08 5.3e-09 6.5e-09 1.4e-10 2.1e-10 0 0 2e-07 1.6e-07 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 1.7e-05 0.003 0.0034 0.003 0.0033 0.00061 0.00059 7.8 7.8 6.2 5.9 0.29 0.34 0.29 0.34 0.31 1e-06 1e-06 9e-07 8.2e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
8 590000 0.98 -0.0095 -0.014 0.18 0.19 -0.00033 0.0014 -0.0075 -0.0091 -0.11 -0.12 -6.5e-05 0.00018 -0.00095 -0.0013 0.027 -0.03 -5.5e-09 -1.4e-08 5.5e-09 6.7e-09 1.6e-10 2.5e-10 0 0 7e-07 6.4e-07 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.9e-05 2.2e-05 0.0033 0.0037 0.0033 0.0037 0.00058 7.9 7.9 4.4 4.2 0.59 0.67 0.59 0.67 0.32 1e-06 1e-06 8.4e-07 7.5e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
9 690000 0.98 -0.0095 -0.0096 -0.014 0.18 0.19 0.0017 0.0032 -0.0068 -0.0083 -0.045 -0.05 4e-05 0.00021 -0.00052 -0.00076 0.048 -0.0089 -3.2e-08 -5.6e-08 1.6e-08 1.3e-08 6.6e-10 3.3e-10 0 0 -8.1e-07 -9.5e-07 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.9e-05 2.7e-05 0.0036 0.004 0.0036 0.004 0.00057 2.6 2.7 2.6 2.7 2.9 2.8 0.23 0.26 0.23 0.26 0.3 0.29 1e-06 1e-06 7.7e-07 6.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
10 790000 0.98 -0.0095 -0.0096 -0.014 0.18 0.19 0.0039 0.0059 -0.0073 -0.009 -0.05 -0.054 0.00025 0.0006 -0.0012 -0.0016 0.045 -0.011 -3.1e-08 -5.5e-08 1.6e-08 1.3e-08 6.3e-10 2.7e-10 0 0 -1.1e-06 -1.3e-06 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.9e-05 3.2e-05 0.0039 0.0044 0.0039 0.0044 0.00057 2.7 2.8 2.7 2.8 2 1.9 0.38 0.42 0.38 0.42 0.27 1e-06 1e-06 6.9e-07 5.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
11 890000 0.98 -0.0095 -0.0096 -0.014 -0.015 0.18 0.19 0.0041 0.006 -0.0053 -0.0068 -0.091 -0.093 0.00025 0.00052 -0.00067 -0.00095 0.025 -0.031 -1.4e-07 -2.2e-07 2.2e-08 1.8e-09 4.5e-09 4.8e-09 0 0 -1.3e-07 -3.3e-07 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 3.5e-05 0.0043 0.0048 0.0043 0.0048 0.00057 0.00056 1.3 1.3 1.4 1.3 0.19 0.2 0.19 0.2 0.26 0.25 1e-06 9.9e-07 1e-06 6.1e-07 5.2e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
12 990000 0.98 -0.0095 -0.0096 -0.015 0.18 0.19 0.0067 0.0091 -0.0053 -0.0071 -0.11 -0.12 0.00082 0.0013 -0.0012 -0.0017 0.0098 -0.046 -1.4e-07 -2.2e-07 2.2e-08 1.4e-09 4.6e-09 4.9e-09 0 0 3.6e-07 1.3e-07 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 3.8e-05 0.0047 0.0053 0.0047 0.0053 0.00057 0.00055 1.4 1.5 1.4 1.5 0.99 0.95 0.28 0.3 0.28 0.3 0.23 1e-06 9.9e-07 1e-06 9.9e-07 5.3e-07 4.5e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
13 1090000 0.98 -0.0096 -0.015 0.18 0.19 0.013 0.015 -0.0068 -0.0083 -0.13 0.00079 0.0012 -0.00077 -0.0011 -0.0066 -0.063 -4.1e-07 -6.1e-07 -9.4e-08 -1.7e-07 1.8e-08 2.1e-08 0 0 7e-07 4.4e-07 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 4.1e-05 0.0051 0.0057 0.0051 0.0057 0.00056 0.00054 0.85 0.92 0.86 0.92 0.72 0.69 0.16 0.17 0.16 0.17 0.21 0.2 9.9e-07 9.8e-07 9.9e-07 9.8e-07 4.6e-07 3.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
14 1190000 0.98 -0.0095 -0.0096 -0.015 0.18 0.19 0.018 0.021 -0.0095 -0.011 -0.1 -0.11 0.0023 0.003 -0.0016 -0.0021 0.0096 -0.047 -4e-07 -5.8e-07 -8.1e-08 -1.5e-07 1.7e-08 2e-08 0 0 -4.4e-06 -4.8e-06 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 4.2e-05 0.0056 0.0063 0.0056 0.0063 0.00055 0.00053 1 1.1 1 1.1 0.56 0.54 0.22 0.24 0.22 0.24 0.2 0.19 9.9e-07 9.8e-07 9.9e-07 9.8e-07 4e-07 3.3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
15 1290000 0.98 -0.0093 -0.015 -0.016 0.18 0.19 0.021 0.024 -0.0083 -0.0097 -0.11 0.002 0.0027 -0.0012 -0.0016 0.0086 -0.048 -1.3e-06 -1.7e-06 -7.9e-07 -1e-06 6.7e-08 7.6e-08 0 0 -7e-06 -7.5e-06 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 4.3e-05 0.0058 0.0064 0.0058 0.0064 0.00054 0.00052 0.79 0.88 0.79 0.88 0.43 0.41 0.14 0.15 0.14 0.15 0.18 9.6e-07 9.5e-07 9.6e-07 9.5e-07 3.5e-07 2.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
16 1390000 0.98 -0.0093 -0.016 0.18 0.19 0.03 0.033 -0.011 -0.012 -0.095 -0.097 0.0046 0.0056 -0.0021 -0.0027 0.018 -0.038 -1.2e-06 -1.6e-06 -7.5e-07 -9.6e-07 6.6e-08 7.3e-08 0 0 -1.3e-05 -1.4e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 4.3e-05 0.0064 0.0071 0.0064 0.0071 0.00053 0.0005 1 1.1 1 1.1 0.34 0.33 0.19 0.21 0.19 0.21 0.16 9.6e-07 9.5e-07 9.6e-07 9.5e-07 3e-07 2.5e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
17 1490000 0.98 -0.0093 -0.009 -0.016 0.18 0.19 0.035 0.03 -0.013 -0.01 -0.11 -0.12 0.0079 0.0044 -0.0032 -0.0018 0.0027 -0.053 -1.2e-06 -3.9e-06 -7.6e-07 -3.4e-06 6.6e-08 2e-07 0 0 -1.1e-05 -1.2e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 2e-05 4.3e-05 0.0071 0.0067 0.0071 0.0067 0.00051 0.00048 1.3 0.95 1.3 0.95 0.27 0.28 0.14 0.28 0.14 0.15 9.6e-07 8.8e-07 9.6e-07 8.8e-07 2.6e-07 2.1e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
18 1590000 0.98 -0.0092 -0.0091 -0.016 0.18 0.19 0.035 0.038 -0.011 -0.012 -0.13 0.0067 0.0077 -0.0025 -0.003 -0.007 -0.063 -3.2e-06 -3.9e-06 -2.9e-06 -3.4e-06 1.8e-07 2e-07 0 0 -1.3e-05 -1.4e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.9e-05 4.3e-05 0.0068 0.0074 0.0068 0.0074 0.0005 0.00047 1.1 1.3 1.1 1.3 0.23 0.19 0.2 0.19 0.2 0.14 9.1e-07 8.8e-07 9.1e-07 8.8e-07 2.2e-07 1.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
19 1690000 0.98 -0.0092 -0.0088 -0.016 0.18 0.19 0.043 0.033 -0.012 -0.0083 -0.13 0.011 0.0054 -0.0036 -0.0019 -0.012 -0.068 -3.1e-06 -7.3e-06 -2.8e-06 -7.5e-06 1.8e-07 3.8e-07 0 0 -1.7e-05 -1.8e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.9e-05 4.2e-05 0.0075 0.0064 0.0075 0.0064 0.00048 0.00045 1.5 1 1.5 1 0.19 0.27 0.14 0.27 0.14 0.13 9.1e-07 7.8e-07 9.1e-07 7.8e-07 1.9e-07 1.6e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
20 1790000 0.98 -0.009 -0.016 0.18 0.19 0.04 0.042 -0.0094 -0.0099 -0.13 0.0082 0.0092 -0.0025 -0.0029 -0.011 -0.067 -6.2e-06 -7.2e-06 -6.6e-06 -7.4e-06 3.4e-07 3.8e-07 0 0 -2.7e-05 -2.8e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.8e-05 4.2e-05 0.0066 0.007 0.0066 0.007 0.00046 0.00043 1.2 1.3 1.2 1.3 0.17 0.16 0.18 0.2 0.18 0.2 0.13 0.12 8.1e-07 7.8e-07 8.1e-07 7.8e-07 1.7e-07 1.4e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
21 1890000 0.98 -0.009 -0.0089 -0.016 0.18 0.19 0.047 0.049 -0.0081 -0.0086 -0.14 0.013 0.014 -0.0033 -0.0037 -0.019 -0.076 -6.2e-06 -7.2e-06 -6.6e-06 -7.4e-06 3.4e-07 3.7e-07 0 0 -3.1e-05 -3.2e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.8e-05 4.1e-05 0.0073 0.0076 0.0072 0.0076 0.00045 0.00042 1.6 1.7 1.6 1.7 0.15 0.28 0.31 0.28 0.31 0.12 8.1e-07 7.8e-07 8.1e-07 7.8e-07 1.5e-07 1.2e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
22 1990000 0.98 -0.0087 -0.0085 -0.016 0.18 0.19 0.038 0.039 -0.0042 -0.14 0.0088 0.0096 -0.002 -0.0021 -0.018 -0.074 -9.8e-06 -1.1e-05 -1.2e-05 -1.3e-05 5.3e-07 5.7e-07 0 0 -4.4e-05 -4.6e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.7e-05 4e-05 0.0059 0.0061 0.0059 0.0061 0.00043 0.0004 1.2 1.3 1.2 1.3 0.13 0.18 0.2 0.18 0.2 0.11 7e-07 6.6e-07 7e-07 6.6e-07 1.3e-07 1.1e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
23 2090000 0.98 -0.0087 -0.0086 -0.016 0.18 0.19 0.045 0.047 -0.0043 -0.0042 -0.14 0.013 0.014 -0.0024 -0.0026 -0.015 -0.071 -9.7e-06 -1.1e-05 -1.2e-05 -1.3e-05 5.2e-07 5.6e-07 0 0 -6.3e-05 -6.5e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.7e-05 3.9e-05 0.0064 0.0066 0.0064 0.0066 0.00042 0.00039 1.5 1.7 1.5 1.7 0.12 0.28 0.31 0.28 0.31 0.11 7e-07 6.6e-07 7e-07 6.6e-07 1.1e-07 9.7e-08 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
24 2190000 0.98 -0.0083 -0.0082 -0.015 0.18 0.19 0.035 -0.0017 -0.0012 -0.14 0.0085 0.0091 -0.0012 -0.021 -0.077 -1.3e-05 -1.4e-05 -1.7e-05 -1.8e-05 6.8e-07 7.2e-07 0 0 -7.3e-05 -7.5e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.5e-05 3.7e-05 0.0049 0.005 0.0049 0.005 0.0004 0.00038 1.1 1.2 1.1 1.2 0.12 0.11 0.18 0.2 0.18 0.2 0.11 5.9e-07 5.5e-07 5.9e-07 5.5e-07 9.9e-08 8.6e-08 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
25 2290000 0.98 -0.0084 -0.0082 -0.016 0.18 0.19 0.04 -0.00055 6.6e-05 -0.14 0.012 0.013 -0.0013 -0.0012 -0.019 -0.075 -1.3e-05 -1.4e-05 -1.7e-05 -1.8e-05 6.7e-07 7.1e-07 0 0 -9.5e-05 -9.8e-05 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.5e-05 3.7e-05 0.0054 0.0054 0.00039 0.00036 1.4 1.5 1.4 1.5 0.11 0.27 0.29 0.27 0.3 0.1 5.9e-07 5.5e-07 5.9e-07 5.5e-07 8.8e-08 7.6e-08 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
26 2390000 0.98 -0.0082 -0.008 -0.015 0.18 0.19 0.031 0.00032 0.001 -0.14 0.0077 0.0082 -0.00055 -0.00047 -0.016 -0.072 -1.5e-05 -1.7e-05 -2.2e-05 -2.3e-05 7.7e-07 8.1e-07 0 0 -0.00012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.4e-05 3.5e-05 0.004 0.004 0.00038 0.00035 0.99 1 0.99 1 0.1 0.17 0.19 0.17 0.19 0.098 4.9e-07 4.5e-07 4.9e-07 4.5e-07 7.9e-08 6.8e-08 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
27 2490000 0.98 -0.0081 -0.0079 -0.015 0.18 0.19 0.033 0.0022 0.0031 -0.14 0.011 -0.00044 -0.00027 -0.023 -0.079 -1.5e-05 -1.7e-05 -2.2e-05 -2.3e-05 7.7e-07 8.1e-07 0 0 -0.00013 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.4e-05 3.4e-05 0.0044 0.0044 0.00036 0.00034 1.2 1.3 1.2 1.3 0.1 0.25 0.28 0.25 0.28 0.097 4.9e-07 4.5e-07 4.9e-07 4.5e-07 7e-08 6.1e-08 4e-06 4e-06 3.7e-06 0 0 0 0 0 0 0 0
28 2590000 0.98 -0.008 -0.0078 -0.015 0.18 0.19 0.023 0.0014 0.0022 -0.15 0.0066 0.0069 -7.8e-05 8.2e-05 -0.028 -0.085 -1.7e-05 -1.8e-05 -2.7e-05 8.3e-07 8.7e-07 0 0 -0.00015 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.3e-05 3.3e-05 0.0033 0.0032 0.0033 0.0032 0.00035 0.00033 0.86 0.89 0.86 0.89 0.099 0.16 0.18 0.16 0.18 0.094 4.1e-07 3.8e-07 4.1e-07 3.8e-07 6.3e-08 5.5e-08 4e-06 4e-06 3.6e-06 0 0 0 0 0 0 0 0
29 2690000 0.98 -0.008 -0.0078 -0.015 0.18 0.19 0.027 0.0034 0.0043 -0.15 0.0092 0.0095 0.00016 0.00041 -0.028 -0.084 -1.7e-05 -1.8e-05 -2.7e-05 8.3e-07 8.7e-07 0 0 -0.00018 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.3e-05 3.2e-05 0.0036 0.0035 0.0036 0.0035 0.00034 0.00032 1.1 1.1 0.097 0.24 0.25 0.24 0.25 0.091 4.1e-07 3.8e-07 4.1e-07 3.8e-07 5.7e-08 5e-08 4e-06 4e-06 3.6e-06 0 0 0 0 0 0 0 0
30 2790000 0.98 -0.0079 -0.0077 -0.015 0.18 0.19 0.021 0.0037 0.0046 -0.14 0.0057 0.006 0.0003 0.00051 -0.025 -0.081 -1.8e-05 -1.9e-05 -3e-05 8.6e-07 8.9e-07 0 0 -0.00022 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.2e-05 3.1e-05 0.0027 0.0027 0.00033 0.00031 0.74 0.77 0.74 0.77 0.096 0.15 0.16 0.15 0.16 0.089 3.4e-07 3.2e-07 3.4e-07 3.2e-07 5.1e-08 4.5e-08 4e-06 4e-06 3.5e-06 0 0 0 0 0 0 0 0
31 2890000 0.98 -0.0079 -0.0077 -0.015 0.18 0.19 0.025 0.0032 0.0043 -0.14 0.0081 0.0084 0.0006 0.00092 -0.025 -0.082 -1.8e-05 -1.9e-05 -3e-05 8.6e-07 8.9e-07 0 0 -0.00025 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.2e-05 3e-05 0.003 0.0029 0.003 0.0029 0.00032 0.0003 0.92 0.95 0.92 0.95 0.096 0.22 0.23 0.22 0.23 0.089 3.4e-07 3.2e-07 3.4e-07 3.2e-07 4.6e-08 4.1e-08 4e-06 4e-06 3.4e-06 0 0 0 0 0 0 0 0
32 2990000 0.98 -0.0078 -0.0076 -0.014 -0.015 0.18 0.19 0.019 0.0023 0.0032 -0.15 0.0052 0.0055 0.00045 0.00069 -0.03 -0.086 -1.9e-05 -2e-05 -3.3e-05 8.8e-07 9.1e-07 0 0 -0.00027 -0.00028 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.1e-05 2.9e-05 0.0023 0.0023 0.00031 0.00029 0.65 0.67 0.65 0.67 0.095 0.14 0.15 0.14 0.15 0.088 2.9e-07 2.7e-07 2.9e-07 2.7e-07 4.2e-08 3.7e-08 4e-06 4e-06 3.3e-06 0 0 0 0 0 0 0 0
33 3090000 0.98 -0.0078 -0.0076 -0.015 0.18 0.19 0.025 0.026 0.0012 0.0024 -0.15 0.0075 0.0077 0.00057 0.00092 -0.032 -0.088 -1.9e-05 -2e-05 -3.3e-05 8.7e-07 9e-07 0 0 -0.00031 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1.1e-05 2.9e-05 0.0026 0.0025 0.0026 0.0025 0.0003 0.00028 0.81 0.82 0.81 0.82 0.095 0.2 0.22 0.2 0.22 0.086 2.9e-07 2.7e-07 2.9e-07 2.7e-07 3.8e-08 3.4e-08 4e-06 4e-06 3.2e-06 0 0 0 0 0 0 0 0
34 3190000 0.98 -0.0078 -0.0076 -0.014 -0.015 0.18 0.19 0.021 1.8e-05 0.0011 -0.15 0.0049 0.0052 0.00029 0.00052 -0.042 -0.098 -2e-05 -3.6e-05 8.9e-07 9.1e-07 0 0 -0.00032 -0.00033 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1e-05 2.8e-05 0.002 0.002 0.00029 0.00027 0.58 0.59 0.58 0.59 0.096 0.14 0.14 0.087 2.4e-07 2.3e-07 2.4e-07 2.3e-07 3.5e-08 3.1e-08 4e-06 4e-06 3.1e-06 0 0 0 0 0 0 0 0
35 3290000 0.98 -0.0077 -0.0075 -0.015 0.18 0.19 0.024 0.0007 0.0019 -0.15 0.0072 0.0075 0.00026 0.00061 -0.05 -0.11 -2e-05 -3.6e-05 8.8e-07 9.1e-07 0 0 -0.00034 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 1e-05 2.7e-05 0.0022 0.0022 0.00028 0.00027 0.71 0.73 0.72 0.73 0.095 0.19 0.2 0.19 0.2 0.086 2.4e-07 2.3e-07 2.4e-07 2.3e-07 3.2e-08 2.9e-08 4e-06 4e-06 3e-06 0 0 0 0 0 0 0 0
36 3390000 0.98 -0.0075 -0.0073 -0.014 0.18 0.19 0.019 0.0021 0.0032 -0.15 0.0048 0.0051 0.00019 0.00045 -0.048 -0.1 -2e-05 -2.1e-05 -3.8e-05 8.9e-07 9.1e-07 0 0 -0.00039 -0.0004 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 9.6e-06 2.6e-05 0.0018 0.0017 0.0018 0.0017 0.00028 0.00026 0.52 0.53 0.52 0.53 0.095 0.13 0.14 0.13 0.14 0.085 2.1e-07 1.9e-07 2.1e-07 1.9e-07 2.9e-08 2.6e-08 4e-06 4e-06 2.9e-06 0 0 0 0 0 0 0 0
37 3490000 0.98 -0.0074 -0.0072 -0.014 0.18 0.19 0.024 0.0052 0.0064 -0.15 0.007 0.0073 0.00055 0.00092 -0.048 -0.1 -2e-05 -2.1e-05 -3.8e-05 8.9e-07 9.1e-07 0 0 -0.00043 -0.00044 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 9.5e-06 2.6e-05 0.002 0.0019 0.002 0.0019 0.00027 0.00025 0.64 0.65 0.64 0.65 0.095 0.18 0.19 0.18 0.19 0.086 2.1e-07 1.9e-07 2.1e-07 1.9e-07 2.7e-08 2.4e-08 4e-06 4e-06 2.8e-06 0 0 0 0 0 0 0 0
38 3590000 0.98 -0.0073 -0.0071 -0.014 0.18 0.19 0.028 0.021 0.0054 0.0056 -0.15 0.0097 0.0051 0.0011 0.00082 -0.055 -0.11 -2e-05 -2.2e-05 -3.8e-05 -4e-05 8.9e-07 9.1e-07 0 0 -0.00046 -0.00047 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 9.3e-06 2.5e-05 0.0022 0.0015 0.0022 0.0015 0.00026 0.00025 0.79 0.48 0.79 0.48 0.094 0.24 0.13 0.24 0.13 0.086 2.1e-07 1.6e-07 2.1e-07 1.6e-07 2.5e-08 2.2e-08 4e-06 4e-06 2.6e-06 0 0 0 0 0 0 0 0
39 3690000 0.98 -0.0073 -0.0071 -0.014 0.18 0.19 0.022 0.023 0.0058 0.0071 -0.15 0.007 0.0074 0.00099 0.0014 -0.052 -0.11 -2.1e-05 -4e-05 8.9e-07 9.1e-07 0 0 -0.00051 -0.00052 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 8.9e-06 2.5e-05 0.0017 0.0017 0.00026 0.00024 0.58 0.59 0.58 0.59 0.093 0.17 0.18 0.17 0.18 0.085 1.7e-07 1.6e-07 1.7e-07 1.6e-07 2.3e-08 2.1e-08 4e-06 4e-06 2.5e-06 0 0 0 0 0 0 0 0
40 3790000 0.98 -0.0072 -0.007 -0.014 0.18 0.19 0.024 0.018 0.01 0.0098 -0.15 0.0094 0.005 0.0019 0.0012 -0.057 -0.11 -2.1e-05 -2.2e-05 -4e-05 -4.2e-05 8.9e-07 9e-07 0 0 -0.00054 -0.00055 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 8.8e-06 2.4e-05 0.0019 0.0014 0.0019 0.0014 0.00025 0.00023 0.71 0.44 0.71 0.44 0.093 0.23 0.12 0.23 0.12 0.086 1.7e-07 1.4e-07 1.7e-07 1.4e-07 2.1e-08 1.9e-08 4e-06 4e-06 2.4e-06 0 0 0 0 0 0 0 0
41 3890000 0.98 -0.0072 -0.007 -0.014 0.18 0.19 0.018 0.019 0.01 0.011 -0.14 0.0065 0.0069 0.0018 0.0023 -0.058 -0.11 -2.1e-05 -2.2e-05 -4.3e-05 -4.2e-05 8.8e-07 9e-07 0 0 -0.00058 -0.00059 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 8.4e-06 2.4e-05 0.0015 0.0015 0.00024 0.00023 0.54 0.54 0.091 0.16 0.17 0.16 0.17 0.086 1.5e-07 1.4e-07 1.5e-07 1.4e-07 2e-08 1.8e-08 4e-06 4e-06 2.2e-06 0 0 0 0 0 0 0 0
42 3990000 0.98 -0.0071 -0.007 -0.014 0.18 0.19 0.023 0.011 0.013 -0.14 0.0087 0.0091 0.0028 0.0035 -0.056 -0.11 -2.1e-05 -2.2e-05 -4.2e-05 8.8e-07 9e-07 0 0 -0.00063 -0.00064 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 8.3e-06 2.3e-05 0.0017 0.0017 0.00024 0.00022 0.65 0.66 0.65 0.66 0.089 0.21 0.22 0.21 0.22 0.085 1.5e-07 1.4e-07 1.5e-07 1.4e-07 1.8e-08 1.7e-08 4e-06 4e-06 2.1e-06 0 0 0 0 0 0 0 0
43 4090000 0.98 -0.0071 -0.0069 -0.014 0.18 0.19 0.019 0.02 0.0093 0.011 -0.12 0.0063 0.0067 0.0023 0.0028 -0.042 -0.098 -2.1e-05 -2.2e-05 -4.5e-05 -4.4e-05 8.7e-07 8.8e-07 0 0 -0.00071 -0.00072 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 8e-06 2.3e-05 0.0014 0.0013 0.0014 0.0013 0.00023 0.00022 0.49 0.5 0.49 0.5 0.087 0.15 0.16 0.15 0.16 0.085 1.2e-07 1.2e-07 1.7e-08 1.6e-08 4e-06 4e-06 2e-06 0 0 0 0 0 0 0 0
44 4190000 0.98 -0.0072 -0.007 -0.014 0.18 0.19 0.022 0.023 0.0097 0.011 -0.12 0.0083 0.0088 0.0032 0.0039 -0.045 -0.1 -2.1e-05 -2.2e-05 -4.4e-05 8.7e-07 8.8e-07 0 0 -0.00074 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 7.8e-06 2.2e-05 0.0015 0.0015 0.00023 0.00021 0.6 0.6 0.086 0.2 0.21 0.2 0.21 0.086 1.2e-07 1.2e-07 1.6e-08 1.5e-08 4e-06 4e-06 1.9e-06 0 0 0 0 0 0 0 0
45 4290000 0.98 -0.0073 -0.0072 -0.014 0.18 0.19 0.019 0.02 0.0088 0.01 -0.13 -0.12 0.006 0.0064 0.0024 0.0029 -0.05 -0.11 -2.1e-05 -2.2e-05 -4.7e-05 -4.6e-05 8.6e-07 8.7e-07 0 0 -0.00076 -0.00077 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 7.5e-06 2.2e-05 0.0012 0.0012 0.00022 0.00021 0.45 0.46 0.46 0.084 0.14 0.15 0.14 0.15 0.085 1e-07 9.6e-08 1e-07 9.6e-08 1.5e-08 1.4e-08 4e-06 4e-06 1.7e-06 0 0 0 0 0 0 0 0
46 4390000 0.98 -0.0072 -0.0071 -0.014 0.18 0.19 0.023 0.024 0.0084 0.01 -0.11 0.0082 0.0087 0.0032 0.0039 -0.039 -0.095 -2.1e-05 -2.2e-05 -4.6e-05 8.5e-07 8.7e-07 0 0 -0.00083 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 7.4e-06 2.1e-05 0.0013 0.0013 0.00022 0.0002 0.55 0.56 0.55 0.56 0.081 0.19 0.2 0.19 0.2 0.084 1e-07 9.6e-08 1e-07 9.6e-08 1.4e-08 1.3e-08 4e-06 4e-06 1.6e-06 0 0 0 0 0 0 0 0
47 4490000 0.98 -0.0073 -0.0072 -0.013 -0.014 0.18 0.19 0.019 0.0089 0.01 -0.11 0.006 0.0064 0.0024 0.0029 -0.04 -0.095 -2.1e-05 -4.8e-05 8.4e-07 8.5e-07 0 0 -0.00086 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 7.2e-06 2.1e-05 0.0011 0.001 0.0011 0.001 0.00021 0.0002 0.42 0.43 0.42 0.43 0.08 0.14 0.14 0.085 8.2e-08 7.9e-08 8.2e-08 7.9e-08 1.3e-08 1.2e-08 4e-06 4e-06 1.5e-06 0 0 0 0 0 0 0 0
48 4590000 0.98 -0.0073 -0.0071 -0.013 -0.014 0.18 0.19 0.022 0.023 0.0085 0.01 -0.11 0.008 0.0085 0.0033 0.0039 -0.042 -0.098 -2.1e-05 -4.8e-05 8.4e-07 8.5e-07 0 0 -0.00088 -0.00089 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 7.1e-06 2e-05 0.0012 0.0011 0.0012 0.0011 0.00021 0.0002 0.5 0.51 0.5 0.51 0.077 0.18 0.19 0.18 0.19 0.084 8.2e-08 7.9e-08 8.2e-08 7.9e-08 1.2e-08 1.1e-08 4e-06 4e-06 1.4e-06 0 0 0 0 0 0 0 0
49 4690000 0.98 -0.0073 -0.0071 -0.013 0.18 0.19 0.016 0.017 0.007 0.0083 -0.1 0.0058 0.0062 0.0023 0.0029 -0.035 -0.09 -2.1e-05 -5e-05 8.3e-07 8.4e-07 0 0 -0.00093 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 6.8e-06 2e-05 0.00093 0.00092 0.00093 0.00092 0.0002 0.00019 0.39 0.39 0.075 0.074 0.13 0.14 0.13 0.14 0.083 6.6e-08 6.4e-08 6.6e-08 6.4e-08 1.1e-08 4e-06 4e-06 1.3e-06 0 0 0 0 0 0 0 0
50 4790000 0.98 -0.0072 -0.007 -0.013 0.18 0.19 0.014 0.0081 0.0094 -0.1 -0.099 0.0072 0.0078 0.0031 0.0038 -0.037 -0.093 -2.1e-05 -5e-05 8.3e-07 8.4e-07 0 0 -0.00095 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 6.7e-06 2e-05 0.001 0.001 0.0002 0.00019 0.46 0.47 0.46 0.47 0.073 0.17 0.18 0.17 0.18 0.084 6.6e-08 6.4e-08 6.6e-08 6.4e-08 1.1e-08 9.9e-09 4e-06 4e-06 1.2e-06 0 0 0 0 0 0 0 0
51 4890000 0.98 -0.0072 -0.007 -0.013 0.18 0.19 0.0097 0.01 0.0043 0.0054 -0.094 -0.093 0.0048 0.0052 0.0021 0.0026 -0.033 -0.088 -2.1e-05 -5.2e-05 -5.1e-05 8.2e-07 0 0 -0.00098 -0.00099 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 6.5e-06 1.9e-05 0.00081 0.0008 0.00081 0.0008 0.0002 0.00018 0.35 0.36 0.35 0.36 0.07 0.12 0.13 0.12 0.13 0.083 5.4e-08 5.2e-08 5.4e-08 5.2e-08 1e-08 9.3e-09 4e-06 4e-06 1.1e-06 0 0 0 0 0 0 0 0
52 4990000 0.98 -0.0071 -0.007 -0.013 0.18 0.19 0.013 0.014 0.006 0.0072 -0.086 -0.085 0.0059 0.0064 0.0027 0.0033 -0.028 -0.083 -2.1e-05 -5.1e-05 8.2e-07 0 0 -0.001 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 6.4e-06 1.9e-05 0.00087 0.00087 0.00019 0.00018 0.42 0.43 0.42 0.43 0.067 0.16 0.17 0.16 0.17 0.082 5.4e-08 5.2e-08 5.4e-08 5.2e-08 9.5e-09 8.8e-09 4e-06 4e-06 1.1e-06 1e-06 0 0 0 0 0 0 0 0
53 5090000 0.98 -0.007 -0.0069 -0.013 0.18 0.19 0.0096 0.01 0.0054 0.0064 -0.083 -0.082 0.0041 0.0045 0.0018 0.0023 -0.026 -0.082 -2.1e-05 -5.3e-05 -5.2e-05 8.1e-07 0 0 -0.001 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 6.3e-06 1.9e-05 0.0007 0.0007 0.00019 0.00018 0.32 0.33 0.32 0.33 0.066 0.065 0.12 0.12 0.082 4.3e-08 4.2e-08 4.3e-08 4.2e-08 8.9e-09 8.3e-09 4e-06 4e-06 9.9e-07 9.8e-07 0 0 0 0 0 0 0 0
54 5190000 0.98 -0.0069 -0.0067 -0.013 0.18 0.19 0.0083 0.0089 0.0085 0.0096 -0.08 0.005 0.0054 0.0025 0.0031 -0.024 -0.079 -2.1e-05 -5.3e-05 -5.2e-05 8.1e-07 0 0 -0.0011 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 6.2e-06 1.8e-05 0.00075 0.00075 0.00018 0.00017 0.38 0.39 0.38 0.39 0.063 0.16 0.16 0.081 4.3e-08 4.2e-08 4.3e-08 4.2e-08 8.4e-09 7.9e-09 4e-06 4e-06 9.2e-07 9.1e-07 0 0 0 0 0 0 0 0
55 5290000 0.98 -0.0068 -0.0066 -0.013 0.18 0.19 0.0066 0.0071 0.0083 0.0092 -0.069 -0.068 0.0034 0.0037 0.002 0.0024 -0.017 -0.072 -2.1e-05 -5.4e-05 -5.3e-05 8e-07 0 0 -0.0011 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 6e-06 1.8e-05 0.0006 0.0006 0.00018 0.00017 0.3 0.3 0.06 0.11 0.12 0.11 0.12 0.08 3.5e-08 3.4e-08 3.5e-08 3.4e-08 8e-09 7.4e-09 4e-06 4e-06 8.5e-07 8.4e-07 0 0 0 0 0 0 0 0
56 5390000 0.98 -0.0067 -0.0066 -0.013 0.18 0.19 0.005 0.0055 0.011 0.012 -0.065 0.004 0.0044 0.0029 0.0034 -0.012 -0.067 -2.1e-05 -5.3e-05 8e-07 0 0 -0.0011 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.9e-06 1.8e-05 0.00065 0.00065 0.00018 0.00017 0.35 0.36 0.35 0.36 0.058 0.057 0.15 0.15 0.079 3.5e-08 3.4e-08 3.5e-08 3.4e-08 7.5e-09 7.1e-09 4e-06 4e-06 7.9e-07 7.8e-07 0 0 0 0 0 0 0 0
57 5490000 0.98 -0.0068 -0.0066 -0.013 0.18 0.19 0.004 0.0043 0.012 0.013 -0.061 -0.06 0.0026 0.0028 0.0024 0.0028 -0.0099 -0.065 -2e-05 -2.1e-05 -5.4e-05 7.9e-07 0 0 -0.0011 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.8e-06 1.7e-05 0.00052 0.00052 0.00017 0.00016 0.27 0.28 0.27 0.28 0.056 0.11 0.11 0.079 2.8e-08 2.8e-08 7.1e-09 6.7e-09 4e-06 4e-06 7.3e-07 0 0 0 0 0 0 0 0
58 5590000 0.98 -0.0068 -0.0066 -0.013 0.18 0.19 0.0041 0.0043 0.016 0.017 -0.054 -0.053 0.0031 0.0033 0.0038 0.0044 -0.0031 -0.058 -2e-05 -2.1e-05 -5.4e-05 7.9e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.7e-06 1.7e-05 0.00056 0.00056 0.00017 0.00016 0.32 0.32 0.054 0.053 0.14 0.15 0.14 0.15 0.078 2.8e-08 2.8e-08 6.8e-09 6.3e-09 4e-06 4e-06 6.8e-07 6.7e-07 0 0 0 0 0 0 0 0
59 5690000 0.98 -0.0067 -0.013 0.18 0.19 0.0051 0.0034 0.019 0.017 -0.053 -0.052 0.0035 0.0022 0.0056 0.0036 -0.00026 -0.056 -2e-05 -5.4e-05 -5.5e-05 7.9e-07 7.8e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.6e-06 1.7e-05 0.0006 0.00045 0.0006 0.00045 0.00017 0.00016 0.37 0.25 0.37 0.25 0.051 0.18 0.11 0.18 0.11 0.077 0.076 2.8e-08 2.2e-08 2.8e-08 2.2e-08 6.4e-09 6e-09 4e-06 4e-06 6.3e-07 6.2e-07 0 0 0 0 0 0 0 0
60 5790000 0.98 -0.0067 -0.0065 -0.013 0.18 0.19 0.0038 0.004 0.019 0.02 -0.05 -0.049 0.0024 0.0026 0.0049 0.0054 0.0021 -0.053 -2e-05 -5.5e-05 7.8e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.5e-06 1.6e-05 0.00048 0.00048 0.00017 0.00016 0.29 0.29 0.05 0.13 0.14 0.13 0.14 0.077 2.3e-08 2.2e-08 2.3e-08 2.2e-08 6.1e-09 5.7e-09 4e-06 4e-06 5.9e-07 5.8e-07 0 0 0 0 0 0 0 0
61 5890000 0.98 -0.0066 -0.013 0.18 0.19 0.0064 0.005 0.02 0.018 -0.048 0.0029 0.0018 0.0068 0.0044 -0.00038 -0.056 -2e-05 -1.9e-05 -5.5e-05 7.8e-07 7.6e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.4e-06 1.6e-05 0.00051 0.00039 0.00051 0.00039 0.00016 0.00015 0.34 0.23 0.34 0.23 0.048 0.17 0.1 0.17 0.1 0.075 2.3e-08 1.8e-08 2.3e-08 1.8e-08 5.8e-09 5.5e-09 4e-06 4e-06 5.5e-07 5.4e-07 0 0 0 0 0 0 0 0
62 5990000 0.98 -0.0067 -0.0065 -0.013 0.18 0.19 0.006 0.0061 0.018 0.019 -0.042 -0.041 0.0022 0.0024 0.0056 0.0062 0.0052 -0.05 -1.9e-05 -5.5e-05 7.6e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.3e-06 1.6e-05 0.00041 0.00041 0.00016 0.00015 0.26 0.27 0.26 0.27 0.046 0.045 0.13 0.13 0.074 1.8e-08 1.8e-08 5.5e-09 5.2e-09 4e-06 4e-06 5.1e-07 5e-07 0 0 0 0 0 0 0 0
63 6090000 0.98 -0.0067 -0.0065 -0.013 0.18 0.19 0.0057 0.0058 0.02 0.021 -0.039 0.0028 0.003 0.0075 0.0082 0.0078 -0.048 -1.9e-05 -5.5e-05 7.6e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.2e-06 1.6e-05 0.00044 0.00044 0.00016 0.00015 0.3 0.31 0.3 0.31 0.044 0.16 0.17 0.16 0.17 0.074 1.8e-08 1.8e-08 5.3e-09 5e-09 4e-06 4e-06 4.8e-07 4.7e-07 0 0 0 0 0 0 0 0
64 6190000 0.98 -0.0068 -0.0067 -0.013 0.18 0.19 0.0036 0.0037 0.018 0.019 -0.038 -0.037 0.0021 0.0022 0.006 0.0066 0.0086 -0.047 -1.9e-05 -5.6e-05 7.5e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5.1e-06 1.5e-05 0.00036 0.00036 0.00016 0.00015 0.24 0.24 0.042 0.12 0.13 0.12 0.13 0.073 1.5e-08 1.5e-08 5e-09 4.7e-09 4e-06 4e-06 4.4e-07 0 0 0 0 0 0 0 0
65 6290000 0.98 -0.0068 -0.0066 -0.013 0.18 0.19 0.0022 0.02 0.021 -0.041 0.0024 0.0026 0.0078 0.0085 0.002 -0.053 -1.9e-05 -5.6e-05 7.5e-07 0 0 -0.0012 0.2 -6.1e-09 0.002 0.43 0.44 0 0 0 0 0 5e-06 1.5e-05 0.00038 0.00038 0.00015 0.00014 0.27 0.28 0.27 0.28 0.041 0.04 0.15 0.16 0.15 0.16 0.072 1.5e-08 1.5e-08 4.8e-09 4.5e-09 4e-06 4e-06 4.1e-07 0 0 0 0 0 0 0 0
66 6390000 0.98 -0.0067 -0.0066 -0.013 0.19 0.0032 0.017 0.018 -0.042 0.0016 0.0017 0.0062 0.0068 -0.00048 -0.056 -1.8e-05 -5.6e-05 7.3e-07 0 0 -0.0012 0.2 0.002 0.43 0 0 0 0 0 6.2e-05 0.0003 0.0003 0.0017 0.0015 0.2 0.2 0.039 0.12 0.12 0.072 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 3.9e-07 3.8e-07 0 0 0 0 0 0 0 0
67 6490000 0.98 -0.0066 -0.013 0.19 0.00094 0.00098 0.016 0.017 -0.039 0.0019 0.0078 0.0085 0.002 -0.053 -1.8e-05 -5.6e-05 7.1e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.8e-05 4.2e-05 0.0003 0.0003 0.0011 0.00096 0.21 0.2 0.21 0.038 0.14 0.15 0.14 0.15 0.071 0.07 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 3.6e-07 0 0 0 0 0 0 0 0
68 6590000 0.98 -0.0066 -0.0065 -0.013 0.19 0.00022 0.00028 0.019 0.02 -0.042 0.002 0.0095 0.01 -0.0009 -0.056 -1.8e-05 -5.6e-05 6.9e-07 6.8e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-05 3.2e-05 0.0003 0.0003 0.00076 0.00071 0.21 0.21 0.036 0.18 0.18 0.069 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 3.4e-07 3.3e-07 0 0 0 0 0 0 0 0
69 6690000 0.98 -0.0065 -0.0064 -0.013 0.19 -0.0024 0.021 0.022 -0.044 0.0018 0.0019 0.012 -0.0016 -0.057 -1.8e-05 -5.6e-05 6.5e-07 6.4e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.1e-05 2.6e-05 0.0003 0.0003 0.0006 0.00056 0.22 0.22 0.035 0.21 0.22 0.21 0.22 0.068 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 3.1e-07 0 0 0 0 0 0 0 0
70 6790000 0.98 -0.0065 -0.0064 -0.013 0.19 -0.0007 -0.00059 0.023 0.024 -0.042 0.0016 0.0017 0.014 0.015 -0.0023 -0.058 -1.8e-05 -5.6e-05 6.2e-07 6e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 1.8e-05 2.3e-05 0.0003 0.0003 0.0005 0.00048 0.23 0.23 0.034 0.25 0.26 0.25 0.26 0.068 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 2.9e-07 0 0 0 0 0 0 0 0
71 6890000 0.98 -0.0063 -0.0062 -0.013 0.19 -0.0012 -0.0011 0.023 0.024 -0.039 -0.038 0.0015 0.0016 0.016 0.017 0.00034 -0.055 -1.8e-05 -5.6e-05 6e-07 5.8e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 1.5e-05 2e-05 0.00031 0.00031 0.00042 0.00041 0.25 0.25 0.032 0.3 0.31 0.3 0.31 0.067 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 2.8e-07 2.7e-07 0 0 0 0 0 0 0 0
72 6990000 0.98 -0.0062 -0.013 0.19 -0.0013 -0.0011 0.025 0.026 -0.037 0.0014 0.0015 0.018 0.02 0.00071 -0.055 -1.8e-05 -5.6e-05 5.9e-07 5.7e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 1.3e-05 1.8e-05 0.00031 0.00031 0.00037 0.00035 0.27 0.27 0.031 0.35 0.36 0.35 0.36 0.066 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 2.6e-07 0 0 0 0 0 0 0 0
73 7090000 0.98 -0.0061 -0.012 0.19 -0.0022 -0.002 0.03 0.031 -0.038 -0.037 0.0012 0.0013 0.021 0.023 -0.00035 -0.056 -1.8e-05 -5.6e-05 6e-07 5.7e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 1.2e-05 1.7e-05 0.00031 0.00031 0.00033 0.00032 0.29 0.29 0.03 0.41 0.42 0.41 0.42 0.066 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 2.4e-07 0 0 0 0 0 0 0 0
74 7190000 0.98 -0.006 -0.013 0.19 -0.0027 -0.0025 0.032 0.034 -0.037 -0.036 0.00089 0.0011 0.024 0.026 -0.003 -0.058 -1.8e-05 -5.6e-05 5.3e-07 5e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 1.1e-05 1.6e-05 0.00032 0.00032 0.00029 0.32 0.32 0.029 0.47 0.49 0.47 0.49 0.065 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 2.3e-07 0 0 0 0 0 0 0 0
75 7290000 0.98 -0.006 -0.013 0.19 -0.002 -0.0017 0.037 0.038 -0.034 0.00061 0.0008 0.028 0.029 0.00094 -0.054 -1.8e-05 -5.6e-05 5.4e-07 5e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 9.6e-06 1.5e-05 0.00032 0.00032 0.00027 0.00026 0.34 0.35 0.34 0.35 0.028 0.55 0.56 0.55 0.56 0.064 1.2e-08 1.2e-08 4.7e-09 4.5e-09 4e-06 4e-06 2.1e-07 0 0 0 0 0 0 0 0
76 7390000 0.98 -0.0059 -0.013 0.19 -0.0037 -0.0035 0.04 0.041 -0.032 0.00034 0.00056 0.031 0.033 0.0032 -0.052 -1.8e-05 -5.6e-05 5.6e-07 5.1e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 8.9e-06 1.4e-05 0.00033 0.00033 0.00025 0.00024 0.38 0.38 0.027 0.63 0.64 0.63 0.64 0.064 1.2e-08 1.2e-08 4.7e-09 4.4e-09 4e-06 4e-06 2e-07 0 0 0 0 0 0 0 0
77 7490000 0.98 -0.0059 -0.0058 -0.013 0.19 -0.0015 -0.0012 0.043 0.045 -0.026 0.00013 0.00037 0.036 0.038 0.0095 -0.046 -1.8e-05 -5.6e-05 6.7e-07 6.2e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 8.2e-06 1.3e-05 0.00034 0.00034 0.00023 0.00022 0.41 0.42 0.41 0.42 0.026 0.72 0.73 0.72 0.73 0.063 1.2e-08 1.2e-08 4.7e-09 4.4e-09 4e-06 4e-06 1.9e-07 0 0 0 0 0 0 0 0
78 7590000 0.98 -0.006 -0.0059 -0.013 0.19 -0.00051 -0.00017 0.046 0.048 -0.023 4.1e-05 0.00032 0.04 0.042 0.015 -0.041 -1.8e-05 -5.6e-05 6.9e-07 6.3e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 7.6e-06 1.3e-05 0.00034 0.00034 0.00021 0.45 0.45 0.025 0.81 0.83 0.82 0.83 0.062 1.2e-08 1.2e-08 4.7e-09 4.4e-09 4e-06 4e-06 1.8e-07 0 0 0 0 0 0 0 0
79 7690000 0.98 -0.006 -0.0059 -0.013 0.19 -0.00089 -0.00052 0.05 0.052 -0.022 -2.6e-05 0.00028 0.045 0.047 0.019 -0.036 -1.8e-05 -5.6e-05 6.6e-07 5.9e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 7.2e-06 1.2e-05 0.00035 0.00035 0.0002 0.49 0.5 0.49 0.5 0.025 0.93 0.95 0.93 0.95 0.062 1.2e-08 1.2e-08 4.6e-09 4.4e-09 4e-06 4e-06 1.7e-07 0 0 0 0 0 0 0 0
80 7790000 0.98 -0.0058 -0.013 0.19 0.00066 0.0011 0.053 0.054 -0.025 -0.024 -4.8e-05 0.00029 0.05 0.052 0.014 -0.041 -1.8e-05 -5.6e-05 5.8e-07 5.1e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 6.8e-06 1.2e-05 0.00036 0.00036 0.00019 0.00018 0.54 0.54 0.024 1.1 1.1 0.061 1.2e-08 1.2e-08 4.6e-09 4.4e-09 4e-06 4e-06 1.6e-07 0 0 0 0 0 0 0 0
81 7890000 0.98 -0.0059 -0.0058 -0.013 0.19 -0.00072 -0.00028 0.057 0.059 -0.025 -0.00014 0.00024 0.055 0.057 0.011 -0.045 -1.8e-05 -5.6e-05 5.3e-07 4.6e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 6.4e-06 1.1e-05 0.00037 0.00037 0.00018 0.00017 0.58 0.59 0.58 0.59 0.023 1.2 1.2 0.06 1.2e-08 1.2e-08 4.6e-09 4.4e-09 4e-06 4e-06 1.5e-07 0 0 0 0 0 0 0 0
82 7990000 0.98 -0.0058 -0.0057 -0.013 0.19 -0.0005 -3.6e-05 0.06 0.062 -0.022 -0.021 -0.0002 0.00022 0.06 0.063 0.014 -0.042 -1.8e-05 -5.6e-05 5.4e-07 4.6e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 6.1e-06 1.1e-05 0.00038 0.00037 0.00038 0.00037 0.00017 0.64 0.64 0.022 1.4 1.4 0.059 1.2e-08 1.2e-08 4.6e-09 4.4e-09 4e-06 4e-06 1.4e-07 0 0 0 0 0 0 0 0
83 8090000 0.98 -0.0056 -0.013 0.19 0.00093 0.0014 0.065 0.067 -0.022 -0.00015 0.00031 0.066 0.069 0.012 -0.044 -1.8e-05 -5.6e-05 2.8e-07 2e-07 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 5.9e-06 1.1e-05 0.00038 0.00038 0.00016 0.69 0.7 0.69 0.7 0.022 1.5 1.5 0.059 1.2e-08 1.2e-08 4.6e-09 4.4e-09 4e-06 4e-06 1.4e-07 0 0 0 0 0 0 0 0
84 8190000 0.98 -0.0057 -0.0056 -0.013 0.19 0.0015 0.002 0.071 0.073 -0.018 -5.7e-05 0.00045 0.073 0.076 0.018 -0.038 -1.8e-05 -5.6e-05 7.1e-08 -1.9e-09 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 5.6e-06 1.1e-05 0.00039 0.00039 0.00015 0.75 0.76 0.75 0.76 0.021 1.7 1.7 0.058 1.2e-08 1.2e-08 4.6e-09 4.4e-09 4e-06 4e-06 1.3e-07 0 0 0 0 0 0 0 0
85 8290000 0.98 -0.0057 -0.0056 -0.013 0.19 0.0036 0.0042 0.075 0.077 -0.017 -0.016 0.00018 0.00073 0.079 0.082 0.018 -0.038 -1.8e-05 -5.6e-05 -6.3e-09 -8.3e-08 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 5.4e-06 1e-05 0.0004 0.0004 0.00015 0.8 0.81 0.81 0.02 1.9 1.9 0.057 1.2e-08 1.1e-08 1.2e-08 1.1e-08 4.6e-09 4.3e-09 4e-06 4e-06 1.2e-07 0 0 0 0 0 0 0 0
86 8390000 0.98 -0.0056 -0.013 0.19 0.0014 0.002 0.077 0.08 -0.016 -0.015 0.00043 0.001 0.086 0.09 0.019 -0.036 -1.8e-05 -5.6e-05 -8.2e-08 -1.6e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 5.2e-06 1e-05 0.00041 0.00041 0.00014 0.87 0.88 0.87 0.88 0.02 2.1 2.2 2.1 2.2 0.057 1.2e-08 1.1e-08 1.2e-08 1.1e-08 4.5e-09 4.3e-09 4e-06 4e-06 1.2e-07 0 0 0 0 0 0 0 0
87 8490000 0.98 -0.0055 -0.013 0.19 0.0011 0.0018 0.081 0.084 -0.017 0.00057 0.0012 0.092 0.096 0.015 -0.041 -1.8e-05 -5.6e-05 7.5e-08 -1.7e-08 0 0 -0.0013 0.2 0.002 0.43 0 0 0 0 0 5.1e-06 1e-05 0.00042 0.00042 0.00014 0.93 0.94 0.93 0.94 0.019 2.4 2.4 0.056 1.1e-08 1.1e-08 4.5e-09 4.3e-09 4e-06 4e-06 1.1e-07 0 0 0 0 0 0 0 0
88 8590000 0.98 -0.0055 -0.0054 -0.013 0.19 0.0021 0.0028 0.085 0.088 -0.012 0.00069 0.0014 0.1 0.019 -0.036 -1.8e-05 -5.6e-05 -4.7e-08 -1.4e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.9e-06 9.9e-06 0.00043 0.00043 0.00013 1 1 0.019 0.018 2.6 2.7 2.6 2.7 0.055 1.1e-08 1.1e-08 4.5e-09 4.3e-09 4e-06 4e-06 1.1e-07 0 0 0 0 0 0 0 0
89 8690000 0.98 -0.0055 -0.013 0.19 0.0021 0.0028 0.086 0.089 -0.014 0.00084 0.0016 0.11 0.018 -0.037 -1.8e-05 -5.6e-05 -1.7e-08 -1.2e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.8e-06 9.8e-06 0.00043 0.00043 0.00013 1.1 1.1 0.018 2.9 2.9 0.055 1.1e-08 1.1e-08 4.5e-09 4.3e-09 4e-06 4e-06 1e-07 0 0 0 0 0 0 0 0
90 8790000 0.98 -0.0055 -0.0054 -0.013 0.19 0.0034 0.0042 0.09 0.093 -0.014 -0.013 0.00098 0.0018 0.12 0.021 -0.035 -1.8e-05 -5.6e-05 -2.5e-07 -3.5e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.7e-06 9.7e-06 0.00045 0.00045 0.00013 1.1 1.2 1.1 1.2 0.018 3.2 3.3 3.2 3.3 0.055 1.1e-08 1.1e-08 4.4e-09 4.2e-09 4e-06 4e-06 9.6e-08 0 0 0 0 0 0 0 0
91 8890000 0.98 -0.0056 -0.0055 -0.013 0.19 0.0034 0.0042 0.093 0.095 -0.0092 -0.0091 0.0013 0.0022 0.12 0.13 0.027 -0.029 -1.8e-05 -5.6e-05 -6.5e-08 -1.8e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.6e-06 9.5e-06 0.00045 0.00045 0.00012 1.2 1.2 0.017 3.5 3.5 3.6 0.054 1.1e-08 1.1e-08 4.4e-09 4.2e-09 4e-06 4e-06 9.2e-08 9.1e-08 0 0 0 0 0 0 0 0
92 8990000 0.98 -0.0055 -0.0054 -0.013 0.19 0.0025 0.0033 0.098 0.1 -0.0084 -0.0083 0.0016 0.0026 0.13 0.14 0.024 -0.032 -1.7e-05 -1.8e-05 -5.6e-05 2.1e-07 8.4e-08 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.5e-06 9.5e-06 0.00046 0.00046 0.00012 1.3 1.3 0.017 3.9 4 3.9 4 0.054 1.1e-08 1.1e-08 4.4e-09 4.2e-09 4e-06 4e-06 8.8e-08 0 0 0 0 0 0 0 0
93 9090000 0.98 -0.0055 -0.013 0.19 0.0028 0.0036 0.1 -0.0094 -0.0093 0.0019 0.0029 0.13 0.14 0.024 -0.032 -1.7e-05 -5.6e-05 5.2e-07 3.8e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.4e-06 9.4e-06 0.00046 0.00046 0.00012 1.3 1.3 0.016 4.2 4.2 0.053 1.1e-08 1.1e-08 4.4e-09 4.2e-09 4e-06 4e-06 8.4e-08 0 0 0 0 0 0 0 0
94 9190000 0.98 -0.0055 -0.0054 -0.013 0.19 0.0064 0.0072 0.1 0.11 -0.0089 -0.0088 0.0024 0.0035 0.14 0.15 0.023 -0.032 -1.7e-05 -5.6e-05 8e-07 6.4e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.4e-06 9.3e-06 0.00047 0.00047 0.00012 1.4 1.4 0.016 4.6 4.7 4.6 4.7 0.052 1.1e-08 1.1e-08 4.3e-09 4.1e-09 4e-06 4e-06 8e-08 0 0 0 0 0 0 0 0
95 9290000 0.98 -0.0054 -0.0053 -0.013 0.19 0.0086 0.0094 0.1 0.11 -0.0073 -0.0072 0.0031 0.0042 0.15 0.026 -0.03 -1.7e-05 -5.7e-05 -5.6e-05 8.8e-07 7.2e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.3e-06 9.2e-06 0.00047 0.00047 0.00012 0.00011 1.5 1.5 0.015 4.9 5 4.9 5 0.052 1.1e-08 1.1e-08 4.3e-09 4.1e-09 4e-06 4e-06 7.7e-08 7.6e-08 0 0 0 0 0 0 0 0
96 9390000 0.98 -0.0053 -0.0052 -0.013 0.19 0.0086 0.0095 0.11 -0.0062 -0.0061 0.0039 0.0051 0.16 0.025 -0.03 -1.7e-05 -5.7e-05 -5.6e-05 5.6e-07 4e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.3e-06 9.2e-06 0.00048 0.00048 0.00012 0.00011 1.6 1.6 0.015 5.4 5.5 5.5 0.052 1.1e-08 1.1e-08 4.2e-09 4.1e-09 4e-06 4e-06 7.4e-08 7.3e-08 0 0 0 0 0 0 0 0
97 9490000 0.98 -0.0054 -0.0053 -0.013 0.19 0.0084 0.0092 0.11 -0.0045 -0.0044 0.0045 0.0058 0.16 0.17 0.028 -0.027 -1.7e-05 -5.7e-05 6.8e-07 5.1e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.2e-06 9.1e-06 0.00047 0.00047 0.00011 1.6 1.6 0.015 5.7 5.8 5.7 5.8 0.051 1e-08 1e-08 4.2e-09 4e-09 4e-06 4e-06 7.1e-08 7e-08 0 0 0 0 0 0 0 0
98 9590000 0.98 -0.0054 -0.013 0.19 0.0082 0.0091 0.11 -0.0044 -0.0043 0.0052 0.0065 0.17 0.18 0.027 -0.029 -1.7e-05 -5.7e-05 -5.6e-05 4e-08 -1.1e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.2e-06 9.1e-06 0.00049 0.00049 0.00011 1.7 1.7 0.014 6.3 6.4 6.3 6.4 0.05 1e-08 1e-08 4.2e-09 4e-09 4e-06 4e-06 6.8e-08 6.7e-08 0 0 0 0 0 0 0 0
99 9690000 0.98 -0.0055 -0.0054 -0.013 0.19 0.0079 0.0088 0.11 -0.0015 -0.0014 0.0056 0.0069 0.17 0.18 0.028 -0.027 -1.7e-05 -5.7e-05 -1.5e-07 -2.9e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 9e-06 0.00047 0.00047 0.00011 1.7 1.7 0.014 6.5 6.6 6.5 6.6 0.05 1e-08 9.9e-09 1e-08 9.9e-09 4.1e-09 3.9e-09 4e-06 4e-06 6.5e-08 0 0 0 0 0 0 0 0
100 9790000 0.98 -0.0054 -0.013 0.19 0.0092 0.01 0.11 -0.0028 -0.0027 0.0063 0.0077 0.18 0.19 0.027 -0.028 -1.7e-05 -5.7e-05 -7.8e-07 -9.1e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 9e-06 0.00049 0.00049 0.00011 1.8 1.8 0.014 7.2 7.3 7.2 7.3 0.05 1e-08 9.9e-09 1e-08 9.9e-09 4.1e-09 3.9e-09 4e-06 4e-06 6.3e-08 6.2e-08 0 0 0 0 0 0 0 0
101 9890000 0.98 -0.0054 -0.0055 -0.013 0.19 0.011 0.012 0.11 -0.0015 -0.0014 0.0074 0.0082 0.19 0.18 0.027 -0.029 -1.7e-05 -1.6e-05 -5.7e-05 -6.5e-07 -8e-07 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 8.9e-06 0.0005 0.00047 0.0005 0.00047 0.00011 1.9 1.8 1.9 1.8 0.013 7.9 7.4 7.9 7.4 0.049 1e-08 9.6e-09 1e-08 9.6e-09 4e-09 3.9e-09 4e-06 4e-06 6e-08 0 0 0 0 0 0 0 0
102 9990000 0.98 -0.0055 -0.0054 -0.013 0.19 0.013 0.014 0.11 -0.00082 -0.00073 0.0079 0.0093 0.19 0.2 0.025 -0.031 -1.6e-05 -5.7e-05 -1.2e-06 -1.3e-06 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 8.9e-06 0.00049 0.00049 0.00011 1.9 1.9 0.013 8.1 8.2 8.1 8.2 0.049 9.7e-09 9.6e-09 9.7e-09 9.6e-09 4e-09 3.8e-09 4e-06 4e-06 5.8e-08 0 0 0 0 0 0 0 0
103 10090000 0.98 -0.0054 -0.0055 -0.013 0.19 0.011 0.012 0.11 0.0004 0.00048 0.009 0.0096 0.2 0.19 0.027 -0.029 -1.6e-05 -5.7e-05 -1.8e-06 -1.9e-06 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 8.9e-06 0.0005 0.00046 0.0005 0.00046 0.00011 2 1.9 2 1.9 0.013 8.9 8.2 8.9 8.2 0.049 0.048 9.7e-09 9.3e-09 9.7e-09 9.3e-09 3.9e-09 3.8e-09 4e-06 4e-06 5.6e-08 0 0 0 0 0 0 0 0
104 10190000 0.98 -0.0055 -0.013 0.19 0.009 0.0099 0.11 0.0013 0.0014 0.0091 0.011 0.19 0.2 0.025 -0.03 -1.6e-05 -5.7e-05 -2.5e-06 -2.6e-06 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.9e-06 0.00048 0.00048 0.00011 2 2 0.013 0.012 8.9 9 8.9 9 0.048 9.4e-09 9.3e-09 9.4e-09 9.3e-09 3.9e-09 3.7e-09 4e-06 4e-06 5.4e-08 0 0 0 0 0 0 0 0
105 10290000 0.98 -0.0055 -0.013 0.19 0.0095 0.01 0.11 0.00021 0.00029 0.01 0.012 0.2 0.21 0.026 -0.029 -1.6e-05 -5.7e-05 -2.2e-06 -2.3e-06 0 0 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.9e-06 0.00049 0.00049 0.00011 2.1 2.1 0.012 9.8 9.9 9.8 9.9 0.048 9.4e-09 9.3e-09 9.4e-09 9.3e-09 3.8e-09 3.7e-09 4e-06 4e-06 5.2e-08 0 0 0 0 0 0 0 0
106 10390000 0.98 -0.0055 -0.012 0.19 0.0069 0.007 0.005 0.0051 -0.0025 0.00075 0.00014 0.027 -0.028 -1.6e-05 -5.7e-05 -2e-06 -2.1e-06 -3.6e-10 2.5e-10 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00051 0.00051 0.00011 0.25 0.25 0.56 0.25 0.25 0.048 9.4e-09 9.3e-09 9.4e-09 9.3e-09 3.8e-09 3.6e-09 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
107 10490000 0.98 -0.0054 -0.012 0.19 0.0082 0.0083 0.0072 0.0074 0.007 0.0015 0.00071 0.00073 0.033 -0.023 -1.6e-05 -5.7e-05 -2.6e-06 -2.7e-06 -1.2e-08 8.4e-09 8.3e-09 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00053 0.00053 0.00011 0.26 0.26 0.55 0.26 0.26 0.057 9.4e-09 9.3e-09 9.4e-09 9.3e-09 3.7e-09 3.6e-09 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
108 10590000 0.98 -0.0054 -0.0053 -0.012 0.19 -0.0014 0.0051 0.0053 0.013 -0.0012 -0.0054 0.035 -0.021 -1.6e-05 -5.7e-05 -2.2e-06 -2.3e-06 3.2e-06 3.8e-08 6.7e-08 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00053 0.00053 0.00011 0.13 0.13 0.27 0.13 0.13 0.055 9.3e-09 9.2e-09 9.3e-09 9.2e-09 3.7e-09 3.5e-09 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
109 10690000 0.98 -0.0053 -0.012 0.19 -0.00043 -0.00034 0.0061 0.0064 0.016 -0.0013 -0.0049 0.038 -0.017 -1.6e-05 -5.7e-05 -2.4e-06 -2.5e-06 3.2e-06 4.5e-08 7.5e-08 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00055 0.00055 0.00011 0.14 0.14 0.26 0.14 0.14 0.065 9.3e-09 9.2e-09 9.3e-09 9.2e-09 3.6e-09 3.5e-09 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
110 10790000 0.98 -0.0054 -0.012 0.19 0.0014 0.0015 0.0026 0.0029 0.014 -0.00079 -0.00078 -0.0047 0.04 -0.015 -1.6e-05 -5.7e-05 -2.4e-06 -2.6e-06 5e-06 5.1e-06 4.6e-06 4.7e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00054 0.00054 0.00011 0.1 0.1 0.17 0.091 0.091 0.062 9.1e-09 9e-09 9.1e-09 9e-09 3.6e-09 3.4e-09 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
111 10890000 0.98 -0.0054 -0.0053 -0.012 -0.013 0.19 0.0014 0.0015 0.0059 0.0064 0.01 -0.00064 -0.00063 -0.0043 0.038 -0.018 -1.6e-05 -5.7e-05 -1.8e-06 -1.9e-06 5e-06 5.1e-06 4.6e-06 4.7e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00056 0.00056 0.00011 0.12 0.12 0.16 0.098 0.098 0.068 9.1e-09 9e-09 9.1e-09 9e-09 3.5e-09 3.4e-09 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
112 10990000 0.98 -0.0055 -0.0054 -0.013 0.19 0.00094 0.001 0.012 0.016 -0.00047 -0.00046 -0.0031 -0.003 0.044 -0.012 -1.5e-05 -1.6e-05 -5.7e-05 -2e-06 -2.1e-06 6.3e-06 6.5e-06 6.9e-06 7.2e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00053 0.00053 0.00011 0.092 0.092 0.12 0.073 0.073 0.065 8.7e-09 8.6e-09 8.7e-09 8.6e-09 3.5e-09 3.3e-09 3.9e-06 3.9e-06 5e-08 0 0 0 0 0 0 0 0
113 11090000 0.98 -0.0056 -0.0055 -0.013 0.19 0.0018 0.0019 0.017 0.02 -0.00037 -0.00036 -0.0017 -0.0016 0.048 -0.0075 -1.5e-05 -1.6e-05 -5.7e-05 -2.7e-06 -2.8e-06 6.3e-06 6.5e-06 6.9e-06 7.2e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00054 0.00054 0.00011 0.11 0.11 0.11 0.08 0.08 0.069 8.7e-09 8.6e-09 8.7e-09 8.6e-09 3.4e-09 3.3e-09 3.9e-06 3.9e-06 5e-08 0 0 0 0 0 0 0 0
114 11190000 0.98 -0.0058 -0.013 0.19 0.0035 0.0036 0.016 0.017 0.026 0.001 -0.0018 0.055 -0.00047 -1.5e-05 -5.7e-05 -3e-06 -3.1e-06 5.8e-06 6.2e-06 1.5e-05 1.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00049 0.00049 0.00011 0.092 0.092 0.083 0.063 0.063 0.066 8.1e-09 8e-09 8.1e-09 8e-09 3.3e-09 3.2e-09 3.8e-06 3.8e-06 5e-08 0 0 0 0 0 0 0 0
115 11290000 0.98 -0.0058 -0.013 0.19 0.0036 0.0037 0.018 0.026 0.0013 0.0014 -5.3e-05 2.7e-05 0.055 -0.00024 -1.5e-05 -5.7e-05 -3.2e-06 -3.3e-06 5.9e-06 6.2e-06 1.5e-05 1.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00051 0.00051 0.00011 0.11 0.11 0.077 0.07 0.07 0.069 8.1e-09 8e-09 8.1e-09 8e-09 3.3e-09 3.2e-09 3.8e-06 3.8e-06 5e-08 0 0 0 0 0 0 0 0
116 11390000 0.98 -0.006 -0.0059 -0.013 0.19 0.0021 0.0022 0.015 0.016 0.016 0.00084 0.00085 -0.00083 -0.00079 0.047 -0.0087 -1.4e-05 -5.8e-05 -3.1e-06 -3.2e-06 1.1e-05 2.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00044 0.00044 0.00011 0.093 0.093 0.062 0.057 0.057 0.066 7.4e-09 7.4e-09 3.2e-09 3.1e-09 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
117 11490000 0.98 -0.0059 -0.013 0.19 0.0011 0.0012 0.016 0.017 0.02 0.00093 0.00095 0.00076 0.00085 0.053 -0.0026 -1.4e-05 -5.8e-05 -3e-06 -3.1e-06 1.1e-05 2.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00046 0.00046 0.00011 0.11 0.11 0.057 0.065 0.065 0.067 7.4e-09 7.4e-09 3.2e-09 3e-09 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
118 11590000 0.98 -0.0062 -0.012 0.19 0.003 0.0031 0.013 0.018 0.0008 0.00081 -0.00027 -0.00023 0.052 -0.0037 -1.3e-05 -5.8e-05 -3e-06 -3.1e-06 1.4e-05 1.5e-05 2.9e-05 3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.8e-06 0.00039 0.00039 0.00011 0.092 0.092 0.048 0.054 0.054 0.065 6.8e-09 6.7e-09 6.8e-09 6.7e-09 3.1e-09 3e-09 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
119 11690000 0.98 -0.0062 -0.0061 -0.012 0.19 0.0034 0.0035 0.017 0.018 0.0011 0.0012 0.0012 0.0013 0.051 -0.0051 -1.3e-05 -5.8e-05 -2.7e-06 -2.8e-06 1.5e-05 2.9e-05 3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.0004 0.0004 0.00011 0.11 0.11 0.044 0.062 0.062 0.066 6.8e-09 6.7e-09 6.8e-09 6.7e-09 3e-09 2.9e-09 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
120 11790000 0.98 -0.0066 -0.0065 -0.012 0.19 0.0022 0.0023 0.011 0.019 0.00067 0.00068 -0.0016 0.054 -0.0021 -1.2e-05 -5.9e-05 -2e-06 -2.2e-06 2e-05 3.8e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00034 0.00034 0.00011 0.089 0.089 0.09 0.037 0.052 0.052 0.063 6.2e-09 6.2e-09 3e-09 2.9e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
121 11890000 0.98 -0.0067 -0.0066 -0.012 0.19 0.0048 0.0049 0.013 0.017 0.00096 0.00098 -0.00049 -0.00042 0.054 -0.0014 -1.2e-05 -5.9e-05 -2.1e-06 -2.2e-06 2e-05 3.8e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00035 0.00035 0.00011 0.0001 0.11 0.11 0.034 0.06 0.06 0.063 6.2e-09 6.2e-09 2.9e-09 2.8e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
122 11990000 0.98 -0.0068 -0.012 0.19 0.0078 0.0079 0.012 0.013 0.015 0.0021 -0.0017 -0.0016 0.051 -0.0051 -1.2e-05 -5.9e-05 -1.8e-06 -2e-06 2e-05 4e-05 4.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.0003 0.0003 0.00011 0.086 0.086 0.03 0.051 0.051 0.061 5.7e-09 5.7e-09 2.9e-09 2.8e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
123 12090000 0.98 -0.0067 -0.012 0.19 0.0094 0.0095 0.012 0.013 0.018 0.0029 0.003 -0.00044 -0.00037 0.057 0.00096 -1.2e-05 -5.9e-05 -1.8e-06 -1.9e-06 1.9e-05 2e-05 4e-05 4.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00031 0.00031 0.00011 0.1 0.1 0.027 0.059 0.059 0.06 5.7e-09 5.7e-09 2.8e-09 2.7e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
124 12190000 0.98 -0.0066 -0.012 0.19 0.0076 0.0077 0.012 0.017 0.0018 0.00052 0.00055 0.058 0.0028 -1.2e-05 -5.9e-05 -2e-06 -2.1e-06 2.2e-05 2.3e-05 3.9e-05 4.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00027 0.00027 0.00011 0.0001 0.081 0.081 0.024 0.05 0.05 0.058 5.3e-09 5.3e-09 2.8e-09 2.7e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
125 12290000 0.98 -0.0067 -0.012 0.19 0.0053 0.0054 0.011 0.016 0.0024 0.0017 0.059 0.0038 -1.2e-05 -5.9e-05 -2.2e-06 -2.3e-06 2.2e-05 2.3e-05 3.9e-05 4.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00028 0.00028 0.00011 0.096 0.096 0.022 0.059 0.059 0.058 5.3e-09 5.3e-09 2.7e-09 2.6e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
126 12390000 0.98 -0.0068 -0.012 0.19 0.0039 0.004 0.0076 0.0078 0.014 0.0017 0.00062 0.00064 0.053 -0.0022 -1.2e-05 -5.9e-05 -2.1e-06 -2.2e-06 2.5e-05 2.6e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00025 0.00025 0.00011 0.076 0.076 0.02 0.05 0.05 0.056 5e-09 4.9e-09 5e-09 4.9e-09 2.6e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
127 12490000 0.98 -0.0068 -0.012 0.19 0.0039 0.004 0.0087 0.0089 0.018 0.0021 0.0014 0.0015 0.055 -0.00019 -1.2e-05 -5.9e-05 -2.1e-06 -2.2e-06 2.5e-05 2.6e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00026 0.00026 0.00011 0.0001 0.089 0.089 0.018 0.058 0.058 0.055 5e-09 4.9e-09 5e-09 4.9e-09 2.6e-09 2.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
128 12590000 0.98 -0.007 -0.012 0.19 0.0077 0.0078 0.002 0.0022 0.02 0.0033 -0.0012 0.057 0.0016 -1.1e-05 -5.9e-05 -2.1e-06 -2.2e-06 2.5e-05 2.6e-05 4.4e-05 4.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00023 0.00023 0.00011 0.071 0.071 0.017 0.049 0.049 0.054 4.7e-09 4.7e-09 2.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
129 12690000 0.98 -0.007 -0.012 0.19 0.0082 0.0083 -0.00012 9.1e-05 0.019 0.004 -0.0011 0.059 0.0032 -1.1e-05 -5.9e-05 -2e-06 -2.1e-06 2.5e-05 2.6e-05 4.4e-05 4.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00024 0.00024 0.00011 0.0001 0.083 0.083 0.016 0.058 0.058 0.053 4.7e-09 4.7e-09 2.5e-09 2.4e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
130 12790000 0.98 -0.0072 -0.012 0.19 0.0098 0.0099 -0.0036 -0.0034 0.021 0.0041 -0.0043 0.061 0.0053 -1.1e-05 -5.9e-05 -1.1e-06 -1.2e-06 2.6e-05 2.7e-05 4.5e-05 4.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00022 0.00022 0.00011 0.0001 0.067 0.067 0.014 0.049 0.049 0.052 4.5e-09 4.4e-09 4.5e-09 4.4e-09 2.4e-09 2.3e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
131 12890000 0.98 -0.0072 -0.012 0.19 0.01 -0.0044 -0.0042 0.022 0.0051 -0.0047 -0.0046 0.064 0.0083 -1.1e-05 -5.9e-05 -5.5e-07 -6.7e-07 2.6e-05 2.7e-05 4.5e-05 4.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.7e-06 0.00023 0.00023 0.00011 0.0001 0.077 0.077 0.013 0.058 0.058 0.051 4.5e-09 4.4e-09 4.5e-09 4.4e-09 2.4e-09 2.3e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
132 12990000 0.98 -0.0072 -0.012 0.19 0.0079 0.008 -0.0025 -0.0023 0.022 0.0036 -0.0035 -0.0034 0.065 0.0095 -1.1e-05 -6e-05 -7.6e-10 -1.2e-07 2.7e-05 4.4e-05 4.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 8.6e-06 0.00021 0.00021 0.00011 0.0001 0.063 0.063 0.012 0.049 0.049 0.05 4.2e-09 4.2e-09 2.3e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
133 13090000 0.98 -0.0072 -0.012 0.19 0.0088 0.0089 -0.0023 -0.0022 0.02 0.0044 -0.0036 0.064 0.0084 -1.1e-05 -6e-05 7e-07 5.7e-07 2.7e-05 2.8e-05 4.4e-05 4.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.00022 0.00022 0.00011 0.0001 0.072 0.072 0.012 0.057 0.057 0.049 4.2e-09 4.2e-09 2.3e-09 2.2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
134 13190000 0.98 -0.0072 -0.012 0.19 0.0039 -0.0041 -0.0039 0.019 0.00095 0.00096 -0.0045 -0.0044 0.065 0.009 -1.1e-05 -6e-05 1.2e-06 1e-06 2.8e-05 2.9e-05 4.3e-05 4.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.00021 0.00021 0.00011 0.0001 0.059 0.059 0.011 0.049 0.049 0.047 4e-09 4e-09 2.2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
135 13290000 0.98 -0.0073 -0.012 0.19 0.0035 0.0036 -0.005 -0.0048 0.016 0.0013 -0.0049 -0.0048 0.064 0.0083 -1.1e-05 -6e-05 1.3e-06 1.1e-06 2.8e-05 2.9e-05 4.3e-05 4.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.00021 0.00021 0.00011 0.0001 0.067 0.067 0.01 0.057 0.057 0.047 4e-09 4e-09 2.2e-09 2.1e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
136 13390000 0.98 -0.0072 -0.012 0.19 0.0027 -0.0031 -0.0029 0.016 0.00085 -0.0036 0.065 0.009 -1.1e-05 -6e-05 1.1e-06 9.8e-07 2.9e-05 3e-05 4.3e-05 4.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.0002 0.0002 0.0001 0.056 0.056 0.0097 0.049 0.049 0.046 3.8e-09 3.8e-09 2.1e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
137 13490000 0.98 -0.0072 -0.012 0.19 0.0031 0.0032 -0.0014 -0.0012 0.015 0.0011 0.0012 -0.0038 0.061 0.0051 -1.1e-05 -6e-05 1.3e-06 1.2e-06 3e-05 3.1e-05 4.2e-05 4.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.00021 0.00021 0.0001 0.063 0.063 0.0093 0.056 0.056 0.045 3.8e-09 3.8e-09 2.1e-09 2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
138 13590000 0.98 -0.0072 -0.012 0.19 0.0076 -0.0016 -0.0015 0.017 0.004 -0.0031 0.059 0.0036 -1.1e-05 -6e-05 1.2e-06 1.1e-06 3.1e-05 3.2e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.0002 0.0002 0.0001 0.053 0.053 0.0088 0.048 0.048 0.044 3.7e-09 3.6e-09 3.7e-09 3.6e-09 2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
139 13690000 0.98 -0.0071 -0.012 0.19 0.0076 -0.003 -0.0029 0.017 0.0047 0.0048 -0.0033 0.062 0.0063 -1.1e-05 -6e-05 1.6e-06 1.5e-06 3.1e-05 3.2e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.0002 0.0002 0.0001 0.06 0.06 0.0085 0.056 0.056 0.044 3.7e-09 3.6e-09 3.7e-09 3.6e-09 2e-09 1.9e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
140 13790000 0.98 -0.0071 -0.012 0.19 0.015 0.0011 0.017 0.0083 -0.00087 -0.00086 0.061 0.0058 -1.1e-05 -5.9e-05 1.5e-06 1.4e-06 3.5e-05 3.6e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.0002 0.0002 0.0001 0.05 0.05 0.0082 0.048 0.048 0.043 3.5e-09 3.5e-09 1.9e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
141 13890000 0.98 -0.007 -0.012 0.19 0.016 0.0018 0.0019 0.018 0.0098 -0.00072 -0.0007 0.064 0.008 -1.1e-05 -5.9e-05 2e-06 1.9e-06 3.5e-05 3.6e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.6e-06 0.0002 0.0002 0.0001 0.057 0.057 0.008 0.056 0.056 0.042 3.5e-09 3.5e-09 1.9e-09 1.8e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
142 13990000 0.98 -0.0071 -0.007 -0.012 0.19 0.015 0.0019 0.002 0.017 0.0074 -0.0022 0.062 0.0069 -1.1e-05 -5.9e-05 2.5e-06 2.4e-06 3.3e-05 3.4e-05 3.9e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.5e-06 0.00019 0.00019 0.0001 0.048 0.048 0.0077 0.048 0.048 0.041 3.3e-09 3.3e-09 1.8e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
143 14090000 0.98 -0.0071 -0.012 0.19 0.013 -0.0025 -0.0024 0.018 0.0088 -0.0023 0.059 0.0033 -1.1e-05 -5.9e-05 1.5e-06 3.4e-05 3.5e-05 3.8e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.5e-06 0.0002 0.0002 0.0001 0.055 0.055 0.0075 0.0076 0.055 0.055 0.041 3.3e-09 3.3e-09 1.8e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
144 14190000 0.98 -0.007 -0.012 0.19 0.01 -0.0012 0.018 0.008 -0.0017 0.059 0.0035 -1.1e-05 -5.9e-05 1.1e-06 1e-06 3.5e-05 3.6e-05 3.8e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.5e-06 0.00019 0.00019 0.0001 0.046 0.046 0.0074 0.048 0.048 0.04 3.1e-09 3.1e-09 1.8e-09 1.7e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
145 14290000 0.98 -0.007 -0.011 0.19 0.012 -0.0013 -0.0012 0.016 0.009 -0.0019 -0.0018 0.063 0.0078 -1.1e-05 -6e-05 1.2e-06 1.1e-06 3.5e-05 3.6e-05 3.8e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 8.5e-06 0.0002 0.0002 0.0001 0.053 0.052 0.053 0.052 0.0073 0.055 0.055 0.04 3.1e-09 3.1e-09 1.7e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
146 14390000 0.98 -0.0071 -0.011 0.19 0.012 -0.0043 -0.0042 0.017 0.0084 -0.003 0.068 0.012 -1.1e-05 -6e-05 1.5e-06 3.4e-05 3.7e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 8.5e-06 0.00019 0.00019 0.0001 0.045 0.045 0.0071 0.048 0.048 0.039 3e-09 3e-09 1.7e-09 1.6e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
147 14490000 0.98 -0.0072 -0.011 0.19 0.01 -0.004 0.021 0.0095 -0.0034 0.07 0.014 -1.1e-05 -6e-05 1.1e-06 1e-06 3.3e-05 3.4e-05 3.7e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 8.5e-06 0.0002 0.0002 0.0001 0.051 0.051 0.0071 0.055 0.055 0.038 3e-09 3e-09 1.6e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
148 14590000 0.98 -0.0073 -0.0072 -0.011 0.19 0.0081 -0.0042 -0.0041 0.019 0.0059 -0.0041 0.066 0.01 -1.1e-05 -6e-05 1e-06 9.8e-07 3.1e-05 3.2e-05 3.6e-05 3.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 8.5e-06 0.00019 0.00019 0.0001 0.044 0.044 0.007 0.047 0.047 0.038 2.8e-09 2.8e-09 1.6e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
149 14690000 0.98 -0.0073 -0.0072 -0.011 0.19 0.0073 -0.0041 0.019 0.0067 -0.0045 0.066 0.011 -1.1e-05 -6e-05 1.2e-06 3.2e-05 3.3e-05 3.5e-05 3.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 8.5e-06 0.0002 0.00019 0.00019 0.0001 0.049 0.049 0.007 0.054 0.054 0.037 2.8e-09 2.8e-09 1.6e-09 1.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
150 14790000 0.98 -0.0072 -0.011 0.19 0.009 0.0028 0.019 0.0053 0.00084 0.00085 0.069 0.013 -1.2e-05 -6e-05 1.8e-06 3.2e-05 3.3e-05 4.4e-05 4.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 8.4e-06 0.00019 0.00019 0.0001 9.9e-05 0.043 0.042 0.043 0.042 0.0069 0.047 0.047 0.037 2.6e-09 2.6e-09 1.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
151 14890000 0.98 -0.0071 -0.011 0.19 0.0077 0.00041 0.00044 0.023 0.0061 0.001 0.07 0.014 -1.2e-05 -6e-05 2.3e-06 2.2e-06 3.3e-05 3.4e-05 4.3e-05 4.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 8.4e-06 0.00019 0.00019 0.0001 9.9e-05 0.048 0.048 0.007 0.054 0.054 0.037 2.6e-09 2.6e-09 1.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
152 14990000 0.98 -0.0072 -0.011 0.19 0.0064 0.0065 -0.0012 0.026 0.0048 -0.00062 -0.00061 0.072 0.016 -1.2e-05 -6e-05 2.5e-06 3.1e-05 3.2e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 8.4e-06 0.00019 0.00019 0.0001 9.9e-05 0.042 0.042 0.0069 0.047 0.047 0.036 2.5e-09 2.5e-09 1.5e-09 1.4e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
153 15090000 0.98 -0.0072 -0.011 0.19 0.0065 -0.00014 -0.00012 0.03 0.0054 -0.00073 -0.00072 0.074 0.019 -1.2e-05 -6e-05 2.5e-06 3.1e-05 3.2e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 8.4e-06 0.00019 0.00019 9.9e-05 9.8e-05 0.047 0.047 0.007 0.054 0.054 0.036 2.5e-09 2.5e-09 1.4e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
154 15190000 0.98 -0.0073 -0.011 0.19 0.0046 -0.0012 0.03 0.0043 -0.00069 -0.00068 0.076 0.021 -1.2e-05 -6.1e-05 2.4e-06 3.1e-05 3.2e-05 4.1e-05 4.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 8.4e-06 0.00018 0.00018 9.9e-05 9.8e-05 0.041 0.041 0.007 0.047 0.047 0.036 2.3e-09 2.3e-09 1.4e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
155 15290000 0.98 -0.0074 -0.011 0.19 0.0052 0.0053 -0.0023 0.03 0.0048 -0.00084 -0.00083 0.073 0.017 -1.2e-05 -6e-05 2.8e-06 3.3e-05 3.4e-05 3.8e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 8.4e-06 0.00019 0.00019 9.8e-05 0.046 0.046 0.0071 0.054 0.054 0.035 2.3e-09 2.3e-09 1.4e-09 1.3e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
156 15390000 0.98 -0.0075 -0.011 0.19 0.0054 0.0055 6.3e-05 7e-05 0.029 0.0038 -0.00057 -0.00056 0.073 0.018 -1.2e-05 -6.1e-05 2.8e-06 3.4e-05 3.5e-05 3.8e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 8.3e-06 0.00018 0.00018 9.8e-05 9.7e-05 0.04 0.04 0.007 0.047 0.047 0.035 2.2e-09 2.1e-09 2.2e-09 2.1e-09 1.3e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
157 15490000 0.98 -0.0075 -0.011 0.19 0.0049 -0.0025 -0.0024 0.029 0.0043 -0.00066 -0.00065 0.074 0.019 -1.2e-05 -6.1e-05 2.8e-06 3.5e-05 3.6e-05 3.7e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 8.3e-06 0.00019 0.00019 9.8e-05 9.7e-05 0.045 0.045 0.0072 0.053 0.053 0.035 2.2e-09 2.1e-09 2.2e-09 2.1e-09 1.3e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
158 15590000 0.98 -0.0077 -0.011 0.19 0.0084 -0.0063 0.029 0.0063 -0.0046 0.073 0.017 -1.1e-05 -6.1e-05 3.1e-06 3.8e-05 3.9e-05 2.6e-05 2.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 8.3e-06 0.00018 0.00018 9.7e-05 9.6e-05 0.04 0.04 0.0072 0.046 0.046 0.035 2e-09 2e-09 1.3e-09 1.2e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
159 15690000 0.98 -0.0077 -0.011 0.19 0.01 -0.0094 -0.0093 0.029 0.0072 -0.0054 0.074 0.018 -1.1e-05 -6.1e-05 3.5e-06 3.4e-06 3.9e-05 4e-05 2.6e-05 2.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 8.3e-06 0.00018 0.00018 9.6e-05 0.045 0.044 0.045 0.0073 0.053 0.053 0.034 2e-09 2e-09 1.2e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
160 15790000 0.98 -0.0077 -0.011 0.19 0.0067 -0.0087 0.029 0.0055 -0.0042 0.076 0.02 -1.1e-05 -6.1e-05 4e-06 3.7e-05 3.8e-05 3e-05 3.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 8.3e-06 0.00018 0.00017 9.6e-05 9.5e-05 0.039 0.039 0.0073 0.046 0.046 0.034 1.8e-09 1.8e-09 1.2e-09 3.3e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
161 15890000 0.98 -0.0078 -0.0077 -0.011 0.19 0.0056 -0.0071 0.03 0.0061 0.0062 -0.005 0.075 0.02 -1.1e-05 -6.1e-05 3.6e-06 4e-05 4.1e-05 2.8e-05 2.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 8.3e-06 0.00018 0.00018 9.6e-05 9.5e-05 0.044 0.044 0.0074 0.053 0.053 0.034 1.8e-09 1.8e-09 1.2e-09 3.3e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
162 15990000 0.98 -0.0076 -0.0075 -0.011 0.19 0.0035 -0.0057 0.027 0.0048 0.0049 -0.0038 0.074 0.019 -1.2e-05 -6.1e-05 3.6e-06 4.1e-05 4.2e-05 2.8e-05 2.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 8.2e-06 0.00017 0.00017 9.5e-05 9.4e-05 0.039 0.038 0.039 0.038 0.0074 0.046 0.046 0.034 1.7e-09 1.7e-09 1.2e-09 1.1e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
163 16090000 0.98 -0.0075 -0.011 0.19 0.0029 -0.0069 0.024 0.0051 -0.0045 0.074 0.019 -1.2e-05 -6.1e-05 3.4e-06 4.3e-05 4.4e-05 2.7e-05 2.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 8.2e-06 0.00018 0.00018 0.00017 9.4e-05 0.043 0.043 0.0076 0.053 0.053 0.034 1.7e-09 1.7e-09 1.1e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
164 16190000 0.98 -0.0074 -0.011 0.19 -0.001 -0.0046 0.023 0.0028 -0.0033 0.071 0.016 -1.2e-05 -6.1e-05 3.1e-06 4.4e-05 4.5e-05 2.8e-05 2.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 8.2e-06 0.00017 0.00017 9.4e-05 0.038 0.038 0.0076 0.046 0.046 0.034 1.6e-09 1.5e-09 1.6e-09 1.5e-09 1.1e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
165 16290000 0.98 -0.0075 -0.011 0.19 -0.0007 -0.00067 -0.0061 0.023 0.0026 0.0027 -0.0039 0.072 0.017 -1.2e-05 -6.1e-05 3.3e-06 4.4e-05 4.5e-05 2.7e-05 2.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 8.2e-06 0.00017 0.00017 9.4e-05 9.3e-05 0.043 0.043 0.0077 0.053 0.053 0.034 1.6e-09 1.5e-09 1.6e-09 1.5e-09 1.1e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
166 16390000 0.98 -0.0074 -0.011 0.19 0.0017 0.0018 -0.0054 -0.0055 0.023 0.0037 -0.0029 0.072 0.017 -1.2e-05 -6.1e-05 3.6e-06 5e-05 5.1e-05 2.7e-05 2.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 8.2e-06 0.00016 0.00016 9.3e-05 9.2e-05 0.038 0.037 0.038 0.0077 0.046 0.046 0.034 1.4e-09 1.4e-09 1.1e-09 1e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
167 16490000 0.98 -0.0075 -0.011 0.19 0.0037 -0.007 0.026 0.0039 -0.0036 0.077 0.021 -1.2e-05 -6.1e-05 3.5e-06 4.9e-05 5e-05 2.8e-05 2.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 8.2e-06 0.00017 0.00017 9.3e-05 9.2e-05 0.042 0.042 0.0079 0.053 0.052 0.053 0.034 1.4e-09 1.4e-09 1e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
168 16590000 0.98 -0.0075 -0.011 0.19 0.0078 -0.0071 0.029 0.0034 -0.0028 0.077 0.021 -1.2e-05 -6.1e-05 3.5e-06 5e-05 5.1e-05 2.9e-05 3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 8.1e-06 0.00016 0.00016 9.2e-05 0.037 0.037 0.0079 0.046 0.046 0.034 1.3e-09 1.3e-09 1e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
169 16690000 0.98 -0.0076 -0.011 0.19 0.0092 0.0093 -0.012 0.029 0.0043 -0.0037 0.077 0.022 -1.2e-05 -6.1e-05 3.7e-06 5.1e-05 5.2e-05 2.8e-05 2.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 8.1e-06 0.00016 0.00016 9.2e-05 9.1e-05 0.041 0.042 0.041 0.008 0.052 0.052 0.034 1.3e-09 1.3e-09 9.9e-10 9.8e-10 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
170 16790000 0.98 -0.0074 -0.011 0.19 0.01 -0.011 0.028 0.0033 -0.0027 0.077 0.022 -1.2e-05 -6.1e-05 3.8e-06 5.2e-05 5.3e-05 3.1e-05 3.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 8.1e-06 0.00016 0.00015 9.1e-05 0.036 0.037 0.036 0.008 0.046 0.046 0.034 1.2e-09 1.2e-09 9.7e-10 9.6e-10 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
171 16890000 0.98 -0.0074 -0.011 0.19 0.0091 0.0092 -0.011 0.029 0.0043 -0.0037 0.076 0.02 -1.2e-05 -6.1e-05 4.2e-06 5.5e-05 5.6e-05 2.9e-05 3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 8.1e-06 0.00016 0.00016 9.1e-05 9e-05 0.041 0.041 0.0082 0.052 0.052 0.034 1.2e-09 1.2e-09 9.5e-10 9.3e-10 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
172 16990000 0.98 -0.0074 -0.011 0.19 0.0088 -0.01 0.029 0.0041 -0.0028 0.074 0.019 -1.3e-05 -6.1e-05 4.3e-06 6.1e-05 6.2e-05 2.9e-05 3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 8e-06 0.00015 0.00015 9e-05 0.036 0.036 0.0082 0.046 0.046 0.034 1.1e-09 1.1e-09 9.3e-10 9.1e-10 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
173 17090000 0.98 -0.0075 -0.011 0.19 0.01 -0.013 0.028 0.0051 -0.004 0.074 0.018 -1.3e-05 -1.2e-05 -6.1e-05 4.2e-06 6.3e-05 6.4e-05 2.7e-05 2.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 8e-06 0.00015 0.00015 9e-05 8.9e-05 0.04 0.04 0.0083 0.052 0.052 0.034 1.1e-09 1.1e-09 9.1e-10 8.9e-10 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
174 17190000 0.98 -0.0076 -0.011 0.19 0.0092 -0.018 0.03 0.0034 -0.0075 0.077 0.021 -1.2e-05 -6.1e-05 3.8e-06 6.1e-05 6.2e-05 2.4e-05 2.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 8e-06 0.00015 0.00015 8.9e-05 0.035 0.035 0.0083 0.046 0.046 0.034 9.7e-10 9.7e-10 8.9e-10 8.8e-10 3.1e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
175 17290000 0.98 -0.0076 -0.011 0.19 0.01 -0.019 0.03 0.0044 -0.0093 0.077 0.021 -1.2e-05 -6.1e-05 3.5e-06 6.4e-05 6.5e-05 2.2e-05 2.4e-05 -0.0013 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 8e-06 0.00015 0.00015 8.9e-05 8.8e-05 0.039 0.039 0.0084 0.052 0.052 0.034 9.7e-10 9.7e-10 8.7e-10 8.6e-10 3.1e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
176 17390000 0.98 -0.0074 -0.011 0.19 0.0069 -0.018 0.029 0.0058 -0.0059 0.076 0.021 -1.3e-05 -6e-05 3.8e-06 7.2e-05 7.3e-05 2.8e-05 2.9e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 8e-06 0.00014 0.00014 8.8e-05 0.035 0.035 0.0084 0.046 0.046 0.034 8.8e-10 8.8e-10 8.5e-10 8.4e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
177 17490000 0.98 -0.0075 -0.011 0.19 0.005 -0.019 0.029 0.0063 -0.0077 0.078 0.022 -1.3e-05 -6e-05 3.6e-06 7.2e-05 7.3e-05 2.7e-05 2.8e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 8e-06 0.00015 0.00014 8.8e-05 0.039 0.039 0.0085 0.052 0.052 0.034 8.8e-10 8.8e-10 8.3e-10 8.2e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
178 17590000 0.98 -0.0074 -0.0073 -0.011 0.19 0.0011 -0.015 0.028 0.0025 -0.0058 0.076 0.02 -1.3e-05 -6.1e-05 3.6e-06 7.1e-05 7.2e-05 3.2e-05 3.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 7.9e-06 0.00014 0.00014 8.7e-05 0.034 0.034 0.0085 0.046 0.046 0.034 8e-10 7.9e-10 8e-10 7.9e-10 8.2e-10 8e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
179 17690000 0.98 -0.0075 -0.0074 -0.011 0.19 0.00019 0.00022 -0.016 0.029 0.0026 -0.0073 0.078 0.022 -1.3e-05 -6.1e-05 3.6e-06 3.7e-06 7.2e-05 7.3e-05 3.2e-05 3.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 7.9e-06 0.00014 0.00014 8.7e-05 8.6e-05 0.038 0.038 0.0086 0.052 0.052 0.034 8e-10 7.9e-10 8e-10 7.9e-10 8e-10 7.9e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
180 17790000 0.98 -0.0074 -0.011 0.19 0.0028 -0.014 0.029 0.0035 0.0036 -0.0062 0.083 0.028 -1.4e-05 -6e-05 3.7e-06 7.5e-05 7.6e-05 3.8e-05 3.9e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 7.9e-06 0.00014 0.00013 8.7e-05 8.6e-05 0.033 0.033 0.0086 0.045 0.045 0.034 7.2e-10 7.2e-10 7.8e-10 7.7e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
181 17890000 0.98 -0.0073 -0.011 0.19 0.0049 0.005 -0.016 0.029 0.004 -0.0077 0.088 0.032 -1.4e-05 -6e-05 3.8e-06 7.4e-05 7.5e-05 3.9e-05 4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 7.9e-06 0.00014 0.00014 8.6e-05 0.037 0.037 0.0086 0.052 0.052 0.035 7.2e-10 7.2e-10 7.7e-10 7.6e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
182 17990000 0.98 -0.0071 -0.011 0.19 0.0043 -0.0092 -0.0093 0.029 0.0031 0.0032 -0.0019 -0.002 0.088 0.033 -1.4e-05 -6e-05 3.7e-06 3.8e-06 7.8e-05 7.9e-05 4.9e-05 5.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 7.9e-06 0.00013 0.00013 8.5e-05 0.033 0.033 0.0086 0.045 0.045 0.034 6.5e-10 6.5e-10 7.5e-10 7.4e-10 3e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
183 18090000 0.98 -0.0072 -0.011 0.19 0.0038 0.0039 -0.0097 -0.0098 0.028 0.0036 0.0037 -0.0029 -0.003 0.086 0.031 -1.4e-05 -6e-05 3.7e-06 8.1e-05 8.2e-05 4.7e-05 4.9e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 7.8e-06 0.00013 0.00013 8.5e-05 0.036 0.036 0.0087 0.052 0.051 0.052 0.051 0.035 6.5e-10 6.5e-10 7.3e-10 3e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
184 18190000 0.98 -0.0072 -0.011 0.19 0.0039 -0.0087 -0.0088 0.028 0.0042 -0.0022 0.084 0.029 -1.4e-05 -6e-05 4.1e-06 8.7e-05 8.8e-05 4.6e-05 4.8e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 7.8e-06 0.00013 0.00013 8.5e-05 8.4e-05 0.032 0.032 0.0086 0.045 0.045 0.035 5.9e-10 5.9e-10 7.2e-10 7.1e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
185 18290000 0.98 -0.0072 -0.011 0.19 0.0048 -0.0092 -0.0093 0.027 0.0046 -0.003 -0.0031 0.083 0.027 -1.4e-05 -6e-05 4.1e-06 8.9e-05 9e-05 4.4e-05 4.6e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 7.8e-06 0.00013 0.00013 8.4e-05 0.035 0.035 0.0087 0.051 0.051 0.035 5.9e-10 5.9e-10 7e-10 6.9e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
186 18390000 0.98 -0.0072 -0.0071 -0.011 0.19 0.0056 0.0057 -0.0079 -0.008 0.027 0.0062 -0.0023 0.082 0.026 -1.4e-05 -6e-05 3.9e-06 4e-06 9.5e-05 9.6e-05 4.4e-05 4.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 7.8e-06 0.00012 0.00012 8.3e-05 0.031 0.031 0.0086 0.045 0.045 0.035 5.3e-10 5.3e-10 6.9e-10 6.8e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
187 18490000 0.98 -0.0072 -0.011 0.19 0.0084 -0.0079 -0.008 0.026 0.007 -0.0031 0.083 0.028 -1.4e-05 -6e-05 4.1e-06 9.5e-05 9.7e-05 4.3e-05 4.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 7.8e-06 0.00013 0.00013 8.3e-05 0.035 0.034 0.035 0.034 0.0087 0.051 0.051 0.035 5.3e-10 5.3e-10 6.8e-10 6.7e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
188 18590000 0.98 -0.007 -0.011 0.19 0.0068 -0.0073 -0.0074 0.026 0.0056 -0.0024 0.086 0.03 -1.5e-05 -6e-05 3.8e-06 3.9e-06 9.4e-05 9.5e-05 4.6e-05 4.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 7.8e-06 0.00012 0.00012 8.3e-05 8.2e-05 0.03 0.031 0.03 0.0087 0.045 0.045 0.035 4.8e-10 4.8e-10 6.6e-10 6.5e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
189 18690000 0.98 -0.007 -0.011 0.19 0.0068 0.0069 -0.0063 0.024 0.0063 -0.0031 0.085 0.029 -1.5e-05 -6e-05 4e-06 9.6e-05 9.8e-05 4.4e-05 4.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3e-06 7.7e-06 0.00012 0.00012 8.2e-05 0.034 0.034 0.0087 0.051 0.051 0.035 4.8e-10 4.8e-10 6.5e-10 6.4e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
190 18790000 0.98 -0.007 -0.011 0.19 0.0058 -0.0059 -0.006 0.023 0.024 0.0063 -0.0025 0.082 0.027 -1.5e-05 -6e-05 3.9e-06 4e-06 0.0001 4.3e-05 4.4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3e-06 7.7e-06 0.00012 0.00012 8.2e-05 0.03 0.03 0.0087 0.045 0.045 0.035 4.4e-10 4.4e-10 6.4e-10 6.3e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
191 18890000 0.98 -0.0069 -0.011 0.19 0.0045 -0.0056 0.021 0.0068 -0.0031 -0.0032 0.078 0.023 -1.5e-05 -6e-05 3.8e-06 0.0001 4e-05 4.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3e-06 7.7e-06 0.00012 0.00012 8.1e-05 0.033 0.033 0.0087 0.051 0.051 0.035 4.4e-10 4.4e-10 6.2e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
192 18990000 0.98 -0.0069 -0.011 0.19 0.0028 0.0029 -0.0057 0.022 0.0056 -0.0025 0.082 0.026 -1.5e-05 -6e-05 3.7e-06 3.8e-06 0.0001 4.2e-05 4.4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3e-06 7.7e-06 0.00012 0.00011 8.1e-05 0.029 0.029 0.0086 0.045 0.045 0.035 4e-10 4e-10 6.1e-10 6e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
193 19090000 0.98 -0.007 -0.011 0.19 0.00086 0.00087 -0.0062 0.023 0.0059 -0.003 -0.0031 0.078 0.022 -1.5e-05 -6e-05 3.9e-06 0.00011 3.9e-05 4.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3e-06 7.7e-06 0.00012 0.00012 8.1e-05 8e-05 0.032 0.032 0.0087 0.051 0.051 0.036 4e-10 4e-10 6e-10 5.9e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
194 19190000 0.98 -0.0069 -0.011 0.19 -0.00065 -0.00064 -0.0058 -0.0059 0.022 0.0049 -0.0025 0.077 0.021 -1.5e-05 -6e-05 3.5e-06 0.00011 4e-05 4.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 3e-06 7.7e-06 0.00011 0.00011 8e-05 0.028 0.028 0.0086 0.045 0.045 0.036 3.6e-10 3.6e-10 5.9e-10 5.8e-10 2.9e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
195 19290000 0.98 -0.0068 -0.011 0.19 -0.0015 -0.0057 0.023 0.0048 -0.003 -0.0031 0.076 0.02 -1.5e-05 -6e-05 3.4e-06 0.00011 3.8e-05 4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 7.6e-06 0.00011 0.00011 8e-05 7.9e-05 0.031 0.031 0.0087 0.05 0.05 0.036 3.6e-10 3.6e-10 5.8e-10 5.7e-10 2.9e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
196 19390000 0.98 -0.0069 -0.011 0.19 -0.002 -0.0022 0.024 0.0041 -0.0011 -0.0012 0.075 0.019 -1.5e-05 -6e-05 3.3e-06 0.00011 4e-05 4.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 7.6e-06 0.00011 0.00011 7.9e-05 0.028 0.028 0.0086 0.045 0.045 0.036 3.3e-10 3.3e-10 5.7e-10 5.6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
197 19490000 0.98 -0.007 -0.0069 -0.011 0.19 -0.0028 -0.0022 0.023 0.0039 -0.0014 0.074 0.019 -1.5e-05 -6e-05 3e-06 0.00011 3.9e-05 4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 7.6e-06 0.00011 0.00011 7.9e-05 0.03 0.03 0.0087 0.05 0.05 0.036 3.3e-10 3.3e-10 5.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
198 19590000 0.98 -0.0069 -0.011 0.19 -0.0039 -0.0051 0.025 0.0044 -0.0024 0.075 0.019 -1.5e-05 -6e-05 2.9e-06 0.00011 0.00012 3.6e-05 3.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 7.6e-06 0.00011 0.00011 7.8e-05 0.027 0.027 0.0086 0.044 0.044 0.036 3e-10 3e-10 5.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
199 19690000 0.98 -0.0069 -0.011 0.19 -0.0056 -0.0055 -0.0036 -0.0037 0.023 0.004 -0.0028 0.074 0.018 -1.5e-05 -6e-05 3e-06 3.1e-06 0.00012 3.4e-05 3.6e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 7.6e-06 0.00011 0.00011 7.8e-05 0.03 0.03 0.0086 0.05 0.05 0.036 3e-10 3e-10 5.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
200 19790000 0.98 -0.007 -0.011 0.19 -0.0056 -0.0022 0.022 0.0064 -0.0023 0.07 0.014 -1.5e-05 -6e-05 2.8e-06 0.00012 3.1e-05 3.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 7.6e-06 0.00011 0.0001 7.8e-05 7.7e-05 0.026 0.026 0.0086 0.044 0.044 0.036 2.8e-10 2.8e-10 5.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
201 19890000 0.98 -0.0071 -0.007 -0.011 0.19 -0.0056 -0.0019 -0.002 0.022 0.0058 -0.0025 0.068 0.013 -1.5e-05 -6e-05 2.7e-06 0.00012 0.00013 3e-05 3.2e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 7.6e-06 0.00011 0.00011 7.7e-05 0.029 0.029 0.0086 0.05 0.05 0.036 2.8e-10 2.8e-10 5.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
202 19990000 0.98 -0.0071 -0.011 0.19 -0.0053 -0.0019 0.019 0.0062 -0.00088 -0.00091 0.065 0.0096 -1.5e-05 -5.9e-05 2.7e-06 2.8e-06 0.00013 2.9e-05 3.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 7.5e-06 0.0001 0.0001 7.6e-05 0.026 0.026 0.0085 0.044 0.044 0.036 2.5e-10 2.5e-10 5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
203 20090000 0.98 -0.0071 -0.011 0.19 -0.0048 -0.0041 0.019 0.0056 -0.0012 0.068 0.013 -1.5e-05 -5.9e-05 2.7e-06 0.00013 3e-05 3.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 7.5e-06 0.00011 0.0001 7.6e-05 0.028 0.028 0.0086 0.05 0.05 0.036 2.5e-10 2.5e-10 4.9e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
204 20190000 0.98 -0.0071 -0.011 0.19 -0.0038 -0.0015 -0.0016 0.02 0.0066 -0.00088 -0.0009 0.068 0.013 -1.5e-05 -5.9e-05 2.4e-06 2.5e-06 0.00013 2.9e-05 3.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 7.5e-06 0.0001 0.0001 7.6e-05 0.025 0.025 0.0085 0.044 0.044 0.036 2.3e-10 2.3e-10 4.9e-10 4.8e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
205 20290000 0.98 -0.0071 -0.007 -0.011 0.19 -0.007 -0.0026 -0.0027 0.02 0.0061 -0.001 -0.0011 0.069 0.013 -1.5e-05 -5.9e-05 2.3e-06 2.4e-06 0.00013 2.9e-05 3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 7.5e-06 0.0001 0.0001 7.5e-05 0.027 0.027 0.0085 0.049 0.049 0.036 2.3e-10 2.3e-10 4.8e-10 4.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
206 20390000 0.98 -0.007 -0.011 0.19 -0.0077 -0.0014 -0.0015 0.02 0.021 0.0069 -0.00075 -0.00077 0.07 0.014 -1.5e-05 -5.9e-05 2.5e-06 0.00013 0.00014 2.8e-05 3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 7.5e-06 0.0001 9.9e-05 7.5e-05 0.024 0.024 0.0084 0.044 0.044 0.036 2.1e-10 2.1e-10 4.7e-10 4.6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
207 20490000 0.98 -0.007 -0.011 0.19 -0.012 -0.0024 0.02 0.0059 0.006 -0.00092 -0.00095 0.068 0.012 -1.5e-05 -5.9e-05 2.4e-06 2.5e-06 0.00014 2.7e-05 2.8e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 7.5e-06 0.0001 0.0001 7.5e-05 7.4e-05 0.027 0.027 0.0085 0.049 0.049 0.036 2.1e-10 2.1e-10 4.6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
208 20590000 0.98 -0.007 -0.011 0.19 -0.011 -0.0033 -0.0034 0.02 0.007 -0.00076 -0.00079 0.066 0.011 -1.5e-05 -5.9e-05 2.6e-06 2.7e-06 0.00014 2.5e-05 2.6e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 7.4e-06 9.9e-05 9.8e-05 7.4e-05 0.024 0.024 0.0084 0.044 0.044 0.036 2e-10 2e-10 4.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
209 20690000 0.98 -0.0069 -0.011 0.19 -0.013 -0.0021 -0.0022 0.021 0.0058 -0.00099 -0.001 0.067 0.011 -1.5e-05 -5.9e-05 2.4e-06 2.5e-06 0.00014 2.4e-05 2.6e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 7.4e-06 0.0001 9.9e-05 7.4e-05 0.026 0.026 0.0084 0.049 0.049 0.036 2e-10 2e-10 4.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
210 20790000 0.98 -0.0063 -0.011 0.19 -0.016 0.00046 0.00041 0.0055 0.0049 -0.00078 -0.00081 0.065 0.0096 -1.5e-05 -5.9e-05 2.5e-06 2.6e-06 0.00014 2.3e-05 2.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 7.4e-06 9.8e-05 9.6e-05 7.3e-05 0.023 0.023 0.0084 0.043 0.043 0.036 1.8e-10 1.8e-10 4.4e-10 4.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
211 20890000 0.98 0.0028 -0.0073 0.19 -0.021 0.012 -0.11 0.003 -9.5e-05 -0.00013 0.059 0.0033 -1.5e-05 -5.9e-05 2.5e-06 0.00014 0.00015 2.2e-05 2.4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 7.4e-06 9.8e-05 9.7e-05 7.3e-05 0.026 0.026 0.0084 0.049 0.049 0.036 1.8e-10 1.8e-10 4.3e-10 4.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
212 20990000 0.98 0.0061 -0.0038 0.19 -0.032 0.03 -0.25 0.0023 0.00055 0.00052 0.044 -0.011 -1.5e-05 -5.9e-05 2.4e-06 2.5e-06 0.00014 0.00015 2.1e-05 2.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 7.4e-06 9.6e-05 9.5e-05 7.3e-05 7.2e-05 0.023 0.023 0.0083 0.043 0.043 0.036 1.7e-10 1.7e-10 4.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
213 21090000 0.98 0.0045 -0.0042 0.19 -0.046 0.046 -0.37 -0.0016 0.0044 0.014 -0.042 -1.5e-05 -5.9e-05 2.4e-06 2.5e-06 0.00014 2.1e-05 2.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 7.4e-06 9.7e-05 9.6e-05 9.5e-05 7.2e-05 0.026 0.026 0.0084 0.048 0.048 0.036 1.7e-10 1.7e-10 4.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
214 21190000 0.98 0.0017 -0.0058 0.19 -0.049 0.05 -0.5 -0.0012 0.0035 -0.022 -0.078 -1.4e-05 -5.9e-05 2.5e-06 0.00014 1.5e-05 1.6e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.4e-06 9.5e-05 9.3e-05 7.2e-05 0.023 0.023 0.0083 0.043 0.043 0.036 1.5e-10 1.5e-10 4.1e-10 4e-10 2.8e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
215 21290000 0.98 -0.0005 -0.00049 -0.0072 0.19 -0.049 0.054 -0.63 -0.0061 0.0088 0.0087 -0.081 -0.14 -1.4e-05 -5.9e-05 2.2e-06 0.00014 0.00015 1.4e-05 1.6e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 9.5e-05 9.4e-05 7.1e-05 0.026 0.026 0.0083 0.048 0.048 0.036 1.5e-10 1.5e-10 4e-10 3.9e-10 2.8e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
216 21390000 0.98 -0.002 -0.0079 0.19 -0.044 0.05 -0.75 -0.005 0.011 -0.15 -0.2 -1.4e-05 -5.9e-05 2.2e-06 0.00015 1.1e-05 1.2e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 9.3e-05 9.2e-05 9.1e-05 7.1e-05 0.023 0.023 0.0082 0.043 0.043 0.036 1.4e-10 1.4e-10 3.9e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
217 21490000 0.98 -0.0028 -0.0083 0.19 -0.04 0.047 -0.89 -0.0092 0.016 -0.23 -0.29 -1.4e-05 -5.9e-05 2.3e-06 0.00015 9.7e-06 1.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 9.3e-05 9.2e-05 7.1e-05 0.026 0.026 0.0083 0.048 0.048 0.036 1.4e-10 1.4e-10 3.8e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
218 21590000 0.98 -0.0033 -0.0083 0.19 -0.031 0.043 -1 -0.0079 0.017 0.016 -0.32 -0.38 -1.4e-05 -5.9e-05 2.4e-06 0.00015 9.1e-06 1.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 9.1e-05 9e-05 7e-05 0.023 0.023 0.0082 0.043 0.043 0.036 1.3e-10 1.3e-10 3.8e-10 3.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
219 21690000 0.98 -0.0036 -0.0082 0.19 -0.029 0.039 -1.1 -0.011 0.021 -0.43 -0.49 -1.4e-05 -5.9e-05 2.5e-06 2.6e-06 0.00015 7.3e-06 9.1e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 9.1e-05 9e-05 7e-05 0.025 0.025 0.0083 0.048 0.048 0.036 1.3e-10 1.3e-10 3.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
220 21790000 0.98 -0.004 -0.0084 0.19 -0.021 0.033 -1.3 -0.0037 0.018 -0.55 -0.61 -1.4e-05 -5.8e-05 2.7e-06 0.00015 0.00016 5.2e-06 6.9e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 8.9e-05 8.8e-05 7e-05 0.023 0.023 0.0082 0.043 0.043 0.036 1.2e-10 1.2e-10 3.7e-10 3.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
221 21890000 0.98 -0.0043 -0.0085 0.19 -0.018 0.028 -1.4 -0.0057 0.021 -0.69 -0.75 -1.4e-05 -5.8e-05 2.6e-06 0.00016 3.9e-06 5.6e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 8.9e-05 8.8e-05 6.9e-05 0.025 0.025 0.0082 0.048 0.048 0.036 1.2e-10 1.2e-10 3.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
222 21990000 0.98 -0.005 -0.0088 0.19 -0.014 0.023 -1.4 -0.00032 0.017 -0.83 -0.89 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00015 6.2e-06 7.9e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 7.3e-06 8.7e-05 8.6e-05 6.9e-05 0.022 0.022 0.0082 0.043 0.043 0.036 1.1e-10 1.1e-10 3.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
223 22090000 0.98 -0.0057 -0.0096 0.19 -0.012 0.019 -1.4 -0.0016 0.019 -0.97 -1 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.00015 0.00016 4.9e-06 6.6e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.3e-06 8.7e-05 8.6e-05 6.9e-05 0.024 0.024 0.0082 0.048 0.048 0.036 1.1e-10 1.1e-10 3.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
224 22190000 0.98 -0.0062 -0.0099 0.19 -0.0035 0.013 -1.4 0.0061 0.013 -1.1 -1.2 -1.4e-05 -5.8e-05 2.9e-06 3e-06 0.00015 0.00016 5.1e-06 6.8e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.2e-06 8.5e-05 8.4e-05 6.8e-05 0.021 0.021 0.0081 0.043 0.043 0.036 1.1e-10 1.1e-10 3.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
225 22290000 0.98 -0.0069 -0.01 0.19 0.0017 0.0078 -1.4 0.006 0.014 -1.3 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.00016 4.2e-06 5.9e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.2e-06 8.6e-05 8.5e-05 8.4e-05 6.8e-05 0.023 0.023 0.0081 0.048 0.048 0.036 1.1e-10 1.1e-10 3.4e-10 3.3e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
226 22390000 0.98 -0.0072 -0.01 0.19 0.0067 -0.0017 -0.0018 -1.4 0.013 0.0042 -1.4 -1.5 -1.4e-05 -5.8e-05 2.7e-06 0.00015 0.00016 3.7e-07 2.1e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.2e-06 8.4e-05 8.3e-05 6.8e-05 0.021 0.021 0.0081 0.042 0.043 0.036 1e-10 1e-10 3.3e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
227 22490000 0.98 -0.0074 -0.011 0.19 0.011 -0.0077 -1.4 0.014 0.0037 0.0036 -1.5 -1.6 -1.4e-05 -5.8e-05 2.5e-06 2.6e-06 0.00016 -3.3e-07 1.4e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.2e-06 8.4e-05 8.3e-05 6.7e-05 0.022 0.022 0.0081 0.047 0.047 0.036 1e-10 1e-10 3.3e-10 3.2e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
228 22590000 0.98 -0.0073 -0.011 0.19 0.02 -0.017 -1.4 0.026 -0.0053 -1.7 -1.4e-05 -5.8e-05 2.7e-06 0.00016 -2.1e-06 -3.6e-07 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.2e-06 8.2e-05 8.1e-05 6.7e-05 0.02 0.02 0.0081 0.042 0.042 0.036 9.4e-11 9.4e-11 3.2e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
229 22690000 0.98 -0.0072 -0.012 0.19 0.022 -0.021 -1.4 0.028 -0.0072 -1.8 -1.9 -1.4e-05 -5.8e-05 2.6e-06 0.00016 -2.8e-06 -1.1e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.2e-06 8.3e-05 8.2e-05 6.7e-05 0.021 0.021 0.0081 0.047 0.047 0.036 9.4e-11 9.4e-11 3.2e-10 3.1e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
230 22790000 0.98 -0.0072 -0.012 0.19 0.028 -0.029 -1.4 0.038 -0.017 -2 -1.4e-05 -5.8e-05 2.4e-06 2.5e-06 0.00016 -3.9e-06 -2.2e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 7.2e-06 8.1e-05 8e-05 6.6e-05 0.019 0.019 0.0081 0.042 0.042 0.036 8.9e-11 8.8e-11 8.9e-11 3.1e-10 2.8e-06 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
231 22890000 0.98 -0.0074 -0.012 0.19 0.031 -0.035 -1.4 0.041 -0.02 -2.1 -2.2 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00016 -4.8e-06 -3.1e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 7.2e-06 8.2e-05 8.1e-05 8e-05 6.6e-05 0.021 0.021 0.0081 0.047 0.047 0.036 8.9e-11 8.9e-11 3.1e-10 3e-10 2.8e-06 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
232 22990000 0.98 -0.0074 -0.013 0.19 0.036 -0.04 -1.4 0.051 -0.031 -2.3 -1.4e-05 -5.8e-05 2.7e-06 2.8e-06 0.00016 -6.2e-06 -4.4e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 7.1e-06 8e-05 7.9e-05 6.6e-05 0.019 0.019 0.0081 0.042 0.042 0.036 8.4e-11 8.4e-11 3e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
233 23090000 0.98 -0.0074 -0.013 0.19 0.041 -0.044 -1.4 0.055 -0.035 -2.4 -2.5 -1.4e-05 -5.8e-05 2.7e-06 2.8e-06 0.00016 -6.5e-06 -4.7e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 7.1e-06 8e-05 7.9e-05 6.5e-05 0.02 0.02 0.0081 0.046 0.046 0.036 8.4e-11 8.4e-11 3e-10 2.9e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
234 23190000 0.98 -0.0074 -0.013 0.19 0.047 -0.046 -1.4 0.066 -0.045 -2.6 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00016 0.00017 -8e-06 -6.2e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 7.1e-06 7.9e-05 7.8e-05 6.5e-05 0.018 0.018 0.008 0.042 0.042 0.035 7.9e-11 7.9e-11 2.9e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
235 23290000 0.98 -0.0079 -0.013 0.19 0.052 -0.051 -1.4 0.071 -0.05 -2.7 -2.8 -1.4e-05 -5.8e-05 2.7e-06 0.00017 -8.5e-06 -6.8e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 7.1e-06 8e-05 7.9e-05 7.8e-05 6.5e-05 0.02 0.019 0.02 0.0081 0.046 0.046 0.036 7.9e-11 7.9e-11 2.9e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
236 23390000 0.98 -0.0078 -0.014 0.19 0.057 -0.053 -1.4 0.082 -0.055 -2.8 -2.9 -1.4e-05 -5.8e-05 2.5e-06 0.00017 -5.8e-06 -4.1e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7.1e-06 7.8e-05 7.7e-05 6.4e-05 0.018 0.018 0.008 0.041 0.041 0.036 7.5e-11 7.5e-11 2.8e-10 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
237 23490000 0.98 -0.0079 -0.014 0.18 0.061 -0.055 -1.4 0.088 -0.061 -3 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00017 -6.3e-06 -4.5e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7.1e-06 7.9e-05 7.8e-05 7.7e-05 6.4e-05 0.019 0.019 0.0081 0.046 0.046 0.036 7.5e-11 7.5e-11 2.8e-10 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
238 23590000 0.98 -0.0082 -0.014 0.18 0.064 -0.058 -1.4 0.095 -0.07 -3.1 -3.2 -1.4e-05 -5.8e-05 2.7e-06 0.00017 -7.5e-06 -5.7e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7e-06 7.8e-05 7.7e-05 6.4e-05 0.017 0.017 0.008 0.041 0.041 0.035 7.2e-11 7.2e-11 2.7e-10 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
239 23690000 0.98 -0.0088 -0.014 0.18 0.062 -0.061 -1.3 0.1 -0.076 -3.3 -1.4e-05 -5.8e-05 2.8e-06 0.00017 -7.7e-06 -5.9e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7e-06 7.8e-05 7.7e-05 6.3e-05 0.018 0.018 0.0081 0.046 0.046 0.036 7.2e-11 7.2e-11 2.7e-10 2.7e-06 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
240 23790000 0.98 -0.011 -0.017 0.18 0.057 -0.058 -0.96 0.11 -0.081 -3.4 -1.4e-05 -5.8e-05 2.9e-06 3e-06 0.00017 -7.7e-06 -5.9e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7e-06 7.7e-05 7.6e-05 6.3e-05 0.016 0.016 0.008 0.041 0.041 0.035 6.8e-11 6.9e-11 6.8e-11 2.7e-10 2.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
241 23890000 0.98 -0.014 -0.021 0.18 0.053 -0.059 -0.52 0.12 -0.087 -3.5 -1.4e-05 -5.8e-05 2.9e-06 3e-06 0.00017 -7.8e-06 -6e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7e-06 7.7e-05 7.6e-05 6.3e-05 0.017 0.017 0.008 0.045 0.045 0.035 6.9e-11 6.9e-11 2.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
242 23990000 0.98 -0.016 -0.024 0.18 0.054 -0.058 -0.14 0.13 -0.089 -3.5 -3.6 -1.4e-05 -5.8e-05 2.9e-06 3e-06 0.00018 -1.3e-05 -1.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7e-06 7.7e-05 7.6e-05 6.3e-05 0.015 0.015 0.008 0.041 0.041 0.036 6.6e-11 6.6e-11 2.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
243 24090000 0.98 -0.016 -0.023 0.18 0.061 -0.066 0.09 0.13 -0.095 -3.5 -3.6 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.00018 -1.4e-05 -1.2e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7e-06 7.7e-05 7.6e-05 6.2e-05 0.016 0.016 0.0081 0.045 0.045 0.036 6.6e-11 6.6e-11 2.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
244 24190000 0.98 -0.013 -0.019 0.18 0.072 -0.071 0.077 0.14 -0.1 -3.5 -3.6 -1.4e-05 -5.8e-05 2.9e-06 0.00019 -2.1e-05 -1.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7e-06 7.7e-05 7.6e-05 6.2e-05 0.015 0.015 0.008 0.04 0.04 0.035 6.3e-11 6.3e-11 2.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
245 24290000 0.98 -0.01 -0.016 0.18 0.075 -0.075 0.055 0.15 -0.11 -3.5 -3.6 -1.4e-05 -5.8e-05 2.9e-06 0.00019 -2.1e-05 -1.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 7e-06 7.7e-05 7.6e-05 6.2e-05 0.016 0.016 0.0081 0.044 0.044 0.036 6.3e-11 6.3e-11 2.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
246 24390000 0.98 -0.0096 -0.015 0.18 0.069 -0.069 0.071 0.15 -0.11 -3.5 -3.6 -1.4e-05 -5.8e-05 3.1e-06 0.00019 -2.9e-05 -2.7e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 7e-06 7.7e-05 7.6e-05 6.1e-05 0.015 0.015 0.008 0.04 0.04 0.035 6.1e-11 6.1e-11 2.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
247 24490000 0.98 -0.0098 -0.015 0.18 0.064 -0.066 0.069 0.16 -0.11 -3.5 -3.6 -1.4e-05 -5.8e-05 3.3e-06 0.00019 -2.9e-05 -2.7e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 7e-06 7.7e-05 7.6e-05 6.1e-05 0.016 0.016 0.008 0.0081 0.044 0.044 0.035 6.1e-11 6.1e-11 2.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
248 24590000 0.98 -0.01 -0.015 0.18 0.061 -0.062 0.065 0.16 -0.11 -3.5 -3.6 -1.4e-05 -5.8e-05 3.3e-06 0.00019 -3.6e-05 -3.4e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.7e-05 7.6e-05 6.1e-05 0.015 0.015 0.008 0.04 0.04 0.036 5.9e-11 5.9e-11 2.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
249 24690000 0.98 -0.011 -0.014 0.18 0.059 -0.061 0.064 0.17 -0.12 -3.5 -3.6 -1.4e-05 -5.8e-05 3.3e-06 0.00019 -3.6e-05 -3.4e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.7e-05 7.6e-05 6e-05 6.1e-05 0.016 0.016 0.0081 0.044 0.044 0.036 5.9e-11 5.9e-11 2.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
250 24790000 0.98 -0.011 -0.014 0.18 0.056 -0.059 0.056 0.17 -0.11 -3.5 -3.6 -1.5e-05 -5.8e-05 3.3e-06 0.00019 -4.2e-05 -3.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.7e-05 7.6e-05 6e-05 0.015 0.015 0.008 0.039 0.039 0.035 5.7e-11 5.7e-11 2.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
251 24890000 0.98 -0.011 -0.013 0.18 0.054 -0.062 0.045 0.18 -0.12 -3.5 -3.6 -1.5e-05 -5.8e-05 3.4e-06 0.00019 -4.2e-05 -3.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.7e-05 7.6e-05 6e-05 0.016 0.016 0.008 0.043 0.043 0.035 5.7e-11 5.7e-11 2.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
252 24990000 0.98 -0.011 -0.013 0.18 0.045 -0.058 0.038 0.18 -0.11 -3.5 -3.6 -1.5e-05 -5.8e-05 3.3e-06 3.4e-06 0.00018 0.00019 -4.8e-05 -4.6e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.7e-05 7.6e-05 6e-05 0.015 0.015 0.008 0.039 0.039 0.035 5.5e-11 5.5e-11 2.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
253 25090000 0.98 -0.011 -0.013 0.18 0.042 -0.057 0.035 0.18 -0.12 -3.5 -3.6 -1.5e-05 -5.8e-05 3.3e-06 0.00019 -4.9e-05 -4.6e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.8e-05 7.6e-05 5.9e-05 0.016 0.016 0.0081 0.043 0.043 0.035 5.5e-11 5.5e-11 2.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
254 25190000 0.98 -0.011 -0.013 0.18 0.037 -0.05 0.035 0.18 -0.11 -3.5 -3.6 -1.5e-05 -5.8e-05 3.2e-06 0.00018 0.00019 -5.3e-05 -5.1e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.8e-05 7.6e-05 5.9e-05 0.015 0.015 0.008 0.039 0.039 0.035 5.3e-11 5.3e-11 2.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
255 25290000 0.98 -0.011 -0.012 0.18 0.032 -0.052 0.029 0.18 -0.11 -3.5 -3.6 -1.5e-05 -5.8e-05 3e-06 3.1e-06 0.00018 0.00019 -5.4e-05 -5.1e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 6.9e-06 7.8e-05 7.7e-05 5.9e-05 0.016 0.016 0.0081 0.043 0.043 0.036 5.3e-11 5.3e-11 2.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
256 25390000 0.98 -0.011 -0.012 0.18 0.024 -0.044 0.028 0.18 -0.1 -3.5 -3.6 -1.5e-05 -5.8e-05 3e-06 3.1e-06 0.00018 -6e-05 -5.8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.9e-06 7.8e-05 7.7e-05 5.9e-05 0.015 0.014 0.015 0.008 0.039 0.039 0.035 5.1e-11 5.1e-11 2.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
257 25490000 0.98 -0.011 -0.012 0.18 0.019 -0.044 0.027 0.18 -0.11 -3.5 -3.6 -1.5e-05 -5.8e-05 2.9e-06 3e-06 0.00018 0.00019 -6.1e-05 -5.8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.9e-06 7.8e-05 7.7e-05 5.8e-05 0.016 0.016 0.0081 0.043 0.043 0.035 5.1e-11 5.1e-11 2.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
258 25590000 0.98 -0.011 -0.012 0.18 0.014 -0.04 0.028 0.18 -0.098 -3.5 -3.6 -1.5e-05 -5.8e-05 2.8e-06 2.9e-06 0.00018 -6.4e-05 -6.2e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.9e-06 7.8e-05 7.7e-05 5.8e-05 0.014 0.014 0.008 0.039 0.039 0.035 5e-11 5e-11 2.1e-10 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
259 25690000 0.98 -0.011 -0.011 0.18 0.013 -0.039 0.017 0.18 -0.1 -3.5 -3.6 -1.5e-05 -5.8e-05 2.8e-06 2.9e-06 0.00018 -6.4e-05 -6.2e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.8e-06 7.8e-05 7.7e-05 5.8e-05 0.015 0.015 0.0081 0.043 0.043 0.035 5e-11 5e-11 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
260 25790000 0.98 -0.011 -0.011 0.18 0.0021 -0.031 0.017 0.17 -0.093 -3.5 -3.6 -1.6e-05 -5.8e-05 2.8e-06 0.00018 -6.9e-05 -6.6e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.8e-06 7.8e-05 7.7e-05 5.8e-05 0.014 0.014 0.008 0.039 0.039 0.035 4.8e-11 4.8e-11 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
261 25890000 0.98 -0.011 -0.011 0.18 0.19 -0.0036 -0.029 0.019 0.17 -0.096 -3.5 -3.6 -1.6e-05 -5.8e-05 2.6e-06 0.00018 0.00019 -6.9e-05 -6.7e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.8e-06 7.8e-05 7.7e-05 5.7e-05 0.015 0.015 0.0081 0.043 0.043 0.036 4.8e-11 4.8e-11 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
262 25990000 0.98 -0.011 -0.011 0.19 -0.013 -0.022 0.013 0.16 -0.086 -3.5 -3.6 -1.6e-05 -5.8e-05 2.5e-06 0.00019 -7.3e-05 -7.1e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.8e-06 7.8e-05 7.7e-05 5.7e-05 0.014 0.014 0.008 0.039 0.039 0.035 4.7e-11 4.7e-11 2e-10 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
263 26090000 0.98 -0.01 -0.011 0.18 -0.018 -0.021 -0.022 0.011 0.16 -0.088 -3.5 -3.6 -1.6e-05 -5.8e-05 2.6e-06 0.00019 -7.3e-05 -7.1e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.8e-06 7.9e-05 7.7e-05 5.7e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.7e-11 4.7e-11 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
264 26190000 0.98 -0.01 -0.011 0.18 -0.024 -0.015 0.0063 0.15 -0.081 -3.5 -3.6 -1.6e-05 -5.8e-05 2.6e-06 0.00019 -7.5e-05 -7.3e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.8e-06 7.9e-05 7.8e-05 7.7e-05 5.7e-05 0.014 0.014 0.008 0.039 0.039 0.035 4.6e-11 4.6e-11 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
265 26290000 0.98 -0.01 -0.012 0.18 -0.026 -0.014 0.00051 0.00052 0.15 -0.083 -3.5 -3.6 -1.6e-05 -5.8e-05 2.5e-06 0.00019 -7.6e-05 -7.3e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 6.8e-06 7.9e-05 7.8e-05 7.7e-05 5.6e-05 0.015 0.015 0.0081 0.042 0.042 0.036 4.6e-11 4.6e-11 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
266 26390000 0.98 -0.0098 -0.012 0.18 -0.031 -0.0064 -0.0065 0.0045 0.13 -0.075 -3.5 -3.6 -1.6e-05 -5.8e-05 2.3e-06 2.4e-06 0.00019 -7.8e-05 -7.6e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.8e-06 7.9e-05 7.8e-05 7.7e-05 5.6e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.4e-11 4.4e-11 1.9e-10 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
267 26490000 0.98 -0.0096 -0.011 0.18 -0.035 -0.0033 0.014 0.13 -0.075 -3.5 -3.6 -1.6e-05 -5.8e-05 2.3e-06 0.00019 -7.8e-05 -7.6e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.8e-06 7.9e-05 7.8e-05 5.6e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.5e-11 4.5e-11 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
268 26590000 0.98 -0.009 -0.012 0.18 -0.036 0.0046 0.014 0.12 -0.068 -3.5 -3.6 -1.6e-05 -5.8e-05 2.2e-06 0.00019 -8e-05 -7.8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.8e-06 7.9e-05 7.8e-05 5.6e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.3e-11 4.3e-11 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
269 26690000 0.98 -0.0089 -0.011 0.18 -0.038 0.0097 0.013 0.12 -0.067 -3.5 -3.6 -1.6e-05 -5.8e-05 2e-06 0.00019 -8e-05 -7.8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 7.9e-05 7.8e-05 5.5e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.3e-11 4.3e-11 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
270 26790000 0.98 -0.0087 -0.011 0.18 -0.045 0.013 0.012 0.11 -0.062 -3.5 -3.6 -1.6e-05 -5.8e-05 1.9e-06 0.00019 -8.2e-05 -8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 7.9e-05 7.8e-05 5.5e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.2e-11 4.2e-11 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
271 26890000 0.98 -0.008 -0.011 0.18 -0.051 0.017 0.016 0.007 0.1 -0.06 -3.5 -3.6 -1.6e-05 -5.8e-05 1.9e-06 0.00019 -8.3e-05 -8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 7.9e-05 7.8e-05 5.5e-05 0.015 0.015 0.0081 0.042 0.042 0.036 4.2e-11 4.2e-11 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
272 26990000 0.98 -0.0075 -0.011 0.18 -0.058 0.023 0.0061 0.088 -0.054 -3.5 -3.6 -1.6e-05 -5.8e-05 1.8e-06 0.00019 -8.5e-05 -8.2e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 7.9e-05 7.8e-05 5.5e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.1e-11 4.1e-11 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
273 27090000 0.98 -0.0073 -0.012 0.18 -0.06 0.03 0.0089 0.082 -0.052 -3.5 -3.6 -1.6e-05 -5.8e-05 1.7e-06 1.8e-06 0.00019 0.0002 -8.6e-05 -8.3e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 7.9e-05 7.8e-05 5.4e-05 5.5e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.1e-11 4.1e-11 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
274 27190000 0.98 -0.0074 -0.012 0.18 -0.066 0.036 0.035 0.011 0.071 -0.046 -3.5 -3.6 -1.6e-05 -5.8e-05 1.7e-06 0.0002 -8.7e-05 -8.5e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 7.9e-05 7.8e-05 5.4e-05 0.014 0.014 0.008 0.038 0.038 0.035 4e-11 4e-11 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
275 27290000 0.98 -0.0075 -0.013 0.18 -0.073 0.041 0.12 0.064 -0.042 -3.5 -3.6 -1.6e-05 -5.8e-05 1.6e-06 1.7e-06 0.0002 -8.8e-05 -8.5e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 8e-05 7.9e-05 7.8e-05 5.4e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4e-11 4e-11 1.7e-10 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
276 27390000 0.98 -0.0089 -0.015 0.18 -0.078 0.047 0.45 0.055 -0.035 -3.5 -1.6e-05 -5.8e-05 1.6e-06 0.0002 -9e-05 -8.8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 6.7e-06 7.9e-05 7.8e-05 5.4e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.9e-11 3.9e-11 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
277 27490000 0.98 -0.01 -0.017 0.18 -0.081 0.053 0.76 0.047 -0.03 -3.4 -3.5 -1.6e-05 -5.8e-05 1.4e-06 0.0002 -9.1e-05 -8.8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.7e-06 8e-05 7.8e-05 5.4e-05 0.014 0.014 0.0081 0.042 0.042 0.035 3.9e-11 3.9e-11 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
278 27590000 0.98 -0.01 -0.016 0.18 -0.075 0.055 0.85 0.038 -0.025 -3.4 -1.6e-05 -5.8e-05 1.3e-06 1.4e-06 0.0002 -9.2e-05 -9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.7e-06 8e-05 7.8e-05 5.3e-05 5.4e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.9e-11 3.9e-11 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
279 27690000 0.98 -0.0089 -0.013 0.18 -0.072 0.052 0.76 0.031 -0.02 -3.3 -1.6e-05 -5.8e-05 1.3e-06 1.4e-06 0.0002 -9.3e-05 -9.1e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.7e-06 8e-05 7.9e-05 5.3e-05 0.014 0.014 0.0081 0.042 0.042 0.035 3.9e-11 3.9e-11 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
280 27790000 0.98 -0.0076 -0.011 0.18 -0.071 0.05 0.75 0.025 -0.018 -3.2 -3.3 -1.6e-05 -5.8e-05 1.3e-06 1.4e-06 0.0002 -8.7e-05 -8.5e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.7e-06 8e-05 7.9e-05 5.3e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.8e-11 3.8e-11 1.6e-10 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
281 27890000 0.98 -0.0072 -0.012 0.18 -0.078 0.057 0.79 0.018 -0.012 -3.1 -3.2 -1.6e-05 -5.8e-05 1.3e-06 0.0002 -8.8e-05 -8.5e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8e-05 7.9e-05 5.3e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.8e-11 3.8e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
282 27990000 0.98 -0.0077 -0.012 0.18 -0.078 0.058 0.78 0.012 -0.011 -3.1 -1.6e-05 -5.8e-05 1.2e-06 1.3e-06 0.00019 0.0002 -8.5e-05 -8.2e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8e-05 7.9e-05 5.3e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.7e-11 3.7e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
283 28090000 0.98 -0.008 -0.012 0.18 -0.082 0.059 0.78 0.0043 -0.0047 -0.0048 -3 -1.6e-05 -5.8e-05 1.3e-06 0.00019 0.0002 -8.5e-05 -8.3e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8e-05 7.9e-05 5.2e-05 0.014 0.014 0.0081 0.041 0.041 0.035 3.7e-11 3.7e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
284 28190000 0.98 -0.0074 -0.012 0.18 -0.082 0.055 0.79 -0.0022 -0.0043 -2.9 -3 -1.6e-05 -5.8e-05 1.3e-06 0.00019 0.0002 -8.2e-05 -7.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8e-05 7.9e-05 5.2e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.6e-11 3.6e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
285 28290000 0.98 -0.0069 -0.012 0.18 -0.087 0.059 0.79 -0.011 0.0014 -2.8 -2.9 -1.6e-05 -5.8e-05 1.3e-06 1.4e-06 0.00019 0.0002 -8.3e-05 -8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8.1e-05 8e-05 7.9e-05 5.2e-05 0.014 0.014 0.0081 0.041 0.041 0.035 3.7e-11 3.7e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
286 28390000 0.98 -0.0069 -0.013 0.18 -0.088 0.061 0.79 -0.015 0.0044 -2.8 -1.5e-05 -5.8e-05 1.4e-06 0.00019 0.0002 -8.2e-05 -7.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8.1e-05 8e-05 7.9e-05 5.2e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.6e-11 3.6e-11 1.5e-10 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
287 28490000 0.98 -0.0072 -0.014 0.18 -0.089 0.066 0.79 -0.024 0.011 -2.7 -2.8 -1.5e-05 -5.8e-05 1.3e-06 1.4e-06 0.00019 0.0002 -8.3e-05 -8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8.1e-05 8e-05 7.9e-05 5.2e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.6e-11 3.6e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
288 28590000 0.98 -0.0073 -0.0072 -0.014 0.18 -0.083 0.061 0.79 -0.027 0.0084 -2.6 -2.7 -1.5e-05 -5.8e-05 1.3e-06 1.4e-06 0.00019 0.0002 -8e-05 -7.8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 6.6e-06 8.1e-05 7.9e-05 5.1e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.5e-11 3.5e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
289 28690000 0.98 -0.007 -0.013 0.18 -0.083 0.062 0.79 -0.036 0.015 -2.5 -2.6 -1.5e-05 -5.8e-05 1.3e-06 0.00019 0.0002 -8.1e-05 -7.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.6e-06 8.1e-05 8e-05 5.1e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.5e-11 3.5e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
290 28790000 0.98 -0.0064 -0.013 0.18 -0.079 0.062 0.79 -0.038 0.016 -2.5 -1.5e-05 -5.8e-05 1.3e-06 1.4e-06 0.00019 0.0002 -8.2e-05 -7.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.6e-06 8.1e-05 8e-05 5.1e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.5e-11 3.5e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
291 28890000 0.98 -0.0062 -0.012 0.18 -0.084 0.064 0.78 -0.046 0.023 -2.4 -2.5 -1.5e-05 -5.8e-05 1.4e-06 0.0002 -8.3e-05 -8e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.6e-06 8.1e-05 8e-05 5.1e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.5e-11 3.5e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
292 28990000 0.98 -0.006 -0.013 0.18 -0.079 0.06 0.78 -0.046 0.022 -2.3 -2.4 -1.5e-05 -5.8e-05 1.4e-06 0.0002 -8.4e-05 -8.2e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.6e-06 8.1e-05 8e-05 5.1e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.4e-11 3.4e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
293 29090000 0.98 -0.0058 -0.013 0.18 -0.082 0.063 0.78 -0.054 0.028 -2.3 -1.5e-05 -5.8e-05 1.3e-06 1.4e-06 0.0002 -8.4e-05 -8.2e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.6e-06 8.1e-05 8e-05 5e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.4e-11 3.4e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
294 29190000 0.98 -0.0058 -0.013 0.18 -0.078 0.061 0.78 -0.051 0.027 -2.2 -1.5e-05 -5.8e-05 1.4e-06 0.0002 -8.6e-05 -8.4e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.6e-06 8.1e-05 8e-05 5e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.4e-11 3.4e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
295 29290000 0.98 -0.006 -0.013 0.18 -0.08 0.067 0.78 -0.059 0.033 -2.1 -2.2 -1.5e-05 -5.8e-05 1.4e-06 0.0002 -8.7e-05 -8.4e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.6e-06 8.1e-05 8e-05 5e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.4e-11 3.4e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
296 29390000 0.98 -0.0065 -0.012 0.18 -0.075 0.065 0.78 -0.057 0.034 -2 -2.1 -1.5e-05 -5.8e-05 1.4e-06 1.5e-06 0.0002 -8.8e-05 -8.6e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.1e-05 8e-05 5e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.3e-11 3.3e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
297 29490000 0.98 -0.0065 -0.012 0.18 -0.078 0.066 0.78 -0.065 0.041 -2 -1.5e-05 -5.8e-05 1.5e-06 1.6e-06 0.0002 -8.9e-05 -8.6e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.2e-05 8.1e-05 8e-05 5e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.3e-11 3.3e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
298 29590000 0.98 -0.0064 -0.012 0.18 -0.074 0.064 0.78 -0.062 0.04 -1.9 -1.5e-05 -5.8e-05 1.6e-06 1.7e-06 0.0002 -9.1e-05 -8.8e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.1e-05 8e-05 4.9e-05 5e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.3e-11 3.3e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
299 29690000 0.98 -0.0064 -0.012 0.18 -0.078 0.063 0.78 -0.07 0.046 -1.8 -1.9 -1.5e-05 -5.8e-05 1.7e-06 0.0002 -9.2e-05 -9e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.2e-05 8.1e-05 8e-05 4.9e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.3e-11 3.3e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
300 29790000 0.98 -0.0063 -0.013 0.18 -0.074 0.056 0.78 -0.065 0.044 -1.7 -1.8 -1.4e-05 -5.8e-05 1.8e-06 0.0002 -9.5e-05 -9.2e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.1e-05 8e-05 4.9e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.2e-11 3.2e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
301 29890000 0.98 -0.0058 -0.0057 -0.013 0.18 -0.074 0.057 0.77 -0.072 0.049 -1.7 -1.4e-05 -5.8e-05 1.9e-06 0.0002 -9.6e-05 -9.4e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.2e-05 8e-05 4.9e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.2e-11 3.2e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
302 29990000 0.98 -0.0059 -0.013 0.18 -0.069 0.052 0.77 -0.068 0.044 -1.6 -1.4e-05 -5.8e-05 1.9e-06 0.0002 0.00021 -0.0001 -9.8e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.1e-05 8e-05 4.9e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.2e-11 3.2e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
303 30090000 0.98 -0.006 -0.013 0.18 -0.069 0.053 0.77 -0.075 0.05 -1.5 -1.6 -1.4e-05 -5.8e-05 1.7e-06 1.8e-06 0.0002 0.00021 -0.0001 -9.9e-05 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.2e-05 8e-05 4.8e-05 4.9e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.2e-11 3.2e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
304 30190000 0.98 -0.006 -0.013 0.18 -0.063 0.05 0.77 -0.068 0.048 -1.4 -1.5 -1.4e-05 -5.7e-05 1.6e-06 0.00021 -0.0001 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.1e-05 8e-05 4.8e-05 4.9e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
305 30290000 0.98 -0.006 -0.013 0.19 -0.062 0.05 0.77 -0.074 0.053 -1.4 -1.4e-05 -5.7e-05 1.6e-06 1.7e-06 0.00021 -0.00011 -0.0001 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 6.5e-06 8.2e-05 8e-05 4.8e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
306 30390000 0.98 -0.0061 -0.013 0.19 -0.055 0.044 0.76 -0.066 0.049 -1.3 -1.4 -1.4e-05 -5.7e-05 1.7e-06 1.8e-06 0.00021 -0.00011 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.8e-05 0.013 0.013 0.0079 0.037 0.037 0.035 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
307 30490000 0.98 -0.0061 -0.006 -0.013 0.18 -0.057 0.044 0.77 -0.072 0.054 -1.2 -1.3 -1.4e-05 -5.7e-05 1.8e-06 0.00021 -0.00011 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.2e-05 8.1e-05 8e-05 4.8e-05 0.014 0.014 0.008 0.041 0.041 0.036 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
308 30590000 0.98 -0.0064 -0.014 0.18 -0.053 0.041 0.76 -0.065 0.05 -1.2 -1.4e-05 -5.7e-05 1.9e-06 0.00022 -0.00012 -0.00011 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.8e-05 0.013 0.013 0.008 0.037 0.037 0.035 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
309 30690000 0.98 -0.0068 -0.014 0.18 -0.051 0.04 0.76 -0.07 0.054 -1.1 -1.4e-05 -5.7e-05 1.9e-06 0.00022 -0.00012 -0.00011 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.7e-05 4.8e-05 0.013 0.013 0.008 0.041 0.041 0.035 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
310 30790000 0.98 -0.0065 -0.0064 -0.013 0.18 -0.044 0.035 0.76 -0.063 0.052 -1 -1.1 -1.4e-05 -5.7e-05 1.9e-06 0.00022 -0.00012 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.7e-05 4.8e-05 0.013 0.013 0.008 0.037 0.037 0.035 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
311 30890000 0.98 -0.0058 -0.013 0.18 -0.044 0.032 0.76 -0.067 0.056 -0.95 -1 -1.4e-05 -5.7e-05 1.8e-06 1.9e-06 0.00022 -0.00012 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.7e-05 0.013 0.013 0.008 0.04 0.04 0.035 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
312 30990000 0.98 -0.006 -0.013 0.18 -0.037 0.026 0.76 -0.057 0.049 -0.88 -0.94 -1.4e-05 -5.7e-05 1.8e-06 1.9e-06 0.00022 0.00023 -0.00012 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.7e-05 0.013 0.013 0.0079 0.037 0.037 0.035 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
313 31090000 0.98 -0.0062 -0.0061 -0.013 0.19 -0.035 0.025 0.76 -0.061 0.051 -0.81 -0.86 -1.4e-05 -5.7e-05 1.8e-06 0.00022 0.00023 -0.00012 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.7e-05 0.013 0.013 0.008 0.04 0.04 0.036 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
314 31190000 0.98 -0.0063 -0.013 0.19 -0.031 0.021 0.76 -0.052 0.046 -0.74 -0.79 -1.4e-05 -5.7e-05 1.9e-06 0.00023 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.5e-06 8.1e-05 8e-05 4.7e-05 0.013 0.013 0.008 0.037 0.037 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
315 31290000 0.98 -0.0066 -0.014 0.18 -0.028 0.018 0.76 -0.055 0.048 -0.67 -0.72 -1.4e-05 -5.7e-05 2e-06 0.00023 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8.1e-05 8e-05 4.7e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
316 31390000 0.98 -0.0064 -0.0063 -0.013 0.18 -0.022 0.012 0.76 -0.046 0.042 -0.59 -0.65 -1.4e-05 -5.7e-05 1.9e-06 0.00023 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8.1e-05 8e-05 7.9e-05 4.6e-05 0.013 0.013 0.0079 0.037 0.037 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
317 31490000 0.98 -0.0061 -0.014 0.19 -0.022 0.009 0.76 -0.049 0.043 -0.52 -0.58 -1.4e-05 -5.7e-05 1.9e-06 0.00023 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8.1e-05 8e-05 4.6e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.9e-11 2.9e-11 1.1e-10 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
318 31590000 0.98 -0.006 -0.0059 -0.014 0.18 -0.018 0.0067 0.0068 0.76 -0.038 0.039 -0.45 -0.51 -1.4e-05 -5.7e-05 1.9e-06 2e-06 0.00023 0.00024 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8.1e-05 8e-05 7.9e-05 4.6e-05 0.012 0.012 0.0079 0.037 0.037 0.035 2.9e-11 2.9e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
319 31690000 0.98 -0.0059 -0.015 0.18 -0.02 0.0057 0.76 -0.04 0.039 -0.38 -0.44 -1.4e-05 -5.7e-05 2e-06 2.1e-06 0.00024 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8.1e-05 8e-05 7.9e-05 4.6e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.9e-11 2.9e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
320 31790000 0.98 -0.0062 -0.015 0.18 -0.011 0.0031 0.76 -0.028 0.037 -0.31 -0.36 -1.4e-05 -5.7e-05 2.1e-06 0.00024 -0.00014 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8e-05 7.9e-05 4.6e-05 0.012 0.012 0.008 0.037 0.037 0.035 2.8e-11 2.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
321 31890000 0.98 -0.0059 -0.015 0.18 -0.008 0.00081 0.00082 0.76 -0.029 0.038 -0.24 -0.3 -1.4e-05 -5.7e-05 2.2e-06 0.00024 -0.00014 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8.1e-05 8e-05 7.9e-05 4.6e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.8e-11 2.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
322 31990000 0.98 -0.0062 -0.0061 -0.015 0.18 -0.00011 -0.0001 0.00015 0.00016 0.75 -0.017 0.034 -0.17 -0.23 -1.3e-05 -5.7e-05 2.1e-06 0.00025 -0.00014 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8e-05 7.9e-05 4.5e-05 4.6e-05 0.012 0.012 0.0079 0.037 0.037 0.035 2.8e-11 2.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
323 32090000 0.98 -0.0065 -0.014 0.18 -0.00064 -0.0033 -0.0032 0.76 -0.017 0.034 -0.1 -0.16 -1.3e-05 -5.7e-05 2.1e-06 0.00025 -0.00014 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 6.4e-06 8e-05 7.9e-05 4.5e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.8e-11 2.8e-11 9.9e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
324 32190000 0.98 -0.0067 -0.015 0.18 0.0047 -0.0065 0.76 -0.006 0.033 -0.037 -0.092 -1.3e-05 -5.7e-05 2.1e-06 0.00025 -0.00014 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 8e-05 7.9e-05 4.5e-05 0.012 0.012 0.0079 0.037 0.037 0.035 2.8e-11 2.8e-11 9.9e-11 9.8e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
325 32290000 0.98 -0.0066 -0.015 0.18 0.0063 -0.0092 -0.0091 0.75 -0.0055 0.032 0.032 -0.024 -1.3e-05 -5.7e-05 2.1e-06 2.2e-06 0.00025 -0.00014 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 8e-05 7.9e-05 4.5e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.8e-11 2.8e-11 9.8e-11 9.7e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
326 32390000 0.98 -0.0067 -0.015 0.18 0.013 -0.01 0.75 0.0057 0.03 0.11 0.051 -1.3e-05 -5.7e-05 2.1e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 8e-05 7.8e-05 4.5e-05 0.012 0.012 0.008 0.037 0.037 0.035 2.7e-11 2.7e-11 9.7e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
327 32490000 0.98 -0.0096 -0.013 0.18 0.039 -0.073 -0.12 0.0089 0.023 0.11 0.054 -1.3e-05 -5.7e-05 2.1e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 8e-05 7.9e-05 4.5e-05 0.015 0.015 0.0078 0.04 0.04 0.035 2.8e-11 2.8e-11 9.6e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
328 32590000 0.98 -0.0095 -0.013 0.18 0.039 -0.075 -0.074 -0.12 0.021 0.02 0.09 0.035 -1.4e-05 -5.7e-05 2.1e-06 2.2e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 7.9e-05 7.7e-05 4.5e-05 0.016 0.016 0.0075 0.037 0.037 0.035 2.7e-11 2.7e-11 9.5e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
329 32690000 0.98 -0.0095 -0.013 0.18 0.035 -0.08 -0.12 0.025 0.012 0.075 0.02 -1.4e-05 -5.7e-05 2.1e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 7.9e-05 7.8e-05 4.4e-05 4.5e-05 0.019 0.019 0.0074 0.041 0.041 0.035 2.7e-11 2.7e-11 9.4e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
330 32790000 0.98 -0.0092 -0.013 0.18 0.034 -0.078 -0.12 0.034 0.01 0.06 0.0042 -1.4e-05 -5.7e-05 2.2e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 7.6e-05 7.5e-05 4.4e-05 0.019 0.019 0.0071 0.037 0.037 0.035 2.7e-11 2.7e-11 9.3e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
331 32890000 0.98 -0.0092 -0.0091 -0.013 0.18 0.033 -0.084 -0.13 0.038 0.0021 0.044 -0.011 -1.4e-05 -5.7e-05 2.2e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 7.6e-05 7.5e-05 4.4e-05 0.023 0.023 0.007 0.041 0.041 0.035 2.7e-11 2.7e-11 9.3e-11 9.2e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
332 32990000 0.98 -0.0089 -0.013 0.18 0.03 -0.08 -0.13 0.045 -0.0011 0.031 -0.024 -1.4e-05 -5.6e-05 2.3e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.4e-06 7.2e-05 7.1e-05 4.4e-05 0.024 0.024 0.0067 0.038 0.038 0.035 2.7e-11 2.7e-11 9.2e-11 9.1e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
333 33090000 0.98 -0.0088 -0.013 0.18 0.026 -0.083 -0.12 0.048 -0.0092 0.024 -0.031 -1.4e-05 -5.6e-05 2.3e-06 0.00026 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 7.2e-05 7.1e-05 4.4e-05 0.028 0.029 0.0066 0.042 0.042 0.035 2.7e-11 2.7e-11 9.1e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
334 33190000 0.98 -0.0085 -0.013 0.18 0.022 -0.079 -0.12 0.054 -0.011 0.018 -0.037 -1.4e-05 -5.6e-05 2.2e-06 0.00025 0.00026 -0.00014 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 6.7e-05 6.6e-05 6.6e-05 4.4e-05 0.029 0.029 0.0064 0.038 0.038 0.035 2.6e-11 2.6e-11 9e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
335 33290000 0.98 -0.0086 -0.013 0.18 0.019 -0.08 -0.12 0.056 -0.019 0.011 -0.045 -1.4e-05 -5.6e-05 2.3e-06 0.00025 0.00026 -0.00014 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 6.7e-05 6.6e-05 4.4e-05 0.035 0.035 0.0063 0.043 0.043 0.034 2.6e-11 2.6e-11 8.9e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
336 33390000 0.98 -0.0081 -0.013 0.18 0.014 -0.066 -0.12 0.059 -0.014 0.0022 -0.053 -1.4e-05 -5.6e-05 2.3e-06 0.00025 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 6e-05 5.9e-05 4.3e-05 4.4e-05 0.035 0.035 0.0062 0.039 0.039 0.034 2.6e-11 2.6e-11 8.9e-11 8.8e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
337 33490000 0.98 -0.0081 -0.013 0.18 0.0094 -0.067 -0.12 0.06 -0.021 -0.0071 -0.063 -1.4e-05 -5.6e-05 2.3e-06 0.00025 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 6e-05 5.9e-05 4.3e-05 0.042 0.042 0.0061 0.044 0.044 0.034 2.6e-11 2.6e-11 8.8e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
338 33590000 0.98 -0.0077 -0.013 0.18 0.0055 -0.058 -0.11 0.063 -0.017 -0.014 -0.069 -1.4e-05 -5.6e-05 2.4e-06 0.00024 -0.00019 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 5.3e-05 5.2e-05 4.3e-05 0.04 0.041 0.006 0.04 0.04 0.034 2.6e-11 2.6e-11 8.7e-11 2.6e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
339 33690000 0.98 -0.0077 -0.013 0.18 0.00084 0.00085 -0.058 -0.11 0.063 -0.023 -0.022 -0.077 -1.4e-05 -5.6e-05 2.4e-06 0.00024 -0.00019 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 5.3e-05 5.3e-05 5.2e-05 4.3e-05 0.048 0.048 0.0059 0.046 0.046 0.034 2.6e-11 2.6e-11 8.7e-11 8.6e-11 2.6e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
340 33790000 0.98 -0.0075 -0.013 0.18 -0.0023 -0.048 -0.11 0.067 -0.018 -0.028 -0.083 -1.4e-05 -5.6e-05 2.3e-06 0.00023 -0.00021 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.3e-06 4.7e-05 4.6e-05 4.6e-05 4.3e-05 0.044 0.045 0.0059 0.041 0.041 0.034 2.6e-11 2.6e-11 8.6e-11 2.5e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
341 33890000 0.98 -0.0075 -0.013 0.18 -0.0065 -0.046 -0.11 0.066 -0.023 -0.034 -0.09 -1.4e-05 -5.6e-05 2.4e-06 0.00023 -0.00021 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 4.7e-05 4.6e-05 4.3e-05 0.052 0.052 0.0058 0.047 0.047 0.033 2.6e-11 2.6e-11 8.5e-11 2.5e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
342 33990000 0.98 -0.0072 -0.013 0.18 -0.0062 -0.031 -0.1 0.069 -0.015 -0.037 -0.092 -1.4e-05 -5.6e-05 2.3e-06 0.00021 -0.00024 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 4.1e-05 4.1e-05 4.3e-05 0.047 0.047 0.0058 0.042 0.042 0.033 2.6e-11 2.6e-11 8.4e-11 2.5e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
343 34090000 0.98 -0.0072 -0.013 0.18 -0.011 -0.031 -0.1 0.069 -0.018 -0.041 -0.096 -1.4e-05 -5.6e-05 2.3e-06 0.00021 -0.00024 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 4.1e-05 4.1e-05 4.3e-05 0.054 0.054 0.0058 0.049 0.049 0.033 2.6e-11 2.6e-11 8.4e-11 2.5e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
344 34190000 0.98 -0.0071 -0.013 0.18 -0.011 -0.021 -0.098 0.072 -0.013 -0.043 -0.099 -1.4e-05 -5.6e-05 2.3e-06 0.00019 -0.00026 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 3.7e-05 3.6e-05 4.2e-05 4.3e-05 0.048 0.047 0.048 0.0058 0.043 0.043 0.033 2.6e-11 2.6e-11 8.3e-11 2.4e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
345 34290000 0.98 -0.0069 -0.013 0.18 -0.012 -0.02 -0.097 0.071 -0.015 -0.049 -0.1 -1.4e-05 -5.6e-05 2.3e-06 0.00019 -0.00026 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 3.7e-05 3.6e-05 4.2e-05 0.054 0.055 0.0058 0.05 0.05 0.033 2.6e-11 2.6e-11 8.2e-11 2.4e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
346 34390000 0.98 -0.0068 -0.013 0.18 -0.013 -0.01 -0.092 0.073 -0.01 -0.052 -0.11 -1.4e-05 -5.6e-05 2.3e-06 0.00017 0.00018 -0.00027 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 3.3e-05 3.3e-05 4.2e-05 0.047 0.047 0.0058 0.044 0.044 0.033 2.6e-11 2.6e-11 8.2e-11 2.3e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
347 34490000 0.98 -0.0069 -0.013 0.18 -0.016 -0.0095 -0.0096 -0.09 0.071 -0.011 -0.055 -0.11 -1.4e-05 -5.6e-05 2.3e-06 0.00017 -0.00027 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 3.3e-05 3.3e-05 4.2e-05 0.053 0.053 0.0059 0.051 0.051 0.032 2.6e-11 2.6e-11 8.1e-11 2.3e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
348 34590000 0.98 -0.0069 -0.013 0.18 -0.014 -0.0052 -0.0053 0.71 0.073 -0.0089 -0.025 -0.081 -1.4e-05 -5.6e-05 2.3e-06 0.00016 -0.00028 -0.00027 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 3.1e-05 3.1e-05 3e-05 4.2e-05 0.044 0.044 0.0059 0.045 0.045 0.032 2.6e-11 2.6e-11 8e-11 2.2e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
349 34690000 0.98 -0.0068 -0.012 0.18 -0.017 -0.0031 -0.0032 1.7 0.071 -0.0093 0.093 0.037 -1.4e-05 -5.6e-05 2.2e-06 2.3e-06 0.00016 -0.00028 -0.00027 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 3.1e-05 3.1e-05 4.2e-05 0.047 0.047 0.006 0.052 0.052 0.032 2.6e-11 2.6e-11 8e-11 2.2e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
350 34790000 0.98 -0.0068 -0.012 0.18 -0.018 0.0016 0.0015 2.7 0.072 -0.0069 0.27 0.21 -1.4e-05 -5.6e-05 2.2e-06 0.00017 0.00018 -0.00029 -0.001 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 2.9e-05 2.9e-05 4.2e-05 0.04 0.04 0.0061 0.045 0.045 0.032 2.6e-11 2.6e-11 7.9e-11 2e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
351 34890000 0.98 -0.0068 -0.012 0.18 -0.022 0.004 0.0039 3.6 0.07 -0.0065 0.56 0.5 -1.4e-05 -5.6e-05 2.2e-06 0.00018 -0.00029 -0.001 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 6.3e-06 3e-05 2.9e-05 2.9e-05 4.2e-05 0.043 0.043 0.0061 0.052 0.052 0.032 2.6e-11 2.6e-11 7.9e-11 7.8e-11 2e-06 2e-06 5e-08 0 0 0 0 0 0 0 0

View File

@ -106,8 +106,8 @@ TEST_F(EkfAirspeedTest, testWindVelocityEstimation)
const Vector3f vel_wind_expected = simulated_velocity_earth - R_to_earth_sim * (Vector3f(airspeed_body(0),
airspeed_body(1), 0.0f));
EXPECT_NEAR(vel_wind_earth(0), vel_wind_expected(0), 1e-2f);
EXPECT_NEAR(vel_wind_earth(1), vel_wind_expected(1), 1e-2f);
EXPECT_NEAR(vel_wind_earth(0), vel_wind_expected(0), 1e-1f);
EXPECT_NEAR(vel_wind_earth(1), vel_wind_expected(1), 1e-1f);
EXPECT_NEAR(height_before_pressure_correction, 0.0f, 1e-5f);

View File

@ -78,7 +78,7 @@ TEST_F(EkfMagTest, fusionStartWithReset)
_sensor_simulator.runSeconds(_init_duration_s);
// THEN: the fusion initializes using the mag data and runs normally
EXPECT_NEAR(_ekf_wrapper.getYawAngle(), mag_heading, radians(0.1f));
EXPECT_NEAR(_ekf_wrapper.getYawAngle(), mag_heading, radians(1.f));
EXPECT_TRUE(_ekf_wrapper.isIntendingMagHeadingFusion());
EXPECT_FALSE(_ekf_wrapper.isIntendingMag3DFusion());
@ -114,7 +114,7 @@ TEST_F(EkfMagTest, suddenLargeStrength)
_sensor_simulator.runSeconds(_init_duration_s);
// THEN: the fusion initializes using the mag data and runs normally
EXPECT_NEAR(_ekf_wrapper.getYawAngle(), mag_heading, radians(0.1f));
EXPECT_NEAR(_ekf_wrapper.getYawAngle(), mag_heading, radians(1.f));
EXPECT_TRUE(_ekf_wrapper.isIntendingMagHeadingFusion());
EXPECT_FALSE(_ekf_wrapper.isIntendingMag3DFusion());