ekf2: use Joseph stabilized covariance update

This commit is contained in:
bresch 2024-02-16 15:34:35 +01:00 committed by Daniel Agar
parent d988005216
commit 9d9766c6cf
13 changed files with 301 additions and 281 deletions

View File

@ -75,7 +75,10 @@ bool ZeroGyroUpdate::update(Ekf &ekf, const estimator::imuSample &imu_delayed)
K(row) = ekf.stateCovariance(row, state_index) / innov_var(i); K(row) = ekf.stateCovariance(row, state_index) / innov_var(i);
} }
ekf.measurementUpdate(K, innov_var(i), innovation(i)); Ekf::VectorState H{};
H(State::gyro_bias.idx + i) = 1.f;
ekf.measurementUpdate(K, H, obs_var, innovation(i), innov_var(i));
} }
// Reset the integrators // Reset the integrators

View File

@ -208,7 +208,7 @@ void Ekf::fuseAirspeed(const airspeedSample &airspeed_sample, estimator_aid_sour
K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) = K_wind; K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) = K_wind;
} }
const bool is_fused = measurementUpdate(K, aid_src.innovation_variance, aid_src.innovation); const bool is_fused = measurementUpdate(K, H, aid_src.observation_variance, aid_src.innovation);
aid_src.fused = is_fused; aid_src.fused = is_fused;
_fault_status.flags.bad_airspeed = !is_fused; _fault_status.flags.bad_airspeed = !is_fused;

View File

@ -222,14 +222,6 @@ void Ekf::constrainStateVariances()
#endif // CONFIG_EKF2_WIND #endif // CONFIG_EKF2_WIND
} }
void Ekf::forceCovarianceSymmetry()
{
// DEBUG
// P.isBlockSymmetric(0, 1e-9f);
P.makeRowColSymmetric<State::size>(0);
}
void Ekf::constrainStateVar(const IdxDof &state, float min, float max) void Ekf::constrainStateVar(const IdxDof &state, float min, float max)
{ {
for (unsigned i = state.idx; i < (state.idx + state.dof); i++) { for (unsigned i = state.idx; i < (state.idx + state.dof); i++) {
@ -256,22 +248,6 @@ void Ekf::constrainStateVarLimitRatio(const IdxDof &state, float min, float max,
} }
} }
// if the covariance correction will result in a negative variance, then
// the covariance matrix is unhealthy and must be corrected
bool Ekf::checkAndFixCovarianceUpdate(const SquareMatrixState &KHP)
{
bool healthy = true;
for (int i = 0; i < State::size; i++) {
if (P(i, i) < KHP(i, i)) {
P.uncorrelateCovarianceSetVariance<1>(i, 0.f);
healthy = false;
}
}
return healthy;
}
void Ekf::resetQuatCov(const float yaw_noise) void Ekf::resetQuatCov(const float yaw_noise)
{ {
const float tilt_var = sq(math::max(_params.initial_tilt_err, 0.01f)); const float tilt_var = sq(math::max(_params.initial_tilt_err, 0.01f));

View File

@ -160,7 +160,7 @@ void Ekf::fuseDrag(const dragSample &drag_sample)
VectorState K = P * H / _aid_src_drag.innovation_variance[axis_index]; VectorState K = P * H / _aid_src_drag.innovation_variance[axis_index];
if (measurementUpdate(K, _aid_src_drag.innovation_variance[axis_index], _aid_src_drag.innovation[axis_index])) { if (measurementUpdate(K, H, R_ACC, _aid_src_drag.innovation[axis_index])) {
fused[axis_index] = true; fused[axis_index] = true;
} }
} }

View File

@ -468,35 +468,39 @@ public:
const auto &aid_src_aux_vel() const { return _aid_src_aux_vel; } const auto &aid_src_aux_vel() const { return _aid_src_aux_vel; }
#endif // CONFIG_EKF2_AUXVEL #endif // CONFIG_EKF2_AUXVEL
bool measurementUpdate(VectorState &K, float innovation_variance, float innovation) bool measurementUpdate(VectorState &K, const VectorState &H, const float R, const float innovation)
{ {
clearInhibitedStateKalmanGains(K); clearInhibitedStateKalmanGains(K);
const VectorState KS = K * innovation_variance; // Efficient implementation of the Joseph stabilized covariance update
SquareMatrixState KHP; // Based on "G. J. Bierman. Factorization Methods for Discrete Sequential Estimation. Academic Press, Dover Publications, New York, 1977, 2006"
for (unsigned row = 0; row < State::size; row++) { // Step 1: conventional update
for (unsigned col = 0; col < State::size; col++) { VectorState PH = P * H;
// Instead of literally computing KHP, use an equivalent
// equation involving less mathematical operations for (unsigned i = 0; i < State::size; i++) {
KHP(row, col) = KS(row) * K(col); for (unsigned j = 0; j <= i; j++) {
P(i, j) = P(i, j) - K(i) * PH(j);
P(j, i) = P(i, j);
} }
} }
const bool is_healthy = checkAndFixCovarianceUpdate(KHP); // Step 2: stabilized update
PH = P * H;
if (is_healthy) { for (unsigned i = 0; i < State::size; i++) {
// apply the covariance corrections for (unsigned j = 0; j <= i; j++) {
P -= KHP; float s = .5f * (P(i, j) - PH(i) * K(j) + P(i, j) - PH(j) * K(i));
P(i, j) = s + K(i) * R * K(j);
P(j, i) = P(i, j);
}
}
constrainStateVariances(); constrainStateVariances();
forceCovarianceSymmetry();
// apply the state corrections // apply the state corrections
fuse(K, innovation); fuse(K, innovation);
} return true;
return is_healthy;
} }
void resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation); void resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, uint64_t timestamp_observation);
@ -942,15 +946,9 @@ private:
#endif // CONFIG_EKF2_WIND #endif // CONFIG_EKF2_WIND
} }
// if the covariance correction will result in a negative variance, then
// the covariance matrix is unhealthy and must be corrected
bool checkAndFixCovarianceUpdate(const SquareMatrixState &KHP);
// limit the diagonal of the covariance matrix // limit the diagonal of the covariance matrix
void constrainStateVariances(); void constrainStateVariances();
void forceCovarianceSymmetry();
void constrainStateVar(const IdxDof &state, float min, float max); void constrainStateVar(const IdxDof &state, float min, float max);
void constrainStateVarLimitRatio(const IdxDof &state, float min, float max, float max_ratio = 1.e6f); void constrainStateVarLimitRatio(const IdxDof &state, float min, float max, float max_ratio = 1.e6f);

View File

@ -134,7 +134,7 @@ void Ekf::fuseGpsYaw(float antenna_yaw_offset)
// only calculate gains for states we are using // only calculate gains for states we are using
VectorState Kfusion = P * H / gnss_yaw.innovation_variance; VectorState Kfusion = P * H / gnss_yaw.innovation_variance;
const bool is_fused = measurementUpdate(Kfusion, gnss_yaw.innovation_variance, gnss_yaw.innovation); const bool is_fused = measurementUpdate(Kfusion, H, gnss_yaw.observation_variance, gnss_yaw.innovation);
_fault_status.flags.bad_hdg = !is_fused; _fault_status.flags.bad_hdg = !is_fused;
gnss_yaw.fused = is_fused; gnss_yaw.fused = is_fused;

View File

@ -111,7 +111,7 @@ void Ekf::controlGravityFusion(const imuSample &imu)
const bool accel_clipping = imu.delta_vel_clipping[0] || imu.delta_vel_clipping[1] || imu.delta_vel_clipping[2]; const bool accel_clipping = imu.delta_vel_clipping[0] || imu.delta_vel_clipping[1] || imu.delta_vel_clipping[2];
if (_control_status.flags.gravity_vector && !_aid_src_gravity.innovation_rejected && !accel_clipping) { if (_control_status.flags.gravity_vector && !_aid_src_gravity.innovation_rejected && !accel_clipping) {
fused[index] = measurementUpdate(K, _aid_src_gravity.innovation_variance[index], _aid_src_gravity.innovation[index]); fused[index] = measurementUpdate(K, H, _aid_src_gravity.observation_variance[index], _aid_src_gravity.innovation[index]);
} }
} }

View File

@ -191,7 +191,7 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo
Kfusion.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) = K_mag_B; Kfusion.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) = K_mag_B;
} }
if (measurementUpdate(Kfusion, aid_src_mag.innovation_variance[index], aid_src_mag.innovation[index])) { if (measurementUpdate(Kfusion, H, aid_src_mag.observation_variance[index], aid_src_mag.innovation[index])) {
fused[index] = true; fused[index] = true;
limitDeclination(); limitDeclination();
@ -261,7 +261,7 @@ bool Ekf::fuseDeclination(float decl_sigma)
// Calculate the Kalman gains // Calculate the Kalman gains
VectorState Kfusion = P * H / innovation_variance; VectorState Kfusion = P * H / innovation_variance;
const bool is_fused = measurementUpdate(Kfusion, innovation_variance, innovation); const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation);
_fault_status.flags.bad_mag_decl = !is_fused; _fault_status.flags.bad_mag_decl = !is_fused;

View File

@ -146,7 +146,7 @@ void Ekf::fuseOptFlow()
VectorState Kfusion = P * H / _aid_src_optical_flow.innovation_variance[index]; VectorState Kfusion = P * H / _aid_src_optical_flow.innovation_variance[index];
if (measurementUpdate(Kfusion, _aid_src_optical_flow.innovation_variance[index], _aid_src_optical_flow.innovation[index])) { if (measurementUpdate(Kfusion, H, _aid_src_optical_flow.observation_variance[index], _aid_src_optical_flow.innovation[index])) {
fused[index] = true; fused[index] = true;
} }
} }

View File

@ -142,7 +142,7 @@ void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip)
K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) = K_wind; K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) = K_wind;
} }
const bool is_fused = measurementUpdate(K, sideslip.innovation_variance, sideslip.innovation); const bool is_fused = measurementUpdate(K, H, sideslip.observation_variance, sideslip.innovation);
sideslip.fused = is_fused; sideslip.fused = is_fused;
_fault_status.flags.bad_sideslip = !is_fused; _fault_status.flags.bad_sideslip = !is_fused;

View File

@ -113,7 +113,7 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H
_innov_check_fail_status.flags.reject_yaw = false; _innov_check_fail_status.flags.reject_yaw = false;
} }
if (measurementUpdate(Kfusion, aid_src_status.innovation_variance, aid_src_status.innovation)) { if (measurementUpdate(Kfusion, H_YAW, aid_src_status.observation_variance, aid_src_status.innovation)) {
_time_last_heading_fuse = _time_delayed_us; _time_last_heading_fuse = _time_delayed_us;

View File

@ -52,20 +52,20 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
4990000,1,-0.0092,-0.012,0.00059,0.013,0.0037,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,5.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.1e-05,0.04,0.04,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4990000,1,-0.0092,-0.012,0.00059,0.013,0.0037,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,5.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.1e-05,0.04,0.04,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.0091,-0.011,0.00066,0.01,0.004,-0.082,0.0045,0.001,-0.081,-0.0021,-0.0053,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00013,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5090000,1,-0.0091,-0.011,0.00066,0.01,0.004,-0.082,0.0045,0.001,-0.081,-0.0021,-0.0053,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00013,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.0089,-0.012,0.0007,0.0098,0.0076,-0.08,0.0055,0.0016,-0.079,-0.0021,-0.0053,5.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5190000,1,-0.0089,-0.012,0.0007,0.0098,0.0076,-0.08,0.0055,0.0016,-0.079,-0.0021,-0.0053,5.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0088,-0.011,0.00075,0.0081,0.0076,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.1e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5290000,1,-0.0088,-0.011,0.00075,0.0081,0.0076,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.2e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0087,-0.011,0.00074,0.0075,0.011,-0.065,0.0046,0.0023,-0.067,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.15,0.16,0.079,0.00035,0.00035,9.2e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5390000,1,-0.0087,-0.011,0.00074,0.0075,0.011,-0.065,0.0046,0.0023,-0.067,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.15,0.16,0.079,0.00035,0.00035,9.2e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0088,-0.011,0.00073,0.007,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,5e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00012,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5490000,1,-0.0088,-0.011,0.00073,0.007,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,5e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00012,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0088,-0.011,0.00066,0.0082,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5590000,1,-0.0088,-0.011,0.00066,0.0082,0.016,-0.053,0.004,0.0036,-0.058,-0.002,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.32,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0089,-0.011,0.00055,0.0074,0.016,-0.052,0.0028,0.0031,-0.055,-0.0019,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.5e-06,0.04,0.04,0.0062,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5690000,1,-0.0089,-0.011,0.00055,0.0074,0.016,-0.052,0.0028,0.0031,-0.055,-0.0019,-0.0055,4.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.5e-06,0.04,0.04,0.0062,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0087,-0.011,0.0005,0.0087,0.018,-0.049,0.0036,0.0048,-0.053,-0.0019,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.5e-06,0.04,0.04,0.0058,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5790000,1,-0.0087,-0.011,0.0005,0.0087,0.018,-0.049,0.0036,0.0048,-0.053,-0.0019,-0.0055,4.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.5e-06,0.04,0.04,0.0058,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0088,-0.011,0.00053,0.0092,0.016,-0.048,0.0027,0.0039,-0.056,-0.0019,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5890000,1,-0.0088,-0.011,0.00053,0.0092,0.016,-0.048,0.0027,0.0039,-0.056,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0088,-0.011,0.00049,0.011,0.017,-0.041,0.0037,0.0055,-0.05,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.046,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5990000,1,-0.0088,-0.011,0.00049,0.011,0.017,-0.041,0.0037,0.0055,-0.05,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.046,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0087,-0.011,0.0003,0.011,0.019,-0.039,0.0048,0.0073,-0.047,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6090000,1,-0.0087,-0.011,0.0003,0.011,0.019,-0.039,0.0048,0.0073,-0.047,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0089,-0.011,0.0003,0.0083,0.017,-0.038,0.0037,0.0059,-0.047,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6190000,1,-0.0089,-0.011,0.0003,0.0083,0.017,-0.038,0.0037,0.0059,-0.047,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0088,-0.011,0.00032,0.0075,0.02,-0.041,0.0045,0.0077,-0.053,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.041,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6290000,1,-0.0088,-0.011,0.00032,0.0075,0.02,-0.041,0.0045,0.0077,-0.053,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.041,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,1,-0.0089,-0.011,0.00033,0.0077,0.017,-0.042,0.0033,0.0062,-0.056,-0.0017,-0.0056,4.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6390000,1,-0.0089,-0.011,0.00033,0.0077,0.017,-0.042,0.0033,0.0062,-0.056,-0.0017,-0.0056,4.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6490000,1,-0.0088,-0.011,0.00022,0.0051,0.017,-0.039,0.004,0.0078,-0.053,-0.0017,-0.0056,4.3e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6490000,1,-0.0088,-0.011,0.00022,0.0051,0.017,-0.039,0.004,0.0078,-0.053,-0.0017,-0.0056,4.3e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6590000,1,-0.0089,-0.011,0.00014,0.0034,0.015,-0.042,0.0027,0.006,-0.056,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6590000,1,-0.0089,-0.011,0.00014,0.0034,0.016,-0.042,0.0027,0.006,-0.056,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6690000,1,-0.0088,-0.011,9.4e-05,0.0016,0.019,-0.044,0.003,0.0077,-0.057,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6690000,1,-0.0088,-0.011,9.4e-05,0.0016,0.019,-0.044,0.003,0.0077,-0.057,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6790000,1,-0.0089,-0.011,5.3e-05,0.0023,0.016,-0.042,0.0019,0.0061,-0.058,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6790000,1,-0.0089,-0.011,5.3e-05,0.0023,0.016,-0.042,0.0019,0.0061,-0.058,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6890000,1,-0.0087,-0.011,-3.7e-05,0.0016,0.016,-0.039,0.0021,0.0076,-0.055,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6890000,1,-0.0087,-0.011,-3.7e-05,0.0016,0.016,-0.039,0.0021,0.0076,-0.055,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
@ -79,18 +79,18 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
7690000,-0.29,0.013,-0.005,0.96,0.0053,-0.0079,-0.022,0.0046,0.0069,-0.036,-0.0016,-0.0057,3.8e-05,-0.0006,0.00053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.24,0.24,0.025,0.35,0.35,0.062,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 7690000,-0.29,0.013,-0.005,0.96,0.0053,-0.0079,-0.022,0.0046,0.0069,-0.036,-0.0016,-0.0057,3.8e-05,-0.0006,0.00053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.24,0.24,0.025,0.35,0.35,0.062,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
7790000,-0.29,0.013,-0.0048,0.96,0.0042,-0.01,-0.025,0.005,0.006,-0.041,-0.0016,-0.0057,3.8e-05,-0.00055,0.00049,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.26,0.26,0.024,0.4,0.4,0.061,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 7790000,-0.29,0.013,-0.0048,0.96,0.0042,-0.01,-0.025,0.005,0.006,-0.041,-0.0016,-0.0057,3.8e-05,-0.00055,0.00049,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.26,0.26,0.024,0.4,0.4,0.061,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
7890000,-0.29,0.013,-0.0049,0.96,0.0064,-0.014,-0.025,0.0056,0.0049,-0.045,-0.0016,-0.0057,3.8e-05,-0.00054,0.00047,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.29,0.29,0.023,0.46,0.46,0.06,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 7890000,-0.29,0.013,-0.0049,0.96,0.0064,-0.014,-0.025,0.0056,0.0049,-0.045,-0.0016,-0.0057,3.8e-05,-0.00054,0.00047,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.29,0.29,0.023,0.46,0.46,0.06,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
7990000,-0.29,0.013,-0.0048,0.96,0.0066,-0.016,-0.021,0.0062,0.0035,-0.042,-0.0016,-0.0057,3.9e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.32,0.32,0.022,0.52,0.52,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 7990000,-0.29,0.013,-0.0048,0.96,0.0066,-0.016,-0.021,0.0062,0.0035,-0.042,-0.0016,-0.0057,3.8e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.32,0.32,0.022,0.52,0.52,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8090000,-0.29,0.013,-0.0046,0.96,0.0059,-0.02,-0.022,0.0068,0.0017,-0.044,-0.0016,-0.0057,3.9e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.35,0.35,0.022,0.6,0.6,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8090000,-0.29,0.013,-0.0046,0.96,0.0059,-0.02,-0.022,0.0068,0.0017,-0.044,-0.0016,-0.0057,3.8e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.35,0.35,0.022,0.6,0.6,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8190000,-0.29,0.013,-0.0047,0.96,0.0063,-0.025,-0.018,0.0074,-0.00064,-0.038,-0.0016,-0.0057,3.9e-05,-0.00081,0.0007,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.38,0.38,0.021,0.68,0.68,0.058,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8190000,-0.29,0.013,-0.0047,0.96,0.0063,-0.025,-0.018,0.0074,-0.00064,-0.038,-0.0016,-0.0057,3.8e-05,-0.00081,0.0007,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.38,0.38,0.021,0.68,0.68,0.058,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8290000,-0.29,0.013,-0.0047,0.96,-0.00096,-0.0043,-0.016,0.0074,-0.0011,-0.038,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8290000,-0.29,0.013,-0.0047,0.96,-0.00096,-0.0043,-0.016,0.0074,-0.0011,-0.038,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8390000,-0.29,0.013,-0.0046,0.96,0.0015,-0.0056,-0.016,0.0074,-0.0015,-0.036,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8390000,-0.29,0.013,-0.0046,0.96,0.0015,-0.0056,-0.016,0.0074,-0.0015,-0.036,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8490000,-0.29,0.013,-0.0045,0.96,0.0026,-0.0096,-0.017,0.0076,-0.0019,-0.041,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.019,51,51,0.056,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8490000,-0.29,0.013,-0.0045,0.96,0.0026,-0.0096,-0.017,0.0076,-0.0019,-0.041,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.019,51,51,0.056,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8590000,-0.29,0.013,-0.0045,0.96,0.0022,-0.013,-0.012,0.0078,-0.003,-0.036,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.019,52,52,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8590000,-0.29,0.013,-0.0045,0.96,0.0022,-0.013,-0.012,0.0078,-0.003,-0.036,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.019,52,52,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8690000,-0.29,0.013,-0.0045,0.96,0.0026,-0.015,-0.014,0.0079,-0.0035,-0.037,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,35,35,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8690000,-0.29,0.013,-0.0045,0.96,0.0026,-0.015,-0.014,0.0079,-0.0035,-0.037,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,35,35,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8790000,-0.29,0.013,-0.0044,0.96,0.0018,-0.018,-0.013,0.0082,-0.0051,-0.035,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,37,37,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00097,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8790000,-0.29,0.013,-0.0044,0.96,0.0018,-0.018,-0.013,0.0082,-0.0051,-0.035,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,37,37,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00097,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8890000,-0.29,0.013,-0.0045,0.96,0.0024,-0.021,-0.0092,0.0082,-0.0058,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.017,28,28,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00093,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8890000,-0.29,0.013,-0.0045,0.96,0.0024,-0.021,-0.0092,0.0082,-0.0058,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.017,28,28,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00093,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8990000,-0.29,0.013,-0.0044,0.96,0.0043,-0.026,-0.0084,0.0086,-0.0081,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,24,24,0.017,30,30,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00089,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8990000,-0.29,0.013,-0.0044,0.96,0.0043,-0.026,-0.0084,0.0086,-0.0081,-0.032,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,24,24,0.017,30,30,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00089,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9090000,-0.29,0.013,-0.0044,0.96,0.0049,-0.03,-0.0094,0.0087,-0.0088,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,25,25,0.053,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00085,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9090000,-0.29,0.013,-0.0044,0.96,0.0049,-0.03,-0.0094,0.0087,-0.0088,-0.032,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,25,25,0.053,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00085,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9190000,-0.29,0.013,-0.0043,0.96,0.002,-0.034,-0.0089,0.009,-0.012,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,27,27,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00081,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9190000,-0.29,0.013,-0.0043,0.96,0.002,-0.034,-0.0089,0.009,-0.012,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,27,27,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00081,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9290000,-0.29,0.013,-0.0042,0.96,0.00017,-0.036,-0.0073,0.0087,-0.013,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,21,21,0.015,23,23,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9290000,-0.29,0.013,-0.0042,0.96,0.00017,-0.036,-0.0073,0.0087,-0.013,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,21,21,0.015,23,23,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9390000,-0.29,0.013,-0.0041,0.96,0.00073,-0.039,-0.0062,0.0087,-0.016,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,21,21,0.015,26,26,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00075,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9390000,-0.29,0.013,-0.0041,0.96,0.00073,-0.039,-0.0062,0.0087,-0.016,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,21,21,0.015,26,26,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00075,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
@ -98,25 +98,25 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
9590000,-0.29,0.013,-0.0041,0.96,0.0017,-0.042,-0.0044,0.0087,-0.02,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,19,19,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00069,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9590000,-0.29,0.013,-0.0041,0.96,0.0017,-0.042,-0.0044,0.0087,-0.02,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,19,19,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00069,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9690000,-0.29,0.013,-0.0041,0.96,0.0022,-0.042,-0.0015,0.0085,-0.02,-0.027,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,22,22,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00066,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9690000,-0.29,0.013,-0.0041,0.96,0.0022,-0.042,-0.0015,0.0085,-0.02,-0.027,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,22,22,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00066,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9790000,-0.29,0.013,-0.0041,0.96,0.0017,-0.047,-0.0028,0.0087,-0.024,-0.028,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00064,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9790000,-0.29,0.013,-0.0041,0.96,0.0017,-0.047,-0.0028,0.0087,-0.024,-0.028,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00064,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9890000,-0.29,0.013,-0.004,0.96,-0.00018,-0.046,-0.0015,0.0085,-0.023,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0018,0.018,15,15,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00061,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9890000,-0.29,0.013,-0.004,0.96,-0.00017,-0.046,-0.0015,0.0085,-0.023,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0018,0.018,15,15,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00061,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9990000,-0.29,0.013,-0.004,0.96,-0.0013,-0.049,-0.0008,0.0085,-0.028,-0.031,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,15,15,0.013,25,25,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9990000,-0.29,0.013,-0.004,0.96,-0.0013,-0.049,-0.0008,0.0085,-0.028,-0.031,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,15,15,0.013,25,25,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10090000,-0.29,0.013,-0.0039,0.96,0.00027,-0.046,0.00042,0.0082,-0.026,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,13,13,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00057,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10090000,-0.29,0.013,-0.0039,0.96,0.00028,-0.046,0.00042,0.0082,-0.026,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,13,13,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00057,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10190000,-0.29,0.013,-0.0039,0.96,0.0026,-0.049,0.0013,0.0083,-0.03,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.013,24,24,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00055,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10190000,-0.29,0.013,-0.0039,0.96,0.0026,-0.049,0.0013,0.0083,-0.03,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.013,24,24,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00055,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10290000,-0.29,0.013,-0.0039,0.96,0.0027,-0.053,0.00023,0.0086,-0.036,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.012,27,27,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00053,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10290000,-0.29,0.013,-0.0039,0.96,0.0027,-0.053,0.00023,0.0086,-0.036,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.012,27,27,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00053,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10390000,-0.29,0.013,-0.0039,0.96,0.014,-0.0047,-0.0025,0.0011,-0.00013,-0.028,-0.0016,-0.0057,3.9e-05,-0.00085,0.00074,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.25,0.25,0.56,0.25,0.25,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00052,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10390000,-0.29,0.013,-0.0039,0.96,0.014,-0.0047,-0.0025,0.0011,-0.00013,-0.028,-0.0016,-0.0057,3.9e-05,-0.00085,0.00074,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.25,0.25,0.56,0.25,0.25,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00052,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10490000,-0.29,0.013,-0.0038,0.96,0.013,-0.0077,0.007,0.0025,-0.0007,-0.023,-0.0016,-0.0057,3.9e-05,-0.00098,0.00083,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.26,0.26,0.55,0.26,0.26,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10490000,-0.29,0.013,-0.0038,0.96,0.013,-0.0077,0.007,0.0025,-0.0007,-0.023,-0.0016,-0.0057,3.9e-05,-0.00098,0.00083,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.26,0.26,0.55,0.26,0.26,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10590000,-0.29,0.013,-0.0038,0.96,0.0018,-0.0063,0.013,0.00044,-0.00048,-0.021,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.13,0.13,0.27,0.26,0.26,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00049,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10590000,-0.29,0.013,-0.0038,0.96,0.0018,-0.0063,0.013,0.00044,-0.00048,-0.021,-0.0016,-0.0057,3.8e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.13,0.13,0.27,0.26,0.26,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00049,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10690000,-0.29,0.013,-0.0037,0.96,0.00059,-0.0081,0.016,0.00055,-0.0012,-0.017,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.14,0.14,0.26,0.27,0.27,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00048,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10690000,-0.29,0.013,-0.0037,0.96,0.00059,-0.0081,0.016,0.00055,-0.0012,-0.017,-0.0016,-0.0057,3.8e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.14,0.14,0.26,0.27,0.27,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00048,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10790000,-0.29,0.013,-0.0037,0.96,-0.0011,-0.012,0.014,0.00022,-0.0018,-0.015,-0.0016,-0.0057,3.9e-05,-0.0013,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.1,0.1,0.17,0.13,0.13,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10790000,-0.29,0.013,-0.0037,0.96,-0.0011,-0.012,0.014,0.00022,-0.0018,-0.015,-0.0016,-0.0057,3.8e-05,-0.0013,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.1,0.1,0.17,0.13,0.13,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10890000,-0.29,0.013,-0.0036,0.96,-0.00075,-0.016,0.01,0.00011,-0.0031,-0.018,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.12,0.12,0.16,0.14,0.14,0.068,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10890000,-0.29,0.013,-0.0036,0.96,-0.00075,-0.016,0.01,0.00011,-0.0031,-0.018,-0.0016,-0.0057,3.8e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.12,0.12,0.16,0.14,0.14,0.068,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10990000,-0.29,0.013,-0.0038,0.96,0.0008,-0.019,0.016,9.8e-05,-0.0017,-0.011,-0.0016,-0.0057,3.8e-05,-0.00092,0.0016,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,0.091,0.091,0.12,0.093,0.093,0.065,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10990000,-0.29,0.013,-0.0038,0.96,0.0008,-0.019,0.016,9.8e-05,-0.0017,-0.011,-0.0016,-0.0057,3.7e-05,-0.00093,0.0016,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,0.091,0.091,0.12,0.093,0.093,0.065,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11090000,-0.29,0.013,-0.0039,0.96,0.0006,-0.025,0.02,0.00019,-0.0038,-0.0074,-0.0016,-0.0057,3.8e-05,-0.00095,0.0017,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.11,0.11,0.11,0.099,0.099,0.069,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11090000,-0.29,0.013,-0.0039,0.96,0.00061,-0.025,0.02,0.00019,-0.0038,-0.0074,-0.0016,-0.0057,3.7e-05,-0.00095,0.0017,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.11,0.11,0.11,0.099,0.099,0.069,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11190000,-0.29,0.013,-0.0042,0.96,0.0056,-0.022,0.026,0.0015,-0.0021,-0.00036,-0.0015,-0.0057,3.5e-05,-6.8e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.09,0.09,0.083,0.073,0.073,0.066,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11190000,-0.29,0.013,-0.0042,0.96,0.0056,-0.022,0.026,0.0015,-0.0021,-0.00036,-0.0015,-0.0057,3.5e-05,-7e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.09,0.09,0.083,0.073,0.073,0.066,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11290000,-0.29,0.013,-0.0041,0.96,0.0061,-0.023,0.026,0.0021,-0.0044,-0.00013,-0.0015,-0.0057,3.5e-05,-5.3e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.11,0.11,0.077,0.08,0.08,0.069,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11290000,-0.29,0.013,-0.0041,0.96,0.0061,-0.023,0.026,0.0021,-0.0044,-0.00013,-0.0015,-0.0057,3.5e-05,-5.5e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.11,0.11,0.077,0.08,0.08,0.069,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11390000,-0.29,0.013,-0.0044,0.96,0.0051,-0.019,0.016,0.0014,-0.0025,-0.0086,-0.0014,-0.0058,3.3e-05,0.00035,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.091,0.091,0.062,0.063,0.063,0.066,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11390000,-0.29,0.013,-0.0044,0.96,0.0051,-0.019,0.016,0.0014,-0.0025,-0.0086,-0.0014,-0.0058,3.2e-05,0.00034,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.091,0.091,0.062,0.063,0.063,0.066,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11490000,-0.29,0.013,-0.0043,0.96,0.0064,-0.021,0.02,0.0021,-0.0045,-0.0025,-0.0014,-0.0058,3.3e-05,0.00032,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.11,0.11,0.057,0.07,0.07,0.067,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11490000,-0.29,0.013,-0.0043,0.96,0.0064,-0.021,0.02,0.0021,-0.0045,-0.0025,-0.0014,-0.0058,3.2e-05,0.00032,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.11,0.11,0.057,0.07,0.07,0.067,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11590000,-0.29,0.013,-0.0047,0.96,0.0023,-0.016,0.018,0.0012,-0.0026,-0.0036,-0.0014,-0.0058,3.1e-05,0.00056,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.09,0.09,0.048,0.057,0.057,0.065,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11590000,-0.29,0.013,-0.0047,0.96,0.0023,-0.016,0.018,0.0012,-0.0026,-0.0036,-0.0014,-0.0058,3e-05,0.00055,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.09,0.09,0.048,0.057,0.057,0.065,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11690000,-0.29,0.013,-0.0046,0.96,0.0027,-0.021,0.018,0.0014,-0.0044,-0.0049,-0.0014,-0.0058,3.1e-05,0.00057,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.044,0.065,0.065,0.066,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11690000,-0.29,0.013,-0.0046,0.96,0.0027,-0.021,0.018,0.0014,-0.0044,-0.0049,-0.0014,-0.0058,3e-05,0.00057,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.044,0.065,0.065,0.066,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11790000,-0.29,0.013,-0.0048,0.96,0.0023,-0.02,0.019,0.001,-0.004,-0.002,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.087,0.087,0.037,0.054,0.054,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11790000,-0.29,0.013,-0.0048,0.96,0.0023,-0.02,0.019,0.001,-0.004,-0.002,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.087,0.087,0.037,0.054,0.054,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11890000,-0.29,0.013,-0.0049,0.96,-3e-05,-0.023,0.017,0.0012,-0.0061,-0.0013,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.1,0.1,0.034,0.062,0.062,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11890000,-0.29,0.013,-0.0049,0.96,-3e-05,-0.023,0.017,0.0012,-0.0061,-0.0013,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.1,0.1,0.034,0.062,0.062,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11990000,-0.29,0.013,-0.0053,0.96,0.0022,-0.015,0.015,0.0028,-0.0031,-0.005,-0.0013,-0.0059,2.6e-05,0.0015,0.0052,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.088,0.088,0.03,0.063,0.063,0.061,4.8e-05,4.8e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11990000,-0.29,0.013,-0.0053,0.96,0.0022,-0.015,0.015,0.0028,-0.0031,-0.005,-0.0013,-0.0059,2.6e-05,0.0015,0.0052,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.088,0.088,0.03,0.063,0.063,0.061,4.8e-05,4.8e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
@ -129,51 +129,51 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
12690000,-0.29,0.013,-0.0054,0.96,-8.4e-05,-0.0036,0.019,0.003,-0.0025,0.0033,-0.0012,-0.0059,2.4e-05,0.0019,0.0057,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00094,0.00094,0.018,0.08,0.08,0.015,0.062,0.062,0.053,4.2e-05,4.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 12690000,-0.29,0.013,-0.0054,0.96,-8.4e-05,-0.0036,0.019,0.003,-0.0025,0.0033,-0.0012,-0.0059,2.4e-05,0.0019,0.0057,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00094,0.00094,0.018,0.08,0.08,0.015,0.062,0.062,0.053,4.2e-05,4.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
12790000,-0.29,0.012,-0.0053,0.96,0.0056,-0.0099,0.021,0.0064,-0.0057,0.0054,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.07,0.07,0.014,0.063,0.063,0.052,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 12790000,-0.29,0.012,-0.0053,0.96,0.0056,-0.0099,0.021,0.0064,-0.0057,0.0054,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.07,0.07,0.014,0.063,0.063,0.052,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
12890000,-0.29,0.012,-0.0053,0.96,0.0062,-0.01,0.022,0.0069,-0.0067,0.0084,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.08,0.08,0.013,0.072,0.072,0.051,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 12890000,-0.29,0.012,-0.0053,0.96,0.0062,-0.01,0.022,0.0069,-0.0067,0.0084,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.08,0.08,0.013,0.072,0.072,0.051,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
12990000,-0.29,0.012,-0.0054,0.96,0.0036,-0.008,0.022,0.0049,-0.0045,0.0096,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00083,0.018,0.063,0.063,0.012,0.058,0.058,0.05,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 12990000,-0.29,0.012,-0.0054,0.96,0.0036,-0.008,0.022,0.0049,-0.0045,0.0096,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00083,0.018,0.063,0.063,0.012,0.058,0.058,0.05,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13090000,-0.29,0.012,-0.0054,0.96,0.0033,-0.0091,0.02,0.0053,-0.0054,0.0085,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00086,0.00086,0.018,0.072,0.072,0.011,0.067,0.067,0.049,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13090000,-0.29,0.012,-0.0054,0.96,0.0033,-0.0091,0.02,0.0053,-0.0054,0.0085,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00086,0.00086,0.018,0.072,0.072,0.011,0.067,0.067,0.049,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13190000,-0.29,0.012,-0.0054,0.96,0.004,-0.0095,0.019,0.0052,-0.0065,0.0091,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.063,0.063,0.011,0.068,0.068,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13190000,-0.29,0.012,-0.0054,0.96,0.004,-0.0095,0.019,0.0052,-0.0065,0.0091,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.063,0.063,0.011,0.068,0.068,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13290000,-0.29,0.012,-0.0054,0.96,0.0046,-0.0095,0.016,0.0056,-0.0075,0.0084,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.072,0.072,0.01,0.078,0.078,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13290000,-0.29,0.012,-0.0054,0.96,0.0046,-0.0095,0.016,0.0056,-0.0075,0.0084,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.072,0.072,0.01,0.078,0.078,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13390000,-0.29,0.012,-0.0054,0.96,0.0031,-0.0074,0.016,0.004,-0.005,0.0091,-0.0012,-0.0059,2.4e-05,0.0021,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.057,0.057,0.0095,0.061,0.061,0.046,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13390000,-0.29,0.012,-0.0054,0.96,0.0031,-0.0074,0.016,0.004,-0.005,0.0091,-0.0012,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.057,0.057,0.0095,0.061,0.061,0.046,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13490000,-0.29,0.012,-0.0054,0.96,0.0032,-0.0099,0.015,0.0043,-0.0059,0.0053,-0.0012,-0.0059,2.4e-05,0.0021,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.064,0.064,0.009,0.07,0.07,0.045,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13490000,-0.29,0.012,-0.0054,0.96,0.0032,-0.0099,0.015,0.0043,-0.0059,0.0053,-0.0012,-0.0059,2.4e-05,0.0021,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.064,0.064,0.009,0.07,0.07,0.045,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13590000,-0.29,0.012,-0.0055,0.96,0.0054,-0.0069,0.017,0.0065,-0.0039,0.0038,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.053,0.053,0.0086,0.057,0.057,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13590000,-0.29,0.012,-0.0055,0.96,0.0054,-0.0069,0.017,0.0065,-0.0039,0.0038,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.053,0.053,0.0086,0.057,0.057,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13690000,-0.29,0.012,-0.0054,0.96,0.0058,-0.0061,0.017,0.0071,-0.0046,0.0064,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.06,0.06,0.0083,0.065,0.065,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13690000,-0.29,0.012,-0.0054,0.96,0.0058,-0.0061,0.017,0.0071,-0.0046,0.0064,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.06,0.06,0.0083,0.065,0.065,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13790000,-0.29,0.012,-0.0055,0.96,0.0079,-0.0045,0.017,0.01,-0.0018,0.0059,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.05,0.05,0.0079,0.054,0.054,0.042,3.3e-05,3.3e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13790000,-0.29,0.012,-0.0055,0.96,0.0079,-0.0045,0.017,0.01,-0.0018,0.0059,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.05,0.05,0.0079,0.054,0.054,0.042,3.4e-05,3.4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13890000,-0.29,0.012,-0.0054,0.96,0.0081,-0.0056,0.018,0.011,-0.0023,0.0081,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.056,0.056,0.0077,0.061,0.061,0.042,3.3e-05,3.3e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13890000,-0.29,0.012,-0.0054,0.96,0.0081,-0.0056,0.018,0.011,-0.0023,0.0081,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.056,0.056,0.0077,0.061,0.061,0.042,3.4e-05,3.4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13990000,-0.29,0.012,-0.0054,0.96,0.0034,-0.0095,0.017,0.0083,-0.0032,0.007,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.048,0.048,0.0074,0.052,0.052,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13990000,-0.29,0.012,-0.0054,0.96,0.0034,-0.0095,0.017,0.0083,-0.0032,0.007,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.048,0.048,0.0074,0.052,0.052,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14090000,-0.29,0.012,-0.0054,0.96,0.0056,-0.0051,0.018,0.0086,-0.0039,0.0035,-0.0012,-0.006,2.3e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.054,0.054,0.0073,0.059,0.059,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14090000,-0.29,0.012,-0.0054,0.96,0.0056,-0.0051,0.018,0.0086,-0.0039,0.0035,-0.0012,-0.006,2.3e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.00079,0.018,0.054,0.054,0.0073,0.059,0.059,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14190000,-0.29,0.012,-0.0054,0.96,0.0075,-0.0044,0.018,0.0083,-0.003,0.0037,-0.0012,-0.006,2.2e-05,0.002,0.0054,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.046,0.046,0.0071,0.05,0.05,0.04,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14190000,-0.29,0.012,-0.0054,0.96,0.0075,-0.0044,0.018,0.0083,-0.003,0.0037,-0.0012,-0.006,2.2e-05,0.002,0.0054,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.046,0.046,0.0071,0.05,0.05,0.04,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14290000,-0.29,0.012,-0.0054,0.96,0.0067,-0.0051,0.016,0.0092,-0.0034,0.0079,-0.0012,-0.006,2.2e-05,0.0019,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.052,0.052,0.007,0.057,0.057,0.039,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14290000,-0.29,0.012,-0.0054,0.96,0.0067,-0.0051,0.016,0.0092,-0.0034,0.0079,-0.0012,-0.006,2.2e-05,0.0019,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.052,0.052,0.007,0.057,0.057,0.039,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14390000,-0.29,0.012,-0.0054,0.96,0.0054,-0.0047,0.018,0.0085,-0.004,0.012,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.045,0.045,0.0068,0.049,0.049,0.039,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14390000,-0.29,0.012,-0.0054,0.96,0.0054,-0.0047,0.018,0.0085,-0.004,0.012,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.045,0.045,0.0068,0.049,0.049,0.039,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14490000,-0.29,0.012,-0.0055,0.96,0.0077,-0.0052,0.021,0.0093,-0.0044,0.015,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.05,0.05,0.0067,0.056,0.056,0.038,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14490000,-0.29,0.012,-0.0055,0.96,0.0077,-0.0052,0.021,0.0093,-0.0044,0.015,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.05,0.05,0.0067,0.056,0.056,0.038,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14590000,-0.29,0.012,-0.0056,0.96,0.002,-0.0072,0.019,0.0058,-0.0049,0.011,-0.0012,-0.006,2.2e-05,0.0024,0.0054,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.044,0.044,0.0066,0.048,0.048,0.038,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14590000,-0.29,0.012,-0.0056,0.96,0.002,-0.0072,0.019,0.0058,-0.0049,0.011,-0.0012,-0.006,2.3e-05,0.0023,0.0054,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.044,0.044,0.0066,0.048,0.048,0.038,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14690000,-0.29,0.012,-0.0055,0.96,0.0031,-0.0078,0.019,0.0061,-0.0056,0.011,-0.0012,-0.006,2.2e-05,0.0024,0.0053,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.049,0.049,0.0066,0.055,0.055,0.037,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14690000,-0.29,0.012,-0.0055,0.96,0.0031,-0.0078,0.019,0.0061,-0.0056,0.011,-0.0012,-0.006,2.3e-05,0.0024,0.0053,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.049,0.049,0.0066,0.055,0.055,0.037,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14790000,-0.29,0.012,-0.0059,0.96,-0.0012,-0.0025,0.019,0.0047,-0.00016,0.014,-0.0011,-0.006,2e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.043,0.043,0.0065,0.048,0.048,0.037,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14790000,-0.29,0.012,-0.0059,0.96,-0.0012,-0.0025,0.019,0.0047,-0.00016,0.014,-0.0011,-0.006,2.1e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.043,0.043,0.0065,0.048,0.048,0.037,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14890000,-0.29,0.012,-0.0058,0.96,-0.00028,7.5e-05,0.023,0.0047,-0.00028,0.015,-0.0011,-0.006,2e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.048,0.048,0.0066,0.054,0.054,0.036,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14890000,-0.29,0.012,-0.0058,0.96,-0.00028,7.5e-05,0.023,0.0047,-0.00028,0.015,-0.0011,-0.006,2.1e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.048,0.048,0.0066,0.054,0.054,0.036,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14990000,-0.29,0.012,-0.0059,0.96,-0.0013,-0.0021,0.026,0.0038,-0.0016,0.017,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.042,0.042,0.0065,0.047,0.047,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14990000,-0.29,0.012,-0.0059,0.96,-0.0012,-0.0021,0.026,0.0038,-0.0016,0.017,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.042,0.042,0.0065,0.047,0.047,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15090000,-0.29,0.012,-0.0058,0.96,-0.001,-0.0034,0.03,0.0037,-0.0019,0.019,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.047,0.047,0.0066,0.054,0.054,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15090000,-0.29,0.012,-0.0058,0.96,-0.001,-0.0034,0.03,0.0037,-0.0019,0.019,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.047,0.047,0.0066,0.054,0.054,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15190000,-0.29,0.012,-0.0059,0.96,-0.0013,-0.0017,0.03,0.003,-0.0013,0.021,-0.0011,-0.006,2.1e-05,0.0022,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.041,0.041,0.0066,0.047,0.047,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15190000,-0.29,0.012,-0.0059,0.96,-0.0013,-0.0017,0.03,0.003,-0.0013,0.021,-0.0011,-0.006,2.1e-05,0.0022,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.041,0.041,0.0066,0.047,0.047,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15290000,-0.29,0.012,-0.006,0.96,-0.0021,-0.001,0.03,0.0028,-0.0015,0.018,-0.0011,-0.006,2e-05,0.0024,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.046,0.046,0.0066,0.053,0.053,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15290000,-0.29,0.012,-0.006,0.96,-0.0021,-0.001,0.03,0.0028,-0.0015,0.018,-0.0011,-0.006,2.1e-05,0.0024,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.046,0.046,0.0066,0.053,0.053,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15390000,-0.29,0.012,-0.0061,0.96,-0.0032,-0.0032,0.029,0.0024,-0.0013,0.018,-0.0011,-0.006,2e-05,0.0024,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.041,0.041,0.0066,0.047,0.047,0.034,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15390000,-0.29,0.012,-0.0061,0.96,-0.0032,-0.0032,0.029,0.0024,-0.0013,0.018,-0.0011,-0.006,2.1e-05,0.0024,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.041,0.041,0.0066,0.047,0.047,0.034,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15490000,-0.29,0.012,-0.0062,0.96,-0.0033,-0.00084,0.029,0.0021,-0.0015,0.019,-0.0011,-0.006,2e-05,0.0025,0.0043,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.046,0.046,0.0067,0.053,0.053,0.035,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15490000,-0.29,0.012,-0.0062,0.96,-0.0033,-0.00084,0.029,0.0021,-0.0015,0.019,-0.0011,-0.006,2.1e-05,0.0025,0.0043,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.046,0.046,0.0067,0.053,0.053,0.035,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15590000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0066,0.029,0.0045,-0.0054,0.018,-0.0012,-0.006,2.2e-05,0.0026,0.0051,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00072,0.00072,0.018,0.04,0.04,0.0067,0.046,0.046,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15590000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0066,0.029,0.0045,-0.0054,0.018,-0.0012,-0.006,2.2e-05,0.0026,0.0051,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00072,0.00072,0.018,0.04,0.04,0.0067,0.046,0.046,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15690000,-0.29,0.012,-0.0059,0.96,-0.0033,-0.0048,0.03,0.0042,-0.006,0.019,-0.0012,-0.006,2.2e-05,0.0027,0.0051,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.045,0.045,0.0068,0.053,0.053,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15690000,-0.29,0.012,-0.0059,0.96,-0.0033,-0.0048,0.03,0.0042,-0.006,0.019,-0.0012,-0.006,2.2e-05,0.0026,0.0051,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.045,0.045,0.0068,0.053,0.053,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15790000,-0.29,0.012,-0.006,0.96,-0.0022,-0.0025,0.03,0.0036,-0.0047,0.021,-0.0012,-0.006,2.2e-05,0.0026,0.0049,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.039,0.039,0.0068,0.046,0.046,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15790000,-0.29,0.012,-0.006,0.96,-0.0022,-0.0025,0.03,0.0036,-0.0047,0.021,-0.0012,-0.006,2.2e-05,0.0026,0.0049,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.039,0.039,0.0068,0.046,0.046,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15890000,-0.29,0.012,-0.0061,0.96,-0.00061,-0.0045,0.03,0.0035,-0.005,0.02,-0.0012,-0.006,2.2e-05,0.0027,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.044,0.044,0.0069,0.053,0.053,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15890000,-0.29,0.012,-0.0061,0.96,-0.00061,-0.0045,0.03,0.0035,-0.005,0.02,-0.0012,-0.006,2.2e-05,0.0027,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.044,0.044,0.0069,0.053,0.053,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15990000,-0.29,0.012,-0.006,0.96,-0.00029,-0.0036,0.027,0.003,-0.004,0.02,-0.0012,-0.006,2.1e-05,0.0028,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.039,0.039,0.0069,0.046,0.046,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15990000,-0.29,0.012,-0.006,0.96,-0.00028,-0.0036,0.027,0.003,-0.004,0.02,-0.0012,-0.006,2.2e-05,0.0028,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.039,0.039,0.0069,0.046,0.046,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16090000,-0.29,0.012,-0.0059,0.96,0.00011,-0.0028,0.025,0.003,-0.0043,0.019,-0.0012,-0.006,2.1e-05,0.0029,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.044,0.044,0.007,0.053,0.053,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16090000,-0.29,0.012,-0.0059,0.96,0.00012,-0.0028,0.025,0.003,-0.0043,0.019,-0.0012,-0.006,2.2e-05,0.0029,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.044,0.044,0.007,0.053,0.053,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16190000,-0.29,0.012,-0.0059,0.96,-0.00023,-0.003,0.024,0.0012,-0.0036,0.016,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.038,0.038,0.0071,0.046,0.046,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16190000,-0.29,0.012,-0.0059,0.96,-0.00023,-0.003,0.024,0.0012,-0.0036,0.016,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.038,0.038,0.0071,0.046,0.046,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16290000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0021,0.024,0.0011,-0.0038,0.018,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.043,0.043,0.0072,0.053,0.053,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16290000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0021,0.024,0.0011,-0.0038,0.018,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.043,0.043,0.0072,0.053,0.053,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16390000,-0.29,0.012,-0.006,0.96,-0.00081,-0.0014,0.024,0.0022,-0.0032,0.018,-0.0012,-0.006,2.1e-05,0.0033,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00067,0.00067,0.018,0.038,0.038,0.0072,0.046,0.046,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16390000,-0.29,0.012,-0.006,0.96,-0.0008,-0.0014,0.024,0.0022,-0.0032,0.018,-0.0012,-0.006,2.1e-05,0.0033,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00067,0.00067,0.018,0.038,0.038,0.0072,0.046,0.046,0.033,1.4e-05,1.4e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16490000,-0.29,0.012,-0.0061,0.96,-0.0031,-0.00073,0.026,0.002,-0.0032,0.022,-0.0012,-0.006,2.1e-05,0.0032,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.042,0.042,0.0073,0.052,0.052,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16490000,-0.29,0.012,-0.0061,0.96,-0.0031,-0.00073,0.026,0.002,-0.0032,0.022,-0.0012,-0.006,2.1e-05,0.0032,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.042,0.042,0.0074,0.052,0.052,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16590000,-0.29,0.012,-0.0061,0.96,-0.0081,-0.0003,0.03,0.0015,-0.0027,0.022,-0.0012,-0.006,2.1e-05,0.0033,0.0038,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.037,0.037,0.0074,0.046,0.046,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16590000,-0.29,0.012,-0.0061,0.96,-0.0081,-0.0003,0.03,0.0015,-0.0027,0.022,-0.0012,-0.006,2.1e-05,0.0033,0.0038,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.037,0.037,0.0074,0.046,0.046,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16690000,-0.29,0.012,-0.0062,0.96,-0.011,0.0035,0.03,0.00053,-0.0025,0.023,-0.0012,-0.006,2.1e-05,0.0034,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00066,0.00066,0.018,0.042,0.042,0.0075,0.052,0.052,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16690000,-0.29,0.012,-0.0062,0.96,-0.011,0.0035,0.03,0.00053,-0.0025,0.023,-0.0012,-0.006,2.1e-05,0.0033,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00066,0.00066,0.018,0.042,0.042,0.0075,0.052,0.052,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16790000,-0.29,0.012,-0.006,0.96,-0.012,0.0032,0.029,0.00072,-0.0023,0.023,-0.0012,-0.0061,2.1e-05,0.0033,0.0038,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.037,0.037,0.0075,0.046,0.046,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16790000,-0.29,0.012,-0.006,0.96,-0.012,0.0032,0.029,0.00072,-0.0023,0.023,-0.0012,-0.0061,2.2e-05,0.0033,0.0038,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.037,0.037,0.0075,0.046,0.046,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16890000,-0.29,0.012,-0.006,0.96,-0.011,0.0036,0.03,-0.00046,-0.0019,0.021,-0.0012,-0.0061,2.1e-05,0.0035,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.041,0.041,0.0076,0.052,0.052,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16890000,-0.29,0.012,-0.006,0.96,-0.011,0.0036,0.03,-0.00046,-0.0019,0.021,-0.0012,-0.0061,2.2e-05,0.0035,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.041,0.041,0.0076,0.052,0.052,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16990000,-0.29,0.012,-0.006,0.96,-0.0067,0.0041,0.03,0.0025,-0.002,0.02,-0.0012,-0.0061,2.2e-05,0.0031,0.004,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.039,0.039,0.0076,0.054,0.054,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16990000,-0.29,0.012,-0.006,0.96,-0.0067,0.0041,0.03,0.0025,-0.002,0.02,-0.0012,-0.0061,2.2e-05,0.0031,0.004,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.039,0.039,0.0076,0.054,0.054,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17090000,-0.29,0.011,-0.0061,0.96,-0.0087,0.0061,0.03,0.0017,-0.0015,0.02,-0.0012,-0.0061,2.2e-05,0.0033,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.044,0.044,0.0077,0.062,0.062,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17090000,-0.29,0.011,-0.0061,0.96,-0.0087,0.0061,0.03,0.0017,-0.0015,0.02,-0.0012,-0.0061,2.2e-05,0.0033,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.044,0.044,0.0077,0.062,0.062,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17190000,-0.29,0.011,-0.006,0.96,-0.0069,0.0049,0.031,0.0036,-0.0048,0.023,-0.0013,-0.0061,2.3e-05,0.0033,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00061,0.00062,0.018,0.041,0.041,0.0077,0.064,0.064,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17190000,-0.29,0.011,-0.006,0.96,-0.0069,0.0049,0.031,0.0036,-0.0048,0.023,-0.0013,-0.0061,2.3e-05,0.0033,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00062,0.00062,0.018,0.041,0.041,0.0077,0.064,0.064,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17290000,-0.29,0.011,-0.006,0.96,-0.0076,0.0046,0.031,0.0029,-0.0044,0.023,-0.0013,-0.0061,2.3e-05,0.0034,0.0046,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.046,0.046,0.0078,0.072,0.072,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17290000,-0.29,0.011,-0.006,0.96,-0.0076,0.0046,0.031,0.0029,-0.0044,0.023,-0.0013,-0.0061,2.3e-05,0.0034,0.0046,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.046,0.046,0.0078,0.072,0.072,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17390000,-0.29,0.011,-0.006,0.96,-4.1e-05,0.011,0.03,0.0064,-0.0019,0.022,-0.0013,-0.0061,2.3e-05,0.0029,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00059,0.00059,0.018,0.038,0.038,0.0078,0.058,0.058,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17390000,-0.29,0.011,-0.006,0.96,-3.9e-05,0.011,0.03,0.0064,-0.0019,0.022,-0.0013,-0.0061,2.3e-05,0.0029,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00059,0.00059,0.018,0.038,0.038,0.0078,0.058,0.058,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17490000,-0.29,0.011,-0.006,0.96,0.0021,0.012,0.03,0.0066,-0.00081,0.024,-0.0013,-0.0061,2.3e-05,0.003,0.0046,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0006,0.0006,0.019,0.042,0.042,0.0079,0.066,0.066,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17490000,-0.29,0.011,-0.006,0.96,0.0021,0.012,0.03,0.0066,-0.00081,0.024,-0.0013,-0.0061,2.3e-05,0.003,0.0046,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0006,0.0006,0.019,0.042,0.042,0.0079,0.066,0.066,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17590000,-0.29,0.011,-0.006,0.96,-0.0017,0.0092,0.029,0.002,-0.0014,0.022,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.036,0.036,0.0079,0.055,0.055,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17590000,-0.29,0.011,-0.006,0.96,-0.0017,0.0092,0.029,0.002,-0.0014,0.022,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.036,0.036,0.0079,0.055,0.055,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17690000,-0.29,0.011,-0.0061,0.96,-0.00094,0.0098,0.03,0.0018,-0.00039,0.024,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.04,0.04,0.008,0.062,0.062,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17690000,-0.29,0.011,-0.0061,0.96,-0.00094,0.0098,0.03,0.0018,-0.00039,0.024,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.04,0.04,0.008,0.062,0.062,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
@ -181,171 +181,171 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
17890000,-0.29,0.011,-0.0061,0.96,-0.0035,0.012,0.03,0.0029,0.0018,0.034,-0.0013,-0.0061,2.3e-05,0.0036,0.0045,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.042,0.042,0.0081,0.072,0.072,0.034,7.6e-06,7.6e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17890000,-0.29,0.011,-0.0061,0.96,-0.0035,0.012,0.03,0.0029,0.0018,0.034,-0.0013,-0.0061,2.3e-05,0.0036,0.0045,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.042,0.042,0.0081,0.072,0.072,0.034,7.6e-06,7.6e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17990000,-0.29,0.011,-0.0061,0.96,-0.0037,0.015,0.03,0.0025,0.0054,0.034,-0.0013,-0.0061,2.3e-05,0.0034,0.0041,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00055,0.00055,0.019,0.035,0.035,0.008,0.058,0.058,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17990000,-0.29,0.011,-0.0061,0.96,-0.0037,0.015,0.03,0.0025,0.0054,0.034,-0.0013,-0.0061,2.3e-05,0.0034,0.0041,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00055,0.00055,0.019,0.035,0.035,0.008,0.058,0.058,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18090000,-0.29,0.011,-0.0062,0.96,-0.0033,0.016,0.029,0.0021,0.007,0.033,-0.0013,-0.0061,2.3e-05,0.0036,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00056,0.00056,0.019,0.039,0.039,0.0081,0.065,0.065,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18090000,-0.29,0.011,-0.0062,0.96,-0.0033,0.016,0.029,0.0021,0.007,0.033,-0.0013,-0.0061,2.3e-05,0.0036,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00056,0.00056,0.019,0.039,0.039,0.0081,0.065,0.065,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18190000,-0.29,0.011,-0.0062,0.96,-0.0012,0.014,0.03,0.0033,0.0048,0.031,-0.0013,-0.0061,2.3e-05,0.0039,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0081,0.054,0.054,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18190000,-0.29,0.011,-0.0062,0.96,-0.0012,0.014,0.03,0.0033,0.0048,0.031,-0.0013,-0.0061,2.4e-05,0.0039,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0081,0.054,0.054,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18290000,-0.29,0.011,-0.0062,0.96,-0.0021,0.014,0.028,0.0032,0.0062,0.029,-0.0013,-0.0061,2.3e-05,0.0041,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.037,0.037,0.0081,0.061,0.061,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18290000,-0.29,0.011,-0.0062,0.96,-0.0021,0.014,0.028,0.0032,0.0062,0.029,-0.0013,-0.0061,2.4e-05,0.0041,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.037,0.037,0.0081,0.061,0.061,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18390000,-0.29,0.011,-0.0061,0.96,0.0013,0.012,0.028,0.0054,0.0045,0.029,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.008,0.052,0.052,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18390000,-0.29,0.011,-0.0061,0.96,0.0013,0.012,0.028,0.0054,0.0045,0.029,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.0081,0.052,0.052,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18490000,-0.29,0.011,-0.0061,0.96,-0.001,0.012,0.027,0.0054,0.0057,0.03,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.0081,0.058,0.058,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18490000,-0.29,0.011,-0.0061,0.96,-0.001,0.012,0.027,0.0054,0.0057,0.03,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.0081,0.058,0.058,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18590000,-0.29,0.011,-0.006,0.96,-0.0014,0.011,0.027,0.0044,0.0043,0.033,-0.0013,-0.0061,2.4e-05,0.0043,0.0046,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.0081,0.05,0.05,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18590000,-0.29,0.011,-0.006,0.96,-0.0014,0.011,0.027,0.0044,0.0043,0.033,-0.0013,-0.0061,2.5e-05,0.0043,0.0046,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.0081,0.05,0.05,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18690000,-0.29,0.011,-0.0059,0.96,-0.00095,0.0098,0.026,0.0042,0.0053,0.031,-0.0013,-0.0061,2.4e-05,0.0045,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.034,0.034,0.0081,0.056,0.056,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18690000,-0.29,0.011,-0.0059,0.96,-0.00095,0.0098,0.026,0.0042,0.0053,0.031,-0.0013,-0.0061,2.5e-05,0.0045,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.034,0.034,0.0081,0.056,0.056,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18790000,-0.29,0.011,-0.0059,0.96,0.00091,0.0092,0.025,0.0048,0.0042,0.029,-0.0014,-0.0061,2.4e-05,0.0047,0.0045,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.0081,0.048,0.048,0.034,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18790000,-0.29,0.011,-0.0059,0.96,0.00091,0.0092,0.025,0.0048,0.0042,0.029,-0.0014,-0.0061,2.5e-05,0.0047,0.0045,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.0081,0.048,0.048,0.034,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18890000,-0.29,0.011,-0.0059,0.96,0.0026,0.0093,0.023,0.005,0.0052,0.025,-0.0013,-0.0061,2.4e-05,0.005,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.033,0.033,0.0081,0.054,0.054,0.035,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18890000,-0.29,0.011,-0.0059,0.96,0.0026,0.0093,0.023,0.005,0.0052,0.025,-0.0013,-0.0061,2.5e-05,0.005,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.033,0.033,0.0081,0.054,0.054,0.035,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18990000,-0.29,0.011,-0.0058,0.96,0.0023,0.009,0.024,0.004,0.004,0.029,-0.0014,-0.0061,2.5e-05,0.0052,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.008,0.047,0.047,0.034,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18990000,-0.29,0.011,-0.0058,0.96,0.0023,0.009,0.024,0.004,0.004,0.029,-0.0014,-0.0061,2.5e-05,0.0052,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.008,0.047,0.047,0.034,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19090000,-0.29,0.011,-0.0059,0.96,0.0044,0.01,0.025,0.0043,0.0049,0.025,-0.0014,-0.0061,2.4e-05,0.0054,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.0081,0.053,0.053,0.035,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19090000,-0.29,0.011,-0.0059,0.96,0.0044,0.01,0.025,0.0043,0.0049,0.025,-0.0014,-0.0061,2.5e-05,0.0054,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.0081,0.053,0.053,0.035,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19190000,-0.29,0.011,-0.0058,0.96,0.0044,0.0094,0.024,0.0034,0.004,0.024,-0.0014,-0.0061,2.5e-05,0.0058,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.008,0.046,0.046,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19190000,-0.29,0.011,-0.0058,0.96,0.0044,0.0094,0.024,0.0034,0.004,0.024,-0.0014,-0.0061,2.5e-05,0.0058,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.008,0.046,0.046,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19290000,-0.29,0.011,-0.0057,0.96,0.0054,0.0095,0.025,0.0039,0.0049,0.023,-0.0014,-0.0061,2.5e-05,0.0059,0.0041,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.008,0.052,0.052,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19290000,-0.29,0.011,-0.0057,0.96,0.0054,0.0095,0.025,0.0039,0.0049,0.023,-0.0014,-0.0061,2.6e-05,0.0059,0.0041,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.008,0.052,0.052,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19390000,-0.29,0.011,-0.0059,0.96,0.005,0.008,0.026,0.003,0.005,0.022,-0.0014,-0.0061,2.4e-05,0.0062,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.029,0.0079,0.045,0.045,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19390000,-0.29,0.011,-0.0059,0.96,0.005,0.008,0.026,0.003,0.005,0.022,-0.0014,-0.0061,2.5e-05,0.0062,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.029,0.029,0.0079,0.045,0.045,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19490000,-0.29,0.011,-0.0059,0.96,0.0059,0.0083,0.025,0.0036,0.0058,0.022,-0.0014,-0.0061,2.4e-05,0.0063,0.0038,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.0079,0.051,0.051,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19490000,-0.29,0.011,-0.0059,0.96,0.0059,0.0083,0.025,0.0036,0.0058,0.022,-0.0014,-0.0061,2.6e-05,0.0063,0.0038,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.0079,0.051,0.051,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19590000,-0.29,0.011,-0.0058,0.96,0.0078,0.0084,0.027,0.0041,0.0036,0.022,-0.0014,-0.0061,2.5e-05,0.0066,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0078,0.045,0.045,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19590000,-0.29,0.011,-0.0058,0.96,0.0079,0.0084,0.027,0.0041,0.0036,0.022,-0.0014,-0.0061,2.6e-05,0.0066,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0078,0.045,0.045,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19690000,-0.29,0.011,-0.0058,0.96,0.01,0.0074,0.026,0.0049,0.0043,0.022,-0.0014,-0.0061,2.5e-05,0.0067,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0078,0.051,0.051,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19690000,-0.29,0.011,-0.0058,0.96,0.01,0.0074,0.026,0.0049,0.0043,0.022,-0.0014,-0.0061,2.6e-05,0.0067,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0078,0.051,0.051,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19790000,-0.29,0.011,-0.0059,0.96,0.013,0.0064,0.024,0.006,0.0043,0.018,-0.0014,-0.0061,2.5e-05,0.0071,0.0037,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.0078,0.053,0.053,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19790000,-0.29,0.011,-0.0059,0.96,0.013,0.0064,0.024,0.006,0.0043,0.018,-0.0014,-0.0061,2.6e-05,0.0071,0.0037,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.0078,0.053,0.053,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19890000,-0.29,0.011,-0.0059,0.96,0.013,0.0062,0.024,0.0073,0.0049,0.016,-0.0014,-0.0061,2.5e-05,0.0072,0.0036,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.033,0.033,0.0078,0.059,0.059,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19890000,-0.29,0.011,-0.0059,0.96,0.013,0.0062,0.024,0.0073,0.0049,0.016,-0.0014,-0.0061,2.6e-05,0.0072,0.0036,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.033,0.033,0.0078,0.059,0.059,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19990000,-0.29,0.011,-0.0059,0.96,0.013,0.0079,0.022,0.0068,0.0051,0.013,-0.0014,-0.0061,2.4e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.028,0.028,0.0077,0.051,0.051,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19990000,-0.29,0.011,-0.0059,0.96,0.013,0.0079,0.022,0.0068,0.0051,0.013,-0.0014,-0.0061,2.6e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00044,0.019,0.028,0.028,0.0077,0.051,0.051,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20090000,-0.29,0.011,-0.0059,0.96,0.012,0.01,0.022,0.0081,0.006,0.017,-0.0014,-0.0061,2.4e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.031,0.031,0.0077,0.057,0.057,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20090000,-0.29,0.011,-0.0059,0.96,0.012,0.01,0.022,0.0081,0.006,0.017,-0.0014,-0.0061,2.6e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.031,0.031,0.0077,0.057,0.057,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20190000,-0.29,0.012,-0.0059,0.96,0.011,0.0071,0.023,0.0077,0.0057,0.016,-0.0014,-0.006,2.4e-05,0.0078,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.03,0.03,0.0076,0.059,0.059,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20190000,-0.29,0.012,-0.0059,0.96,0.011,0.0071,0.023,0.0077,0.0057,0.016,-0.0014,-0.006,2.6e-05,0.0078,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.03,0.03,0.0076,0.059,0.059,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20290000,-0.29,0.012,-0.0059,0.96,0.014,0.009,0.023,0.009,0.0064,0.017,-0.0014,-0.006,2.4e-05,0.0079,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.033,0.033,0.0076,0.066,0.066,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20290000,-0.29,0.012,-0.0059,0.96,0.014,0.009,0.023,0.009,0.0064,0.017,-0.0014,-0.006,2.6e-05,0.0079,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00044,0.019,0.033,0.033,0.0076,0.066,0.066,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20390000,-0.29,0.012,-0.0058,0.96,0.015,0.0077,0.023,0.0085,0.006,0.018,-0.0014,-0.006,2.4e-05,0.0082,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.031,0.031,0.0075,0.068,0.068,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20390000,-0.29,0.012,-0.0058,0.96,0.015,0.0077,0.023,0.0085,0.006,0.018,-0.0014,-0.006,2.6e-05,0.0082,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.031,0.031,0.0075,0.068,0.068,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20490000,-0.29,0.012,-0.0058,0.96,0.02,0.0097,0.023,0.01,0.0068,0.016,-0.0014,-0.006,2.4e-05,0.0084,0.003,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.034,0.034,0.0075,0.076,0.076,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20490000,-0.29,0.012,-0.0058,0.96,0.02,0.0097,0.023,0.01,0.0068,0.016,-0.0014,-0.006,2.6e-05,0.0084,0.003,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.034,0.034,0.0075,0.076,0.076,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20590000,-0.29,0.012,-0.0058,0.96,0.018,0.01,0.023,0.009,0.0063,0.015,-0.0014,-0.006,2.4e-05,0.0088,0.0029,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.033,0.033,0.0074,0.078,0.078,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20590000,-0.29,0.012,-0.0058,0.96,0.018,0.01,0.023,0.009,0.0063,0.015,-0.0014,-0.006,2.6e-05,0.0088,0.0029,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.033,0.033,0.0074,0.078,0.078,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20690000,-0.29,0.012,-0.0057,0.96,0.02,0.0093,0.023,0.011,0.0072,0.015,-0.0014,-0.006,2.4e-05,0.0089,0.0028,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.035,0.035,0.0075,0.086,0.086,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20690000,-0.29,0.012,-0.0057,0.96,0.02,0.0093,0.023,0.011,0.0072,0.015,-0.0014,-0.006,2.6e-05,0.0089,0.0028,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.035,0.035,0.0075,0.086,0.086,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20790000,-0.29,0.012,-0.0052,0.96,0.02,0.0058,0.0084,0.0068,0.0047,0.014,-0.0014,-0.006,2.4e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.028,0.028,0.0074,0.067,0.067,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20790000,-0.29,0.012,-0.0052,0.96,0.02,0.0058,0.0084,0.0068,0.0047,0.014,-0.0014,-0.006,2.7e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.028,0.028,0.0074,0.067,0.067,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20890000,-0.29,0.0066,0.0035,0.96,0.028,-0.0045,-0.11,0.0093,0.0048,0.0075,-0.0014,-0.006,2.4e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.031,0.031,0.0073,0.074,0.074,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20890000,-0.29,0.0066,0.0035,0.96,0.028,-0.0045,-0.11,0.0093,0.0048,0.0075,-0.0014,-0.006,2.7e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.031,0.031,0.0073,0.074,0.074,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20990000,-0.29,0.0029,0.0064,0.96,0.041,-0.021,-0.25,0.0064,0.0033,-0.0075,-0.0014,-0.006,2.4e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.027,0.0072,0.06,0.06,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20990000,-0.29,0.0029,0.0064,0.96,0.041,-0.021,-0.25,0.0064,0.0033,-0.0075,-0.0014,-0.006,2.6e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.027,0.0072,0.06,0.06,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21090000,-0.29,0.0034,0.0049,0.96,0.057,-0.033,-0.37,0.011,0.00058,-0.038,-0.0014,-0.006,2.4e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.029,0.029,0.0073,0.066,0.066,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21090000,-0.29,0.0034,0.0049,0.96,0.057,-0.033,-0.37,0.011,0.00058,-0.038,-0.0014,-0.006,2.6e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.029,0.029,0.0073,0.066,0.066,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21190000,-0.29,0.0054,0.0022,0.96,0.06,-0.037,-0.49,0.0074,0.0014,-0.075,-0.0013,-0.0059,2.3e-05,0.0099,0.0018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0072,0.055,0.055,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21190000,-0.29,0.0054,0.0022,0.96,0.06,-0.037,-0.49,0.0074,0.0014,-0.075,-0.0013,-0.0059,2.6e-05,0.0099,0.0018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0072,0.055,0.055,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21290000,-0.29,0.007,0.00021,0.96,0.061,-0.04,-0.62,0.013,-0.0025,-0.13,-0.0013,-0.0059,2.3e-05,0.0099,0.0017,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.028,0.028,0.0071,0.061,0.061,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21290000,-0.29,0.007,0.00021,0.96,0.061,-0.04,-0.62,0.013,-0.0025,-0.13,-0.0013,-0.0059,2.6e-05,0.0099,0.0017,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.028,0.028,0.0071,0.061,0.061,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21390000,-0.29,0.0079,-0.0014,0.96,0.051,-0.03,-0.75,0.0095,0.0035,-0.2,-0.0013,-0.0059,2.1e-05,0.01,-8.3e-05,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.027,0.028,0.0071,0.063,0.063,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21390000,-0.29,0.0079,-0.0014,0.96,0.051,-0.03,-0.75,0.0095,0.0035,-0.2,-0.0013,-0.0059,2.4e-05,0.01,-8.2e-05,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.027,0.028,0.0071,0.063,0.063,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21490000,-0.29,0.0084,-0.0022,0.96,0.046,-0.028,-0.89,0.014,0.0006,-0.28,-0.0013,-0.0059,2.1e-05,0.01,-0.00018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.03,0.03,0.0071,0.07,0.07,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21490000,-0.29,0.0084,-0.0022,0.96,0.046,-0.028,-0.89,0.014,0.00059,-0.28,-0.0013,-0.0059,2.4e-05,0.01,-0.00018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.03,0.03,0.0071,0.07,0.07,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21590000,-0.29,0.0086,-0.0029,0.96,0.03,-0.018,-1,0.0069,0.0087,-0.37,-0.0012,-0.0059,1.9e-05,0.01,-0.0022,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.029,0.029,0.007,0.072,0.072,0.034,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21590000,-0.29,0.0086,-0.0029,0.96,0.03,-0.018,-1,0.0069,0.0087,-0.37,-0.0012,-0.0059,2.3e-05,0.01,-0.0022,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.029,0.029,0.007,0.072,0.072,0.034,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21690000,-0.29,0.0085,-0.0033,0.96,0.027,-0.013,-1.1,0.0097,0.0072,-0.49,-0.0012,-0.0059,1.9e-05,0.011,-0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.032,0.032,0.007,0.08,0.08,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21690000,-0.29,0.0085,-0.0033,0.96,0.027,-0.013,-1.1,0.0097,0.0071,-0.49,-0.0012,-0.0059,2.3e-05,0.011,-0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.032,0.032,0.007,0.08,0.08,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21790000,-0.29,0.0087,-0.0038,0.96,0.018,-0.0011,-1.3,0.005,0.017,-0.61,-0.0011,-0.0059,1.8e-05,0.011,-0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00038,0.019,0.031,0.031,0.0069,0.081,0.081,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21790000,-0.29,0.0087,-0.0038,0.96,0.018,-0.0011,-1.3,0.005,0.017,-0.61,-0.0011,-0.0059,2.2e-05,0.011,-0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00038,0.019,0.031,0.031,0.0069,0.081,0.081,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21890000,-0.29,0.0088,-0.0041,0.96,0.013,0.0032,-1.4,0.0066,0.017,-0.75,-0.0011,-0.0059,1.8e-05,0.011,-0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.033,0.034,0.0069,0.09,0.09,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21890000,-0.29,0.0088,-0.0041,0.96,0.013,0.0032,-1.4,0.0066,0.017,-0.75,-0.0011,-0.0059,2.2e-05,0.011,-0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.033,0.034,0.0069,0.09,0.09,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21990000,-0.29,0.0094,-0.005,0.96,0.002,0.014,-1.4,-0.0045,0.027,-0.89,-0.0011,-0.0059,1.6e-05,0.011,-0.0063,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.032,0.032,0.0068,0.091,0.091,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21990000,-0.29,0.0094,-0.005,0.96,0.002,0.014,-1.4,-0.0045,0.027,-0.89,-0.0011,-0.0059,2.1e-05,0.011,-0.0063,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.032,0.032,0.0068,0.091,0.091,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22090000,-0.29,0.01,-0.0056,0.96,-0.0017,0.018,-1.4,-0.0045,0.029,-1,-0.0011,-0.0059,1.6e-05,0.011,-0.0064,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0068,0.1,0.1,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22090000,-0.29,0.01,-0.0056,0.96,-0.0017,0.018,-1.4,-0.0045,0.029,-1,-0.0011,-0.0059,2.1e-05,0.011,-0.0064,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0068,0.1,0.1,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22190000,-0.29,0.011,-0.0062,0.96,-0.014,0.026,-1.4,-0.014,0.039,-1.2,-0.0011,-0.0059,1.5e-05,0.012,-0.0077,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0067,0.1,0.1,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22190000,-0.29,0.011,-0.0062,0.96,-0.014,0.026,-1.4,-0.014,0.039,-1.2,-0.0011,-0.0059,2e-05,0.012,-0.0077,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0067,0.1,0.1,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22290000,-0.29,0.011,-0.0069,0.96,-0.021,0.031,-1.4,-0.015,0.041,-1.3,-0.0011,-0.0059,1.5e-05,0.012,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0067,0.11,0.11,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22290000,-0.29,0.011,-0.0069,0.96,-0.021,0.031,-1.4,-0.015,0.041,-1.3,-0.0011,-0.0059,2e-05,0.012,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0067,0.11,0.11,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22390000,-0.29,0.011,-0.0072,0.96,-0.031,0.036,-1.4,-0.025,0.044,-1.5,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0066,0.11,0.11,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22390000,-0.29,0.011,-0.0072,0.96,-0.031,0.036,-1.4,-0.025,0.044,-1.5,-0.0011,-0.0059,2e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0066,0.11,0.11,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22490000,-0.29,0.012,-0.0073,0.96,-0.037,0.043,-1.4,-0.028,0.048,-1.6,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22490000,-0.29,0.012,-0.0073,0.96,-0.037,0.043,-1.4,-0.028,0.048,-1.6,-0.0011,-0.0059,2e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22590000,-0.29,0.012,-0.0071,0.96,-0.042,0.048,-1.4,-0.029,0.052,-1.7,-0.0011,-0.0059,1.5e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.032,0.032,0.0065,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22590000,-0.29,0.012,-0.0071,0.96,-0.042,0.048,-1.4,-0.029,0.052,-1.7,-0.0011,-0.0059,2e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.032,0.032,0.0065,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22690000,-0.29,0.013,-0.007,0.96,-0.046,0.053,-1.4,-0.033,0.057,-1.9,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.13,0.13,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22690000,-0.29,0.013,-0.007,0.96,-0.046,0.053,-1.4,-0.033,0.057,-1.9,-0.0011,-0.0059,2e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.13,0.13,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22790000,-0.29,0.013,-0.0069,0.96,-0.052,0.056,-1.4,-0.039,0.058,-2,-0.0011,-0.0059,1.5e-05,0.013,-0.0081,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0065,0.13,0.13,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22790000,-0.29,0.013,-0.0069,0.96,-0.052,0.056,-1.4,-0.039,0.058,-2,-0.0011,-0.0059,2e-05,0.013,-0.0081,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0065,0.13,0.13,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22890000,-0.29,0.013,-0.0071,0.96,-0.058,0.062,-1.4,-0.045,0.064,-2.2,-0.0011,-0.0059,1.5e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0065,0.14,0.14,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22890000,-0.29,0.013,-0.0071,0.96,-0.058,0.062,-1.4,-0.045,0.064,-2.2,-0.0011,-0.0059,2e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0065,0.14,0.14,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22990000,-0.29,0.014,-0.0069,0.96,-0.062,0.06,-1.4,-0.049,0.061,-2.3,-0.0011,-0.0059,1.5e-05,0.014,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0064,0.14,0.14,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22990000,-0.29,0.014,-0.0069,0.96,-0.062,0.06,-1.4,-0.049,0.061,-2.3,-0.0011,-0.0059,2.1e-05,0.014,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0064,0.14,0.14,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23090000,-0.29,0.014,-0.0069,0.96,-0.068,0.064,-1.4,-0.055,0.067,-2.5,-0.0011,-0.0059,1.5e-05,0.014,-0.0079,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0064,0.15,0.15,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23090000,-0.29,0.014,-0.0069,0.96,-0.068,0.064,-1.4,-0.055,0.067,-2.5,-0.0011,-0.0059,2.1e-05,0.014,-0.0079,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0064,0.15,0.15,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23190000,-0.29,0.014,-0.0067,0.96,-0.069,0.056,-1.4,-0.054,0.059,-2.6,-0.0011,-0.0059,1.5e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.032,0.032,0.0063,0.15,0.15,0.033,9.1e-07,9.1e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23190000,-0.29,0.014,-0.0067,0.96,-0.069,0.056,-1.4,-0.054,0.059,-2.6,-0.0011,-0.0059,2.1e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.032,0.032,0.0063,0.15,0.15,0.033,9.1e-07,9.1e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23290000,-0.29,0.014,-0.0071,0.96,-0.075,0.061,-1.4,-0.061,0.065,-2.8,-0.0011,-0.0059,1.5e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0063,0.16,0.16,0.034,9.1e-07,9.1e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23290000,-0.29,0.014,-0.0071,0.96,-0.075,0.061,-1.4,-0.061,0.065,-2.8,-0.0011,-0.0059,2.1e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.034,0.034,0.0063,0.16,0.16,0.034,9.1e-07,9.1e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23390000,-0.29,0.014,-0.007,0.96,-0.073,0.061,-1.4,-0.054,0.064,-2.9,-0.0011,-0.0059,1.6e-05,0.014,-0.0065,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.032,0.032,0.0063,0.16,0.16,0.033,8.6e-07,8.6e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23390000,-0.29,0.014,-0.007,0.96,-0.073,0.061,-1.4,-0.054,0.064,-2.9,-0.0011,-0.0059,2.2e-05,0.014,-0.0065,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.032,0.032,0.0063,0.16,0.16,0.033,8.6e-07,8.6e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23490000,-0.29,0.015,-0.0071,0.96,-0.078,0.063,-1.4,-0.061,0.07,-3,-0.0011,-0.0059,1.6e-05,0.014,-0.0066,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.033,0.033,0.0063,0.17,0.17,0.033,8.6e-07,8.6e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23490000,-0.29,0.015,-0.0071,0.96,-0.078,0.063,-1.4,-0.061,0.07,-3,-0.0011,-0.0059,2.2e-05,0.014,-0.0066,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.033,0.033,0.0063,0.17,0.17,0.033,8.6e-07,8.6e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23590000,-0.29,0.015,-0.0071,0.96,-0.077,0.054,-1.4,-0.056,0.057,-3.2,-0.0012,-0.0059,1.7e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0062,0.17,0.17,0.033,8.2e-07,8.2e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23590000,-0.29,0.015,-0.0071,0.96,-0.077,0.054,-1.4,-0.056,0.057,-3.2,-0.0012,-0.0059,2.2e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0062,0.17,0.17,0.033,8.2e-07,8.2e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23690000,-0.29,0.015,-0.0077,0.96,-0.076,0.057,-1.3,-0.063,0.063,-3.3,-0.0012,-0.0059,1.7e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.033,0.033,0.0062,0.18,0.18,0.033,8.2e-07,8.2e-07,4.7e-06,0.03,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23690000,-0.29,0.015,-0.0077,0.96,-0.076,0.057,-1.3,-0.063,0.063,-3.3,-0.0012,-0.0059,2.2e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.033,0.033,0.0062,0.18,0.18,0.033,8.2e-07,8.2e-07,4.7e-06,0.03,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23790000,-0.29,0.018,-0.0092,0.96,-0.06,0.053,-0.95,-0.05,0.057,-3.4,-0.0012,-0.0059,1.7e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.03,0.03,0.0061,0.18,0.18,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23790000,-0.29,0.018,-0.0092,0.96,-0.06,0.053,-0.95,-0.05,0.057,-3.4,-0.0012,-0.0059,2.3e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.03,0.03,0.0061,0.18,0.18,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23890000,-0.29,0.023,-0.012,0.96,-0.056,0.054,-0.52,-0.056,0.062,-3.5,-0.0012,-0.0059,1.7e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.031,0.031,0.0061,0.19,0.19,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23890000,-0.29,0.023,-0.012,0.96,-0.056,0.054,-0.52,-0.056,0.062,-3.5,-0.0012,-0.0059,2.3e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.031,0.031,0.0061,0.19,0.19,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23990000,-0.29,0.025,-0.014,0.96,-0.049,0.05,-0.13,-0.044,0.055,-3.6,-0.0012,-0.0059,1.8e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.029,0.029,0.0061,0.19,0.19,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23990000,-0.29,0.025,-0.014,0.96,-0.049,0.05,-0.13,-0.044,0.055,-3.6,-0.0012,-0.0059,2.3e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.029,0.029,0.0061,0.19,0.19,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24090000,-0.29,0.024,-0.013,0.96,-0.057,0.057,0.099,-0.049,0.06,-3.6,-0.0012,-0.0059,1.8e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.03,0.03,0.0061,0.2,0.2,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24090000,-0.29,0.024,-0.013,0.96,-0.057,0.057,0.099,-0.049,0.06,-3.6,-0.0012,-0.0059,2.3e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.03,0.03,0.0061,0.2,0.2,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24190000,-0.29,0.02,-0.011,0.96,-0.06,0.052,0.088,-0.034,0.045,-3.6,-0.0013,-0.0059,1.8e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.029,0.029,0.006,0.2,0.2,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24190000,-0.29,0.02,-0.011,0.96,-0.06,0.052,0.088,-0.034,0.045,-3.6,-0.0013,-0.0059,2.4e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.029,0.029,0.006,0.2,0.2,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24290000,-0.29,0.016,-0.0089,0.96,-0.064,0.054,0.066,-0.04,0.05,-3.6,-0.0013,-0.0059,1.8e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0061,0.21,0.21,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24290000,-0.29,0.016,-0.0089,0.96,-0.064,0.054,0.066,-0.04,0.05,-3.6,-0.0013,-0.0059,2.4e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0061,0.21,0.21,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24390000,-0.29,0.015,-0.0081,0.96,-0.045,0.048,0.083,-0.019,0.04,-3.6,-0.0013,-0.0059,1.9e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.21,0.21,0.033,7e-07,6.9e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24390000,-0.29,0.015,-0.0081,0.96,-0.045,0.048,0.083,-0.019,0.04,-3.6,-0.0013,-0.0059,2.5e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.21,0.21,0.033,7e-07,6.9e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24490000,-0.29,0.015,-0.0084,0.96,-0.04,0.046,0.08,-0.023,0.045,-3.6,-0.0013,-0.0059,1.9e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.006,0.22,0.22,0.033,7e-07,7e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24490000,-0.29,0.015,-0.0084,0.96,-0.04,0.046,0.08,-0.023,0.045,-3.6,-0.0013,-0.0059,2.5e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.006,0.22,0.22,0.033,7e-07,7e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24590000,-0.29,0.015,-0.009,0.96,-0.026,0.043,0.076,-0.0023,0.038,-3.6,-0.0014,-0.006,2e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.22,0.22,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24590000,-0.29,0.015,-0.009,0.96,-0.026,0.043,0.076,-0.0023,0.038,-3.6,-0.0014,-0.006,2.6e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.22,0.22,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24690000,-0.29,0.015,-0.0095,0.96,-0.023,0.043,0.075,-0.0048,0.042,-3.5,-0.0014,-0.006,2e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.006,0.23,0.23,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24690000,-0.29,0.015,-0.0095,0.96,-0.023,0.043,0.075,-0.0048,0.042,-3.5,-0.0014,-0.006,2.6e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.006,0.23,0.23,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24790000,-0.29,0.015,-0.0096,0.96,-0.015,0.04,0.067,0.0088,0.033,-3.5,-0.0014,-0.006,2e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24790000,-0.29,0.015,-0.0096,0.96,-0.015,0.04,0.067,0.0088,0.033,-3.5,-0.0014,-0.006,2.7e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24890000,-0.29,0.014,-0.0095,0.96,-0.013,0.044,0.057,0.0074,0.038,-3.5,-0.0014,-0.006,2e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.24,0.24,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24890000,-0.29,0.014,-0.0095,0.96,-0.013,0.044,0.057,0.0074,0.038,-3.5,-0.0014,-0.006,2.7e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.0059,0.24,0.24,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24990000,-0.29,0.014,-0.0093,0.96,-0.00021,0.044,0.049,0.022,0.031,-3.5,-0.0014,-0.006,2.1e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24990000,-0.29,0.014,-0.0093,0.96,-0.00021,0.044,0.049,0.022,0.031,-3.5,-0.0014,-0.006,2.8e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25090000,-0.29,0.014,-0.0096,0.96,0.0044,0.044,0.047,0.023,0.035,-3.5,-0.0014,-0.006,2.1e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.25,0.25,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25090000,-0.29,0.014,-0.0096,0.96,0.0044,0.044,0.047,0.023,0.035,-3.5,-0.0014,-0.006,2.8e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.25,0.25,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25190000,-0.29,0.014,-0.0098,0.96,0.015,0.038,0.047,0.037,0.023,-3.5,-0.0014,-0.006,2.2e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0058,0.24,0.24,0.032,6e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25190000,-0.29,0.014,-0.0098,0.96,0.015,0.038,0.047,0.037,0.023,-3.5,-0.0014,-0.006,2.9e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0058,0.24,0.24,0.032,6e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25290000,-0.29,0.013,-0.01,0.96,0.02,0.041,0.042,0.039,0.027,-3.5,-0.0014,-0.006,2.2e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0058,0.26,0.26,0.032,6.1e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25290000,-0.29,0.013,-0.01,0.96,0.02,0.041,0.042,0.039,0.027,-3.5,-0.0014,-0.006,2.9e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0058,0.26,0.26,0.032,6.1e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25390000,-0.29,0.013,-0.01,0.96,0.028,0.039,0.041,0.046,0.021,-3.5,-0.0014,-0.006,2.3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.25,0.25,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25390000,-0.29,0.013,-0.01,0.96,0.028,0.039,0.041,0.046,0.021,-3.5,-0.0014,-0.006,3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.25,0.25,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25490000,-0.29,0.013,-0.01,0.96,0.034,0.04,0.04,0.05,0.025,-3.5,-0.0014,-0.006,2.3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.27,0.27,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25490000,-0.29,0.013,-0.01,0.96,0.034,0.04,0.04,0.05,0.025,-3.5,-0.0014,-0.006,3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.27,0.27,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25590000,-0.29,0.012,-0.01,0.96,0.039,0.034,0.041,0.054,0.0079,-3.5,-0.0015,-0.006,2.4e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.26,0.26,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25590000,-0.29,0.012,-0.01,0.96,0.039,0.034,0.041,0.054,0.0079,-3.5,-0.0014,-0.006,3.1e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.26,0.26,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25690000,-0.29,0.012,-0.0098,0.96,0.041,0.033,0.031,0.058,0.011,-3.5,-0.0015,-0.006,2.4e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.28,0.28,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25690000,-0.29,0.012,-0.0098,0.96,0.041,0.033,0.031,0.058,0.011,-3.5,-0.0014,-0.006,3.1e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.28,0.28,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25790000,-0.29,0.011,-0.0096,0.96,0.05,0.027,0.03,0.062,0.00075,-3.5,-0.0015,-0.006,2.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.27,0.27,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25790000,-0.29,0.011,-0.0096,0.96,0.05,0.027,0.03,0.062,0.00075,-3.5,-0.0015,-0.006,3.2e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0057,0.27,0.27,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25890000,-0.29,0.011,-0.0097,0.96,0.057,0.027,0.033,0.068,0.0034,-3.5,-0.0015,-0.006,2.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.28,0.28,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25890000,-0.29,0.011,-0.0097,0.96,0.057,0.027,0.033,0.068,0.0034,-3.5,-0.0015,-0.006,3.2e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.28,0.28,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25990000,-0.29,0.012,-0.0097,0.96,0.056,0.02,0.026,0.059,-0.0086,-3.5,-0.0015,-0.0059,2.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.28,0.28,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25990000,-0.29,0.012,-0.0097,0.96,0.056,0.02,0.026,0.059,-0.0086,-3.5,-0.0015,-0.0059,3.3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.28,0.28,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26090000,-0.29,0.012,-0.0094,0.96,0.062,0.021,0.025,0.065,-0.0065,-3.5,-0.0015,-0.0059,2.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.29,0.29,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26090000,-0.29,0.012,-0.0094,0.96,0.062,0.021,0.025,0.065,-0.0065,-3.5,-0.0015,-0.0059,3.3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.29,0.29,0.032,5.4e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26190000,-0.29,0.012,-0.0093,0.96,0.063,0.011,0.02,0.063,-0.023,-3.5,-0.0015,-0.0059,2.8e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0056,0.29,0.29,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26190000,-0.29,0.012,-0.0093,0.96,0.063,0.011,0.02,0.063,-0.023,-3.5,-0.0015,-0.0059,3.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.29,0.29,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26290000,-0.29,0.012,-0.0092,0.96,0.065,0.01,0.015,0.069,-0.022,-3.5,-0.0015,-0.0059,2.8e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.03,0.0057,0.3,0.3,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26290000,-0.29,0.012,-0.0092,0.96,0.065,0.01,0.015,0.069,-0.022,-3.5,-0.0015,-0.0059,3.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.03,0.0057,0.3,0.3,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26390000,-0.29,0.012,-0.0086,0.96,0.06,0.00029,0.019,0.056,-0.037,-3.5,-0.0015,-0.0059,2.9e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0056,0.3,0.3,0.032,5e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26390000,-0.29,0.012,-0.0086,0.96,0.06,0.00028,0.019,0.056,-0.037,-3.5,-0.0015,-0.0059,3.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.3,0.3,0.032,5.1e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26490000,-0.29,0.012,-0.0084,0.96,0.064,-0.0022,0.028,0.062,-0.037,-3.5,-0.0015,-0.0059,2.9e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.029,0.0056,0.31,0.31,0.032,5.1e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26490000,-0.29,0.012,-0.0084,0.96,0.064,-0.0023,0.028,0.062,-0.037,-3.5,-0.0015,-0.0059,3.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.31,0.31,0.032,5.1e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26590000,-0.29,0.013,-0.0078,0.96,0.06,-0.013,0.028,0.057,-0.05,-3.5,-0.0015,-0.0059,3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.31,0.31,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26590000,-0.29,0.013,-0.0078,0.96,0.06,-0.013,0.028,0.057,-0.05,-3.5,-0.0015,-0.0059,3.7e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.31,0.31,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26690000,-0.29,0.012,-0.0077,0.96,0.063,-0.018,0.027,0.063,-0.052,-3.5,-0.0015,-0.0059,3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.32,0.32,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26690000,-0.29,0.012,-0.0077,0.96,0.063,-0.018,0.027,0.063,-0.052,-3.5,-0.0015,-0.0059,3.7e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.32,0.32,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26790000,-0.29,0.012,-0.0075,0.96,0.063,-0.025,0.026,0.056,-0.065,-3.5,-0.0015,-0.0059,3.1e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.028,0.0056,0.31,0.31,0.031,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26790000,-0.29,0.012,-0.0075,0.96,0.063,-0.025,0.026,0.056,-0.065,-3.5,-0.0015,-0.0059,3.8e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.028,0.0056,0.31,0.31,0.031,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26890000,-0.29,0.012,-0.0069,0.96,0.069,-0.027,0.022,0.062,-0.067,-3.5,-0.0015,-0.0059,3.1e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.33,0.33,0.032,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26890000,-0.29,0.012,-0.0069,0.96,0.069,-0.027,0.022,0.062,-0.067,-3.5,-0.0015,-0.0059,3.8e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.33,0.33,0.032,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26990000,-0.29,0.012,-0.0063,0.96,0.067,-0.034,0.021,0.051,-0.073,-3.5,-0.0015,-0.0058,3.2e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.32,0.32,0.031,4.7e-07,4.6e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26990000,-0.29,0.012,-0.0063,0.96,0.067,-0.034,0.021,0.051,-0.073,-3.5,-0.0015,-0.0058,3.9e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.32,0.32,0.031,4.7e-07,4.6e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27090000,-0.29,0.013,-0.0061,0.96,0.07,-0.041,0.024,0.058,-0.077,-3.5,-0.0015,-0.0058,3.1e-05,0.019,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.34,0.34,0.031,4.7e-07,4.7e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27090000,-0.29,0.013,-0.0061,0.96,0.07,-0.041,0.024,0.058,-0.077,-3.5,-0.0015,-0.0058,3.9e-05,0.019,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.34,0.34,0.031,4.7e-07,4.7e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27190000,-0.29,0.013,-0.0062,0.96,0.068,-0.044,0.027,0.044,-0.079,-3.5,-0.0015,-0.0058,3.2e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.33,0.33,0.032,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27190000,-0.29,0.013,-0.0062,0.96,0.068,-0.044,0.027,0.044,-0.079,-3.5,-0.0015,-0.0058,4e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.33,0.33,0.032,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27290000,-0.29,0.014,-0.0063,0.96,0.075,-0.049,0.14,0.051,-0.083,-3.5,-0.0015,-0.0058,3.2e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.028,0.029,0.0055,0.35,0.35,0.031,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27290000,-0.29,0.014,-0.0063,0.96,0.075,-0.049,0.14,0.051,-0.083,-3.5,-0.0015,-0.0058,4e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.028,0.029,0.0055,0.35,0.35,0.031,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27390000,-0.29,0.016,-0.0075,0.96,0.071,-0.04,0.46,0.015,-0.029,-3.5,-0.0014,-0.0058,3.1e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0055,0.15,0.15,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27390000,-0.29,0.016,-0.0075,0.96,0.071,-0.04,0.46,0.015,-0.029,-3.5,-0.0014,-0.0058,3.9e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0055,0.15,0.15,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27490000,-0.29,0.018,-0.0087,0.96,0.075,-0.045,0.78,0.022,-0.033,-3.5,-0.0014,-0.0058,3.1e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0055,0.16,0.16,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27490000,-0.29,0.018,-0.0087,0.96,0.075,-0.045,0.78,0.022,-0.033,-3.5,-0.0014,-0.0058,3.9e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0055,0.16,0.16,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27590000,-0.29,0.017,-0.0088,0.96,0.063,-0.046,0.87,0.011,-0.022,-3.4,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27590000,-0.29,0.017,-0.0088,0.96,0.063,-0.046,0.87,0.011,-0.022,-3.4,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27690000,-0.29,0.014,-0.0079,0.96,0.059,-0.043,0.78,0.017,-0.026,-3.3,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27690000,-0.29,0.014,-0.0079,0.96,0.059,-0.043,0.78,0.017,-0.026,-3.3,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27790000,-0.29,0.013,-0.0067,0.96,0.053,-0.04,0.77,0.012,-0.02,-3.2,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.018,0.0054,0.076,0.076,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27790000,-0.29,0.013,-0.0067,0.96,0.053,-0.04,0.77,0.012,-0.02,-3.2,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.018,0.0054,0.076,0.076,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27890000,-0.29,0.013,-0.0063,0.96,0.061,-0.046,0.81,0.018,-0.025,-3.2,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.08,0.08,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27890000,-0.29,0.013,-0.0063,0.96,0.061,-0.046,0.81,0.018,-0.025,-3.2,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.08,0.08,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27990000,-0.29,0.013,-0.0068,0.96,0.06,-0.048,0.8,0.02,-0.027,-3.1,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0054,0.082,0.082,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27990000,-0.29,0.013,-0.0068,0.96,0.06,-0.048,0.8,0.02,-0.027,-3.1,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0054,0.082,0.082,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28090000,-0.29,0.013,-0.007,0.96,0.063,-0.048,0.8,0.027,-0.032,-3,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.02,0.02,0.0054,0.086,0.086,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28090000,-0.29,0.013,-0.007,0.96,0.063,-0.048,0.8,0.027,-0.032,-3,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0054,0.086,0.086,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28190000,-0.29,0.014,-0.0064,0.96,0.059,-0.046,0.81,0.027,-0.035,-2.9,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0054,0.089,0.089,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28190000,-0.29,0.014,-0.0064,0.96,0.059,-0.046,0.81,0.027,-0.035,-2.9,-0.0014,-0.0058,4e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0054,0.089,0.089,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28290000,-0.29,0.014,-0.0059,0.96,0.064,-0.049,0.81,0.033,-0.039,-2.9,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.093,0.093,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28290000,-0.29,0.014,-0.0059,0.96,0.064,-0.049,0.81,0.033,-0.039,-2.9,-0.0014,-0.0058,4e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.093,0.093,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28390000,-0.29,0.014,-0.0059,0.96,0.064,-0.05,0.81,0.034,-0.04,-2.8,-0.0014,-0.0058,3e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.096,0.096,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28390000,-0.29,0.014,-0.0059,0.96,0.064,-0.05,0.81,0.034,-0.04,-2.8,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.096,0.096,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28490000,-0.29,0.015,-0.0061,0.96,0.066,-0.054,0.81,0.04,-0.045,-2.7,-0.0014,-0.0058,3e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.022,0.022,0.0054,0.1,0.1,0.031,4.1e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28490000,-0.29,0.015,-0.0061,0.96,0.066,-0.054,0.81,0.04,-0.045,-2.7,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0054,0.1,0.1,0.031,4.1e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28590000,-0.29,0.015,-0.0062,0.96,0.057,-0.053,0.81,0.039,-0.048,-2.6,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0054,0.1,0.1,0.031,4e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28590000,-0.29,0.015,-0.0062,0.96,0.057,-0.053,0.81,0.039,-0.048,-2.6,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.1,0.1,0.031,4e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28690000,-0.29,0.014,-0.006,0.96,0.056,-0.054,0.81,0.045,-0.053,-2.6,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0054,0.11,0.11,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28690000,-0.29,0.014,-0.006,0.96,0.056,-0.054,0.81,0.045,-0.053,-2.6,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0054,0.11,0.11,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28790000,-0.29,0.014,-0.0054,0.96,0.053,-0.052,0.81,0.045,-0.051,-2.5,-0.0014,-0.0058,2.9e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0053,0.11,0.11,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28790000,-0.29,0.014,-0.0054,0.96,0.053,-0.052,0.81,0.045,-0.051,-2.5,-0.0014,-0.0058,3.8e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0053,0.11,0.11,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28890000,-0.29,0.014,-0.0053,0.96,0.057,-0.053,0.81,0.05,-0.056,-2.4,-0.0014,-0.0058,2.9e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0054,0.12,0.12,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28890000,-0.29,0.014,-0.0053,0.96,0.057,-0.053,0.81,0.05,-0.056,-2.4,-0.0014,-0.0058,3.8e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0054,0.12,0.12,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28990000,-0.29,0.014,-0.005,0.96,0.053,-0.051,0.81,0.05,-0.055,-2.3,-0.0013,-0.0058,2.9e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.12,0.12,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28990000,-0.29,0.014,-0.005,0.96,0.053,-0.051,0.81,0.05,-0.055,-2.3,-0.0013,-0.0058,3.8e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.12,0.12,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29090000,-0.29,0.014,-0.0049,0.96,0.056,-0.052,0.81,0.055,-0.06,-2.3,-0.0013,-0.0058,2.9e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.13,0.13,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29090000,-0.29,0.014,-0.0049,0.96,0.056,-0.052,0.81,0.055,-0.061,-2.3,-0.0013,-0.0058,3.8e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.024,0.024,0.0053,0.13,0.13,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29190000,-0.29,0.014,-0.0048,0.96,0.055,-0.05,0.8,0.056,-0.058,-2.2,-0.0013,-0.0058,2.8e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.13,0.13,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29190000,-0.29,0.014,-0.0048,0.96,0.055,-0.05,0.8,0.056,-0.058,-2.2,-0.0013,-0.0058,3.7e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.13,0.13,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29290000,-0.29,0.014,-0.0051,0.96,0.057,-0.056,0.81,0.061,-0.064,-2.1,-0.0013,-0.0058,2.8e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.14,0.14,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29290000,-0.29,0.014,-0.0051,0.96,0.057,-0.056,0.81,0.061,-0.064,-2.1,-0.0013,-0.0058,3.7e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0053,0.14,0.14,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29390000,-0.29,0.014,-0.0056,0.96,0.053,-0.052,0.81,0.058,-0.059,-2,-0.0013,-0.0058,2.7e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.14,0.14,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29390000,-0.29,0.014,-0.0056,0.96,0.053,-0.052,0.81,0.058,-0.059,-2,-0.0013,-0.0058,3.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.024,0.024,0.0053,0.14,0.14,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29490000,-0.29,0.014,-0.0056,0.96,0.055,-0.052,0.81,0.064,-0.064,-2,-0.0013,-0.0058,2.7e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.15,0.15,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29490000,-0.29,0.014,-0.0056,0.96,0.055,-0.052,0.81,0.064,-0.064,-2,-0.0013,-0.0058,3.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.15,0.15,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29590000,-0.29,0.013,-0.0056,0.96,0.051,-0.049,0.81,0.06,-0.061,-1.9,-0.0013,-0.0058,2.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.15,0.15,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29590000,-0.29,0.013,-0.0056,0.96,0.051,-0.049,0.81,0.06,-0.061,-1.9,-0.0013,-0.0058,3.5e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.15,0.15,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29690000,-0.29,0.013,-0.0056,0.96,0.054,-0.047,0.81,0.065,-0.066,-1.8,-0.0013,-0.0058,2.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.16,0.16,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29690000,-0.29,0.013,-0.0056,0.96,0.054,-0.047,0.81,0.065,-0.066,-1.8,-0.0013,-0.0058,3.5e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.16,0.16,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29790000,-0.29,0.014,-0.0054,0.96,0.051,-0.04,0.8,0.062,-0.061,-1.7,-0.0013,-0.0058,2.5e-05,0.022,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.16,0.16,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29790000,-0.29,0.014,-0.0054,0.96,0.051,-0.04,0.8,0.062,-0.061,-1.7,-0.0013,-0.0058,3.5e-05,0.022,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.16,0.16,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29890000,-0.29,0.014,-0.0049,0.96,0.051,-0.041,0.8,0.067,-0.065,-1.7,-0.0013,-0.0058,2.5e-05,0.023,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.17,0.17,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29890000,-0.29,0.014,-0.0049,0.96,0.051,-0.041,0.8,0.067,-0.065,-1.7,-0.0013,-0.0058,3.5e-05,0.023,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.17,0.17,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29990000,-0.29,0.014,-0.005,0.96,0.046,-0.038,0.8,0.061,-0.063,-1.6,-0.0013,-0.0058,2.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.17,0.17,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29990000,-0.29,0.014,-0.005,0.96,0.046,-0.038,0.8,0.061,-0.064,-1.6,-0.0013,-0.0058,3.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0053,0.17,0.17,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30090000,-0.29,0.014,-0.0051,0.96,0.046,-0.039,0.8,0.065,-0.067,-1.5,-0.0013,-0.0058,2.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.18,0.18,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30090000,-0.29,0.014,-0.0051,0.96,0.046,-0.039,0.8,0.065,-0.067,-1.5,-0.0013,-0.0058,3.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.18,0.18,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30190000,-0.29,0.014,-0.0052,0.96,0.041,-0.033,0.8,0.06,-0.058,-1.5,-0.0013,-0.0058,2.4e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.18,0.18,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30190000,-0.29,0.014,-0.0052,0.96,0.041,-0.033,0.8,0.06,-0.058,-1.5,-0.0013,-0.0058,3.4e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.18,0.18,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30290000,-0.29,0.014,-0.0052,0.96,0.039,-0.033,0.8,0.064,-0.062,-1.4,-0.0013,-0.0058,2.3e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.19,0.19,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30290000,-0.29,0.014,-0.0052,0.96,0.039,-0.033,0.8,0.064,-0.062,-1.4,-0.0013,-0.0058,3.4e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.19,0.19,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30390000,-0.29,0.014,-0.0052,0.96,0.036,-0.026,0.79,0.062,-0.055,-1.3,-0.0012,-0.0058,2.2e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.19,0.19,0.03,3.4e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30390000,-0.29,0.014,-0.0052,0.96,0.036,-0.026,0.79,0.062,-0.055,-1.3,-0.0012,-0.0058,3.3e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.19,0.19,0.03,3.4e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30490000,-0.29,0.014,-0.0052,0.96,0.038,-0.025,0.8,0.066,-0.057,-1.2,-0.0012,-0.0058,2.2e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.2,0.2,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30490000,-0.29,0.014,-0.0052,0.96,0.038,-0.025,0.8,0.066,-0.057,-1.2,-0.0012,-0.0058,3.3e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.2,0.2,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30590000,-0.29,0.015,-0.0055,0.96,0.037,-0.023,0.8,0.062,-0.053,-1.2,-0.0012,-0.0058,2.2e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.2,0.2,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30590000,-0.29,0.015,-0.0055,0.96,0.037,-0.023,0.8,0.062,-0.053,-1.2,-0.0012,-0.0058,3.3e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.2,0.2,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30690000,-0.29,0.015,-0.0059,0.96,0.034,-0.022,0.8,0.065,-0.055,-1.1,-0.0012,-0.0058,2.2e-05,0.025,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.21,0.21,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30690000,-0.29,0.015,-0.0059,0.96,0.034,-0.022,0.8,0.065,-0.055,-1.1,-0.0012,-0.0058,3.3e-05,0.025,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.21,0.21,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30790000,-0.29,0.014,-0.0057,0.96,0.027,-0.012,0.79,0.058,-0.042,-1,-0.0012,-0.0058,2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.21,0.21,0.03,3.3e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30790000,-0.29,0.014,-0.0057,0.96,0.027,-0.012,0.79,0.058,-0.042,-1,-0.0012,-0.0058,3.2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.21,0.21,0.03,3.3e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30890000,-0.29,0.014,-0.0051,0.96,0.026,-0.0084,0.79,0.06,-0.043,-0.95,-0.0012,-0.0058,2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.22,0.22,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30890000,-0.29,0.014,-0.0051,0.96,0.026,-0.0084,0.79,0.06,-0.043,-0.95,-0.0012,-0.0058,3.2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.026,0.026,0.0052,0.22,0.22,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30990000,-0.29,0.014,-0.0052,0.96,0.023,-0.007,0.79,0.057,-0.042,-0.88,-0.0012,-0.0058,2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.22,0.22,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30990000,-0.29,0.014,-0.0052,0.96,0.023,-0.007,0.79,0.057,-0.042,-0.88,-0.0012,-0.0058,3.2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.22,0.22,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31090000,-0.29,0.014,-0.0054,0.96,0.021,-0.006,0.79,0.059,-0.043,-0.81,-0.0012,-0.0058,2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.23,0.23,0.031,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31090000,-0.29,0.014,-0.0054,0.96,0.021,-0.006,0.79,0.059,-0.043,-0.81,-0.0012,-0.0058,3.2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.026,0.026,0.0052,0.23,0.23,0.031,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31190000,-0.29,0.014,-0.0055,0.96,0.019,-0.0017,0.8,0.055,-0.038,-0.74,-0.0012,-0.0058,1.9e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.23,0.23,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31190000,-0.29,0.014,-0.0055,0.96,0.019,-0.0017,0.8,0.055,-0.038,-0.74,-0.0012,-0.0058,3.1e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.23,0.23,0.03,3.2e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31290000,-0.29,0.015,-0.0058,0.96,0.016,0.00067,0.8,0.057,-0.038,-0.67,-0.0012,-0.0058,1.9e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.24,0.24,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31290000,-0.29,0.015,-0.0058,0.96,0.016,0.00066,0.8,0.057,-0.038,-0.67,-0.0012,-0.0058,3.1e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.24,0.24,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31390000,-0.29,0.014,-0.0056,0.96,0.011,0.0044,0.8,0.05,-0.036,-0.59,-0.0012,-0.0058,1.9e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.24,0.24,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31390000,-0.29,0.014,-0.0056,0.96,0.011,0.0044,0.8,0.05,-0.036,-0.59,-0.0012,-0.0058,3.1e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.24,0.24,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31490000,-0.29,0.015,-0.0053,0.96,0.0098,0.0074,0.8,0.051,-0.035,-0.52,-0.0012,-0.0058,1.9e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31490000,-0.29,0.015,-0.0053,0.96,0.0098,0.0074,0.8,0.051,-0.035,-0.52,-0.0012,-0.0058,3.1e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31590000,-0.29,0.015,-0.0051,0.96,0.011,0.0095,0.8,0.05,-0.031,-0.45,-0.0012,-0.0058,1.9e-05,0.027,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31590000,-0.29,0.015,-0.0051,0.96,0.011,0.0095,0.8,0.05,-0.031,-0.45,-0.0012,-0.0058,3.1e-05,0.027,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31690000,-0.29,0.016,-0.005,0.96,0.013,0.011,0.8,0.051,-0.03,-0.38,-0.0012,-0.0058,1.9e-05,0.027,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.26,0.26,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31690000,-0.29,0.016,-0.005,0.96,0.013,0.011,0.8,0.051,-0.03,-0.38,-0.0012,-0.0058,3.1e-05,0.028,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.26,0.26,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31790000,-0.29,0.016,-0.0052,0.96,0.008,0.017,0.8,0.049,-0.02,-0.31,-0.0012,-0.0058,1.8e-05,0.028,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.26,0.26,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31790000,-0.29,0.016,-0.0052,0.96,0.008,0.017,0.8,0.049,-0.02,-0.31,-0.0012,-0.0058,3e-05,0.028,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.26,0.26,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31890000,-0.29,0.016,-0.005,0.96,0.0045,0.019,0.8,0.05,-0.018,-0.24,-0.0012,-0.0058,1.8e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.27,0.27,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31890000,-0.29,0.016,-0.005,0.96,0.0045,0.019,0.8,0.05,-0.018,-0.24,-0.0012,-0.0058,3e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.27,0.27,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31990000,-0.29,0.015,-0.0053,0.96,0.0019,0.02,0.79,0.049,-0.014,-0.17,-0.0012,-0.0058,1.7e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.27,0.27,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31990000,-0.29,0.015,-0.0053,0.96,0.0019,0.02,0.79,0.049,-0.014,-0.17,-0.0012,-0.0058,3e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.27,0.27,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32090000,-0.29,0.015,-0.0058,0.96,0.0019,0.024,0.8,0.05,-0.012,-0.097,-0.0012,-0.0058,1.7e-05,0.029,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32090000,-0.29,0.015,-0.0058,0.96,0.0019,0.024,0.8,0.05,-0.012,-0.097,-0.0012,-0.0058,3e-05,0.029,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32190000,-0.29,0.015,-0.006,0.96,-0.00056,0.03,0.8,0.047,-0.003,-0.029,-0.0012,-0.0058,1.6e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32190000,-0.29,0.015,-0.006,0.96,-0.00056,0.03,0.8,0.047,-0.003,-0.029,-0.0012,-0.0058,3e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32290000,-0.29,0.016,-0.0059,0.96,-0.0024,0.033,0.79,0.047,0.00024,0.041,-0.0012,-0.0058,1.6e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0051,0.29,0.29,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32290000,-0.29,0.016,-0.0059,0.96,-0.0024,0.033,0.79,0.047,0.00022,0.041,-0.0012,-0.0058,3e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0051,0.29,0.29,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32390000,-0.29,0.016,-0.006,0.96,-0.0051,0.034,0.79,0.045,0.0028,0.12,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.29,0.29,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32390000,-0.29,0.016,-0.006,0.96,-0.0051,0.034,0.79,0.045,0.0028,0.12,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.29,0.29,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32490000,-0.29,0.014,-0.0091,0.96,-0.045,0.092,-0.078,0.041,0.011,0.12,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.027,0.027,0.0051,0.3,0.3,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32490000,-0.29,0.014,-0.0091,0.96,-0.045,0.092,-0.078,0.041,0.011,0.12,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.027,0.027,0.0051,0.3,0.3,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32590000,-0.29,0.014,-0.009,0.96,-0.039,0.091,-0.08,0.048,0.003,0.1,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.026,0.026,0.0051,0.3,0.3,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32590000,-0.29,0.014,-0.009,0.96,-0.039,0.091,-0.08,0.048,0.003,0.1,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.3,0.3,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32690000,-0.29,0.014,-0.009,0.96,-0.036,0.098,-0.082,0.044,0.013,0.087,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.027,0.027,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32690000,-0.29,0.014,-0.009,0.96,-0.036,0.098,-0.082,0.044,0.012,0.087,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.027,0.027,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32790000,-0.29,0.014,-0.0089,0.96,-0.03,0.096,-0.083,0.049,0.0035,0.072,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32790000,-0.29,0.014,-0.0089,0.96,-0.03,0.096,-0.083,0.049,0.0035,0.072,-0.0012,-0.0058,3.1e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32890000,-0.29,0.014,-0.0088,0.96,-0.03,0.1,-0.084,0.046,0.013,0.057,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.32,0.32,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32890000,-0.29,0.014,-0.0088,0.96,-0.03,0.1,-0.084,0.046,0.013,0.057,-0.0012,-0.0058,3.1e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.32,0.32,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32990000,-0.29,0.014,-0.0087,0.96,-0.025,0.097,-0.084,0.05,-0.0012,0.043,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.31,0.31,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32990000,-0.29,0.014,-0.0087,0.96,-0.025,0.097,-0.084,0.05,-0.0012,0.043,-0.0012,-0.0058,3.2e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.31,0.31,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33090000,-0.29,0.014,-0.0086,0.96,-0.021,0.1,-0.081,0.048,0.0087,0.036,-0.0012,-0.0058,1.8e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.33,0.33,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33090000,-0.29,0.014,-0.0086,0.96,-0.021,0.1,-0.081,0.048,0.0087,0.036,-0.0012,-0.0058,3.2e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.33,0.33,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33190000,-0.29,0.014,-0.0085,0.96,-0.016,0.097,-0.08,0.051,-0.0085,0.028,-0.0012,-0.0057,1.8e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.32,0.32,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33190000,-0.29,0.014,-0.0085,0.96,-0.016,0.097,-0.08,0.051,-0.0086,0.028,-0.0012,-0.0057,3.3e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.32,0.32,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33290000,-0.29,0.014,-0.0085,0.96,-0.013,0.1,-0.079,0.05,0.0014,0.02,-0.0012,-0.0057,1.8e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.026,0.0051,0.34,0.34,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33290000,-0.29,0.014,-0.0085,0.96,-0.013,0.1,-0.079,0.05,0.0014,0.02,-0.0012,-0.0057,3.3e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.026,0.0051,0.34,0.34,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33390000,-0.29,0.014,-0.0084,0.96,-0.008,0.096,-0.078,0.052,-0.0084,0.011,-0.0013,-0.0057,1.9e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.33,0.33,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33390000,-0.29,0.014,-0.0084,0.96,-0.0079,0.096,-0.078,0.052,-0.0084,0.011,-0.0013,-0.0057,3.4e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.33,0.33,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33490000,-0.29,0.014,-0.0084,0.96,-0.0042,0.1,-0.077,0.051,0.0015,0.0017,-0.0013,-0.0057,1.9e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.35,0.35,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33490000,-0.29,0.014,-0.0084,0.96,-0.0042,0.1,-0.077,0.051,0.0014,0.0017,-0.0013,-0.0057,3.4e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.35,0.35,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33590000,-0.29,0.014,-0.0082,0.96,-0.00096,0.097,-0.073,0.052,-0.013,-0.0062,-0.0013,-0.0057,2e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.025,0.025,0.0051,0.34,0.34,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33590000,-0.29,0.014,-0.0082,0.96,-0.00094,0.097,-0.073,0.052,-0.013,-0.0062,-0.0013,-0.0057,3.5e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.0051,0.34,0.34,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33690000,-0.29,0.014,-0.0082,0.96,0.0028,0.1,-0.074,0.052,-0.0031,-0.014,-0.0013,-0.0057,2e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33690000,-0.29,0.014,-0.0082,0.96,0.0029,0.1,-0.074,0.052,-0.0031,-0.014,-0.0013,-0.0057,3.5e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33790000,-0.29,0.014,-0.0081,0.96,0.007,0.098,-0.069,0.051,-0.018,-0.021,-0.0013,-0.0057,2.1e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.0051,0.35,0.35,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33790000,-0.29,0.014,-0.0081,0.96,0.007,0.098,-0.069,0.051,-0.018,-0.021,-0.0013,-0.0057,3.6e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.0051,0.35,0.35,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33890000,-0.29,0.014,-0.0081,0.96,0.011,0.1,-0.068,0.052,-0.0078,-0.028,-0.0013,-0.0057,2.1e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33890000,-0.29,0.014,-0.0081,0.96,0.011,0.1,-0.068,0.052,-0.0079,-0.028,-0.0013,-0.0057,3.6e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33990000,-0.29,0.014,-0.008,0.96,0.014,0.098,-0.065,0.053,-0.018,-0.031,-0.0013,-0.0057,2.2e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.36,0.36,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33990000,-0.29,0.014,-0.008,0.96,0.014,0.098,-0.065,0.053,-0.018,-0.031,-0.0013,-0.0057,3.7e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.36,0.36,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34090000,-0.29,0.014,-0.008,0.96,0.017,0.1,-0.063,0.055,-0.0074,-0.036,-0.0013,-0.0057,2.3e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.37,0.37,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34090000,-0.29,0.014,-0.008,0.96,0.017,0.1,-0.063,0.055,-0.0075,-0.036,-0.0013,-0.0057,3.8e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.37,0.37,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34190000,-0.29,0.014,-0.0079,0.96,0.02,0.099,-0.061,0.052,-0.02,-0.039,-0.0013,-0.0057,2.3e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.37,0.37,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34190000,-0.29,0.014,-0.0079,0.96,0.02,0.099,-0.061,0.052,-0.02,-0.039,-0.0013,-0.0057,3.9e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.37,0.37,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34290000,-0.29,0.014,-0.0078,0.96,0.02,0.1,-0.06,0.054,-0.0099,-0.045,-0.0013,-0.0057,2.3e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.38,0.38,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34290000,-0.29,0.014,-0.0078,0.96,0.02,0.1,-0.06,0.054,-0.0099,-0.045,-0.0013,-0.0057,3.9e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.38,0.38,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34390000,-0.29,0.014,-0.0076,0.96,0.022,0.099,-0.055,0.052,-0.023,-0.049,-0.0013,-0.0057,2.4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.024,0.005,0.38,0.38,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34390000,-0.29,0.014,-0.0076,0.96,0.022,0.099,-0.055,0.052,-0.023,-0.049,-0.0013,-0.0057,4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.024,0.005,0.38,0.38,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34490000,-0.29,0.014,-0.0077,0.96,0.025,0.1,-0.053,0.054,-0.012,-0.052,-0.0013,-0.0057,2.4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.39,0.39,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34490000,-0.29,0.014,-0.0077,0.96,0.025,0.1,-0.053,0.054,-0.012,-0.052,-0.0013,-0.0057,4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.39,0.39,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34590000,-0.29,0.014,-0.0076,0.96,0.026,0.095,0.74,0.05,-0.028,-0.023,-0.0013,-0.0057,2.6e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.39,0.39,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34590000,-0.29,0.014,-0.0076,0.96,0.026,0.095,0.74,0.05,-0.028,-0.023,-0.0013,-0.0057,4.1e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.39,0.39,0.03,2.7e-07,2.6e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34690000,-0.29,0.013,-0.0076,0.96,0.03,0.095,1.7,0.053,-0.018,0.096,-0.0013,-0.0057,2.5e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.024,0.0051,0.4,0.4,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34690000,-0.29,0.013,-0.0076,0.96,0.03,0.095,1.7,0.053,-0.018,0.096,-0.0013,-0.0057,4.1e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.024,0.0051,0.4,0.4,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34790000,-0.29,0.013,-0.0076,0.96,0.032,0.087,2.7,0.049,-0.032,0.27,-0.0013,-0.0057,2.6e-05,0.035,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.4,0.4,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34790000,-0.29,0.013,-0.0076,0.96,0.032,0.087,2.7,0.049,-0.032,0.27,-0.0013,-0.0057,4.2e-05,0.035,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.4,0.4,0.03,2.7e-07,2.6e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34890000,-0.29,0.013,-0.0076,0.96,0.037,0.087,3.7,0.053,-0.024,0.57,-0.0013,-0.0057,2.5e-05,0.036,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.025,0.005,0.41,0.41,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34890000,-0.29,0.013,-0.0076,0.96,0.037,0.087,3.7,0.053,-0.024,0.57,-0.0013,-0.0057,4.2e-05,0.036,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.024,0.005,0.41,0.41,0.03,2.7e-07,2.6e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1

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]
52 4990000,1,-0.0092,-0.012,0.00059,0.013,0.0037,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,5.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.1e-05,0.04,0.04,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
53 5090000,1,-0.0091,-0.011,0.00066,0.01,0.004,-0.082,0.0045,0.001,-0.081,-0.0021,-0.0053,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00013,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
54 5190000,1,-0.0089,-0.012,0.0007,0.0098,0.0076,-0.08,0.0055,0.0016,-0.079,-0.0021,-0.0053,5.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
55 5290000,1,-0.0088,-0.011,0.00075,0.0081,0.0076,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.1e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5290000,1,-0.0088,-0.011,0.00075,0.0081,0.0076,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.2e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
56 5390000,1,-0.0087,-0.011,0.00074,0.0075,0.011,-0.065,0.0046,0.0023,-0.067,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.15,0.16,0.079,0.00035,0.00035,9.2e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
57 5490000,1,-0.0088,-0.011,0.00073,0.007,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,5e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00012,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
58 5590000,1,-0.0088,-0.011,0.00066,0.0082,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5590000,1,-0.0088,-0.011,0.00066,0.0082,0.016,-0.053,0.004,0.0036,-0.058,-0.002,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.32,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
59 5690000,1,-0.0089,-0.011,0.00055,0.0074,0.016,-0.052,0.0028,0.0031,-0.055,-0.0019,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.5e-06,0.04,0.04,0.0062,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5690000,1,-0.0089,-0.011,0.00055,0.0074,0.016,-0.052,0.0028,0.0031,-0.055,-0.0019,-0.0055,4.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.5e-06,0.04,0.04,0.0062,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
60 5790000,1,-0.0087,-0.011,0.0005,0.0087,0.018,-0.049,0.0036,0.0048,-0.053,-0.0019,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.5e-06,0.04,0.04,0.0058,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5790000,1,-0.0087,-0.011,0.0005,0.0087,0.018,-0.049,0.0036,0.0048,-0.053,-0.0019,-0.0055,4.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.5e-06,0.04,0.04,0.0058,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
61 5890000,1,-0.0088,-0.011,0.00053,0.0092,0.016,-0.048,0.0027,0.0039,-0.056,-0.0019,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5890000,1,-0.0088,-0.011,0.00053,0.0092,0.016,-0.048,0.0027,0.0039,-0.056,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
62 5990000,1,-0.0088,-0.011,0.00049,0.011,0.017,-0.041,0.0037,0.0055,-0.05,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.046,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
63 6090000,1,-0.0087,-0.011,0.0003,0.011,0.019,-0.039,0.0048,0.0073,-0.047,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
64 6190000,1,-0.0089,-0.011,0.0003,0.0083,0.017,-0.038,0.0037,0.0059,-0.047,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
65 6290000,1,-0.0088,-0.011,0.00032,0.0075,0.02,-0.041,0.0045,0.0077,-0.053,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.041,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
66 6390000,1,-0.0089,-0.011,0.00033,0.0077,0.017,-0.042,0.0033,0.0062,-0.056,-0.0017,-0.0056,4.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
67 6490000,1,-0.0088,-0.011,0.00022,0.0051,0.017,-0.039,0.004,0.0078,-0.053,-0.0017,-0.0056,4.3e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
68 6590000,1,-0.0089,-0.011,0.00014,0.0034,0.015,-0.042,0.0027,0.006,-0.056,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6590000,1,-0.0089,-0.011,0.00014,0.0034,0.016,-0.042,0.0027,0.006,-0.056,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
69 6690000,1,-0.0088,-0.011,9.4e-05,0.0016,0.019,-0.044,0.003,0.0077,-0.057,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
70 6790000,1,-0.0089,-0.011,5.3e-05,0.0023,0.016,-0.042,0.0019,0.0061,-0.058,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
71 6890000,1,-0.0087,-0.011,-3.7e-05,0.0016,0.016,-0.039,0.0021,0.0076,-0.055,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
79 7690000,-0.29,0.013,-0.005,0.96,0.0053,-0.0079,-0.022,0.0046,0.0069,-0.036,-0.0016,-0.0057,3.8e-05,-0.0006,0.00053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.24,0.24,0.025,0.35,0.35,0.062,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
80 7790000,-0.29,0.013,-0.0048,0.96,0.0042,-0.01,-0.025,0.005,0.006,-0.041,-0.0016,-0.0057,3.8e-05,-0.00055,0.00049,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.26,0.26,0.024,0.4,0.4,0.061,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
81 7890000,-0.29,0.013,-0.0049,0.96,0.0064,-0.014,-0.025,0.0056,0.0049,-0.045,-0.0016,-0.0057,3.8e-05,-0.00054,0.00047,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.29,0.29,0.023,0.46,0.46,0.06,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
82 7990000,-0.29,0.013,-0.0048,0.96,0.0066,-0.016,-0.021,0.0062,0.0035,-0.042,-0.0016,-0.0057,3.9e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.32,0.32,0.022,0.52,0.52,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 7990000,-0.29,0.013,-0.0048,0.96,0.0066,-0.016,-0.021,0.0062,0.0035,-0.042,-0.0016,-0.0057,3.8e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.32,0.32,0.022,0.52,0.52,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
83 8090000,-0.29,0.013,-0.0046,0.96,0.0059,-0.02,-0.022,0.0068,0.0017,-0.044,-0.0016,-0.0057,3.9e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.35,0.35,0.022,0.6,0.6,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8090000,-0.29,0.013,-0.0046,0.96,0.0059,-0.02,-0.022,0.0068,0.0017,-0.044,-0.0016,-0.0057,3.8e-05,-0.00064,0.00056,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.35,0.35,0.022,0.6,0.6,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
84 8190000,-0.29,0.013,-0.0047,0.96,0.0063,-0.025,-0.018,0.0074,-0.00064,-0.038,-0.0016,-0.0057,3.9e-05,-0.00081,0.0007,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.38,0.38,0.021,0.68,0.68,0.058,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8190000,-0.29,0.013,-0.0047,0.96,0.0063,-0.025,-0.018,0.0074,-0.00064,-0.038,-0.0016,-0.0057,3.8e-05,-0.00081,0.0007,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.38,0.38,0.021,0.68,0.68,0.058,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
85 8290000,-0.29,0.013,-0.0047,0.96,-0.00096,-0.0043,-0.016,0.0074,-0.0011,-0.038,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8290000,-0.29,0.013,-0.0047,0.96,-0.00096,-0.0043,-0.016,0.0074,-0.0011,-0.038,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
86 8390000,-0.29,0.013,-0.0046,0.96,0.0015,-0.0056,-0.016,0.0074,-0.0015,-0.036,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8390000,-0.29,0.013,-0.0046,0.96,0.0015,-0.0056,-0.016,0.0074,-0.0015,-0.036,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
87 8490000,-0.29,0.013,-0.0045,0.96,0.0026,-0.0096,-0.017,0.0076,-0.0019,-0.041,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.019,51,51,0.056,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8490000,-0.29,0.013,-0.0045,0.96,0.0026,-0.0096,-0.017,0.0076,-0.0019,-0.041,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.019,51,51,0.056,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
88 8590000,-0.29,0.013,-0.0045,0.96,0.0022,-0.013,-0.012,0.0078,-0.003,-0.036,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.019,52,52,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8590000,-0.29,0.013,-0.0045,0.96,0.0022,-0.013,-0.012,0.0078,-0.003,-0.036,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.019,52,52,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
89 8690000,-0.29,0.013,-0.0045,0.96,0.0026,-0.015,-0.014,0.0079,-0.0035,-0.037,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,35,35,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8690000,-0.29,0.013,-0.0045,0.96,0.0026,-0.015,-0.014,0.0079,-0.0035,-0.037,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,35,35,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
90 8790000,-0.29,0.013,-0.0044,0.96,0.0018,-0.018,-0.013,0.0082,-0.0051,-0.035,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,37,37,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00097,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8790000,-0.29,0.013,-0.0044,0.96,0.0018,-0.018,-0.013,0.0082,-0.0051,-0.035,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,37,37,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00097,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
91 8890000,-0.29,0.013,-0.0045,0.96,0.0024,-0.021,-0.0092,0.0082,-0.0058,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.017,28,28,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00093,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
92 8990000,-0.29,0.013,-0.0044,0.96,0.0043,-0.026,-0.0084,0.0086,-0.0081,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,24,24,0.017,30,30,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00089,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 8990000,-0.29,0.013,-0.0044,0.96,0.0043,-0.026,-0.0084,0.0086,-0.0081,-0.032,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,24,24,0.017,30,30,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00089,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
93 9090000,-0.29,0.013,-0.0044,0.96,0.0049,-0.03,-0.0094,0.0087,-0.0088,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,25,25,0.053,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00085,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9090000,-0.29,0.013,-0.0044,0.96,0.0049,-0.03,-0.0094,0.0087,-0.0088,-0.032,-0.0016,-0.0057,3.8e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,25,25,0.053,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00085,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
94 9190000,-0.29,0.013,-0.0043,0.96,0.002,-0.034,-0.0089,0.009,-0.012,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,27,27,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00081,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
95 9290000,-0.29,0.013,-0.0042,0.96,0.00017,-0.036,-0.0073,0.0087,-0.013,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0016,0.0016,0.018,21,21,0.015,23,23,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
96 9390000,-0.29,0.013,-0.0041,0.96,0.00073,-0.039,-0.0062,0.0087,-0.016,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,21,21,0.015,26,26,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00075,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
98 9590000,-0.29,0.013,-0.0041,0.96,0.0017,-0.042,-0.0044,0.0087,-0.02,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,19,19,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00069,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
99 9690000,-0.29,0.013,-0.0041,0.96,0.0022,-0.042,-0.0015,0.0085,-0.02,-0.027,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,22,22,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00066,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
100 9790000,-0.29,0.013,-0.0041,0.96,0.0017,-0.047,-0.0028,0.0087,-0.024,-0.028,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00064,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
101 9890000,-0.29,0.013,-0.004,0.96,-0.00018,-0.046,-0.0015,0.0085,-0.023,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0018,0.018,15,15,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00061,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 9890000,-0.29,0.013,-0.004,0.96,-0.00017,-0.046,-0.0015,0.0085,-0.023,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0018,0.018,15,15,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00061,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
102 9990000,-0.29,0.013,-0.004,0.96,-0.0013,-0.049,-0.0008,0.0085,-0.028,-0.031,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,15,15,0.013,25,25,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
103 10090000,-0.29,0.013,-0.0039,0.96,0.00027,-0.046,0.00042,0.0082,-0.026,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,13,13,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00057,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10090000,-0.29,0.013,-0.0039,0.96,0.00028,-0.046,0.00042,0.0082,-0.026,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,13,13,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00057,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
104 10190000,-0.29,0.013,-0.0039,0.96,0.0026,-0.049,0.0013,0.0083,-0.03,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.013,24,24,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00055,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
105 10290000,-0.29,0.013,-0.0039,0.96,0.0027,-0.053,0.00023,0.0086,-0.036,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.012,27,27,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00053,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
106 10390000,-0.29,0.013,-0.0039,0.96,0.014,-0.0047,-0.0025,0.0011,-0.00013,-0.028,-0.0016,-0.0057,3.9e-05,-0.00085,0.00074,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.25,0.25,0.56,0.25,0.25,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00052,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
107 10490000,-0.29,0.013,-0.0038,0.96,0.013,-0.0077,0.007,0.0025,-0.0007,-0.023,-0.0016,-0.0057,3.9e-05,-0.00098,0.00083,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.26,0.26,0.55,0.26,0.26,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
108 10590000,-0.29,0.013,-0.0038,0.96,0.0018,-0.0063,0.013,0.00044,-0.00048,-0.021,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.13,0.13,0.27,0.26,0.26,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00049,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10590000,-0.29,0.013,-0.0038,0.96,0.0018,-0.0063,0.013,0.00044,-0.00048,-0.021,-0.0016,-0.0057,3.8e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.13,0.13,0.27,0.26,0.26,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00049,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
109 10690000,-0.29,0.013,-0.0037,0.96,0.00059,-0.0081,0.016,0.00055,-0.0012,-0.017,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.14,0.14,0.26,0.27,0.27,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00048,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10690000,-0.29,0.013,-0.0037,0.96,0.00059,-0.0081,0.016,0.00055,-0.0012,-0.017,-0.0016,-0.0057,3.8e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.14,0.14,0.26,0.27,0.27,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00048,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
110 10790000,-0.29,0.013,-0.0037,0.96,-0.0011,-0.012,0.014,0.00022,-0.0018,-0.015,-0.0016,-0.0057,3.9e-05,-0.0013,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.1,0.1,0.17,0.13,0.13,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10790000,-0.29,0.013,-0.0037,0.96,-0.0011,-0.012,0.014,0.00022,-0.0018,-0.015,-0.0016,-0.0057,3.8e-05,-0.0013,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.1,0.1,0.17,0.13,0.13,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
111 10890000,-0.29,0.013,-0.0036,0.96,-0.00075,-0.016,0.01,0.00011,-0.0031,-0.018,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.12,0.12,0.16,0.14,0.14,0.068,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10890000,-0.29,0.013,-0.0036,0.96,-0.00075,-0.016,0.01,0.00011,-0.0031,-0.018,-0.0016,-0.0057,3.8e-05,-0.0012,0.0011,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.12,0.12,0.16,0.14,0.14,0.068,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
112 10990000,-0.29,0.013,-0.0038,0.96,0.0008,-0.019,0.016,9.8e-05,-0.0017,-0.011,-0.0016,-0.0057,3.8e-05,-0.00092,0.0016,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,0.091,0.091,0.12,0.093,0.093,0.065,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 10990000,-0.29,0.013,-0.0038,0.96,0.0008,-0.019,0.016,9.8e-05,-0.0017,-0.011,-0.0016,-0.0057,3.7e-05,-0.00093,0.0016,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.002,0.002,0.018,0.091,0.091,0.12,0.093,0.093,0.065,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
113 11090000,-0.29,0.013,-0.0039,0.96,0.0006,-0.025,0.02,0.00019,-0.0038,-0.0074,-0.0016,-0.0057,3.8e-05,-0.00095,0.0017,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.11,0.11,0.11,0.099,0.099,0.069,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11090000,-0.29,0.013,-0.0039,0.96,0.00061,-0.025,0.02,0.00019,-0.0038,-0.0074,-0.0016,-0.0057,3.7e-05,-0.00095,0.0017,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.11,0.11,0.11,0.099,0.099,0.069,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
114 11190000,-0.29,0.013,-0.0042,0.96,0.0056,-0.022,0.026,0.0015,-0.0021,-0.00036,-0.0015,-0.0057,3.5e-05,-6.8e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.09,0.09,0.083,0.073,0.073,0.066,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11190000,-0.29,0.013,-0.0042,0.96,0.0056,-0.022,0.026,0.0015,-0.0021,-0.00036,-0.0015,-0.0057,3.5e-05,-7e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.09,0.09,0.083,0.073,0.073,0.066,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
115 11290000,-0.29,0.013,-0.0041,0.96,0.0061,-0.023,0.026,0.0021,-0.0044,-0.00013,-0.0015,-0.0057,3.5e-05,-5.3e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.11,0.11,0.077,0.08,0.08,0.069,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11290000,-0.29,0.013,-0.0041,0.96,0.0061,-0.023,0.026,0.0021,-0.0044,-0.00013,-0.0015,-0.0057,3.5e-05,-5.5e-05,0.0023,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.11,0.11,0.077,0.08,0.08,0.069,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
116 11390000,-0.29,0.013,-0.0044,0.96,0.0051,-0.019,0.016,0.0014,-0.0025,-0.0086,-0.0014,-0.0058,3.3e-05,0.00035,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.091,0.091,0.062,0.063,0.063,0.066,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11390000,-0.29,0.013,-0.0044,0.96,0.0051,-0.019,0.016,0.0014,-0.0025,-0.0086,-0.0014,-0.0058,3.2e-05,0.00034,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.091,0.091,0.062,0.063,0.063,0.066,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
117 11490000,-0.29,0.013,-0.0043,0.96,0.0064,-0.021,0.02,0.0021,-0.0045,-0.0025,-0.0014,-0.0058,3.3e-05,0.00032,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.11,0.11,0.057,0.07,0.07,0.067,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11490000,-0.29,0.013,-0.0043,0.96,0.0064,-0.021,0.02,0.0021,-0.0045,-0.0025,-0.0014,-0.0058,3.2e-05,0.00032,0.0033,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.11,0.11,0.057,0.07,0.07,0.067,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
118 11590000,-0.29,0.013,-0.0047,0.96,0.0023,-0.016,0.018,0.0012,-0.0026,-0.0036,-0.0014,-0.0058,3.1e-05,0.00056,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.09,0.09,0.048,0.057,0.057,0.065,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11590000,-0.29,0.013,-0.0047,0.96,0.0023,-0.016,0.018,0.0012,-0.0026,-0.0036,-0.0014,-0.0058,3e-05,0.00055,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.09,0.09,0.048,0.057,0.057,0.065,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
119 11690000,-0.29,0.013,-0.0046,0.96,0.0027,-0.021,0.018,0.0014,-0.0044,-0.0049,-0.0014,-0.0058,3.1e-05,0.00057,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.044,0.065,0.065,0.066,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 11690000,-0.29,0.013,-0.0046,0.96,0.0027,-0.021,0.018,0.0014,-0.0044,-0.0049,-0.0014,-0.0058,3e-05,0.00057,0.0041,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.044,0.065,0.065,0.066,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
120 11790000,-0.29,0.013,-0.0048,0.96,0.0023,-0.02,0.019,0.001,-0.004,-0.002,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.087,0.087,0.037,0.054,0.054,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
121 11890000,-0.29,0.013,-0.0049,0.96,-3e-05,-0.023,0.017,0.0012,-0.0061,-0.0013,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.1,0.1,0.034,0.062,0.062,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
122 11990000,-0.29,0.013,-0.0053,0.96,0.0022,-0.015,0.015,0.0028,-0.0031,-0.005,-0.0013,-0.0059,2.6e-05,0.0015,0.0052,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.088,0.088,0.03,0.063,0.063,0.061,4.8e-05,4.8e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
129 12690000,-0.29,0.013,-0.0054,0.96,-8.4e-05,-0.0036,0.019,0.003,-0.0025,0.0033,-0.0012,-0.0059,2.4e-05,0.0019,0.0057,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00094,0.00094,0.018,0.08,0.08,0.015,0.062,0.062,0.053,4.2e-05,4.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
130 12790000,-0.29,0.012,-0.0053,0.96,0.0056,-0.0099,0.021,0.0064,-0.0057,0.0054,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.07,0.07,0.014,0.063,0.063,0.052,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
131 12890000,-0.29,0.012,-0.0053,0.96,0.0062,-0.01,0.022,0.0069,-0.0067,0.0084,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.08,0.08,0.013,0.072,0.072,0.051,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
132 12990000,-0.29,0.012,-0.0054,0.96,0.0036,-0.008,0.022,0.0049,-0.0045,0.0096,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00083,0.018,0.063,0.063,0.012,0.058,0.058,0.05,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 12990000,-0.29,0.012,-0.0054,0.96,0.0036,-0.008,0.022,0.0049,-0.0045,0.0096,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00083,0.018,0.063,0.063,0.012,0.058,0.058,0.05,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
133 13090000,-0.29,0.012,-0.0054,0.96,0.0033,-0.0091,0.02,0.0053,-0.0054,0.0085,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00086,0.00086,0.018,0.072,0.072,0.011,0.067,0.067,0.049,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13090000,-0.29,0.012,-0.0054,0.96,0.0033,-0.0091,0.02,0.0053,-0.0054,0.0085,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00086,0.00086,0.018,0.072,0.072,0.011,0.067,0.067,0.049,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
134 13190000,-0.29,0.012,-0.0054,0.96,0.004,-0.0095,0.019,0.0052,-0.0065,0.0091,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.063,0.063,0.011,0.068,0.068,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13190000,-0.29,0.012,-0.0054,0.96,0.004,-0.0095,0.019,0.0052,-0.0065,0.0091,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.063,0.063,0.011,0.068,0.068,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
135 13290000,-0.29,0.012,-0.0054,0.96,0.0046,-0.0095,0.016,0.0056,-0.0075,0.0084,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.072,0.072,0.01,0.078,0.078,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13290000,-0.29,0.012,-0.0054,0.96,0.0046,-0.0095,0.016,0.0056,-0.0075,0.0084,-0.0013,-0.0059,2.5e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.072,0.072,0.01,0.078,0.078,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
136 13390000,-0.29,0.012,-0.0054,0.96,0.0031,-0.0074,0.016,0.004,-0.005,0.0091,-0.0012,-0.0059,2.4e-05,0.0021,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.057,0.057,0.0095,0.061,0.061,0.046,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13390000,-0.29,0.012,-0.0054,0.96,0.0031,-0.0074,0.016,0.004,-0.005,0.0091,-0.0012,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.057,0.057,0.0095,0.061,0.061,0.046,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
137 13490000,-0.29,0.012,-0.0054,0.96,0.0032,-0.0099,0.015,0.0043,-0.0059,0.0053,-0.0012,-0.0059,2.4e-05,0.0021,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.064,0.064,0.009,0.07,0.07,0.045,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
138 13590000,-0.29,0.012,-0.0055,0.96,0.0054,-0.0069,0.017,0.0065,-0.0039,0.0038,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.053,0.053,0.0086,0.057,0.057,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
139 13690000,-0.29,0.012,-0.0054,0.96,0.0058,-0.0061,0.017,0.0071,-0.0046,0.0064,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.06,0.06,0.0083,0.065,0.065,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
140 13790000,-0.29,0.012,-0.0055,0.96,0.0079,-0.0045,0.017,0.01,-0.0018,0.0059,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.05,0.05,0.0079,0.054,0.054,0.042,3.3e-05,3.3e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13790000,-0.29,0.012,-0.0055,0.96,0.0079,-0.0045,0.017,0.01,-0.0018,0.0059,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.05,0.05,0.0079,0.054,0.054,0.042,3.4e-05,3.4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
141 13890000,-0.29,0.012,-0.0054,0.96,0.0081,-0.0056,0.018,0.011,-0.0023,0.0081,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.056,0.056,0.0077,0.061,0.061,0.042,3.3e-05,3.3e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 13890000,-0.29,0.012,-0.0054,0.96,0.0081,-0.0056,0.018,0.011,-0.0023,0.0081,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.056,0.056,0.0077,0.061,0.061,0.042,3.4e-05,3.4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
142 13990000,-0.29,0.012,-0.0054,0.96,0.0034,-0.0095,0.017,0.0083,-0.0032,0.007,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.048,0.048,0.0074,0.052,0.052,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
143 14090000,-0.29,0.012,-0.0054,0.96,0.0056,-0.0051,0.018,0.0086,-0.0039,0.0035,-0.0012,-0.006,2.3e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.054,0.054,0.0073,0.059,0.059,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14090000,-0.29,0.012,-0.0054,0.96,0.0056,-0.0051,0.018,0.0086,-0.0039,0.0035,-0.0012,-0.006,2.3e-05,0.002,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0008,0.00079,0.018,0.054,0.054,0.0073,0.059,0.059,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
144 14190000,-0.29,0.012,-0.0054,0.96,0.0075,-0.0044,0.018,0.0083,-0.003,0.0037,-0.0012,-0.006,2.2e-05,0.002,0.0054,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.046,0.046,0.0071,0.05,0.05,0.04,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
145 14290000,-0.29,0.012,-0.0054,0.96,0.0067,-0.0051,0.016,0.0092,-0.0034,0.0079,-0.0012,-0.006,2.2e-05,0.0019,0.0055,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.052,0.052,0.007,0.057,0.057,0.039,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
146 14390000,-0.29,0.012,-0.0054,0.96,0.0054,-0.0047,0.018,0.0085,-0.004,0.012,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.045,0.045,0.0068,0.049,0.049,0.039,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
147 14490000,-0.29,0.012,-0.0055,0.96,0.0077,-0.0052,0.021,0.0093,-0.0044,0.015,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.05,0.05,0.0067,0.056,0.056,0.038,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
148 14590000,-0.29,0.012,-0.0056,0.96,0.002,-0.0072,0.019,0.0058,-0.0049,0.011,-0.0012,-0.006,2.2e-05,0.0024,0.0054,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.044,0.044,0.0066,0.048,0.048,0.038,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14590000,-0.29,0.012,-0.0056,0.96,0.002,-0.0072,0.019,0.0058,-0.0049,0.011,-0.0012,-0.006,2.3e-05,0.0023,0.0054,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.044,0.044,0.0066,0.048,0.048,0.038,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
149 14690000,-0.29,0.012,-0.0055,0.96,0.0031,-0.0078,0.019,0.0061,-0.0056,0.011,-0.0012,-0.006,2.2e-05,0.0024,0.0053,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.049,0.049,0.0066,0.055,0.055,0.037,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14690000,-0.29,0.012,-0.0055,0.96,0.0031,-0.0078,0.019,0.0061,-0.0056,0.011,-0.0012,-0.006,2.3e-05,0.0024,0.0053,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.049,0.049,0.0066,0.055,0.055,0.037,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
150 14790000,-0.29,0.012,-0.0059,0.96,-0.0012,-0.0025,0.019,0.0047,-0.00016,0.014,-0.0011,-0.006,2e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.043,0.043,0.0065,0.048,0.048,0.037,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14790000,-0.29,0.012,-0.0059,0.96,-0.0012,-0.0025,0.019,0.0047,-0.00016,0.014,-0.0011,-0.006,2.1e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.043,0.043,0.0065,0.048,0.048,0.037,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
151 14890000,-0.29,0.012,-0.0058,0.96,-0.00028,7.5e-05,0.023,0.0047,-0.00028,0.015,-0.0011,-0.006,2e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.048,0.048,0.0066,0.054,0.054,0.036,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14890000,-0.29,0.012,-0.0058,0.96,-0.00028,7.5e-05,0.023,0.0047,-0.00028,0.015,-0.0011,-0.006,2.1e-05,0.002,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.048,0.048,0.0066,0.054,0.054,0.036,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
152 14990000,-0.29,0.012,-0.0059,0.96,-0.0013,-0.0021,0.026,0.0038,-0.0016,0.017,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.042,0.042,0.0065,0.047,0.047,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 14990000,-0.29,0.012,-0.0059,0.96,-0.0012,-0.0021,0.026,0.0038,-0.0016,0.017,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.042,0.042,0.0065,0.047,0.047,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
153 15090000,-0.29,0.012,-0.0058,0.96,-0.001,-0.0034,0.03,0.0037,-0.0019,0.019,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.047,0.047,0.0066,0.054,0.054,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
154 15190000,-0.29,0.012,-0.0059,0.96,-0.0013,-0.0017,0.03,0.003,-0.0013,0.021,-0.0011,-0.006,2.1e-05,0.0022,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.041,0.041,0.0066,0.047,0.047,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
155 15290000,-0.29,0.012,-0.006,0.96,-0.0021,-0.001,0.03,0.0028,-0.0015,0.018,-0.0011,-0.006,2e-05,0.0024,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.046,0.046,0.0066,0.053,0.053,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15290000,-0.29,0.012,-0.006,0.96,-0.0021,-0.001,0.03,0.0028,-0.0015,0.018,-0.0011,-0.006,2.1e-05,0.0024,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.046,0.046,0.0066,0.053,0.053,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
156 15390000,-0.29,0.012,-0.0061,0.96,-0.0032,-0.0032,0.029,0.0024,-0.0013,0.018,-0.0011,-0.006,2e-05,0.0024,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.041,0.041,0.0066,0.047,0.047,0.034,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15390000,-0.29,0.012,-0.0061,0.96,-0.0032,-0.0032,0.029,0.0024,-0.0013,0.018,-0.0011,-0.006,2.1e-05,0.0024,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.041,0.041,0.0066,0.047,0.047,0.034,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
157 15490000,-0.29,0.012,-0.0062,0.96,-0.0033,-0.00084,0.029,0.0021,-0.0015,0.019,-0.0011,-0.006,2e-05,0.0025,0.0043,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.046,0.046,0.0067,0.053,0.053,0.035,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15490000,-0.29,0.012,-0.0062,0.96,-0.0033,-0.00084,0.029,0.0021,-0.0015,0.019,-0.0011,-0.006,2.1e-05,0.0025,0.0043,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.046,0.046,0.0067,0.053,0.053,0.035,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
158 15590000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0066,0.029,0.0045,-0.0054,0.018,-0.0012,-0.006,2.2e-05,0.0026,0.0051,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00072,0.00072,0.018,0.04,0.04,0.0067,0.046,0.046,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
159 15690000,-0.29,0.012,-0.0059,0.96,-0.0033,-0.0048,0.03,0.0042,-0.006,0.019,-0.0012,-0.006,2.2e-05,0.0027,0.0051,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.045,0.045,0.0068,0.053,0.053,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15690000,-0.29,0.012,-0.0059,0.96,-0.0033,-0.0048,0.03,0.0042,-0.006,0.019,-0.0012,-0.006,2.2e-05,0.0026,0.0051,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.045,0.045,0.0068,0.053,0.053,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
160 15790000,-0.29,0.012,-0.006,0.96,-0.0022,-0.0025,0.03,0.0036,-0.0047,0.021,-0.0012,-0.006,2.2e-05,0.0026,0.0049,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.039,0.039,0.0068,0.046,0.046,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
161 15890000,-0.29,0.012,-0.0061,0.96,-0.00061,-0.0045,0.03,0.0035,-0.005,0.02,-0.0012,-0.006,2.2e-05,0.0027,0.0048,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.044,0.044,0.0069,0.053,0.053,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
162 15990000,-0.29,0.012,-0.006,0.96,-0.00029,-0.0036,0.027,0.003,-0.004,0.02,-0.0012,-0.006,2.1e-05,0.0028,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.039,0.039,0.0069,0.046,0.046,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 15990000,-0.29,0.012,-0.006,0.96,-0.00028,-0.0036,0.027,0.003,-0.004,0.02,-0.0012,-0.006,2.2e-05,0.0028,0.0045,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.039,0.039,0.0069,0.046,0.046,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
163 16090000,-0.29,0.012,-0.0059,0.96,0.00011,-0.0028,0.025,0.003,-0.0043,0.019,-0.0012,-0.006,2.1e-05,0.0029,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.044,0.044,0.007,0.053,0.053,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16090000,-0.29,0.012,-0.0059,0.96,0.00012,-0.0028,0.025,0.003,-0.0043,0.019,-0.0012,-0.006,2.2e-05,0.0029,0.0044,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.044,0.044,0.007,0.053,0.053,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
164 16190000,-0.29,0.012,-0.0059,0.96,-0.00023,-0.003,0.024,0.0012,-0.0036,0.016,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.038,0.038,0.0071,0.046,0.046,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
165 16290000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0021,0.024,0.0011,-0.0038,0.018,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.043,0.043,0.0072,0.053,0.053,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
166 16390000,-0.29,0.012,-0.006,0.96,-0.00081,-0.0014,0.024,0.0022,-0.0032,0.018,-0.0012,-0.006,2.1e-05,0.0033,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00067,0.00067,0.018,0.038,0.038,0.0072,0.046,0.046,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16390000,-0.29,0.012,-0.006,0.96,-0.0008,-0.0014,0.024,0.0022,-0.0032,0.018,-0.0012,-0.006,2.1e-05,0.0033,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00067,0.00067,0.018,0.038,0.038,0.0072,0.046,0.046,0.033,1.4e-05,1.4e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
167 16490000,-0.29,0.012,-0.0061,0.96,-0.0031,-0.00073,0.026,0.002,-0.0032,0.022,-0.0012,-0.006,2.1e-05,0.0032,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.042,0.042,0.0073,0.052,0.052,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16490000,-0.29,0.012,-0.0061,0.96,-0.0031,-0.00073,0.026,0.002,-0.0032,0.022,-0.0012,-0.006,2.1e-05,0.0032,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.042,0.042,0.0074,0.052,0.052,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
168 16590000,-0.29,0.012,-0.0061,0.96,-0.0081,-0.0003,0.03,0.0015,-0.0027,0.022,-0.0012,-0.006,2.1e-05,0.0033,0.0038,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.037,0.037,0.0074,0.046,0.046,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
169 16690000,-0.29,0.012,-0.0062,0.96,-0.011,0.0035,0.03,0.00053,-0.0025,0.023,-0.0012,-0.006,2.1e-05,0.0034,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00066,0.00066,0.018,0.042,0.042,0.0075,0.052,0.052,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16690000,-0.29,0.012,-0.0062,0.96,-0.011,0.0035,0.03,0.00053,-0.0025,0.023,-0.0012,-0.006,2.1e-05,0.0033,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00066,0.00066,0.018,0.042,0.042,0.0075,0.052,0.052,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
170 16790000,-0.29,0.012,-0.006,0.96,-0.012,0.0032,0.029,0.00072,-0.0023,0.023,-0.0012,-0.0061,2.1e-05,0.0033,0.0038,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.037,0.037,0.0075,0.046,0.046,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16790000,-0.29,0.012,-0.006,0.96,-0.012,0.0032,0.029,0.00072,-0.0023,0.023,-0.0012,-0.0061,2.2e-05,0.0033,0.0038,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.037,0.037,0.0075,0.046,0.046,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
171 16890000,-0.29,0.012,-0.006,0.96,-0.011,0.0036,0.03,-0.00046,-0.0019,0.021,-0.0012,-0.0061,2.1e-05,0.0035,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.041,0.041,0.0076,0.052,0.052,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 16890000,-0.29,0.012,-0.006,0.96,-0.011,0.0036,0.03,-0.00046,-0.0019,0.021,-0.0012,-0.0061,2.2e-05,0.0035,0.0037,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.041,0.041,0.0076,0.052,0.052,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
172 16990000,-0.29,0.012,-0.006,0.96,-0.0067,0.0041,0.03,0.0025,-0.002,0.02,-0.0012,-0.0061,2.2e-05,0.0031,0.004,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.039,0.039,0.0076,0.054,0.054,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
173 17090000,-0.29,0.011,-0.0061,0.96,-0.0087,0.0061,0.03,0.0017,-0.0015,0.02,-0.0012,-0.0061,2.2e-05,0.0033,0.0039,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.044,0.044,0.0077,0.062,0.062,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
174 17190000,-0.29,0.011,-0.006,0.96,-0.0069,0.0049,0.031,0.0036,-0.0048,0.023,-0.0013,-0.0061,2.3e-05,0.0033,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00061,0.00062,0.018,0.041,0.041,0.0077,0.064,0.064,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17190000,-0.29,0.011,-0.006,0.96,-0.0069,0.0049,0.031,0.0036,-0.0048,0.023,-0.0013,-0.0061,2.3e-05,0.0033,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00062,0.00062,0.018,0.041,0.041,0.0077,0.064,0.064,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
175 17290000,-0.29,0.011,-0.006,0.96,-0.0076,0.0046,0.031,0.0029,-0.0044,0.023,-0.0013,-0.0061,2.3e-05,0.0034,0.0046,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.046,0.046,0.0078,0.072,0.072,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
176 17390000,-0.29,0.011,-0.006,0.96,-4.1e-05,0.011,0.03,0.0064,-0.0019,0.022,-0.0013,-0.0061,2.3e-05,0.0029,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00059,0.00059,0.018,0.038,0.038,0.0078,0.058,0.058,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 17390000,-0.29,0.011,-0.006,0.96,-3.9e-05,0.011,0.03,0.0064,-0.0019,0.022,-0.0013,-0.0061,2.3e-05,0.0029,0.0047,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.00059,0.00059,0.018,0.038,0.038,0.0078,0.058,0.058,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
177 17490000,-0.29,0.011,-0.006,0.96,0.0021,0.012,0.03,0.0066,-0.00081,0.024,-0.0013,-0.0061,2.3e-05,0.003,0.0046,-0.14,-0.017,-0.0038,0.57,0,0,0,0,0,0.0006,0.0006,0.019,0.042,0.042,0.0079,0.066,0.066,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
178 17590000,-0.29,0.011,-0.006,0.96,-0.0017,0.0092,0.029,0.002,-0.0014,0.022,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.036,0.036,0.0079,0.055,0.055,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
179 17690000,-0.29,0.011,-0.0061,0.96,-0.00094,0.0098,0.03,0.0018,-0.00039,0.024,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.04,0.04,0.008,0.062,0.062,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
181 17890000,-0.29,0.011,-0.0061,0.96,-0.0035,0.012,0.03,0.0029,0.0018,0.034,-0.0013,-0.0061,2.3e-05,0.0036,0.0045,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.042,0.042,0.0081,0.072,0.072,0.034,7.6e-06,7.6e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
182 17990000,-0.29,0.011,-0.0061,0.96,-0.0037,0.015,0.03,0.0025,0.0054,0.034,-0.0013,-0.0061,2.3e-05,0.0034,0.0041,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00055,0.00055,0.019,0.035,0.035,0.008,0.058,0.058,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
183 18090000,-0.29,0.011,-0.0062,0.96,-0.0033,0.016,0.029,0.0021,0.007,0.033,-0.0013,-0.0061,2.3e-05,0.0036,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00056,0.00056,0.019,0.039,0.039,0.0081,0.065,0.065,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
184 18190000,-0.29,0.011,-0.0062,0.96,-0.0012,0.014,0.03,0.0033,0.0048,0.031,-0.0013,-0.0061,2.3e-05,0.0039,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0081,0.054,0.054,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18190000,-0.29,0.011,-0.0062,0.96,-0.0012,0.014,0.03,0.0033,0.0048,0.031,-0.0013,-0.0061,2.4e-05,0.0039,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0081,0.054,0.054,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
185 18290000,-0.29,0.011,-0.0062,0.96,-0.0021,0.014,0.028,0.0032,0.0062,0.029,-0.0013,-0.0061,2.3e-05,0.0041,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.037,0.037,0.0081,0.061,0.061,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18290000,-0.29,0.011,-0.0062,0.96,-0.0021,0.014,0.028,0.0032,0.0062,0.029,-0.0013,-0.0061,2.4e-05,0.0041,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.037,0.037,0.0081,0.061,0.061,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
186 18390000,-0.29,0.011,-0.0061,0.96,0.0013,0.012,0.028,0.0054,0.0045,0.029,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.008,0.052,0.052,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18390000,-0.29,0.011,-0.0061,0.96,0.0013,0.012,0.028,0.0054,0.0045,0.029,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.0081,0.052,0.052,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
187 18490000,-0.29,0.011,-0.0061,0.96,-0.001,0.012,0.027,0.0054,0.0057,0.03,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.0081,0.058,0.058,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
188 18590000,-0.29,0.011,-0.006,0.96,-0.0014,0.011,0.027,0.0044,0.0043,0.033,-0.0013,-0.0061,2.4e-05,0.0043,0.0046,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.0081,0.05,0.05,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18590000,-0.29,0.011,-0.006,0.96,-0.0014,0.011,0.027,0.0044,0.0043,0.033,-0.0013,-0.0061,2.5e-05,0.0043,0.0046,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.0081,0.05,0.05,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
189 18690000,-0.29,0.011,-0.0059,0.96,-0.00095,0.0098,0.026,0.0042,0.0053,0.031,-0.0013,-0.0061,2.4e-05,0.0045,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.034,0.034,0.0081,0.056,0.056,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18690000,-0.29,0.011,-0.0059,0.96,-0.00095,0.0098,0.026,0.0042,0.0053,0.031,-0.0013,-0.0061,2.5e-05,0.0045,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.034,0.034,0.0081,0.056,0.056,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
190 18790000,-0.29,0.011,-0.0059,0.96,0.00091,0.0092,0.025,0.0048,0.0042,0.029,-0.0014,-0.0061,2.4e-05,0.0047,0.0045,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.0081,0.048,0.048,0.034,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18790000,-0.29,0.011,-0.0059,0.96,0.00091,0.0092,0.025,0.0048,0.0042,0.029,-0.0014,-0.0061,2.5e-05,0.0047,0.0045,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.0081,0.048,0.048,0.034,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
191 18890000,-0.29,0.011,-0.0059,0.96,0.0026,0.0093,0.023,0.005,0.0052,0.025,-0.0013,-0.0061,2.4e-05,0.005,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.033,0.033,0.0081,0.054,0.054,0.035,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 18890000,-0.29,0.011,-0.0059,0.96,0.0026,0.0093,0.023,0.005,0.0052,0.025,-0.0013,-0.0061,2.5e-05,0.005,0.0043,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.033,0.033,0.0081,0.054,0.054,0.035,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
192 18990000,-0.29,0.011,-0.0058,0.96,0.0023,0.009,0.024,0.004,0.004,0.029,-0.0014,-0.0061,2.5e-05,0.0052,0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.008,0.047,0.047,0.034,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
193 19090000,-0.29,0.011,-0.0059,0.96,0.0044,0.01,0.025,0.0043,0.0049,0.025,-0.0014,-0.0061,2.4e-05,0.0054,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.0081,0.053,0.053,0.035,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19090000,-0.29,0.011,-0.0059,0.96,0.0044,0.01,0.025,0.0043,0.0049,0.025,-0.0014,-0.0061,2.5e-05,0.0054,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.0081,0.053,0.053,0.035,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
194 19190000,-0.29,0.011,-0.0058,0.96,0.0044,0.0094,0.024,0.0034,0.004,0.024,-0.0014,-0.0061,2.5e-05,0.0058,0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.008,0.046,0.046,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
195 19290000,-0.29,0.011,-0.0057,0.96,0.0054,0.0095,0.025,0.0039,0.0049,0.023,-0.0014,-0.0061,2.5e-05,0.0059,0.0041,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.008,0.052,0.052,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19290000,-0.29,0.011,-0.0057,0.96,0.0054,0.0095,0.025,0.0039,0.0049,0.023,-0.0014,-0.0061,2.6e-05,0.0059,0.0041,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.008,0.052,0.052,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
196 19390000,-0.29,0.011,-0.0059,0.96,0.005,0.008,0.026,0.003,0.005,0.022,-0.0014,-0.0061,2.4e-05,0.0062,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.029,0.0079,0.045,0.045,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19390000,-0.29,0.011,-0.0059,0.96,0.005,0.008,0.026,0.003,0.005,0.022,-0.0014,-0.0061,2.5e-05,0.0062,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.029,0.029,0.0079,0.045,0.045,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
197 19490000,-0.29,0.011,-0.0059,0.96,0.0059,0.0083,0.025,0.0036,0.0058,0.022,-0.0014,-0.0061,2.4e-05,0.0063,0.0038,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.0079,0.051,0.051,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19490000,-0.29,0.011,-0.0059,0.96,0.0059,0.0083,0.025,0.0036,0.0058,0.022,-0.0014,-0.0061,2.6e-05,0.0063,0.0038,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.0079,0.051,0.051,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
198 19590000,-0.29,0.011,-0.0058,0.96,0.0078,0.0084,0.027,0.0041,0.0036,0.022,-0.0014,-0.0061,2.5e-05,0.0066,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0078,0.045,0.045,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19590000,-0.29,0.011,-0.0058,0.96,0.0079,0.0084,0.027,0.0041,0.0036,0.022,-0.0014,-0.0061,2.6e-05,0.0066,0.004,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0078,0.045,0.045,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
199 19690000,-0.29,0.011,-0.0058,0.96,0.01,0.0074,0.026,0.0049,0.0043,0.022,-0.0014,-0.0061,2.5e-05,0.0067,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0078,0.051,0.051,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19690000,-0.29,0.011,-0.0058,0.96,0.01,0.0074,0.026,0.0049,0.0043,0.022,-0.0014,-0.0061,2.6e-05,0.0067,0.0039,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0078,0.051,0.051,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
200 19790000,-0.29,0.011,-0.0059,0.96,0.013,0.0064,0.024,0.006,0.0043,0.018,-0.0014,-0.0061,2.5e-05,0.0071,0.0037,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.0078,0.053,0.053,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19790000,-0.29,0.011,-0.0059,0.96,0.013,0.0064,0.024,0.006,0.0043,0.018,-0.0014,-0.0061,2.6e-05,0.0071,0.0037,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.0078,0.053,0.053,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
201 19890000,-0.29,0.011,-0.0059,0.96,0.013,0.0062,0.024,0.0073,0.0049,0.016,-0.0014,-0.0061,2.5e-05,0.0072,0.0036,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.033,0.033,0.0078,0.059,0.059,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19890000,-0.29,0.011,-0.0059,0.96,0.013,0.0062,0.024,0.0073,0.0049,0.016,-0.0014,-0.0061,2.6e-05,0.0072,0.0036,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.033,0.033,0.0078,0.059,0.059,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
202 19990000,-0.29,0.011,-0.0059,0.96,0.013,0.0079,0.022,0.0068,0.0051,0.013,-0.0014,-0.0061,2.4e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.028,0.028,0.0077,0.051,0.051,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 19990000,-0.29,0.011,-0.0059,0.96,0.013,0.0079,0.022,0.0068,0.0051,0.013,-0.0014,-0.0061,2.6e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00044,0.019,0.028,0.028,0.0077,0.051,0.051,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
203 20090000,-0.29,0.011,-0.0059,0.96,0.012,0.01,0.022,0.0081,0.006,0.017,-0.0014,-0.0061,2.4e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.031,0.031,0.0077,0.057,0.057,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20090000,-0.29,0.011,-0.0059,0.96,0.012,0.01,0.022,0.0081,0.006,0.017,-0.0014,-0.0061,2.6e-05,0.0075,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.031,0.031,0.0077,0.057,0.057,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
204 20190000,-0.29,0.012,-0.0059,0.96,0.011,0.0071,0.023,0.0077,0.0057,0.016,-0.0014,-0.006,2.4e-05,0.0078,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.03,0.03,0.0076,0.059,0.059,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20190000,-0.29,0.012,-0.0059,0.96,0.011,0.0071,0.023,0.0077,0.0057,0.016,-0.0014,-0.006,2.6e-05,0.0078,0.0033,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.03,0.03,0.0076,0.059,0.059,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
205 20290000,-0.29,0.012,-0.0059,0.96,0.014,0.009,0.023,0.009,0.0064,0.017,-0.0014,-0.006,2.4e-05,0.0079,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.033,0.033,0.0076,0.066,0.066,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20290000,-0.29,0.012,-0.0059,0.96,0.014,0.009,0.023,0.009,0.0064,0.017,-0.0014,-0.006,2.6e-05,0.0079,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00045,0.00044,0.019,0.033,0.033,0.0076,0.066,0.066,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
206 20390000,-0.29,0.012,-0.0058,0.96,0.015,0.0077,0.023,0.0085,0.006,0.018,-0.0014,-0.006,2.4e-05,0.0082,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.031,0.031,0.0075,0.068,0.068,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20390000,-0.29,0.012,-0.0058,0.96,0.015,0.0077,0.023,0.0085,0.006,0.018,-0.0014,-0.006,2.6e-05,0.0082,0.0032,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.031,0.031,0.0075,0.068,0.068,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
207 20490000,-0.29,0.012,-0.0058,0.96,0.02,0.0097,0.023,0.01,0.0068,0.016,-0.0014,-0.006,2.4e-05,0.0084,0.003,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.034,0.034,0.0075,0.076,0.076,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20490000,-0.29,0.012,-0.0058,0.96,0.02,0.0097,0.023,0.01,0.0068,0.016,-0.0014,-0.006,2.6e-05,0.0084,0.003,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.034,0.034,0.0075,0.076,0.076,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
208 20590000,-0.29,0.012,-0.0058,0.96,0.018,0.01,0.023,0.009,0.0063,0.015,-0.0014,-0.006,2.4e-05,0.0088,0.0029,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.033,0.033,0.0074,0.078,0.078,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20590000,-0.29,0.012,-0.0058,0.96,0.018,0.01,0.023,0.009,0.0063,0.015,-0.0014,-0.006,2.6e-05,0.0088,0.0029,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.033,0.033,0.0074,0.078,0.078,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
209 20690000,-0.29,0.012,-0.0057,0.96,0.02,0.0093,0.023,0.011,0.0072,0.015,-0.0014,-0.006,2.4e-05,0.0089,0.0028,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.035,0.035,0.0075,0.086,0.086,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20690000,-0.29,0.012,-0.0057,0.96,0.02,0.0093,0.023,0.011,0.0072,0.015,-0.0014,-0.006,2.6e-05,0.0089,0.0028,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.035,0.035,0.0075,0.086,0.086,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
210 20790000,-0.29,0.012,-0.0052,0.96,0.02,0.0058,0.0084,0.0068,0.0047,0.014,-0.0014,-0.006,2.4e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.028,0.028,0.0074,0.067,0.067,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20790000,-0.29,0.012,-0.0052,0.96,0.02,0.0058,0.0084,0.0068,0.0047,0.014,-0.0014,-0.006,2.7e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.028,0.028,0.0074,0.067,0.067,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
211 20890000,-0.29,0.0066,0.0035,0.96,0.028,-0.0045,-0.11,0.0093,0.0048,0.0075,-0.0014,-0.006,2.4e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.031,0.031,0.0073,0.074,0.074,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20890000,-0.29,0.0066,0.0035,0.96,0.028,-0.0045,-0.11,0.0093,0.0048,0.0075,-0.0014,-0.006,2.7e-05,0.0095,0.0026,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.031,0.031,0.0073,0.074,0.074,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
212 20990000,-0.29,0.0029,0.0064,0.96,0.041,-0.021,-0.25,0.0064,0.0033,-0.0075,-0.0014,-0.006,2.4e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.027,0.0072,0.06,0.06,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 20990000,-0.29,0.0029,0.0064,0.96,0.041,-0.021,-0.25,0.0064,0.0033,-0.0075,-0.0014,-0.006,2.6e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.027,0.0072,0.06,0.06,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
213 21090000,-0.29,0.0034,0.0049,0.96,0.057,-0.033,-0.37,0.011,0.00058,-0.038,-0.0014,-0.006,2.4e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.029,0.029,0.0073,0.066,0.066,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21090000,-0.29,0.0034,0.0049,0.96,0.057,-0.033,-0.37,0.011,0.00058,-0.038,-0.0014,-0.006,2.6e-05,0.0097,0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.029,0.029,0.0073,0.066,0.066,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
214 21190000,-0.29,0.0054,0.0022,0.96,0.06,-0.037,-0.49,0.0074,0.0014,-0.075,-0.0013,-0.0059,2.3e-05,0.0099,0.0018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0072,0.055,0.055,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21190000,-0.29,0.0054,0.0022,0.96,0.06,-0.037,-0.49,0.0074,0.0014,-0.075,-0.0013,-0.0059,2.6e-05,0.0099,0.0018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0072,0.055,0.055,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
215 21290000,-0.29,0.007,0.00021,0.96,0.061,-0.04,-0.62,0.013,-0.0025,-0.13,-0.0013,-0.0059,2.3e-05,0.0099,0.0017,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.028,0.028,0.0071,0.061,0.061,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21290000,-0.29,0.007,0.00021,0.96,0.061,-0.04,-0.62,0.013,-0.0025,-0.13,-0.0013,-0.0059,2.6e-05,0.0099,0.0017,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.028,0.028,0.0071,0.061,0.061,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
216 21390000,-0.29,0.0079,-0.0014,0.96,0.051,-0.03,-0.75,0.0095,0.0035,-0.2,-0.0013,-0.0059,2.1e-05,0.01,-8.3e-05,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.027,0.028,0.0071,0.063,0.063,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21390000,-0.29,0.0079,-0.0014,0.96,0.051,-0.03,-0.75,0.0095,0.0035,-0.2,-0.0013,-0.0059,2.4e-05,0.01,-8.2e-05,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.027,0.028,0.0071,0.063,0.063,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
217 21490000,-0.29,0.0084,-0.0022,0.96,0.046,-0.028,-0.89,0.014,0.0006,-0.28,-0.0013,-0.0059,2.1e-05,0.01,-0.00018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.03,0.03,0.0071,0.07,0.07,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21490000,-0.29,0.0084,-0.0022,0.96,0.046,-0.028,-0.89,0.014,0.00059,-0.28,-0.0013,-0.0059,2.4e-05,0.01,-0.00018,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.03,0.03,0.0071,0.07,0.07,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
218 21590000,-0.29,0.0086,-0.0029,0.96,0.03,-0.018,-1,0.0069,0.0087,-0.37,-0.0012,-0.0059,1.9e-05,0.01,-0.0022,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.029,0.029,0.007,0.072,0.072,0.034,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21590000,-0.29,0.0086,-0.0029,0.96,0.03,-0.018,-1,0.0069,0.0087,-0.37,-0.0012,-0.0059,2.3e-05,0.01,-0.0022,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.029,0.029,0.007,0.072,0.072,0.034,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
219 21690000,-0.29,0.0085,-0.0033,0.96,0.027,-0.013,-1.1,0.0097,0.0072,-0.49,-0.0012,-0.0059,1.9e-05,0.011,-0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.032,0.032,0.007,0.08,0.08,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21690000,-0.29,0.0085,-0.0033,0.96,0.027,-0.013,-1.1,0.0097,0.0071,-0.49,-0.0012,-0.0059,2.3e-05,0.011,-0.0024,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.032,0.032,0.007,0.08,0.08,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
220 21790000,-0.29,0.0087,-0.0038,0.96,0.018,-0.0011,-1.3,0.005,0.017,-0.61,-0.0011,-0.0059,1.8e-05,0.011,-0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00038,0.019,0.031,0.031,0.0069,0.081,0.081,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21790000,-0.29,0.0087,-0.0038,0.96,0.018,-0.0011,-1.3,0.005,0.017,-0.61,-0.0011,-0.0059,2.2e-05,0.011,-0.0042,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00038,0.019,0.031,0.031,0.0069,0.081,0.081,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
221 21890000,-0.29,0.0088,-0.0041,0.96,0.013,0.0032,-1.4,0.0066,0.017,-0.75,-0.0011,-0.0059,1.8e-05,0.011,-0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.033,0.034,0.0069,0.09,0.09,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21890000,-0.29,0.0088,-0.0041,0.96,0.013,0.0032,-1.4,0.0066,0.017,-0.75,-0.0011,-0.0059,2.2e-05,0.011,-0.0044,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.033,0.034,0.0069,0.09,0.09,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
222 21990000,-0.29,0.0094,-0.005,0.96,0.002,0.014,-1.4,-0.0045,0.027,-0.89,-0.0011,-0.0059,1.6e-05,0.011,-0.0063,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.032,0.032,0.0068,0.091,0.091,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 21990000,-0.29,0.0094,-0.005,0.96,0.002,0.014,-1.4,-0.0045,0.027,-0.89,-0.0011,-0.0059,2.1e-05,0.011,-0.0063,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.032,0.032,0.0068,0.091,0.091,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
223 22090000,-0.29,0.01,-0.0056,0.96,-0.0017,0.018,-1.4,-0.0045,0.029,-1,-0.0011,-0.0059,1.6e-05,0.011,-0.0064,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0068,0.1,0.1,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22090000,-0.29,0.01,-0.0056,0.96,-0.0017,0.018,-1.4,-0.0045,0.029,-1,-0.0011,-0.0059,2.1e-05,0.011,-0.0064,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0068,0.1,0.1,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
224 22190000,-0.29,0.011,-0.0062,0.96,-0.014,0.026,-1.4,-0.014,0.039,-1.2,-0.0011,-0.0059,1.5e-05,0.012,-0.0077,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0067,0.1,0.1,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22190000,-0.29,0.011,-0.0062,0.96,-0.014,0.026,-1.4,-0.014,0.039,-1.2,-0.0011,-0.0059,2e-05,0.012,-0.0077,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0067,0.1,0.1,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
225 22290000,-0.29,0.011,-0.0069,0.96,-0.021,0.031,-1.4,-0.015,0.041,-1.3,-0.0011,-0.0059,1.5e-05,0.012,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0067,0.11,0.11,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22290000,-0.29,0.011,-0.0069,0.96,-0.021,0.031,-1.4,-0.015,0.041,-1.3,-0.0011,-0.0059,2e-05,0.012,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0067,0.11,0.11,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
226 22390000,-0.29,0.011,-0.0072,0.96,-0.031,0.036,-1.4,-0.025,0.044,-1.5,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0066,0.11,0.11,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22390000,-0.29,0.011,-0.0072,0.96,-0.031,0.036,-1.4,-0.025,0.044,-1.5,-0.0011,-0.0059,2e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0066,0.11,0.11,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
227 22490000,-0.29,0.012,-0.0073,0.96,-0.037,0.043,-1.4,-0.028,0.048,-1.6,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22490000,-0.29,0.012,-0.0073,0.96,-0.037,0.043,-1.4,-0.028,0.048,-1.6,-0.0011,-0.0059,2e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
228 22590000,-0.29,0.012,-0.0071,0.96,-0.042,0.048,-1.4,-0.029,0.052,-1.7,-0.0011,-0.0059,1.5e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.032,0.032,0.0065,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22590000,-0.29,0.012,-0.0071,0.96,-0.042,0.048,-1.4,-0.029,0.052,-1.7,-0.0011,-0.0059,2e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.032,0.032,0.0065,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
229 22690000,-0.29,0.013,-0.007,0.96,-0.046,0.053,-1.4,-0.033,0.057,-1.9,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.13,0.13,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22690000,-0.29,0.013,-0.007,0.96,-0.046,0.053,-1.4,-0.033,0.057,-1.9,-0.0011,-0.0059,2e-05,0.013,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.13,0.13,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
230 22790000,-0.29,0.013,-0.0069,0.96,-0.052,0.056,-1.4,-0.039,0.058,-2,-0.0011,-0.0059,1.5e-05,0.013,-0.0081,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0065,0.13,0.13,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22790000,-0.29,0.013,-0.0069,0.96,-0.052,0.056,-1.4,-0.039,0.058,-2,-0.0011,-0.0059,2e-05,0.013,-0.0081,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0065,0.13,0.13,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
231 22890000,-0.29,0.013,-0.0071,0.96,-0.058,0.062,-1.4,-0.045,0.064,-2.2,-0.0011,-0.0059,1.5e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0065,0.14,0.14,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22890000,-0.29,0.013,-0.0071,0.96,-0.058,0.062,-1.4,-0.045,0.064,-2.2,-0.0011,-0.0059,2e-05,0.013,-0.0082,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0065,0.14,0.14,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
232 22990000,-0.29,0.014,-0.0069,0.96,-0.062,0.06,-1.4,-0.049,0.061,-2.3,-0.0011,-0.0059,1.5e-05,0.014,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0064,0.14,0.14,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 22990000,-0.29,0.014,-0.0069,0.96,-0.062,0.06,-1.4,-0.049,0.061,-2.3,-0.0011,-0.0059,2.1e-05,0.014,-0.0078,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0064,0.14,0.14,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
233 23090000,-0.29,0.014,-0.0069,0.96,-0.068,0.064,-1.4,-0.055,0.067,-2.5,-0.0011,-0.0059,1.5e-05,0.014,-0.0079,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0064,0.15,0.15,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23090000,-0.29,0.014,-0.0069,0.96,-0.068,0.064,-1.4,-0.055,0.067,-2.5,-0.0011,-0.0059,2.1e-05,0.014,-0.0079,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0064,0.15,0.15,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
234 23190000,-0.29,0.014,-0.0067,0.96,-0.069,0.056,-1.4,-0.054,0.059,-2.6,-0.0011,-0.0059,1.5e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.032,0.032,0.0063,0.15,0.15,0.033,9.1e-07,9.1e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23190000,-0.29,0.014,-0.0067,0.96,-0.069,0.056,-1.4,-0.054,0.059,-2.6,-0.0011,-0.0059,2.1e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.032,0.032,0.0063,0.15,0.15,0.033,9.1e-07,9.1e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
235 23290000,-0.29,0.014,-0.0071,0.96,-0.075,0.061,-1.4,-0.061,0.065,-2.8,-0.0011,-0.0059,1.5e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0063,0.16,0.16,0.034,9.1e-07,9.1e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23290000,-0.29,0.014,-0.0071,0.96,-0.075,0.061,-1.4,-0.061,0.065,-2.8,-0.0011,-0.0059,2.1e-05,0.014,-0.0071,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.034,0.034,0.0063,0.16,0.16,0.034,9.1e-07,9.1e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
236 23390000,-0.29,0.014,-0.007,0.96,-0.073,0.061,-1.4,-0.054,0.064,-2.9,-0.0011,-0.0059,1.6e-05,0.014,-0.0065,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.032,0.032,0.0063,0.16,0.16,0.033,8.6e-07,8.6e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23390000,-0.29,0.014,-0.007,0.96,-0.073,0.061,-1.4,-0.054,0.064,-2.9,-0.0011,-0.0059,2.2e-05,0.014,-0.0065,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.032,0.032,0.0063,0.16,0.16,0.033,8.6e-07,8.6e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
237 23490000,-0.29,0.015,-0.0071,0.96,-0.078,0.063,-1.4,-0.061,0.07,-3,-0.0011,-0.0059,1.6e-05,0.014,-0.0066,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.033,0.033,0.0063,0.17,0.17,0.033,8.6e-07,8.6e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23490000,-0.29,0.015,-0.0071,0.96,-0.078,0.063,-1.4,-0.061,0.07,-3,-0.0011,-0.0059,2.2e-05,0.014,-0.0066,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.033,0.033,0.0063,0.17,0.17,0.033,8.6e-07,8.6e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
238 23590000,-0.29,0.015,-0.0071,0.96,-0.077,0.054,-1.4,-0.056,0.057,-3.2,-0.0012,-0.0059,1.7e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0062,0.17,0.17,0.033,8.2e-07,8.2e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23590000,-0.29,0.015,-0.0071,0.96,-0.077,0.054,-1.4,-0.056,0.057,-3.2,-0.0012,-0.0059,2.2e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0062,0.17,0.17,0.033,8.2e-07,8.2e-07,4.7e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
239 23690000,-0.29,0.015,-0.0077,0.96,-0.076,0.057,-1.3,-0.063,0.063,-3.3,-0.0012,-0.0059,1.7e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.033,0.033,0.0062,0.18,0.18,0.033,8.2e-07,8.2e-07,4.7e-06,0.03,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23690000,-0.29,0.015,-0.0077,0.96,-0.076,0.057,-1.3,-0.063,0.063,-3.3,-0.0012,-0.0059,2.2e-05,0.014,-0.0058,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.033,0.033,0.0062,0.18,0.18,0.033,8.2e-07,8.2e-07,4.7e-06,0.03,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
240 23790000,-0.29,0.018,-0.0092,0.96,-0.06,0.053,-0.95,-0.05,0.057,-3.4,-0.0012,-0.0059,1.7e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.03,0.03,0.0061,0.18,0.18,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23790000,-0.29,0.018,-0.0092,0.96,-0.06,0.053,-0.95,-0.05,0.057,-3.4,-0.0012,-0.0059,2.3e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.03,0.03,0.0061,0.18,0.18,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
241 23890000,-0.29,0.023,-0.012,0.96,-0.056,0.054,-0.52,-0.056,0.062,-3.5,-0.0012,-0.0059,1.7e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.031,0.031,0.0061,0.19,0.19,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23890000,-0.29,0.023,-0.012,0.96,-0.056,0.054,-0.52,-0.056,0.062,-3.5,-0.0012,-0.0059,2.3e-05,0.014,-0.0053,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.031,0.031,0.0061,0.19,0.19,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
242 23990000,-0.29,0.025,-0.014,0.96,-0.049,0.05,-0.13,-0.044,0.055,-3.6,-0.0012,-0.0059,1.8e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.029,0.029,0.0061,0.19,0.19,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 23990000,-0.29,0.025,-0.014,0.96,-0.049,0.05,-0.13,-0.044,0.055,-3.6,-0.0012,-0.0059,2.3e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.029,0.029,0.0061,0.19,0.19,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
243 24090000,-0.29,0.024,-0.013,0.96,-0.057,0.057,0.099,-0.049,0.06,-3.6,-0.0012,-0.0059,1.8e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.03,0.03,0.0061,0.2,0.2,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24090000,-0.29,0.024,-0.013,0.96,-0.057,0.057,0.099,-0.049,0.06,-3.6,-0.0012,-0.0059,2.3e-05,0.015,-0.0059,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.03,0.03,0.0061,0.2,0.2,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
244 24190000,-0.29,0.02,-0.011,0.96,-0.06,0.052,0.088,-0.034,0.045,-3.6,-0.0013,-0.0059,1.8e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.029,0.029,0.006,0.2,0.2,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24190000,-0.29,0.02,-0.011,0.96,-0.06,0.052,0.088,-0.034,0.045,-3.6,-0.0013,-0.0059,2.4e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.029,0.029,0.006,0.2,0.2,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
245 24290000,-0.29,0.016,-0.0089,0.96,-0.064,0.054,0.066,-0.04,0.05,-3.6,-0.0013,-0.0059,1.8e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0061,0.21,0.21,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24290000,-0.29,0.016,-0.0089,0.96,-0.064,0.054,0.066,-0.04,0.05,-3.6,-0.0013,-0.0059,2.4e-05,0.016,-0.0073,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0061,0.21,0.21,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
246 24390000,-0.29,0.015,-0.0081,0.96,-0.045,0.048,0.083,-0.019,0.04,-3.6,-0.0013,-0.0059,1.9e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.21,0.21,0.033,7e-07,6.9e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24390000,-0.29,0.015,-0.0081,0.96,-0.045,0.048,0.083,-0.019,0.04,-3.6,-0.0013,-0.0059,2.5e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.21,0.21,0.033,7e-07,6.9e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
247 24490000,-0.29,0.015,-0.0084,0.96,-0.04,0.046,0.08,-0.023,0.045,-3.6,-0.0013,-0.0059,1.9e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.006,0.22,0.22,0.033,7e-07,7e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24490000,-0.29,0.015,-0.0084,0.96,-0.04,0.046,0.08,-0.023,0.045,-3.6,-0.0013,-0.0059,2.5e-05,0.016,-0.0083,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.006,0.22,0.22,0.033,7e-07,7e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
248 24590000,-0.29,0.015,-0.009,0.96,-0.026,0.043,0.076,-0.0023,0.038,-3.6,-0.0014,-0.006,2e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.22,0.22,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24590000,-0.29,0.015,-0.009,0.96,-0.026,0.043,0.076,-0.0023,0.038,-3.6,-0.0014,-0.006,2.6e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.22,0.22,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
249 24690000,-0.29,0.015,-0.0095,0.96,-0.023,0.043,0.075,-0.0048,0.042,-3.5,-0.0014,-0.006,2e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.006,0.23,0.23,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24690000,-0.29,0.015,-0.0095,0.96,-0.023,0.043,0.075,-0.0048,0.042,-3.5,-0.0014,-0.006,2.6e-05,0.017,-0.009,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.006,0.23,0.23,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
250 24790000,-0.29,0.015,-0.0096,0.96,-0.015,0.04,0.067,0.0088,0.033,-3.5,-0.0014,-0.006,2e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24790000,-0.29,0.015,-0.0096,0.96,-0.015,0.04,0.067,0.0088,0.033,-3.5,-0.0014,-0.006,2.7e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
251 24890000,-0.29,0.014,-0.0095,0.96,-0.013,0.044,0.057,0.0074,0.038,-3.5,-0.0014,-0.006,2e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.24,0.24,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24890000,-0.29,0.014,-0.0095,0.96,-0.013,0.044,0.057,0.0074,0.038,-3.5,-0.0014,-0.006,2.7e-05,0.017,-0.0096,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.0059,0.24,0.24,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
252 24990000,-0.29,0.014,-0.0093,0.96,-0.00021,0.044,0.049,0.022,0.031,-3.5,-0.0014,-0.006,2.1e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 24990000,-0.29,0.014,-0.0093,0.96,-0.00021,0.044,0.049,0.022,0.031,-3.5,-0.0014,-0.006,2.8e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
253 25090000,-0.29,0.014,-0.0096,0.96,0.0044,0.044,0.047,0.023,0.035,-3.5,-0.0014,-0.006,2.1e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.25,0.25,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25090000,-0.29,0.014,-0.0096,0.96,0.0044,0.044,0.047,0.023,0.035,-3.5,-0.0014,-0.006,2.8e-05,0.017,-0.01,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.25,0.25,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
254 25190000,-0.29,0.014,-0.0098,0.96,0.015,0.038,0.047,0.037,0.023,-3.5,-0.0014,-0.006,2.2e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0058,0.24,0.24,0.032,6e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25190000,-0.29,0.014,-0.0098,0.96,0.015,0.038,0.047,0.037,0.023,-3.5,-0.0014,-0.006,2.9e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0058,0.24,0.24,0.032,6e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
255 25290000,-0.29,0.013,-0.01,0.96,0.02,0.041,0.042,0.039,0.027,-3.5,-0.0014,-0.006,2.2e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0058,0.26,0.26,0.032,6.1e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25290000,-0.29,0.013,-0.01,0.96,0.02,0.041,0.042,0.039,0.027,-3.5,-0.0014,-0.006,2.9e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0058,0.26,0.26,0.032,6.1e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
256 25390000,-0.29,0.013,-0.01,0.96,0.028,0.039,0.041,0.046,0.021,-3.5,-0.0014,-0.006,2.3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.25,0.25,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25390000,-0.29,0.013,-0.01,0.96,0.028,0.039,0.041,0.046,0.021,-3.5,-0.0014,-0.006,3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.25,0.25,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
257 25490000,-0.29,0.013,-0.01,0.96,0.034,0.04,0.04,0.05,0.025,-3.5,-0.0014,-0.006,2.3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.27,0.27,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25490000,-0.29,0.013,-0.01,0.96,0.034,0.04,0.04,0.05,0.025,-3.5,-0.0014,-0.006,3e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.27,0.27,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
258 25590000,-0.29,0.012,-0.01,0.96,0.039,0.034,0.041,0.054,0.0079,-3.5,-0.0015,-0.006,2.4e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.26,0.26,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25590000,-0.29,0.012,-0.01,0.96,0.039,0.034,0.041,0.054,0.0079,-3.5,-0.0014,-0.006,3.1e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.26,0.26,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
259 25690000,-0.29,0.012,-0.0098,0.96,0.041,0.033,0.031,0.058,0.011,-3.5,-0.0015,-0.006,2.4e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.28,0.28,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25690000,-0.29,0.012,-0.0098,0.96,0.041,0.033,0.031,0.058,0.011,-3.5,-0.0014,-0.006,3.1e-05,0.018,-0.011,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.28,0.28,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
260 25790000,-0.29,0.011,-0.0096,0.96,0.05,0.027,0.03,0.062,0.00075,-3.5,-0.0015,-0.006,2.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.27,0.27,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25790000,-0.29,0.011,-0.0096,0.96,0.05,0.027,0.03,0.062,0.00075,-3.5,-0.0015,-0.006,3.2e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0057,0.27,0.27,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
261 25890000,-0.29,0.011,-0.0097,0.96,0.057,0.027,0.033,0.068,0.0034,-3.5,-0.0015,-0.006,2.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.28,0.28,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25890000,-0.29,0.011,-0.0097,0.96,0.057,0.027,0.033,0.068,0.0034,-3.5,-0.0015,-0.006,3.2e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.28,0.28,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
262 25990000,-0.29,0.012,-0.0097,0.96,0.056,0.02,0.026,0.059,-0.0086,-3.5,-0.0015,-0.0059,2.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.28,0.28,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 25990000,-0.29,0.012,-0.0097,0.96,0.056,0.02,0.026,0.059,-0.0086,-3.5,-0.0015,-0.0059,3.3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.28,0.28,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
263 26090000,-0.29,0.012,-0.0094,0.96,0.062,0.021,0.025,0.065,-0.0065,-3.5,-0.0015,-0.0059,2.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.29,0.29,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26090000,-0.29,0.012,-0.0094,0.96,0.062,0.021,0.025,0.065,-0.0065,-3.5,-0.0015,-0.0059,3.3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.29,0.29,0.032,5.4e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
264 26190000,-0.29,0.012,-0.0093,0.96,0.063,0.011,0.02,0.063,-0.023,-3.5,-0.0015,-0.0059,2.8e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0056,0.29,0.29,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26190000,-0.29,0.012,-0.0093,0.96,0.063,0.011,0.02,0.063,-0.023,-3.5,-0.0015,-0.0059,3.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.29,0.29,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
265 26290000,-0.29,0.012,-0.0092,0.96,0.065,0.01,0.015,0.069,-0.022,-3.5,-0.0015,-0.0059,2.8e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.03,0.0057,0.3,0.3,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26290000,-0.29,0.012,-0.0092,0.96,0.065,0.01,0.015,0.069,-0.022,-3.5,-0.0015,-0.0059,3.5e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.03,0.0057,0.3,0.3,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
266 26390000,-0.29,0.012,-0.0086,0.96,0.06,0.00029,0.019,0.056,-0.037,-3.5,-0.0015,-0.0059,2.9e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0056,0.3,0.3,0.032,5e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26390000,-0.29,0.012,-0.0086,0.96,0.06,0.00028,0.019,0.056,-0.037,-3.5,-0.0015,-0.0059,3.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.3,0.3,0.032,5.1e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
267 26490000,-0.29,0.012,-0.0084,0.96,0.064,-0.0022,0.028,0.062,-0.037,-3.5,-0.0015,-0.0059,2.9e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.029,0.0056,0.31,0.31,0.032,5.1e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26490000,-0.29,0.012,-0.0084,0.96,0.064,-0.0023,0.028,0.062,-0.037,-3.5,-0.0015,-0.0059,3.6e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.31,0.31,0.032,5.1e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
268 26590000,-0.29,0.013,-0.0078,0.96,0.06,-0.013,0.028,0.057,-0.05,-3.5,-0.0015,-0.0059,3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.31,0.31,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26590000,-0.29,0.013,-0.0078,0.96,0.06,-0.013,0.028,0.057,-0.05,-3.5,-0.0015,-0.0059,3.7e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.31,0.31,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
269 26690000,-0.29,0.012,-0.0077,0.96,0.063,-0.018,0.027,0.063,-0.052,-3.5,-0.0015,-0.0059,3e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.32,0.32,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26690000,-0.29,0.012,-0.0077,0.96,0.063,-0.018,0.027,0.063,-0.052,-3.5,-0.0015,-0.0059,3.7e-05,0.018,-0.012,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.32,0.32,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
270 26790000,-0.29,0.012,-0.0075,0.96,0.063,-0.025,0.026,0.056,-0.065,-3.5,-0.0015,-0.0059,3.1e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.028,0.0056,0.31,0.31,0.031,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26790000,-0.29,0.012,-0.0075,0.96,0.063,-0.025,0.026,0.056,-0.065,-3.5,-0.0015,-0.0059,3.8e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.028,0.0056,0.31,0.31,0.031,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
271 26890000,-0.29,0.012,-0.0069,0.96,0.069,-0.027,0.022,0.062,-0.067,-3.5,-0.0015,-0.0059,3.1e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.33,0.33,0.032,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26890000,-0.29,0.012,-0.0069,0.96,0.069,-0.027,0.022,0.062,-0.067,-3.5,-0.0015,-0.0059,3.8e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.33,0.33,0.032,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
272 26990000,-0.29,0.012,-0.0063,0.96,0.067,-0.034,0.021,0.051,-0.073,-3.5,-0.0015,-0.0058,3.2e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.32,0.32,0.031,4.7e-07,4.6e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 26990000,-0.29,0.012,-0.0063,0.96,0.067,-0.034,0.021,0.051,-0.073,-3.5,-0.0015,-0.0058,3.9e-05,0.018,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.32,0.32,0.031,4.7e-07,4.6e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
273 27090000,-0.29,0.013,-0.0061,0.96,0.07,-0.041,0.024,0.058,-0.077,-3.5,-0.0015,-0.0058,3.1e-05,0.019,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.34,0.34,0.031,4.7e-07,4.7e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27090000,-0.29,0.013,-0.0061,0.96,0.07,-0.041,0.024,0.058,-0.077,-3.5,-0.0015,-0.0058,3.9e-05,0.019,-0.013,-0.13,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.34,0.34,0.031,4.7e-07,4.7e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
274 27190000,-0.29,0.013,-0.0062,0.96,0.068,-0.044,0.027,0.044,-0.079,-3.5,-0.0015,-0.0058,3.2e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.33,0.33,0.032,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27190000,-0.29,0.013,-0.0062,0.96,0.068,-0.044,0.027,0.044,-0.079,-3.5,-0.0015,-0.0058,4e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.33,0.33,0.032,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
275 27290000,-0.29,0.014,-0.0063,0.96,0.075,-0.049,0.14,0.051,-0.083,-3.5,-0.0015,-0.0058,3.2e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.028,0.029,0.0055,0.35,0.35,0.031,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27290000,-0.29,0.014,-0.0063,0.96,0.075,-0.049,0.14,0.051,-0.083,-3.5,-0.0015,-0.0058,4e-05,0.019,-0.013,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.028,0.029,0.0055,0.35,0.35,0.031,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
276 27390000,-0.29,0.016,-0.0075,0.96,0.071,-0.04,0.46,0.015,-0.029,-3.5,-0.0014,-0.0058,3.1e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0055,0.15,0.15,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27390000,-0.29,0.016,-0.0075,0.96,0.071,-0.04,0.46,0.015,-0.029,-3.5,-0.0014,-0.0058,3.9e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0055,0.15,0.15,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
277 27490000,-0.29,0.018,-0.0087,0.96,0.075,-0.045,0.78,0.022,-0.033,-3.5,-0.0014,-0.0058,3.1e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0055,0.16,0.16,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27490000,-0.29,0.018,-0.0087,0.96,0.075,-0.045,0.78,0.022,-0.033,-3.5,-0.0014,-0.0058,3.9e-05,0.019,-0.014,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0055,0.16,0.16,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
278 27590000,-0.29,0.017,-0.0088,0.96,0.063,-0.046,0.87,0.011,-0.022,-3.4,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27590000,-0.29,0.017,-0.0088,0.96,0.063,-0.046,0.87,0.011,-0.022,-3.4,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
279 27690000,-0.29,0.014,-0.0079,0.96,0.059,-0.043,0.78,0.017,-0.026,-3.3,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27690000,-0.29,0.014,-0.0079,0.96,0.059,-0.043,0.78,0.017,-0.026,-3.3,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
280 27790000,-0.29,0.013,-0.0067,0.96,0.053,-0.04,0.77,0.012,-0.02,-3.2,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.018,0.0054,0.076,0.076,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27790000,-0.29,0.013,-0.0067,0.96,0.053,-0.04,0.77,0.012,-0.02,-3.2,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.018,0.0054,0.076,0.076,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
281 27890000,-0.29,0.013,-0.0063,0.96,0.061,-0.046,0.81,0.018,-0.025,-3.2,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.08,0.08,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27890000,-0.29,0.013,-0.0063,0.96,0.061,-0.046,0.81,0.018,-0.025,-3.2,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.08,0.08,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
282 27990000,-0.29,0.013,-0.0068,0.96,0.06,-0.048,0.8,0.02,-0.027,-3.1,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0054,0.082,0.082,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 27990000,-0.29,0.013,-0.0068,0.96,0.06,-0.048,0.8,0.02,-0.027,-3.1,-0.0014,-0.0058,3.9e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0054,0.082,0.082,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
283 28090000,-0.29,0.013,-0.007,0.96,0.063,-0.048,0.8,0.027,-0.032,-3,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.02,0.02,0.0054,0.086,0.086,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28090000,-0.29,0.013,-0.007,0.96,0.063,-0.048,0.8,0.027,-0.032,-3,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0054,0.086,0.086,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
284 28190000,-0.29,0.014,-0.0064,0.96,0.059,-0.046,0.81,0.027,-0.035,-2.9,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0054,0.089,0.089,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28190000,-0.29,0.014,-0.0064,0.96,0.059,-0.046,0.81,0.027,-0.035,-2.9,-0.0014,-0.0058,4e-05,0.02,-0.015,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0054,0.089,0.089,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
285 28290000,-0.29,0.014,-0.0059,0.96,0.064,-0.049,0.81,0.033,-0.039,-2.9,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.093,0.093,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28290000,-0.29,0.014,-0.0059,0.96,0.064,-0.049,0.81,0.033,-0.039,-2.9,-0.0014,-0.0058,4e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.093,0.093,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
286 28390000,-0.29,0.014,-0.0059,0.96,0.064,-0.05,0.81,0.034,-0.04,-2.8,-0.0014,-0.0058,3e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.096,0.096,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28390000,-0.29,0.014,-0.0059,0.96,0.064,-0.05,0.81,0.034,-0.04,-2.8,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.096,0.096,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
287 28490000,-0.29,0.015,-0.0061,0.96,0.066,-0.054,0.81,0.04,-0.045,-2.7,-0.0014,-0.0058,3e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.022,0.022,0.0054,0.1,0.1,0.031,4.1e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28490000,-0.29,0.015,-0.0061,0.96,0.066,-0.054,0.81,0.04,-0.045,-2.7,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0054,0.1,0.1,0.031,4.1e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
288 28590000,-0.29,0.015,-0.0062,0.96,0.057,-0.053,0.81,0.039,-0.048,-2.6,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0054,0.1,0.1,0.031,4e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28590000,-0.29,0.015,-0.0062,0.96,0.057,-0.053,0.81,0.039,-0.048,-2.6,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.1,0.1,0.031,4e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
289 28690000,-0.29,0.014,-0.006,0.96,0.056,-0.054,0.81,0.045,-0.053,-2.6,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0054,0.11,0.11,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28690000,-0.29,0.014,-0.006,0.96,0.056,-0.054,0.81,0.045,-0.053,-2.6,-0.0014,-0.0058,3.9e-05,0.02,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0054,0.11,0.11,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290 28790000,-0.29,0.014,-0.0054,0.96,0.053,-0.052,0.81,0.045,-0.051,-2.5,-0.0014,-0.0058,2.9e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0053,0.11,0.11,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28790000,-0.29,0.014,-0.0054,0.96,0.053,-0.052,0.81,0.045,-0.051,-2.5,-0.0014,-0.0058,3.8e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0053,0.11,0.11,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
291 28890000,-0.29,0.014,-0.0053,0.96,0.057,-0.053,0.81,0.05,-0.056,-2.4,-0.0014,-0.0058,2.9e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0054,0.12,0.12,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28890000,-0.29,0.014,-0.0053,0.96,0.057,-0.053,0.81,0.05,-0.056,-2.4,-0.0014,-0.0058,3.8e-05,0.021,-0.016,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0054,0.12,0.12,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
292 28990000,-0.29,0.014,-0.005,0.96,0.053,-0.051,0.81,0.05,-0.055,-2.3,-0.0013,-0.0058,2.9e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.12,0.12,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 28990000,-0.29,0.014,-0.005,0.96,0.053,-0.051,0.81,0.05,-0.055,-2.3,-0.0013,-0.0058,3.8e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.12,0.12,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
293 29090000,-0.29,0.014,-0.0049,0.96,0.056,-0.052,0.81,0.055,-0.06,-2.3,-0.0013,-0.0058,2.9e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.13,0.13,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29090000,-0.29,0.014,-0.0049,0.96,0.056,-0.052,0.81,0.055,-0.061,-2.3,-0.0013,-0.0058,3.8e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.024,0.024,0.0053,0.13,0.13,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
294 29190000,-0.29,0.014,-0.0048,0.96,0.055,-0.05,0.8,0.056,-0.058,-2.2,-0.0013,-0.0058,2.8e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.13,0.13,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29190000,-0.29,0.014,-0.0048,0.96,0.055,-0.05,0.8,0.056,-0.058,-2.2,-0.0013,-0.0058,3.7e-05,0.021,-0.017,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.13,0.13,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
295 29290000,-0.29,0.014,-0.0051,0.96,0.057,-0.056,0.81,0.061,-0.064,-2.1,-0.0013,-0.0058,2.8e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.14,0.14,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29290000,-0.29,0.014,-0.0051,0.96,0.057,-0.056,0.81,0.061,-0.064,-2.1,-0.0013,-0.0058,3.7e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0053,0.14,0.14,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
296 29390000,-0.29,0.014,-0.0056,0.96,0.053,-0.052,0.81,0.058,-0.059,-2,-0.0013,-0.0058,2.7e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.14,0.14,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29390000,-0.29,0.014,-0.0056,0.96,0.053,-0.052,0.81,0.058,-0.059,-2,-0.0013,-0.0058,3.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.024,0.024,0.0053,0.14,0.14,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
297 29490000,-0.29,0.014,-0.0056,0.96,0.055,-0.052,0.81,0.064,-0.064,-2,-0.0013,-0.0058,2.7e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.15,0.15,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29490000,-0.29,0.014,-0.0056,0.96,0.055,-0.052,0.81,0.064,-0.064,-2,-0.0013,-0.0058,3.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.15,0.15,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
298 29590000,-0.29,0.013,-0.0056,0.96,0.051,-0.049,0.81,0.06,-0.061,-1.9,-0.0013,-0.0058,2.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.15,0.15,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29590000,-0.29,0.013,-0.0056,0.96,0.051,-0.049,0.81,0.06,-0.061,-1.9,-0.0013,-0.0058,3.5e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.15,0.15,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
299 29690000,-0.29,0.013,-0.0056,0.96,0.054,-0.047,0.81,0.065,-0.066,-1.8,-0.0013,-0.0058,2.6e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.16,0.16,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29690000,-0.29,0.013,-0.0056,0.96,0.054,-0.047,0.81,0.065,-0.066,-1.8,-0.0013,-0.0058,3.5e-05,0.022,-0.018,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.16,0.16,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
300 29790000,-0.29,0.014,-0.0054,0.96,0.051,-0.04,0.8,0.062,-0.061,-1.7,-0.0013,-0.0058,2.5e-05,0.022,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.16,0.16,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29790000,-0.29,0.014,-0.0054,0.96,0.051,-0.04,0.8,0.062,-0.061,-1.7,-0.0013,-0.0058,3.5e-05,0.022,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.16,0.16,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
301 29890000,-0.29,0.014,-0.0049,0.96,0.051,-0.041,0.8,0.067,-0.065,-1.7,-0.0013,-0.0058,2.5e-05,0.023,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.17,0.17,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29890000,-0.29,0.014,-0.0049,0.96,0.051,-0.041,0.8,0.067,-0.065,-1.7,-0.0013,-0.0058,3.5e-05,0.023,-0.019,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.17,0.17,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
302 29990000,-0.29,0.014,-0.005,0.96,0.046,-0.038,0.8,0.061,-0.063,-1.6,-0.0013,-0.0058,2.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.17,0.17,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 29990000,-0.29,0.014,-0.005,0.96,0.046,-0.038,0.8,0.061,-0.064,-1.6,-0.0013,-0.0058,3.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0053,0.17,0.17,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
303 30090000,-0.29,0.014,-0.0051,0.96,0.046,-0.039,0.8,0.065,-0.067,-1.5,-0.0013,-0.0058,2.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.18,0.18,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30090000,-0.29,0.014,-0.0051,0.96,0.046,-0.039,0.8,0.065,-0.067,-1.5,-0.0013,-0.0058,3.5e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.18,0.18,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
304 30190000,-0.29,0.014,-0.0052,0.96,0.041,-0.033,0.8,0.06,-0.058,-1.5,-0.0013,-0.0058,2.4e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.18,0.18,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30190000,-0.29,0.014,-0.0052,0.96,0.041,-0.033,0.8,0.06,-0.058,-1.5,-0.0013,-0.0058,3.4e-05,0.023,-0.02,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.18,0.18,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
305 30290000,-0.29,0.014,-0.0052,0.96,0.039,-0.033,0.8,0.064,-0.062,-1.4,-0.0013,-0.0058,2.3e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.19,0.19,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30290000,-0.29,0.014,-0.0052,0.96,0.039,-0.033,0.8,0.064,-0.062,-1.4,-0.0013,-0.0058,3.4e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.19,0.19,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
306 30390000,-0.29,0.014,-0.0052,0.96,0.036,-0.026,0.79,0.062,-0.055,-1.3,-0.0012,-0.0058,2.2e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.19,0.19,0.03,3.4e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30390000,-0.29,0.014,-0.0052,0.96,0.036,-0.026,0.79,0.062,-0.055,-1.3,-0.0012,-0.0058,3.3e-05,0.024,-0.021,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.19,0.19,0.03,3.4e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
307 30490000,-0.29,0.014,-0.0052,0.96,0.038,-0.025,0.8,0.066,-0.057,-1.2,-0.0012,-0.0058,2.2e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.2,0.2,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30490000,-0.29,0.014,-0.0052,0.96,0.038,-0.025,0.8,0.066,-0.057,-1.2,-0.0012,-0.0058,3.3e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.2,0.2,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
308 30590000,-0.29,0.015,-0.0055,0.96,0.037,-0.023,0.8,0.062,-0.053,-1.2,-0.0012,-0.0058,2.2e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.2,0.2,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30590000,-0.29,0.015,-0.0055,0.96,0.037,-0.023,0.8,0.062,-0.053,-1.2,-0.0012,-0.0058,3.3e-05,0.024,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.2,0.2,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
309 30690000,-0.29,0.015,-0.0059,0.96,0.034,-0.022,0.8,0.065,-0.055,-1.1,-0.0012,-0.0058,2.2e-05,0.025,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.21,0.21,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30690000,-0.29,0.015,-0.0059,0.96,0.034,-0.022,0.8,0.065,-0.055,-1.1,-0.0012,-0.0058,3.3e-05,0.025,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.21,0.21,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
310 30790000,-0.29,0.014,-0.0057,0.96,0.027,-0.012,0.79,0.058,-0.042,-1,-0.0012,-0.0058,2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.21,0.21,0.03,3.3e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30790000,-0.29,0.014,-0.0057,0.96,0.027,-0.012,0.79,0.058,-0.042,-1,-0.0012,-0.0058,3.2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.21,0.21,0.03,3.3e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
311 30890000,-0.29,0.014,-0.0051,0.96,0.026,-0.0084,0.79,0.06,-0.043,-0.95,-0.0012,-0.0058,2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.22,0.22,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30890000,-0.29,0.014,-0.0051,0.96,0.026,-0.0084,0.79,0.06,-0.043,-0.95,-0.0012,-0.0058,3.2e-05,0.025,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.026,0.026,0.0052,0.22,0.22,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
312 30990000,-0.29,0.014,-0.0052,0.96,0.023,-0.007,0.79,0.057,-0.042,-0.88,-0.0012,-0.0058,2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.22,0.22,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 30990000,-0.29,0.014,-0.0052,0.96,0.023,-0.007,0.79,0.057,-0.042,-0.88,-0.0012,-0.0058,3.2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.22,0.22,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
313 31090000,-0.29,0.014,-0.0054,0.96,0.021,-0.006,0.79,0.059,-0.043,-0.81,-0.0012,-0.0058,2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.23,0.23,0.031,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31090000,-0.29,0.014,-0.0054,0.96,0.021,-0.006,0.79,0.059,-0.043,-0.81,-0.0012,-0.0058,3.2e-05,0.026,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.026,0.026,0.0052,0.23,0.23,0.031,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
314 31190000,-0.29,0.014,-0.0055,0.96,0.019,-0.0017,0.8,0.055,-0.038,-0.74,-0.0012,-0.0058,1.9e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.23,0.23,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31190000,-0.29,0.014,-0.0055,0.96,0.019,-0.0017,0.8,0.055,-0.038,-0.74,-0.0012,-0.0058,3.1e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.23,0.23,0.03,3.2e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
315 31290000,-0.29,0.015,-0.0058,0.96,0.016,0.00067,0.8,0.057,-0.038,-0.67,-0.0012,-0.0058,1.9e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.24,0.24,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31290000,-0.29,0.015,-0.0058,0.96,0.016,0.00066,0.8,0.057,-0.038,-0.67,-0.0012,-0.0058,3.1e-05,0.026,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.24,0.24,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
316 31390000,-0.29,0.014,-0.0056,0.96,0.011,0.0044,0.8,0.05,-0.036,-0.59,-0.0012,-0.0058,1.9e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.24,0.24,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31390000,-0.29,0.014,-0.0056,0.96,0.011,0.0044,0.8,0.05,-0.036,-0.59,-0.0012,-0.0058,3.1e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.24,0.24,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
317 31490000,-0.29,0.015,-0.0053,0.96,0.0098,0.0074,0.8,0.051,-0.035,-0.52,-0.0012,-0.0058,1.9e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31490000,-0.29,0.015,-0.0053,0.96,0.0098,0.0074,0.8,0.051,-0.035,-0.52,-0.0012,-0.0058,3.1e-05,0.027,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
318 31590000,-0.29,0.015,-0.0051,0.96,0.011,0.0095,0.8,0.05,-0.031,-0.45,-0.0012,-0.0058,1.9e-05,0.027,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31590000,-0.29,0.015,-0.0051,0.96,0.011,0.0095,0.8,0.05,-0.031,-0.45,-0.0012,-0.0058,3.1e-05,0.027,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
319 31690000,-0.29,0.016,-0.005,0.96,0.013,0.011,0.8,0.051,-0.03,-0.38,-0.0012,-0.0058,1.9e-05,0.027,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.26,0.26,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31690000,-0.29,0.016,-0.005,0.96,0.013,0.011,0.8,0.051,-0.03,-0.38,-0.0012,-0.0058,3.1e-05,0.028,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.26,0.26,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
320 31790000,-0.29,0.016,-0.0052,0.96,0.008,0.017,0.8,0.049,-0.02,-0.31,-0.0012,-0.0058,1.8e-05,0.028,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.26,0.26,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31790000,-0.29,0.016,-0.0052,0.96,0.008,0.017,0.8,0.049,-0.02,-0.31,-0.0012,-0.0058,3e-05,0.028,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.26,0.26,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
321 31890000,-0.29,0.016,-0.005,0.96,0.0045,0.019,0.8,0.05,-0.018,-0.24,-0.0012,-0.0058,1.8e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.27,0.27,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31890000,-0.29,0.016,-0.005,0.96,0.0045,0.019,0.8,0.05,-0.018,-0.24,-0.0012,-0.0058,3e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.27,0.27,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
322 31990000,-0.29,0.015,-0.0053,0.96,0.0019,0.02,0.79,0.049,-0.014,-0.17,-0.0012,-0.0058,1.7e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.27,0.27,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 31990000,-0.29,0.015,-0.0053,0.96,0.0019,0.02,0.79,0.049,-0.014,-0.17,-0.0012,-0.0058,3e-05,0.028,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.27,0.27,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
323 32090000,-0.29,0.015,-0.0058,0.96,0.0019,0.024,0.8,0.05,-0.012,-0.097,-0.0012,-0.0058,1.7e-05,0.029,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32090000,-0.29,0.015,-0.0058,0.96,0.0019,0.024,0.8,0.05,-0.012,-0.097,-0.0012,-0.0058,3e-05,0.029,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
324 32190000,-0.29,0.015,-0.006,0.96,-0.00056,0.03,0.8,0.047,-0.003,-0.029,-0.0012,-0.0058,1.6e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32190000,-0.29,0.015,-0.006,0.96,-0.00056,0.03,0.8,0.047,-0.003,-0.029,-0.0012,-0.0058,3e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
325 32290000,-0.29,0.016,-0.0059,0.96,-0.0024,0.033,0.79,0.047,0.00024,0.041,-0.0012,-0.0058,1.6e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0051,0.29,0.29,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32290000,-0.29,0.016,-0.0059,0.96,-0.0024,0.033,0.79,0.047,0.00022,0.041,-0.0012,-0.0058,3e-05,0.029,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0051,0.29,0.29,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
326 32390000,-0.29,0.016,-0.006,0.96,-0.0051,0.034,0.79,0.045,0.0028,0.12,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.29,0.29,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32390000,-0.29,0.016,-0.006,0.96,-0.0051,0.034,0.79,0.045,0.0028,0.12,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.29,0.29,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
327 32490000,-0.29,0.014,-0.0091,0.96,-0.045,0.092,-0.078,0.041,0.011,0.12,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.027,0.027,0.0051,0.3,0.3,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32490000,-0.29,0.014,-0.0091,0.96,-0.045,0.092,-0.078,0.041,0.011,0.12,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.027,0.027,0.0051,0.3,0.3,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
328 32590000,-0.29,0.014,-0.009,0.96,-0.039,0.091,-0.08,0.048,0.003,0.1,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.026,0.026,0.0051,0.3,0.3,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32590000,-0.29,0.014,-0.009,0.96,-0.039,0.091,-0.08,0.048,0.003,0.1,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.3,0.3,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
329 32690000,-0.29,0.014,-0.009,0.96,-0.036,0.098,-0.082,0.044,0.013,0.087,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.027,0.027,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32690000,-0.29,0.014,-0.009,0.96,-0.036,0.098,-0.082,0.044,0.012,0.087,-0.0012,-0.0058,3e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.027,0.027,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
330 32790000,-0.29,0.014,-0.0089,0.96,-0.03,0.096,-0.083,0.049,0.0035,0.072,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32790000,-0.29,0.014,-0.0089,0.96,-0.03,0.096,-0.083,0.049,0.0035,0.072,-0.0012,-0.0058,3.1e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
331 32890000,-0.29,0.014,-0.0088,0.96,-0.03,0.1,-0.084,0.046,0.013,0.057,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.32,0.32,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32890000,-0.29,0.014,-0.0088,0.96,-0.03,0.1,-0.084,0.046,0.013,0.057,-0.0012,-0.0058,3.1e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.32,0.32,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
332 32990000,-0.29,0.014,-0.0087,0.96,-0.025,0.097,-0.084,0.05,-0.0012,0.043,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.31,0.31,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 32990000,-0.29,0.014,-0.0087,0.96,-0.025,0.097,-0.084,0.05,-0.0012,0.043,-0.0012,-0.0058,3.2e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.31,0.31,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
333 33090000,-0.29,0.014,-0.0086,0.96,-0.021,0.1,-0.081,0.048,0.0087,0.036,-0.0012,-0.0058,1.8e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.33,0.33,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33090000,-0.29,0.014,-0.0086,0.96,-0.021,0.1,-0.081,0.048,0.0087,0.036,-0.0012,-0.0058,3.2e-05,0.03,-0.028,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.33,0.33,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
334 33190000,-0.29,0.014,-0.0085,0.96,-0.016,0.097,-0.08,0.051,-0.0085,0.028,-0.0012,-0.0057,1.8e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.32,0.32,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33190000,-0.29,0.014,-0.0085,0.96,-0.016,0.097,-0.08,0.051,-0.0086,0.028,-0.0012,-0.0057,3.3e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.32,0.32,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
335 33290000,-0.29,0.014,-0.0085,0.96,-0.013,0.1,-0.079,0.05,0.0014,0.02,-0.0012,-0.0057,1.8e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.026,0.0051,0.34,0.34,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33290000,-0.29,0.014,-0.0085,0.96,-0.013,0.1,-0.079,0.05,0.0014,0.02,-0.0012,-0.0057,3.3e-05,0.03,-0.027,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.026,0.0051,0.34,0.34,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
336 33390000,-0.29,0.014,-0.0084,0.96,-0.008,0.096,-0.078,0.052,-0.0084,0.011,-0.0013,-0.0057,1.9e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.33,0.33,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33390000,-0.29,0.014,-0.0084,0.96,-0.0079,0.096,-0.078,0.052,-0.0084,0.011,-0.0013,-0.0057,3.4e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.33,0.33,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
337 33490000,-0.29,0.014,-0.0084,0.96,-0.0042,0.1,-0.077,0.051,0.0015,0.0017,-0.0013,-0.0057,1.9e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.35,0.35,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33490000,-0.29,0.014,-0.0084,0.96,-0.0042,0.1,-0.077,0.051,0.0014,0.0017,-0.0013,-0.0057,3.4e-05,0.031,-0.026,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.35,0.35,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
338 33590000,-0.29,0.014,-0.0082,0.96,-0.00096,0.097,-0.073,0.052,-0.013,-0.0062,-0.0013,-0.0057,2e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.025,0.025,0.0051,0.34,0.34,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33590000,-0.29,0.014,-0.0082,0.96,-0.00094,0.097,-0.073,0.052,-0.013,-0.0062,-0.0013,-0.0057,3.5e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.0051,0.34,0.34,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
339 33690000,-0.29,0.014,-0.0082,0.96,0.0028,0.1,-0.074,0.052,-0.0031,-0.014,-0.0013,-0.0057,2e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33690000,-0.29,0.014,-0.0082,0.96,0.0029,0.1,-0.074,0.052,-0.0031,-0.014,-0.0013,-0.0057,3.5e-05,0.031,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
340 33790000,-0.29,0.014,-0.0081,0.96,0.007,0.098,-0.069,0.051,-0.018,-0.021,-0.0013,-0.0057,2.1e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.0051,0.35,0.35,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33790000,-0.29,0.014,-0.0081,0.96,0.007,0.098,-0.069,0.051,-0.018,-0.021,-0.0013,-0.0057,3.6e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.0051,0.35,0.35,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
341 33890000,-0.29,0.014,-0.0081,0.96,0.011,0.1,-0.068,0.052,-0.0078,-0.028,-0.0013,-0.0057,2.1e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33890000,-0.29,0.014,-0.0081,0.96,0.011,0.1,-0.068,0.052,-0.0079,-0.028,-0.0013,-0.0057,3.6e-05,0.032,-0.025,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
342 33990000,-0.29,0.014,-0.008,0.96,0.014,0.098,-0.065,0.053,-0.018,-0.031,-0.0013,-0.0057,2.2e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.36,0.36,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 33990000,-0.29,0.014,-0.008,0.96,0.014,0.098,-0.065,0.053,-0.018,-0.031,-0.0013,-0.0057,3.7e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.36,0.36,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
343 34090000,-0.29,0.014,-0.008,0.96,0.017,0.1,-0.063,0.055,-0.0074,-0.036,-0.0013,-0.0057,2.3e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.37,0.37,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34090000,-0.29,0.014,-0.008,0.96,0.017,0.1,-0.063,0.055,-0.0075,-0.036,-0.0013,-0.0057,3.8e-05,0.032,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.37,0.37,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
344 34190000,-0.29,0.014,-0.0079,0.96,0.02,0.099,-0.061,0.052,-0.02,-0.039,-0.0013,-0.0057,2.3e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.37,0.37,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34190000,-0.29,0.014,-0.0079,0.96,0.02,0.099,-0.061,0.052,-0.02,-0.039,-0.0013,-0.0057,3.9e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.37,0.37,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
345 34290000,-0.29,0.014,-0.0078,0.96,0.02,0.1,-0.06,0.054,-0.0099,-0.045,-0.0013,-0.0057,2.3e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.38,0.38,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34290000,-0.29,0.014,-0.0078,0.96,0.02,0.1,-0.06,0.054,-0.0099,-0.045,-0.0013,-0.0057,3.9e-05,0.032,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.38,0.38,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
346 34390000,-0.29,0.014,-0.0076,0.96,0.022,0.099,-0.055,0.052,-0.023,-0.049,-0.0013,-0.0057,2.4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.024,0.005,0.38,0.38,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34390000,-0.29,0.014,-0.0076,0.96,0.022,0.099,-0.055,0.052,-0.023,-0.049,-0.0013,-0.0057,4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.024,0.005,0.38,0.38,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
347 34490000,-0.29,0.014,-0.0077,0.96,0.025,0.1,-0.053,0.054,-0.012,-0.052,-0.0013,-0.0057,2.4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.39,0.39,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34490000,-0.29,0.014,-0.0077,0.96,0.025,0.1,-0.053,0.054,-0.012,-0.052,-0.0013,-0.0057,4e-05,0.033,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.39,0.39,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
348 34590000,-0.29,0.014,-0.0076,0.96,0.026,0.095,0.74,0.05,-0.028,-0.023,-0.0013,-0.0057,2.6e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.39,0.39,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34590000,-0.29,0.014,-0.0076,0.96,0.026,0.095,0.74,0.05,-0.028,-0.023,-0.0013,-0.0057,4.1e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.39,0.39,0.03,2.7e-07,2.6e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
349 34690000,-0.29,0.013,-0.0076,0.96,0.03,0.095,1.7,0.053,-0.018,0.096,-0.0013,-0.0057,2.5e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.024,0.0051,0.4,0.4,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34690000,-0.29,0.013,-0.0076,0.96,0.03,0.095,1.7,0.053,-0.018,0.096,-0.0013,-0.0057,4.1e-05,0.033,-0.022,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.024,0.0051,0.4,0.4,0.03,2.7e-07,2.7e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
350 34790000,-0.29,0.013,-0.0076,0.96,0.032,0.087,2.7,0.049,-0.032,0.27,-0.0013,-0.0057,2.6e-05,0.035,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.4,0.4,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34790000,-0.29,0.013,-0.0076,0.96,0.032,0.087,2.7,0.049,-0.032,0.27,-0.0013,-0.0057,4.2e-05,0.035,-0.023,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.4,0.4,0.03,2.7e-07,2.6e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
351 34890000,-0.29,0.013,-0.0076,0.96,0.037,0.087,3.7,0.053,-0.024,0.57,-0.0013,-0.0057,2.5e-05,0.036,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.025,0.005,0.41,0.41,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 34890000,-0.29,0.013,-0.0076,0.96,0.037,0.087,3.7,0.053,-0.024,0.57,-0.0013,-0.0057,4.2e-05,0.036,-0.024,-0.12,-0.017,-0.0038,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.024,0.005,0.41,0.41,0.03,2.7e-07,2.6e-07,4.8e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1

View File

@ -301,4 +301,47 @@ TEST_F(EkfFlowTest, yawMotionCorrectionWithFlowGyroData)
<< "estimated vel = " << estimated_horz_velocity(0); << "estimated vel = " << estimated_horz_velocity(0);
EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f) EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f)
<< "estimated vel = " << estimated_horz_velocity(1); << "estimated vel = " << estimated_horz_velocity(1);
_ekf->state().vector().print();
_ekf->covariances().print();
}
TEST_F(EkfFlowTest, yawMotionNoMagFusion)
{
// WHEN: fusing range finder and optical flow data in air
const float simulated_distance_to_ground = 5.f;
startRangeFinderFusion(simulated_distance_to_ground);
startZeroFlowFusion();
_ekf_wrapper.setMagFuseTypeNone();
_ekf->set_in_air_status(true);
_ekf->set_vehicle_at_rest(false);
_sensor_simulator.runSeconds(5.f);
// AND WHEN: there is a pure yaw rotation
const Vector3f body_rate(0.f, 0.f, 3.14159f);
const Vector3f flow_offset(-0.15, 0.05f, 0.2f);
_ekf_wrapper.setFlowOffset(flow_offset);
const Vector2f simulated_horz_velocity(body_rate % flow_offset);
flowSample flow_sample = _sensor_simulator._flow.dataAtRest();
setFlowFromHorizontalVelocityAndDistance(flow_sample, simulated_horz_velocity, simulated_distance_to_ground);
// use flow sensor gyro data
// for clarification of the sign, see definition of flowSample
flow_sample.gyro_rate = -body_rate;
_sensor_simulator._flow.setData(flow_sample);
_sensor_simulator._imu.setGyroData(body_rate);
_sensor_simulator.runSeconds(10.f);
// THEN: the flow due to the yaw rotation and the offsets is canceled
// and the velocity estimate stays 0
const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity());
EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.01f)
<< "estimated vel = " << estimated_horz_velocity(0);
EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f)
<< "estimated vel = " << estimated_horz_velocity(1);
_ekf->state().vector().print();
_ekf->covariances().print();
} }