Compare commits

...

2 Commits

Author SHA1 Message Date
bresch e9b012fad9 [AUTO COMMIT] update change indication 2023-11-01 10:19:39 +00:00
bresch 5f02c21d73 ekf2: Compute stapdown INS propagation using closed-form solution 2023-10-31 18:42:22 +01:00
5 changed files with 927 additions and 746 deletions

View File

@ -42,6 +42,7 @@
#include "ekf.h"
#include <mathlib/mathlib.h>
#include <ekf_derivation/generated/predict_vel_pos_closed_form.h>
bool Ekf::init(uint64_t timestamp)
{
@ -289,29 +290,18 @@ void Ekf::predictState(const imuSample &imu_delayed)
// subtract component of angular rate due to earth rotation
corrected_delta_ang -= _R_to_earth.transpose() * _earth_rate_NED * imu_delayed.delta_ang_dt;
// Calculate an earth frame delta velocity
const Vector3f delta_vel_bias_scaled = getAccelBias() * imu_delayed.delta_vel_dt;
const Vector3f corrected_delta_vel = imu_delayed.delta_vel - delta_vel_bias_scaled;
sym::PredictVelPosClosedForm(_state.vector(), corrected_delta_vel, imu_delayed.delta_vel_dt, corrected_delta_ang, imu_delayed.delta_ang_dt, CONSTANTS_ONE_G, FLT_EPSILON, &_state.vel, &_state.pos);
const Quatf dq(AxisAnglef{corrected_delta_ang});
// rotate the previous quaternion by the delta quaternion using a quaternion multiplication
_state.quat_nominal = (_state.quat_nominal * dq).normalized();
_R_to_earth = Dcmf(_state.quat_nominal);
// Calculate an earth frame delta velocity
const Vector3f delta_vel_bias_scaled = getAccelBias() * imu_delayed.delta_vel_dt;
const Vector3f corrected_delta_vel = imu_delayed.delta_vel - delta_vel_bias_scaled;
const Vector3f corrected_delta_vel_ef = _R_to_earth * corrected_delta_vel;
// save the previous value of velocity so we can use trapzoidal integration
const Vector3f vel_last = _state.vel;
// calculate the increment in velocity using the current orientation
_state.vel += corrected_delta_vel_ef;
// compensate for acceleration due to gravity
_state.vel(2) += CONSTANTS_ONE_G * imu_delayed.delta_vel_dt;
// predict position states via trapezoidal integration of velocity
_state.pos += (vel_last + _state.vel) * imu_delayed.delta_vel_dt * 0.5f;
constrainStates();
@ -326,6 +316,7 @@ void Ekf::predictState(const imuSample &imu_delayed)
// calculate a filtered horizontal acceleration with a 1 sec time constant
// this are used for manoeuvre detection elsewhere
const float alpha = 1.0f - imu_delayed.delta_vel_dt;
const Vector3f corrected_delta_vel_ef = _R_to_earth * corrected_delta_vel;
_accel_lpf_NE = _accel_lpf_NE * alpha + corrected_delta_vel_ef.xy();
// calculate a yaw change about the earth frame vertical

View File

@ -205,6 +205,63 @@ def predict_covariance(
return P_new
def predict_vel_pos_closed_form(
state: VState,
d_vel: sf.V3,
d_vel_dt: sf.Scalar,
d_ang: sf.V3,
d_ang_dt: sf.Scalar,
g: sf.Scalar,
epsilon: sf.Scalar
) -> (sf.V3, sf.V3):
# Closed-form integration of accelerometer and gyro measurements based on
# Goppert, James, et al. "A Closed-form Solution for the Strapdown Inertial Navigation Initial Value Problem." arXiv preprint arXiv:2310.04886 (2023).
# TODO: check which dt to use
state = vstate_to_state(state)
gyro = d_ang / d_ang_dt
accel = d_vel / d_vel_dt
dt = d_vel_dt
R_0 = state["quat_nominal"].to_rotation_matrix()
P_0 = sf.M32.block_matrix([[state["vel"], state["pos"]]])
R_l_prime = sf.Rot3.from_tangent(d_ang).to_rotation_matrix()
R_r_prime = sf.M33.eye()
A_M = sf.M32([
[0, 0],
[0, 0],
[g, 0]
])
A_N = sf.M32.block_matrix([[accel, sf.V3()]])
B = sf.M22([
[0, 1],
[0, 0]
])
def P(omega, A, B) -> sf.M32:
theta = (gyro.dot(gyro))**0.5
C1 = (1 - theta**2 / 2 - sf.cos(theta)) / sf.Max(theta**2, epsilon)
C2 = (theta - sf.sin(theta)) / sf.Max(theta**3, epsilon)
C3 = (theta**2 / 2 - theta**4 / 24 + sf.cos(theta) - 1) / sf.Max(theta**4, epsilon)
P = A + (A * B) / 2
P += omega * A * (C1 * sf.M22.eye() + C2 * B)
P += omega * omega * A * (C2 * sf.M22.eye() + C3 * B)
return P
P_M = P(sf.M33(), A_M * dt, -B * dt)
P_N = P(sf.M33.skew_symmetric(gyro * dt), A_N * dt, B * dt)
P_new = R_r_prime * R_0 * P_N + (R_r_prime * P_0 + P_M) * (sf.M22.eye() + B * dt)
# The attitude propagation can be computed as follows, but since the result is simple,
# it is directly implemented in the code.
# R_new = R_r_prime * R_0 * R_l_prime
# q_xyzw = sf.Rot3.from_rotation_matrix(R_new).to_storage()
# q_wxyz = sf.V4(q_xyzw[3], q_xyzw[0], q_xyzw[1], q_xyzw[2])
return (P_new.col(0), P_new.col(1))
def compute_airspeed_innov_and_innov_var(
state: VState,
P: MTangent,
@ -652,5 +709,6 @@ generate_px4_function(compute_flow_xy_innov_var_and_hx, output_names=["innov_var
generate_px4_function(compute_flow_y_innov_var_and_h, output_names=["innov_var", "H"])
generate_px4_function(compute_gnss_yaw_pred_innov_var_and_h, output_names=["meas_pred", "innov_var", "H"])
generate_px4_function(compute_gravity_innov_var_and_k_and_h, output_names=["innov", "innov_var", "Kx", "Ky", "Kz"])
generate_px4_function(predict_vel_pos_closed_form, output_names=["v_new", "p_new"])
generate_px4_state(State, tangent_idx)

View File

@ -0,0 +1,132 @@
// -----------------------------------------------------------------------------
// This file was autogenerated by symforce from template:
// function/FUNCTION.h.jinja
// Do NOT modify by hand.
// -----------------------------------------------------------------------------
#pragma once
#include <matrix/math.hpp>
namespace sym {
/**
* This function was autogenerated from a symbolic function. Do not modify by hand.
*
* Symbolic function: predict_vel_pos_closed_form
*
* Args:
* state: Matrix24_1
* d_vel: Matrix31
* d_vel_dt: Scalar
* d_ang: Matrix31
* d_ang_dt: Scalar
* g: Scalar
* epsilon: Scalar
*
* Outputs:
* v_new: Matrix31
* p_new: Matrix31
*/
template <typename Scalar>
void PredictVelPosClosedForm(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 3, 1>& d_vel, const Scalar d_vel_dt,
const matrix::Matrix<Scalar, 3, 1>& d_ang, const Scalar d_ang_dt,
const Scalar g, const Scalar epsilon,
matrix::Matrix<Scalar, 3, 1>* const v_new = nullptr,
matrix::Matrix<Scalar, 3, 1>* const p_new = nullptr) {
// Total ops: 179
// Input arrays
// Intermediate terms (61)
const Scalar _tmp0 = 2 * state(0, 0) * state(3, 0);
const Scalar _tmp1 = 2 * state(2, 0);
const Scalar _tmp2 = _tmp1 * state(1, 0);
const Scalar _tmp3 = -_tmp0 + _tmp2;
const Scalar _tmp4 = d_vel_dt / d_ang_dt;
const Scalar _tmp5 = d_ang(0, 0) * d_vel(2, 0);
const Scalar _tmp6 = d_ang(2, 0) * d_vel(0, 0);
const Scalar _tmp7 = -_tmp4 * _tmp5 + _tmp4 * _tmp6;
const Scalar _tmp8 = std::pow(d_ang_dt, Scalar(-2));
const Scalar _tmp9 = _tmp8 * std::pow(d_ang(0, 0), Scalar(2));
const Scalar _tmp10 = _tmp8 * std::pow(d_ang(2, 0), Scalar(2));
const Scalar _tmp11 = _tmp8 * std::pow(d_ang(1, 0), Scalar(2));
const Scalar _tmp12 = _tmp10 + _tmp11 + _tmp9;
const Scalar _tmp13 = std::pow(_tmp12, Scalar(Scalar(1.0)));
const Scalar _tmp14 = std::sqrt(_tmp12);
const Scalar _tmp15 = std::cos(_tmp14);
const Scalar _tmp16 = (Scalar(1) / Scalar(2)) * _tmp13;
const Scalar _tmp17 = (-_tmp15 - _tmp16 + 1) / math::max<Scalar>(_tmp13, epsilon);
const Scalar _tmp18 = std::pow(d_vel_dt, Scalar(2));
const Scalar _tmp19 = _tmp18 * _tmp8;
const Scalar _tmp20 = _tmp19 * d_ang(1, 0);
const Scalar _tmp21 = _tmp20 * d_ang(2, 0);
const Scalar _tmp22 = _tmp20 * d_ang(0, 0);
const Scalar _tmp23 = -_tmp10 * _tmp18;
const Scalar _tmp24 = -_tmp18 * _tmp9;
const Scalar _tmp25 =
_tmp21 * d_vel(2, 0) + _tmp22 * d_vel(0, 0) + d_vel(1, 0) * (_tmp23 + _tmp24);
const Scalar _tmp26 =
(_tmp14 - std::sin(_tmp14)) / math::max<Scalar>(epsilon, (_tmp12 * std::sqrt(_tmp12)));
const Scalar _tmp27 = _tmp17 * _tmp7 + _tmp25 * _tmp26 + d_vel(1, 0);
const Scalar _tmp28 = -2 * std::pow(state(3, 0), Scalar(2));
const Scalar _tmp29 = 1 - 2 * std::pow(state(2, 0), Scalar(2));
const Scalar _tmp30 = _tmp28 + _tmp29;
const Scalar _tmp31 = -_tmp11 * _tmp18;
const Scalar _tmp32 =
_tmp19 * _tmp5 * d_ang(2, 0) + _tmp22 * d_vel(1, 0) + d_vel(0, 0) * (_tmp23 + _tmp31);
const Scalar _tmp33 = _tmp4 * d_ang(1, 0);
const Scalar _tmp34 = _tmp4 * d_vel(1, 0);
const Scalar _tmp35 = _tmp33 * d_vel(2, 0) - _tmp34 * d_ang(2, 0);
const Scalar _tmp36 = _tmp17 * _tmp35 + _tmp26 * _tmp32 + d_vel(0, 0);
const Scalar _tmp37 = _tmp1 * state(0, 0);
const Scalar _tmp38 = 2 * state(1, 0);
const Scalar _tmp39 = _tmp38 * state(3, 0);
const Scalar _tmp40 = _tmp37 + _tmp39;
const Scalar _tmp41 =
_tmp19 * _tmp6 * d_ang(0, 0) + _tmp21 * d_vel(1, 0) + d_vel(2, 0) * (_tmp24 + _tmp31);
const Scalar _tmp42 = -_tmp33 * d_vel(0, 0) + _tmp34 * d_ang(0, 0);
const Scalar _tmp43 = _tmp17 * _tmp42 + _tmp26 * _tmp41 + d_vel(2, 0);
const Scalar _tmp44 = -2 * std::pow(state(1, 0), Scalar(2));
const Scalar _tmp45 = _tmp28 + _tmp44 + 1;
const Scalar _tmp46 = _tmp0 + _tmp2;
const Scalar _tmp47 = _tmp1 * state(3, 0);
const Scalar _tmp48 = _tmp38 * state(0, 0);
const Scalar _tmp49 = _tmp47 - _tmp48;
const Scalar _tmp50 = _tmp47 + _tmp48;
const Scalar _tmp51 = -_tmp37 + _tmp39;
const Scalar _tmp52 = _tmp29 + _tmp44;
const Scalar _tmp53 = d_vel_dt * g + state(6, 0);
const Scalar _tmp54 = (Scalar(1) / Scalar(2)) * d_vel_dt;
const Scalar _tmp55 = std::pow(_tmp12, Scalar(Scalar(2.0)));
const Scalar _tmp56 = d_vel_dt * (_tmp15 + _tmp16 - Scalar(1) / Scalar(24) * _tmp55 - 1) /
math::max<Scalar>(_tmp55, epsilon);
const Scalar _tmp57 = _tmp26 * d_vel_dt;
const Scalar _tmp58 = _tmp25 * _tmp56 + _tmp54 * d_vel(1, 0) + _tmp57 * _tmp7;
const Scalar _tmp59 = _tmp41 * _tmp56 + _tmp42 * _tmp57 + _tmp54 * d_vel(2, 0);
const Scalar _tmp60 = _tmp32 * _tmp56 + _tmp35 * _tmp57 + _tmp54 * d_vel(0, 0);
// Output terms (2)
if (v_new != nullptr) {
matrix::Matrix<Scalar, 3, 1>& _v_new = (*v_new);
_v_new(0, 0) = _tmp27 * _tmp3 + _tmp30 * _tmp36 + _tmp40 * _tmp43 + state(4, 0);
_v_new(1, 0) = _tmp27 * _tmp45 + _tmp36 * _tmp46 + _tmp43 * _tmp49 + state(5, 0);
_v_new(2, 0) = _tmp27 * _tmp50 + _tmp36 * _tmp51 + _tmp43 * _tmp52 + _tmp53;
}
if (p_new != nullptr) {
matrix::Matrix<Scalar, 3, 1>& _p_new = (*p_new);
_p_new(0, 0) =
_tmp3 * _tmp58 + _tmp30 * _tmp60 + _tmp40 * _tmp59 + d_vel_dt * state(4, 0) + state(7, 0);
_p_new(1, 0) =
_tmp45 * _tmp58 + _tmp46 * _tmp60 + _tmp49 * _tmp59 + d_vel_dt * state(5, 0) + state(8, 0);
_p_new(2, 0) = -Scalar(1) / Scalar(2) * _tmp18 * g + _tmp50 * _tmp58 + _tmp51 * _tmp60 +
_tmp52 * _tmp59 + _tmp53 * d_vel_dt + state(9, 0);
}
} // NOLINT(readability/fn_size)
// NOLINTNEXTLINE(readability/fn_size)
} // namespace sym

View File

@ -1,391 +1,391 @@
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0
90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0
190000,1,-0.0094,-0.011,2.9e-05,6.9e-05,0.0039,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.9e-13,0,0,-2e-09,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0
290000,1,-0.0094,-0.011,6.4e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-2.8e-11,0,0,-4.8e-07,0,0,0,0,0,0,0,0,0.012,0.011,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0
390000,1,-0.0095,-0.011,7.2e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,7.6e-11,0,0,-4.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0
490000,1,-0.0095,-0.012,2.2e-05,0.0039,0.0048,-0.06,0.00024,0.00048,-0.011,1.6e-06,-3.7e-07,1.4e-08,0,0,-1.6e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0
590000,1,-0.0095,-0.012,2.9e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,1.4e-08,0,0,-3.4e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0
690000,1,-0.0097,-0.012,8.9e-05,0.0063,0.0051,-0.06,0.0005,0.00054,-0.013,5.5e-06,-3.2e-06,1.2e-07,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0
790000,1,-0.0098,-0.013,0.0001,0.0086,0.0072,-0.063,0.0012,0.0011,-0.014,5.4e-06,-3.1e-06,1.1e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0
890000,1,-0.0099,-0.013,0.00012,0.01,0.0059,-0.077,0.00096,0.00071,-0.021,1.6e-05,-1.5e-05,3.4e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0
990000,1,-0.0099,-0.013,0.00013,0.015,0.0062,-0.092,0.0022,0.0013,-0.029,1.6e-05,-1.5e-05,3.4e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1090000,1,-0.01,-0.014,0.00013,0.016,0.0048,-0.11,0.0018,0.00084,-0.039,4.1e-05,-6.2e-05,9.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00046,0.92,0.92,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1190000,1,-0.01,-0.014,0.0001,0.02,0.005,-0.12,0.0035,0.0013,-0.051,4.1e-05,-6.2e-05,9.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.025,0.025,0.00054,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1290000,1,-0.01,-0.014,0.00016,0.02,0.0041,-0.14,0.0027,0.00085,-0.064,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.026,0.026,0.00041,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1390000,1,-0.01,-0.014,0.00017,0.026,0.0038,-0.15,0.0051,0.0013,-0.078,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.028,0.028,0.00047,1.1,1.1,2,0.21,0.21,1.7,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1490000,1,-0.01,-0.014,0.00015,0.024,0.0026,-0.16,0.0038,0.00078,-0.093,0.00014,-0.00046,4.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.95,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1590000,1,-0.011,-0.014,0.00014,0.031,0.003,-0.18,0.0065,0.0011,-0.11,0.00014,-0.00046,4.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,0.03,0.03,0.00042,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1690000,1,-0.011,-0.014,0.00011,0.028,-0.00047,-0.19,0.0045,0.00057,-0.13,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1790000,1,-0.011,-0.014,7.5e-05,0.035,-0.0024,-0.2,0.0076,0.00044,-0.15,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1890000,1,-0.011,-0.015,5.5e-05,0.043,-0.0037,-0.22,0.011,0.00014,-0.17,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.031,0.031,0.00042,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1990000,1,-0.011,-0.014,4.7e-05,0.036,-0.0051,-0.23,0.0082,-0.00038,-0.19,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.024,0.024,0.00033,1.3,1.3,2,0.2,0.2,4.7,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2090000,1,-0.011,-0.014,6.8e-06,0.041,-0.0077,-0.24,0.012,-0.001,-0.22,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.026,0.026,0.00037,1.7,1.7,2.1,0.31,0.31,5.3,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2190000,1,-0.011,-0.014,-1.3e-06,0.033,-0.0072,-0.26,0.0079,-0.0011,-0.24,0.00015,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.02,0.02,0.0003,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2290000,1,-0.011,-0.014,-1.7e-05,0.039,-0.0098,-0.27,0.011,-0.0019,-0.27,0.00015,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2390000,1,-0.011,-0.013,-1.9e-05,0.03,-0.009,-0.29,0.0074,-0.0016,-0.3,5.8e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.016,0.016,0.00027,1,1,2.1,0.19,0.19,7.4,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2490000,1,-0.011,-0.013,-4e-05,0.034,-0.011,-0.3,0.011,-0.0025,-0.32,5.8e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.017,0.017,0.0003,1.3,1.3,2.1,0.28,0.28,8.2,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2590000,1,-0.011,-0.013,-4.3e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-5.2e-05,-0.003,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2690000,1,-0.011,-0.013,-5e-05,0.03,-0.011,-0.33,0.0096,-0.0029,-0.39,-5.2e-05,-0.003,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.014,0.014,0.00027,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2790000,1,-0.011,-0.013,-7.1e-05,0.023,-0.0096,-0.34,0.0061,-0.002,-0.42,-0.00017,-0.0033,2.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2890000,1,-0.011,-0.013,-0.00013,0.027,-0.011,-0.35,0.0086,-0.003,-0.46,-0.00017,-0.0033,2.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.012,0.012,0.00025,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2990000,1,-0.011,-0.013,-9.1e-05,0.022,-0.0097,-0.36,0.0056,-0.0021,-0.49,-0.00028,-0.0036,3.1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.009,0.009,0.00021,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3090000,1,-0.011,-0.013,-9.2e-05,0.024,-0.011,-0.38,0.0079,-0.0032,-0.53,-0.00028,-0.0036,3.1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.01,0.0099,0.00023,0.82,0.82,2.2,0.22,0.22,14,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3190000,1,-0.011,-0.013,-0.00016,0.019,-0.0088,-0.39,0.0052,-0.0022,-0.57,-0.00039,-0.0039,3.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0078,0.0078,0.0002,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3290000,1,-0.011,-0.013,-0.00013,0.023,-0.011,-0.4,0.0073,-0.0031,-0.61,-0.00039,-0.0039,3.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3390000,1,-0.011,-0.012,-0.00017,0.018,-0.0094,-0.42,0.0049,-0.0022,-0.65,-0.00049,-0.0041,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00019,0.53,0.53,2.3,0.14,0.14,17,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3490000,1,-0.011,-0.013,-0.00018,0.021,-0.012,-0.43,0.0068,-0.0032,-0.69,-0.00049,-0.0041,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0076,0.0076,0.0002,0.65,0.65,2.3,0.19,0.19,19,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3590000,1,-0.011,-0.012,-0.00017,0.016,-0.011,-0.44,0.0046,-0.0023,-0.73,-0.0006,-0.0044,3.6e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00018,0.48,0.48,2.4,0.13,0.13,20,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3690000,1,-0.011,-0.012,-4.8e-05,0.019,-0.014,-0.46,0.0064,-0.0036,-0.78,-0.0006,-0.0044,3.6e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0068,0.0067,0.00019,0.59,0.59,2.4,0.18,0.18,21,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3790000,1,-0.011,-0.012,-1.3e-05,0.015,-0.014,-0.47,0.0043,-0.0026,-0.83,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0055,0.0055,0.00017,0.44,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3890000,1,-0.011,-0.012,-5.1e-05,0.017,-0.015,-0.48,0.0059,-0.004,-0.87,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.006,0.006,0.00018,0.54,0.54,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3990000,1,-0.011,-0.012,-5.2e-05,0.02,-0.016,-0.5,0.0078,-0.0056,-0.92,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00019,0.66,0.66,2.5,0.22,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4090000,1,-0.011,-0.012,-6.7e-05,0.017,-0.014,-0.51,0.0056,-0.0042,-0.97,-0.00084,-0.0047,4e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.0054,0.0053,0.00017,0.5,0.5,2.5,0.16,0.16,27,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4190000,1,-0.011,-0.012,-9.6e-05,0.02,-0.017,-0.53,0.0075,-0.0057,-1,-0.00084,-0.0047,4e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00018,0.6,0.61,2.5,0.21,0.21,29,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4290000,1,-0.01,-0.012,-0.00015,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00097,-0.0049,4.2e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.46,0.46,2.6,0.15,0.15,31,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4390000,1,-0.01,-0.012,-0.00014,0.018,-0.013,-0.55,0.0072,-0.0055,-1.1,-0.00097,-0.0049,4.2e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,0.0052,0.0051,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4490000,1,-0.01,-0.012,-8.5e-05,0.015,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,4.3e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,2.6,0.14,0.14,34,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4590000,1,-0.01,-0.012,-6e-05,0.018,-0.012,-0.58,0.0068,-0.0049,-1.2,-0.0011,-0.005,4.3e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,0.0045,0.0045,0.00016,0.51,0.51,2.7,0.19,0.19,36,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4690000,1,-0.01,-0.012,-6.7e-05,0.014,-0.01,-0.6,0.0049,-0.0034,-1.3,-0.0012,-0.0052,4.5e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,0.0037,0.0036,0.00015,0.39,0.39,2.7,0.14,0.14,38,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4790000,1,-0.01,-0.012,-8.2e-05,0.016,-0.012,-0.61,0.0064,-0.0045,-1.4,-0.0012,-0.0052,4.5e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,0.004,0.0039,0.00015,0.47,0.47,2.7,0.18,0.18,40,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4890000,1,-0.01,-0.012,-0.0001,0.013,-0.01,-0.63,0.0046,-0.0033,-1.4,-0.0013,-0.0053,4.6e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,2.8,0.13,0.13,42,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4990000,1,-0.01,-0.012,-0.00013,0.015,-0.011,-0.64,0.006,-0.0043,-1.5,-0.0013,-0.0053,4.6e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00015,0.43,0.43,2.8,0.17,0.17,44,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5090000,1,-0.01,-0.011,-9.3e-05,0.012,-0.0086,-0.66,0.0043,-0.0031,-1.6,-0.0013,-0.0054,4.7e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,2.8,0.12,0.12,46,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5190000,1,-0.01,-0.011,-7.2e-05,0.013,-0.01,-0.67,0.0056,-0.004,-1.6,-0.0013,-0.0054,4.7e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.003,0.003,0.00014,0.39,0.39,2.9,0.16,0.16,49,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5290000,1,-0.01,-0.011,-9.1e-05,0.0093,-0.0074,-0.68,0.0039,-0.0029,-1.7,-0.0014,-0.0055,4.8e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00013,0.3,0.3,2.9,0.12,0.12,51,0.00034,0.00034,9.2e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5390000,1,-0.0099,-0.011,-3.8e-05,0.0089,-0.0083,-0.7,0.0048,-0.0037,-1.8,-0.0014,-0.0055,4.8e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00014,0.36,0.36,2.9,0.16,0.16,53,0.00034,0.00034,9.2e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5490000,1,-0.0098,-0.011,-3.4e-05,0.0062,-0.0064,-0.71,0.0033,-0.0026,-1.8,-0.0014,-0.0055,4.9e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,3,0.11,0.11,56,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5590000,1,-0.0098,-0.011,-6e-05,0.0069,-0.0068,-0.73,0.0039,-0.0032,-1.9,-0.0014,-0.0055,4.9e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00013,0.33,0.33,3,0.15,0.15,58,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5690000,1,-0.0096,-0.011,5.9e-06,0.0049,-0.004,-0.74,0.0027,-0.0022,-2,-0.0015,-0.0056,5e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,3.1,0.11,0.11,61,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5790000,1,-0.0096,-0.011,-2.3e-06,0.0053,-0.003,-0.75,0.0031,-0.0026,-2,-0.0015,-0.0056,5e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5890000,1,-0.0095,-0.011,-3.2e-05,0.0045,-0.0011,0.0028,0.0022,-0.0017,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5990000,1,-0.0095,-0.011,-1.4e-05,0.0049,0.00031,0.015,0.0026,-0.0017,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6090000,1,-0.0094,-0.011,-3.4e-05,0.006,0.0015,-0.011,0.0032,-0.0016,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6190000,0.7,0.0013,-0.015,0.71,0.0035,0.0029,-0.005,0.0023,-0.00066,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0013,0.018,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6290000,0.7,0.0013,-0.015,0.71,0.0035,0.0043,-0.012,0.0026,-0.00028,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6390000,0.7,0.0014,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-3.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6490000,0.7,0.0014,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-8.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6590000,0.7,0.0014,-0.014,0.71,0.0017,0.0057,-0.099,0.0034,0.0013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6690000,0.7,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0036,0.0019,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6790000,0.7,0.0014,-0.014,0.71,0.0008,0.0068,-0.11,0.0037,0.0026,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,8.4e-06,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6890000,0.71,0.0014,-0.014,0.71,-0.0012,0.0073,-0.12,0.0037,0.0033,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6990000,0.71,0.0015,-0.014,0.71,-0.0013,0.0082,-0.12,0.0035,0.0041,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7090000,0.71,0.0015,-0.014,0.71,-0.0018,0.0079,-0.13,0.0033,0.0049,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7190000,0.71,0.0015,-0.014,0.71,-0.0035,0.0081,-0.15,0.0031,0.0057,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7290000,0.71,0.0015,-0.014,0.71,-0.005,0.0083,-0.15,0.0026,0.0065,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0015,0.018,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7390000,0.71,0.0015,-0.014,0.71,-0.0051,0.0098,-0.16,0.0021,0.0073,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7490000,0.71,0.0016,-0.014,0.71,-0.0067,0.01,-0.16,0.0015,0.0083,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7590000,0.71,0.0016,-0.014,0.71,-0.0086,0.012,-0.17,0.00072,0.0093,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.51,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7690000,0.71,0.0017,-0.014,0.71,-0.01,0.012,-0.16,-0.00026,0.01,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7790000,0.71,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0014,0.011,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7890000,0.71,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0027,0.013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.65,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0
7990000,0.71,0.0018,-0.014,0.71,-0.016,0.016,-0.16,-0.0043,0.014,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0
8090000,0.71,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.006,0.016,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0
8190000,0.71,0.0017,-0.014,0.71,-0.021,0.019,-0.18,-0.008,0.018,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0
8290000,0.71,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.002,0.018,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.036,0,0,0,0,0,0,0,0
8390000,0.71,0.0018,-0.014,0.71,-0.025,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.002,0.018,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.035,0,0,0,0,0,0,0,0
8490000,0.71,0.0018,-0.014,0.71,-0.026,0.022,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.0021,0.018,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0
8590000,0.71,0.0019,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0
8690000,0.71,0.0019,-0.014,0.71,-0.032,0.025,-0.16,-0.021,0.026,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.033,0,0,0,0,0,0,0,0
8790000,0.71,0.0019,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,6.3e-06,0.04,0.04,0.032,0,0,0,0,0,0,0,0
8890000,0.71,0.0019,-0.014,0.71,-0.036,0.028,-0.15,-0.027,0.03,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.03,0,0,0,0,0,0,0,0
8990000,0.71,0.002,-0.014,0.71,-0.038,0.028,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,6.3e-06,0.04,0.04,0.029,0,0,0,0,0,0,0,0
9090000,0.71,0.002,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.028,0,0,0,0,0,0,0,0
9190000,0.71,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.036,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.027,0,0,0,0,0,0,0,0
9290000,0.71,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.041,0.037,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.025,0,0,0,0,0,0,0,0
9390000,0.71,0.002,-0.014,0.71,-0.044,0.033,-0.14,-0.045,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.7,1.7,0.093,5.8,5.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.024,0,0,0,0,0,0,0,0
9490000,0.71,0.002,-0.014,0.71,-0.045,0.032,-0.13,-0.047,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0025,0.018,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.023,0,0,0,0,0,0,0,0
9590000,0.71,0.002,-0.014,0.71,-0.048,0.034,-0.13,-0.052,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.021,0,0,0,0,0,0,0,0
9690000,0.71,0.002,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.02,0,0,0,0,0,0,0,0
9790000,0.71,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.059,0.047,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.019,0,0,0,0,0,0,0,0
9890000,0.71,0.002,-0.014,0.71,-0.049,0.038,-0.11,-0.06,0.046,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.018,0,0,0,0,0,0,0,0
9990000,0.71,0.0021,-0.014,0.71,-0.051,0.038,-0.1,-0.065,0.05,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0028,0.018,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.017,0,0,0,0,0,0,0,0
10090000,0.71,0.0021,-0.014,0.71,-0.049,0.037,-0.096,-0.064,0.049,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.016,0,0,0,0,0,0,0,0
10190000,0.71,0.0021,-0.014,0.71,-0.051,0.04,-0.096,-0.07,0.053,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0028,0.018,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0
10290000,0.71,0.0021,-0.014,0.71,-0.052,0.041,-0.084,-0.075,0.057,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0029,0.018,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0
10390000,0.71,0.0021,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,4.8e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.003,0.003,0.018,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.013,0,0,0,0,0,0,0,0
10490000,0.71,0.0021,-0.014,0.71,0.0082,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,4.8e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
10590000,0.71,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
10690000,0.71,0.0023,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3.1e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0032,0.0032,0.018,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
10790000,0.71,0.0022,-0.014,0.71,0.0052,-0.003,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
10890000,0.71,0.0022,-0.014,0.71,0.0039,-0.0017,0.02,0.0031,-0.00092,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0032,0.0032,0.018,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
10990000,0.71,0.0022,-0.014,0.71,0.0067,0.0034,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0029,0.018,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
11090000,0.71,0.0022,-0.014,0.71,0.0055,0.0059,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.003,0.003,0.018,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
11190000,0.71,0.002,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11290000,0.71,0.0021,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11390000,0.71,0.0022,-0.014,0.71,0.0053,0.0092,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.0005,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11490000,0.71,0.0022,-0.014,0.71,0.0028,0.012,0.0025,0.0059,-0.00089,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.00051,0.00089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11590000,0.71,0.0021,-0.014,0.71,-0.0016,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,4.6e-05,-8.6e-05,0.00077,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11690000,0.71,0.002,-0.014,0.71,-0.0044,0.013,-0.0079,0.0042,-0.00026,-3.7e+02,-0.0014,-0.0056,4.6e-05,-7.7e-05,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11790000,0.71,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,4.6e-05,3.2e-05,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11890000,0.71,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00076,0.0019,-3.7e+02,-0.0014,-0.0056,4.6e-05,2.7e-05,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11990000,0.71,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.0003,0.0023,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00017,0.00059,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12090000,0.71,0.0021,-0.014,0.71,-0.015,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00018,0.00057,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12190000,0.71,0.0017,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00044,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,0.0012,0.018,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12290000,0.71,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00055,0.0033,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00041,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0012,0.018,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12390000,0.71,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12490000,0.71,0.0014,-0.014,0.71,-0.0063,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12590000,0.71,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.00071,0.0012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.001,0.001,0.018,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0
12690000,0.71,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.00073,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.001,0.001,0.018,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0
12790000,0.71,0.0015,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00077,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00094,0.00094,0.018,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0
12890000,0.71,0.0015,-0.013,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00071,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00097,0.00097,0.018,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0
12990000,0.71,0.0012,-0.014,0.71,-0.0084,0.0066,-0.03,-0.001,0.0012,-3.7e+02,-0.0012,-0.0059,4e-05,0.00068,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
13090000,0.71,0.0012,-0.014,0.71,-0.0091,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0012,-0.0059,4e-05,0.00065,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00092,0.00092,0.018,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
13190000,0.71,0.00091,-0.014,0.71,1.9e-05,0.0061,-0.027,0.0044,0.0012,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00051,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
13290000,0.71,0.00092,-0.014,0.71,-0.00022,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00037,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
13390000,0.71,0.00077,-0.014,0.71,0.0006,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0002,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0
13490000,0.71,0.0008,-0.014,0.71,0.00011,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.00012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0
13590000,0.71,0.00074,-0.014,0.71,0.00036,0.006,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.006,3.7e-05,9e-05,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0
13690000,0.71,0.00072,-0.014,0.71,0.0011,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.006,3.7e-05,0.00012,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0
13790000,0.71,0.0006,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,3.6e-05,-0.0001,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.0008,0.018,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0
13890000,0.71,0.00057,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,3.6e-05,-7.1e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00083,0.00083,0.018,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0
13990000,0.71,0.0005,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0
14090000,0.71,0.00049,-0.014,0.71,0.0025,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00033,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0
14190000,0.71,0.00038,-0.014,0.71,0.0058,0.00062,-0.033,0.0068,-0.0017,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00031,0.00088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0
14290000,0.71,0.00039,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00038,0.00094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.00081,0.018,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0
14390000,0.71,0.00031,-0.014,0.71,0.0084,0.0023,-0.034,0.0088,-0.0013,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00039,0.00069,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.018,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0
14490000,0.71,0.00029,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.0011,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00034,0.00064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0
14590000,0.71,0.00028,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00071,0.001,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0
14690000,0.71,0.00024,-0.013,0.71,0.0063,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00082,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0
14790000,0.71,0.00027,-0.013,0.71,0.0031,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.018,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0
14890000,0.71,0.00026,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0
14990000,0.71,0.00026,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.018,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0
15090000,0.71,0.00018,-0.013,0.71,0.0038,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.019,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0
15190000,0.71,0.0002,-0.013,0.71,0.0032,-0.0008,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00075,0.00075,0.019,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0
15290000,0.71,0.00016,-0.013,0.71,0.0038,-0.00064,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.019,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0
15390000,0.71,0.00017,-0.013,0.71,0.003,-0.0003,-0.024,0.00057,-0.002,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00074,0.00074,0.019,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.3e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0
15490000,0.71,0.00019,-0.013,0.71,0.0043,-0.00068,-0.024,0.00095,-0.0021,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.019,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.3e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0
15590000,0.71,0.0002,-0.013,0.71,0.0024,-0.00067,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0
15690000,0.71,0.0002,-0.013,0.71,0.0027,-0.00085,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00074,0.00074,0.019,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0
15790000,0.71,0.00017,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00095,-0.0028,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00071,0.00071,0.019,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0
15890000,0.71,0.00012,-0.013,0.71,0.0041,-0.003,-0.024,-0.00056,-0.0031,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0
15990000,0.71,6.2e-05,-0.013,0.71,0.004,-0.0039,-0.019,-0.00063,-0.0039,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0019,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0
16090000,0.71,6.5e-05,-0.013,0.71,0.0057,-0.0041,-0.016,-0.00016,-0.0043,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.002,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00071,0.00072,0.019,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0
16190000,0.71,9e-05,-0.013,0.71,0.0057,-0.0033,-0.014,-0.00037,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0
16290000,0.71,0.00011,-0.013,0.71,0.0073,-0.0042,-0.016,0.00029,-0.0038,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0018,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0
16390000,0.71,0.0001,-0.013,0.71,0.0062,-0.0044,-0.015,-4.2e-05,-0.0031,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00067,0.00067,0.019,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0
16490000,0.71,0.00012,-0.013,0.71,0.0054,-0.0039,-0.018,0.00051,-0.0035,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0
16590000,0.71,0.00038,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0024,-8.7e-05,-3.7e+02,-0.0013,-0.006,4e-05,-0.001,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00065,0.019,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0
16690000,0.71,0.00036,-0.013,0.71,0.002,-0.00074,-0.015,-0.0022,-0.00018,-3.7e+02,-0.0013,-0.006,4e-05,-0.0011,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00067,0.00067,0.019,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0
16790000,0.71,0.00051,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0005,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00064,0.00064,0.019,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0
16890000,0.71,0.00053,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0047,0.0027,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00054,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00065,0.019,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0
16990000,0.71,0.00046,-0.013,0.71,-0.0016,0.00032,-0.01,-0.0052,0.00084,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00095,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00062,0.00062,0.019,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
17090000,0.71,0.00043,-0.013,0.71,-0.0008,0.0013,-0.01,-0.0053,0.0009,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00094,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00063,0.00063,0.019,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
17190000,0.71,0.00042,-0.013,0.71,-0.00034,0.0013,-0.011,-0.0056,-0.00054,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0006,0.0006,0.019,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0
17290000,0.71,0.0004,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00038,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00061,0.00061,0.019,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0
17390000,0.71,0.00036,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0046,-0.0016,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00059,0.00059,0.019,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
17490000,0.71,0.00036,-0.013,0.71,0.0029,0.001,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0006,0.0006,0.019,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
17590000,0.71,0.00027,-0.013,0.71,0.0042,-0.00013,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00057,0.00057,0.019,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
17690000,0.71,0.00024,-0.013,0.71,0.0051,0.00058,0.0019,-0.0032,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00058,0.00058,0.019,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
17790000,0.71,0.00015,-0.013,0.71,0.0076,0.0003,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00055,0.019,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
17890000,0.71,0.00016,-0.013,0.71,0.0092,-0.00046,0.00069,-0.0012,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
17990000,0.71,0.00011,-0.013,0.71,0.011,-0.0022,0.0019,-0.00052,-0.0019,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00054,0.00054,0.019,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0
18090000,0.71,0.00011,-0.013,0.71,0.012,-0.0024,0.0043,0.0006,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00055,0.00055,0.019,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0
18190000,0.71,8e-05,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00053,0.019,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0
18290000,0.71,2.1e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0018,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0
18390000,0.71,3.8e-05,-0.013,0.71,0.013,-0.0002,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0
18490000,0.71,5.4e-05,-0.012,0.71,0.014,0.00021,0.0076,0.0047,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00052,0.00052,0.019,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0
18590000,0.71,6e-05,-0.012,0.71,0.013,0.00045,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0
18690000,0.71,2.9e-05,-0.012,0.71,0.014,-0.00024,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.00051,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0
18790000,0.71,5.9e-05,-0.012,0.71,0.012,6.5e-05,0.0035,0.0037,-0.00091,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0
18890000,0.71,8.4e-05,-0.012,0.71,0.013,0.00056,0.0042,0.005,-0.00084,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0
18990000,0.71,7.3e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0
19090000,0.71,5.7e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.0005,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0
19190000,0.71,6.1e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0086,-0.00045,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0
19290000,0.71,8.3e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00026,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0
19390000,0.71,9.6e-05,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0
19490000,0.71,0.00012,-0.012,0.71,0.012,-0.00032,0.0088,0.0092,-0.00028,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0
19590000,0.71,0.00017,-0.012,0.71,0.0096,-0.0013,0.0081,0.0075,-0.00029,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0
19690000,0.71,0.00017,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00054,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0
19790000,0.71,0.00024,-0.012,0.71,0.0077,-0.0044,0.01,0.0068,-0.00044,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00044,0.019,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
19890000,0.71,0.00019,-0.012,0.71,0.0064,-0.0047,0.011,0.0075,-0.0009,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00044,0.019,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
19990000,0.71,0.00018,-0.012,0.71,0.004,-0.0054,0.014,0.0061,-0.00075,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20090000,0.71,0.00018,-0.012,0.71,0.0038,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20190000,0.71,0.00028,-0.012,0.71,0.0014,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20290000,0.71,0.00024,-0.012,0.71,0.00031,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20390000,0.71,0.00026,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20490000,0.71,0.00032,-0.012,0.71,-0.0026,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20590000,0.71,0.00034,-0.012,0.71,-0.0023,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20690000,0.71,0.00036,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,2e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20790000,0.71,0.0004,-0.012,0.71,-0.0034,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.0004,0.019,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
21090000,0.71,0.00039,-0.012,0.71,-0.0042,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
21190000,0.71,0.00043,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21290000,0.71,0.00047,-0.012,0.71,-0.004,-0.018,0.016,0.0034,-0.0055,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21390000,0.71,0.00051,-0.012,0.71,-0.0048,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00035,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21590000,0.71,0.00055,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-4.5e-06,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00038,0.02,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21690000,0.71,0.00056,-0.012,0.71,-0.0057,-0.017,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,4.4e-05,-5.7e-06,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.02,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,7.2e-05,-0.00077,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00052,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21890000,0.71,0.00058,-0.012,0.71,-0.0063,-0.012,0.016,-0.00057,-0.0019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00051,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21990000,0.71,0.00063,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00096,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22090000,0.71,0.00064,-0.012,0.71,-0.0072,-0.0083,0.015,-0.0022,0.0006,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22190000,0.71,0.00061,-0.012,0.71,-0.007,-0.0074,0.015,-0.0018,0.00056,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22290000,0.71,0.00065,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0026,-0.00022,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00037,0.02,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22390000,0.71,0.00063,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.0002,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22490000,0.71,0.00063,-0.012,0.71,-0.0096,-0.0075,0.018,-0.0031,-0.00098,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22590000,0.71,0.00062,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00011,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22690000,0.71,0.00065,-0.012,0.71,-0.011,-0.0068,0.018,-0.0044,-0.00058,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0056,0.019,-0.0055,-0.00046,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00036,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0052,0.021,-0.0067,-0.001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22990000,0.71,0.00063,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00089,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00036,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23190000,0.71,0.00066,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23290000,0.71,0.0006,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23390000,0.71,0.00069,-0.012,0.71,-0.016,-0.0081,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0077,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0025,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23790000,0.71,0.005,0.00066,0.71,-0.089,-0.028,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.002,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.037,-0.2,-0.03,-0.0051,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23990000,0.7,0.00098,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0083,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
10000,1,-0.0094,-0.01,-3.2e-06,0.00019,6e-05,-0.011,7.4e-06,2.3e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0
90000,1,-0.0094,-0.011,6.9e-05,-0.00057,0.0026,-0.026,-3e-05,0.00013,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0
190000,1,-0.0094,-0.011,2.9e-05,-8e-05,0.0039,-0.041,-2.7e-05,0.00046,-0.0044,-3e-11,-2.7e-12,5.9e-13,0,0,-2e-09,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0
290000,1,-0.0094,-0.011,6.4e-05,0.00078,0.0064,-0.053,3.4e-05,0.00038,-0.007,1.1e-09,2.3e-10,-6.2e-11,0,0,-4.8e-07,0,0,0,0,0,0,0,0,0.012,0.011,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0
390000,1,-0.0095,-0.011,7.2e-05,0.0022,0.0083,-0.059,0.00019,0.0012,-0.0094,-1.1e-08,2.9e-09,4.2e-11,0,0,-4.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0,0,0,0,0,0,0,0
490000,1,-0.0095,-0.012,2.2e-05,0.0036,0.0046,-0.06,0.00024,0.00049,-0.011,1.7e-06,-3.5e-07,1.1e-08,0,0,-1.6e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0
590000,1,-0.0095,-0.012,2.9e-05,0.0056,0.0071,-0.059,0.00072,0.0011,-0.012,1.6e-06,-3.2e-07,1e-08,0,0,-3.4e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0,0,0,0,0,0,0,0
690000,1,-0.0097,-0.012,8.9e-05,0.006,0.005,-0.06,0.0005,0.00055,-0.013,5.6e-06,-3.1e-06,1.1e-07,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0
790000,1,-0.0098,-0.013,0.0001,0.0082,0.0071,-0.063,0.0012,0.0012,-0.014,5.5e-06,-3e-06,1.1e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0,0,0,0,0,0,0,0
890000,1,-0.0099,-0.013,0.00012,0.01,0.0058,-0.077,0.00095,0.00072,-0.021,1.6e-05,-1.5e-05,3.2e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0
990000,1,-0.0099,-0.013,0.00013,0.014,0.0061,-0.092,0.0022,0.0013,-0.029,1.6e-05,-1.5e-05,3.2e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1090000,1,-0.01,-0.014,0.00013,0.015,0.0048,-0.11,0.0018,0.00084,-0.039,4.1e-05,-6.2e-05,9.3e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00046,0.92,0.92,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1190000,1,-0.01,-0.014,0.0001,0.019,0.005,-0.12,0.0035,0.0013,-0.051,4.1e-05,-6.2e-05,9.3e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,0.025,0.025,0.00054,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1290000,1,-0.01,-0.014,0.00016,0.019,0.004,-0.14,0.0027,0.00085,-0.064,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.026,0.026,0.00041,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1390000,1,-0.01,-0.014,0.00017,0.025,0.0038,-0.15,0.005,0.0013,-0.078,8.2e-05,-0.00019,2.3e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.028,0.028,0.00047,1.1,1.1,2,0.21,0.21,1.7,0.0095,0.0095,0.00028,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1490000,1,-0.01,-0.014,0.00015,0.024,0.0026,-0.16,0.0038,0.00078,-0.093,0.00014,-0.00045,4.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.95,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1590000,1,-0.011,-0.014,0.00014,0.03,0.003,-0.18,0.0065,0.0011,-0.11,0.00014,-0.00045,4.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,0.03,0.03,0.00042,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1690000,1,-0.011,-0.014,0.00011,0.027,-0.00043,-0.19,0.0045,0.00056,-0.13,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1790000,1,-0.011,-0.014,7.5e-05,0.034,-0.0024,-0.2,0.0076,0.00042,-0.15,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1890000,1,-0.011,-0.015,5.5e-05,0.042,-0.0036,-0.22,0.011,0.00011,-0.17,0.00019,-0.00088,8.1e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,0.031,0.031,0.00042,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0
1990000,1,-0.011,-0.014,4.7e-05,0.035,-0.005,-0.23,0.0082,-0.00039,-0.19,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.024,0.024,0.00033,1.3,1.3,2,0.2,0.2,4.7,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2090000,1,-0.011,-0.014,6.8e-06,0.04,-0.0076,-0.24,0.012,-0.001,-0.22,0.0002,-0.0014,1.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.026,0.026,0.00037,1.7,1.7,2.1,0.31,0.31,5.3,0.0066,0.0066,0.00011,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2190000,1,-0.011,-0.014,-1.2e-06,0.032,-0.007,-0.26,0.0079,-0.0011,-0.24,0.00014,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.02,0.02,0.0003,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2290000,1,-0.011,-0.014,-1.7e-05,0.038,-0.0095,-0.27,0.011,-0.0019,-0.27,0.00014,-0.002,1.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2390000,1,-0.011,-0.013,-1.9e-05,0.029,-0.0088,-0.29,0.0074,-0.0016,-0.3,5.4e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.016,0.016,0.00027,1,1,2.1,0.19,0.19,7.4,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2490000,1,-0.011,-0.013,-4e-05,0.034,-0.011,-0.3,0.011,-0.0025,-0.32,5.4e-05,-0.0025,2.2e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.017,0.017,0.0003,1.3,1.3,2.1,0.28,0.28,8.2,0.0045,0.0045,7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2590000,1,-0.011,-0.013,-4.3e-05,0.026,-0.009,-0.31,0.0067,-0.0018,-0.36,-5.5e-05,-0.0029,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2690000,1,-0.011,-0.013,-5e-05,0.029,-0.011,-0.33,0.0095,-0.0028,-0.39,-5.5e-05,-0.0029,2.6e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.014,0.014,0.00027,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2790000,1,-0.011,-0.013,-7.1e-05,0.022,-0.0093,-0.34,0.0061,-0.002,-0.42,-0.00017,-0.0033,2.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2890000,1,-0.011,-0.013,-0.00012,0.026,-0.011,-0.35,0.0085,-0.003,-0.46,-0.00017,-0.0033,2.8e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.012,0.012,0.00025,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
2990000,1,-0.011,-0.013,-9.1e-05,0.021,-0.0094,-0.36,0.0056,-0.0021,-0.49,-0.00028,-0.0036,3.1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.009,0.009,0.00021,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3090000,1,-0.011,-0.013,-9.2e-05,0.024,-0.011,-0.38,0.0078,-0.0031,-0.53,-0.00028,-0.0036,3.1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.01,0.0099,0.00023,0.82,0.82,2.2,0.22,0.22,14,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3190000,1,-0.011,-0.013,-0.00016,0.019,-0.0085,-0.39,0.0052,-0.0021,-0.57,-0.00039,-0.0039,3.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0078,0.0078,0.0002,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3290000,1,-0.011,-0.013,-0.00013,0.023,-0.01,-0.4,0.0072,-0.0031,-0.61,-0.00039,-0.0039,3.3e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3390000,1,-0.011,-0.012,-0.00017,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00049,-0.0041,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00019,0.53,0.53,2.3,0.14,0.14,17,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3490000,1,-0.011,-0.013,-0.00018,0.021,-0.012,-0.43,0.0069,-0.0032,-0.69,-0.00049,-0.0041,3.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,0.0076,0.0076,0.0002,0.65,0.65,2.3,0.19,0.19,19,0.0019,0.0019,2.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3590000,1,-0.011,-0.012,-0.00017,0.016,-0.011,-0.44,0.0046,-0.0023,-0.73,-0.0006,-0.0043,3.6e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00018,0.48,0.48,2.4,0.13,0.13,20,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3690000,1,-0.011,-0.012,-4.8e-05,0.019,-0.014,-0.46,0.0065,-0.0036,-0.78,-0.0006,-0.0043,3.6e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0068,0.0067,0.00019,0.59,0.59,2.4,0.18,0.18,21,0.0016,0.0016,2.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3790000,1,-0.011,-0.012,-1.2e-05,0.015,-0.013,-0.47,0.0044,-0.0026,-0.83,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0055,0.0055,0.00017,0.44,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3890000,1,-0.011,-0.012,-5.1e-05,0.017,-0.014,-0.48,0.006,-0.004,-0.87,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.006,0.006,0.00018,0.54,0.54,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
3990000,1,-0.011,-0.012,-5.2e-05,0.021,-0.016,-0.5,0.0079,-0.0056,-0.92,-0.00072,-0.0045,3.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00019,0.66,0.66,2.5,0.22,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4090000,1,-0.011,-0.012,-6.7e-05,0.017,-0.014,-0.51,0.0057,-0.0042,-0.97,-0.00084,-0.0047,4e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.0054,0.0053,0.00017,0.5,0.5,2.5,0.16,0.16,27,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4190000,1,-0.011,-0.012,-9.5e-05,0.02,-0.017,-0.53,0.0076,-0.0057,-1,-0.00084,-0.0047,4e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00018,0.6,0.61,2.5,0.21,0.21,29,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4290000,1,-0.01,-0.012,-0.00015,0.017,-0.012,-0.54,0.0055,-0.0042,-1.1,-0.00096,-0.0049,4.1e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.46,0.46,2.6,0.15,0.15,31,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4390000,1,-0.01,-0.012,-0.00013,0.019,-0.013,-0.55,0.0073,-0.0054,-1.1,-0.00096,-0.0049,4.1e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,0.0052,0.0051,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00095,0.00095,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4490000,1,-0.01,-0.012,-8.4e-05,0.015,-0.01,-0.57,0.0052,-0.0038,-1.2,-0.0011,-0.005,4.3e-05,0,0,-8.6e-05,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,2.6,0.14,0.14,34,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4590000,1,-0.01,-0.012,-6e-05,0.018,-0.012,-0.58,0.0069,-0.0049,-1.2,-0.0011,-0.005,4.3e-05,0,0,-8.6e-05,0,0,0,0,0,0,0,0,0.0045,0.0045,0.00016,0.51,0.51,2.7,0.19,0.19,36,0.00078,0.00078,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4690000,1,-0.01,-0.012,-6.7e-05,0.014,-0.0099,-0.6,0.005,-0.0034,-1.3,-0.0012,-0.0052,4.5e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,0.0037,0.0036,0.00015,0.39,0.39,2.7,0.14,0.14,38,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4790000,1,-0.01,-0.012,-8.1e-05,0.016,-0.011,-0.61,0.0065,-0.0045,-1.4,-0.0012,-0.0052,4.5e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,0.004,0.0039,0.00015,0.47,0.47,2.7,0.18,0.18,40,0.00064,0.00064,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4890000,1,-0.01,-0.012,-0.0001,0.013,-0.01,-0.63,0.0047,-0.0033,-1.4,-0.0013,-0.0053,4.6e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,2.8,0.13,0.13,42,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
4990000,1,-0.01,-0.012,-0.00013,0.016,-0.011,-0.64,0.0061,-0.0043,-1.5,-0.0013,-0.0053,4.6e-05,0,0,-7.7e-05,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00015,0.43,0.43,2.8,0.17,0.17,44,0.00052,0.00052,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5090000,1,-0.01,-0.011,-9.3e-05,0.012,-0.0085,-0.66,0.0044,-0.0031,-1.6,-0.0013,-0.0054,4.7e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,2.8,0.12,0.12,46,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5190000,1,-0.01,-0.011,-7.1e-05,0.014,-0.0099,-0.67,0.0057,-0.0041,-1.6,-0.0013,-0.0054,4.7e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.003,0.003,0.00014,0.39,0.39,2.9,0.16,0.16,49,0.00042,0.00042,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5290000,1,-0.01,-0.011,-9e-05,0.0095,-0.0074,-0.68,0.004,-0.0029,-1.7,-0.0014,-0.0055,4.8e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00013,0.3,0.3,2.9,0.12,0.12,51,0.00034,0.00034,9.2e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5390000,1,-0.0099,-0.011,-3.7e-05,0.009,-0.0083,-0.7,0.0049,-0.0037,-1.8,-0.0014,-0.0055,4.8e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00014,0.36,0.36,2.9,0.16,0.16,53,0.00034,0.00034,9.2e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5490000,1,-0.0098,-0.011,-3.4e-05,0.0063,-0.0064,-0.71,0.0033,-0.0026,-1.8,-0.0014,-0.0055,4.9e-05,0,0,-6.5e-05,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,3,0.11,0.11,56,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5590000,1,-0.0098,-0.011,-5.9e-05,0.0071,-0.0068,-0.73,0.004,-0.0033,-1.9,-0.0014,-0.0055,4.9e-05,0,0,-6.5e-05,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00013,0.33,0.33,3,0.15,0.15,58,0.00028,0.00027,8.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5690000,1,-0.0096,-0.011,6.5e-06,0.005,-0.0041,-0.74,0.0027,-0.0023,-2,-0.0015,-0.0056,4.9e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,3.1,0.11,0.11,61,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5790000,1,-0.0096,-0.011,-1.7e-06,0.0054,-0.0031,-0.75,0.0032,-0.0026,-2,-0.0015,-0.0056,4.9e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5890000,1,-0.0095,-0.011,-3.2e-05,0.0046,-0.0013,0.0028,0.0022,-0.0017,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
5990000,1,-0.0095,-0.011,-1.4e-05,0.005,0.00017,0.015,0.0027,-0.0017,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-7.2e-05,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6090000,1,-0.0094,-0.011,-3.3e-05,0.0061,0.0013,-0.011,0.0033,-0.0016,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6190000,0.7,0.0013,-0.015,0.71,0.0037,0.0028,-0.005,0.0023,-0.00067,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-8.7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0013,0.018,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6290000,0.7,0.0013,-0.015,0.71,0.0036,0.0042,-0.012,0.0027,-0.00029,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6390000,0.7,0.0014,-0.014,0.71,0.0026,0.0047,-0.05,0.003,0.00016,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-3.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6490000,0.7,0.0014,-0.015,0.71,0.0024,0.0055,-0.052,0.0033,0.0007,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-8.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6590000,0.7,0.0014,-0.015,0.71,0.0019,0.0057,-0.099,0.0035,0.0013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,9.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6690000,0.7,0.0014,-0.014,0.71,0.0024,0.0067,-0.076,0.0037,0.0019,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6790000,0.7,0.0014,-0.014,0.71,0.0011,0.0067,-0.11,0.0039,0.0026,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,9e-06,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6890000,0.7,0.0014,-0.014,0.71,-0.0009,0.0073,-0.12,0.0038,0.0033,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-4.2e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
6990000,0.71,0.0015,-0.014,0.71,-0.00092,0.0082,-0.12,0.0037,0.0041,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7090000,0.71,0.0015,-0.014,0.71,-0.0015,0.0079,-0.13,0.0036,0.0049,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7190000,0.71,0.0015,-0.014,0.71,-0.0031,0.0081,-0.15,0.0033,0.0057,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.0015,0.0015,0.018,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7290000,0.71,0.0015,-0.014,0.71,-0.0046,0.0084,-0.15,0.0029,0.0065,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0015,0.018,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
7390000,0.71,0.0015,-0.014,0.71,-0.0046,0.0099,-0.16,0.0025,0.0073,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7490000,0.71,0.0016,-0.014,0.71,-0.0062,0.01,-0.16,0.0019,0.0084,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7590000,0.71,0.0016,-0.014,0.71,-0.0081,0.012,-0.17,0.0011,0.0093,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.51,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7690000,0.71,0.0017,-0.014,0.71,-0.0099,0.012,-0.16,0.0002,0.01,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7790000,0.71,0.0017,-0.014,0.71,-0.011,0.013,-0.16,-0.00088,0.012,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
7890000,0.71,0.0017,-0.014,0.71,-0.014,0.015,-0.16,-0.0022,0.013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.65,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0
7990000,0.71,0.0017,-0.014,0.71,-0.016,0.016,-0.16,-0.0037,0.014,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0018,0.0018,0.018,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0
8090000,0.71,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.0054,0.016,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0
8190000,0.71,0.0017,-0.014,0.71,-0.02,0.019,-0.18,-0.0073,0.018,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0
8290000,0.71,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.0094,0.019,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.002,0.002,0.018,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.036,0,0,0,0,0,0,0,0
8390000,0.71,0.0018,-0.014,0.71,-0.024,0.021,-0.17,-0.012,0.021,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.002,0.018,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.035,0,0,0,0,0,0,0,0
8490000,0.71,0.0018,-0.014,0.71,-0.026,0.023,-0.17,-0.014,0.022,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,0.0021,0.0021,0.018,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0
8590000,0.71,0.0019,-0.014,0.71,-0.028,0.025,-0.17,-0.017,0.025,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0
8690000,0.71,0.0019,-0.014,0.71,-0.031,0.026,-0.16,-0.02,0.026,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.033,0,0,0,0,0,0,0,0
8790000,0.71,0.0019,-0.014,0.71,-0.033,0.027,-0.15,-0.023,0.028,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,6.3e-06,0.04,0.04,0.032,0,0,0,0,0,0,0,0
8890000,0.71,0.0019,-0.014,0.71,-0.035,0.028,-0.15,-0.026,0.03,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.03,0,0,0,0,0,0,0,0
8990000,0.71,0.0019,-0.014,0.71,-0.037,0.029,-0.14,-0.03,0.032,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,6.3e-06,0.04,0.04,0.029,0,0,0,0,0,0,0,0
9090000,0.71,0.002,-0.014,0.71,-0.039,0.029,-0.14,-0.033,0.034,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.028,0,0,0,0,0,0,0,0
9190000,0.71,0.002,-0.014,0.71,-0.041,0.03,-0.14,-0.037,0.036,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.027,0,0,0,0,0,0,0,0
9290000,0.71,0.002,-0.014,0.71,-0.041,0.031,-0.14,-0.04,0.037,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0025,0.018,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.025,0,0,0,0,0,0,0,0
9390000,0.71,0.0019,-0.014,0.71,-0.043,0.033,-0.14,-0.044,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.7,1.7,0.093,5.8,5.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.024,0,0,0,0,0,0,0,0
9490000,0.71,0.0019,-0.014,0.71,-0.044,0.033,-0.13,-0.046,0.041,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0025,0.018,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.023,0,0,0,0,0,0,0,0
9590000,0.71,0.002,-0.014,0.71,-0.047,0.034,-0.13,-0.051,0.044,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.021,0,0,0,0,0,0,0,0
9690000,0.71,0.002,-0.014,0.71,-0.047,0.035,-0.12,-0.052,0.044,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.02,0,0,0,0,0,0,0,0
9790000,0.71,0.002,-0.014,0.71,-0.047,0.037,-0.11,-0.058,0.047,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.019,0,0,0,0,0,0,0,0
9890000,0.71,0.002,-0.014,0.71,-0.047,0.038,-0.11,-0.058,0.047,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.018,0,0,0,0,0,0,0,0
9990000,0.71,0.0021,-0.014,0.71,-0.049,0.038,-0.1,-0.063,0.051,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0028,0.018,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.017,0,0,0,0,0,0,0,0
10090000,0.71,0.0021,-0.014,0.71,-0.048,0.037,-0.096,-0.063,0.05,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.016,0,0,0,0,0,0,0,0
10190000,0.71,0.0021,-0.014,0.71,-0.05,0.04,-0.096,-0.068,0.053,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0028,0.0028,0.018,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0
10290000,0.71,0.0021,-0.014,0.71,-0.051,0.041,-0.084,-0.074,0.057,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0029,0.018,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0
10390000,0.71,0.002,-0.014,0.71,0.0095,-0.019,0.0096,0.00086,-0.0017,-3.7e+02,-0.0015,-0.0056,4.8e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.003,0.003,0.018,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.013,0,0,0,0,0,0,0,0
10490000,0.71,0.0021,-0.014,0.71,0.0083,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,4.8e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
10590000,0.71,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00078,-3.7e+02,-0.0015,-0.0056,4.8e-05,-0.00027,2.9e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
10690000,0.71,0.0022,-0.014,0.71,0.0058,-0.0059,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,4.8e-05,-0.00027,3e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0032,0.0032,0.018,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
10790000,0.71,0.0022,-0.014,0.71,0.0053,-0.0031,0.024,0.0026,-0.00069,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0031,0.0031,0.018,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
10890000,0.71,0.0022,-0.014,0.71,0.0041,-0.0018,0.02,0.0031,-0.00089,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0032,0.0032,0.018,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
10990000,0.71,0.0021,-0.014,0.71,0.0068,0.0033,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00075,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0029,0.018,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
11090000,0.71,0.0022,-0.014,0.71,0.0057,0.0058,0.019,0.0053,-0.0017,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00083,0.00075,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.003,0.003,0.018,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
11190000,0.71,0.002,-0.014,0.71,0.011,0.0083,0.0077,0.0067,-0.0027,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0026,0.018,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11290000,0.71,0.0021,-0.014,0.71,0.01,0.011,0.0074,0.0077,-0.0017,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.0027,0.018,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11390000,0.71,0.0021,-0.014,0.71,0.0054,0.0091,0.0017,0.0055,-0.0018,-3.7e+02,-0.0013,-0.0056,4.5e-05,-0.00051,0.00086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0022,0.018,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11490000,0.71,0.0022,-0.014,0.71,0.0029,0.012,0.0025,0.0059,-0.00078,-3.7e+02,-0.0013,-0.0056,4.5e-05,-0.00052,0.00087,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0023,0.018,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
11590000,0.71,0.002,-0.014,0.71,-0.0015,0.01,-0.0034,0.0044,-0.0013,-3.7e+02,-0.0014,-0.0056,4.5e-05,-9.8e-05,0.00074,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11690000,0.71,0.002,-0.014,0.71,-0.0043,0.013,-0.0079,0.0041,-0.00012,-3.7e+02,-0.0014,-0.0056,4.5e-05,-8.8e-05,0.00074,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.0019,0.018,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11790000,0.71,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0017,0.00069,-3.7e+02,-0.0014,-0.0056,4.6e-05,1.9e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11890000,0.71,0.0021,-0.014,0.71,-0.011,0.014,-0.011,0.00063,0.002,-3.7e+02,-0.0014,-0.0056,4.6e-05,1.3e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.0016,0.018,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
11990000,0.71,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.00043,0.0024,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00015,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12090000,0.71,0.0021,-0.014,0.71,-0.014,0.016,-0.022,-0.0018,0.0039,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00017,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0014,0.0014,0.018,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12190000,0.71,0.0017,-0.014,0.71,-0.0079,0.013,-0.017,0.0013,0.0021,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00042,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,0.0012,0.018,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12290000,0.71,0.0017,-0.014,0.71,-0.01,0.015,-0.016,0.0004,0.0035,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00039,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0013,0.0012,0.018,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12390000,0.71,0.0014,-0.014,0.71,-0.005,0.011,-0.015,0.0029,0.0018,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00055,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12490000,0.71,0.0014,-0.014,0.71,-0.0062,0.013,-0.018,0.0023,0.003,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00055,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,0.0011,0.018,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
12590000,0.71,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0029,0.0016,-3.7e+02,-0.0013,-0.0058,4.2e-05,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.001,0.001,0.018,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0
12690000,0.71,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0043,0.0028,-3.7e+02,-0.0013,-0.0058,4.2e-05,0.00071,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.001,0.001,0.018,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0
12790000,0.71,0.0015,-0.013,0.71,-0.02,0.0091,-0.03,-0.0077,0.0014,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00075,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00094,0.00094,0.018,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0
12890000,0.71,0.0015,-0.013,0.71,-0.021,0.009,-0.029,-0.0097,0.0023,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00097,0.00097,0.018,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0
12990000,0.71,0.0012,-0.014,0.71,-0.0083,0.0065,-0.03,-0.0011,0.0013,-3.7e+02,-0.0012,-0.0059,4e-05,0.00067,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
13090000,0.71,0.0012,-0.014,0.71,-0.009,0.0066,-0.03,-0.002,0.0019,-3.7e+02,-0.0012,-0.0059,4e-05,0.00064,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00092,0.00092,0.018,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
13190000,0.71,0.00091,-0.014,0.71,9.3e-05,0.006,-0.027,0.0043,0.0013,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00049,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
13290000,0.71,0.00092,-0.014,0.71,-0.00015,0.0069,-0.024,0.0043,0.0019,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00036,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00089,0.00089,0.018,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
13390000,0.71,0.00077,-0.014,0.71,0.00066,0.0059,-0.02,0.0033,0.0012,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.00019,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0
13490000,0.71,0.0008,-0.014,0.71,0.00017,0.0057,-0.019,0.0033,0.0017,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0001,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00086,0.00086,0.018,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0
13590000,0.71,0.00074,-0.014,0.71,0.00042,0.006,-0.021,0.0024,0.0011,-3.7e+02,-0.0012,-0.006,3.7e-05,7.6e-05,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0
13690000,0.71,0.00072,-0.014,0.71,0.0011,0.0077,-0.025,0.0024,0.0018,-3.7e+02,-0.0012,-0.006,3.7e-05,0.0001,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00084,0.00084,0.018,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0
13790000,0.71,0.0006,-0.014,0.71,0.0017,0.0036,-0.027,0.0035,-0.00055,-3.7e+02,-0.0011,-0.006,3.6e-05,-0.00011,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.0008,0.018,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0
13890000,0.71,0.00057,-0.014,0.71,0.0022,0.0035,-0.031,0.0037,-0.00022,-3.7e+02,-0.0011,-0.006,3.6e-05,-8.4e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00083,0.00083,0.018,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0
13990000,0.71,0.0005,-0.014,0.71,0.0024,0.00097,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00035,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0
14090000,0.71,0.00048,-0.014,0.71,0.0025,0.0011,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00082,0.00082,0.018,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0
14190000,0.71,0.00038,-0.014,0.71,0.0059,0.00056,-0.033,0.0068,-0.0016,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00032,0.00086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0
14290000,0.71,0.00039,-0.014,0.71,0.0066,0.0013,-0.032,0.0074,-0.0015,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00039,0.00092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00081,0.00081,0.018,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0
14390000,0.71,0.00031,-0.014,0.71,0.0084,0.0022,-0.034,0.0087,-0.0013,-3.7e+02,-0.0011,-0.006,3.3e-05,-0.0004,0.00066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.018,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0
14490000,0.71,0.00029,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.00099,-3.7e+02,-0.0011,-0.006,3.3e-05,-0.00035,0.00062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0
14590000,0.71,0.00028,-0.013,0.71,0.005,0.0019,-0.037,0.006,-0.0024,-3.7e+02,-0.0011,-0.0061,3.4e-05,-0.00072,0.001,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0
14690000,0.71,0.00024,-0.013,0.71,0.0063,-0.0011,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.4e-05,-0.00083,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0
14790000,0.71,0.00027,-0.013,0.71,0.0031,-0.0026,-0.03,0.0038,-0.0034,-3.7e+02,-0.0012,-0.0061,3.5e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.018,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0
14890000,0.71,0.00026,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-0.0012,-0.0061,3.5e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00079,0.00079,0.018,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0
14990000,0.71,0.00026,-0.013,0.71,0.0034,-0.0019,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.018,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0
15090000,0.71,0.00018,-0.013,0.71,0.0038,-0.002,-0.032,0.0036,-0.0031,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00078,0.019,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0
15190000,0.71,0.0002,-0.013,0.71,0.0032,-0.00081,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00075,0.00075,0.019,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0
15290000,0.71,0.00016,-0.013,0.71,0.0037,-0.00066,-0.027,0.0032,-0.0025,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00077,0.00077,0.019,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0
15390000,0.71,0.00017,-0.013,0.71,0.003,-0.00031,-0.024,0.00061,-0.002,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0014,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00074,0.00074,0.019,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.3e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0
15490000,0.71,0.00019,-0.013,0.71,0.0042,-0.00071,-0.024,0.00099,-0.0021,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00076,0.019,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.3e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0
15590000,0.71,0.0002,-0.013,0.71,0.0023,-0.0007,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0
15690000,0.71,0.0002,-0.013,0.71,0.0026,-0.00088,-0.023,-0.001,-0.0018,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00074,0.00074,0.019,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0
15790000,0.71,0.00016,-0.013,0.71,0.0031,-0.0025,-0.026,-0.00091,-0.0028,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00071,0.00071,0.019,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0
15890000,0.71,0.00012,-0.013,0.71,0.004,-0.003,-0.024,-0.00052,-0.0031,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00073,0.00073,0.019,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0
15990000,0.71,6.1e-05,-0.013,0.71,0.0039,-0.0039,-0.019,-0.00059,-0.0039,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0019,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0
16090000,0.71,6.3e-05,-0.013,0.71,0.0056,-0.0042,-0.016,-0.00011,-0.0043,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.002,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00071,0.00072,0.019,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0
16190000,0.71,8.9e-05,-0.013,0.71,0.0056,-0.0034,-0.014,-0.00032,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0
16290000,0.71,0.00011,-0.013,0.71,0.0072,-0.0042,-0.016,0.00035,-0.0039,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0018,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0007,0.0007,0.019,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0
16390000,0.71,9.8e-05,-0.013,0.71,0.0061,-0.0044,-0.015,9.6e-06,-0.0031,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00067,0.00067,0.019,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0
16490000,0.71,0.00012,-0.013,0.71,0.0053,-0.004,-0.018,0.00055,-0.0035,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00068,0.00068,0.019,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0
16590000,0.71,0.00037,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0024,-0.00012,-3.7e+02,-0.0013,-0.006,4e-05,-0.001,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00065,0.019,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0
16690000,0.71,0.00036,-0.013,0.71,0.0019,-0.00078,-0.015,-0.0022,-0.00022,-3.7e+02,-0.0013,-0.006,4e-05,-0.0011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00067,0.00067,0.019,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0
16790000,0.71,0.00051,-0.013,0.71,-0.0014,0.0014,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0005,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00064,0.00064,0.019,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0
16890000,0.71,0.00053,-0.013,0.71,-0.0017,0.0023,-0.011,-0.0047,0.0027,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00053,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00065,0.00065,0.019,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0
16990000,0.71,0.00046,-0.013,0.71,-0.0016,0.0003,-0.01,-0.0052,0.00082,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00094,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00062,0.00062,0.019,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
17090000,0.71,0.00043,-0.013,0.71,-0.00088,0.0012,-0.01,-0.0053,0.00088,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00094,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00063,0.00063,0.019,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0
17190000,0.71,0.00042,-0.013,0.71,-0.00041,0.0012,-0.011,-0.0056,-0.00054,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0013,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0006,0.0006,0.019,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0
17290000,0.71,0.00039,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0055,-0.00037,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00061,0.00061,0.019,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0
17390000,0.71,0.00036,-0.013,0.71,0.0023,0.0014,-0.0047,-0.0046,-0.0016,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00059,0.00059,0.019,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
17490000,0.71,0.00035,-0.013,0.71,0.0029,0.001,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0006,0.0006,0.019,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0
17590000,0.71,0.00027,-0.013,0.71,0.0041,-0.00016,0.0025,-0.0036,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00057,0.00057,0.019,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
17690000,0.71,0.00024,-0.013,0.71,0.005,0.00055,0.0019,-0.0032,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00058,0.00058,0.019,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0
17790000,0.71,0.00015,-0.013,0.71,0.0076,0.00028,0.0006,-0.002,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00055,0.019,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
17890000,0.71,0.00016,-0.013,0.71,0.0091,-0.00049,0.0007,-0.0012,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0
17990000,0.71,0.0001,-0.013,0.71,0.011,-0.0022,0.0019,-0.00045,-0.0019,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00054,0.00054,0.019,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0
18090000,0.71,0.00011,-0.013,0.71,0.011,-0.0024,0.0043,0.00067,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00055,0.00055,0.019,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0
18190000,0.71,7.7e-05,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0018,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00053,0.019,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0
18290000,0.71,1.7e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0019,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0018,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0
18390000,0.71,3.5e-05,-0.013,0.71,0.013,-0.00023,0.008,0.0033,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0
18490000,0.71,5e-05,-0.012,0.71,0.014,0.00018,0.0076,0.0047,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00052,0.00052,0.019,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0
18590000,0.71,5.7e-05,-0.012,0.71,0.013,0.00043,0.0058,0.0036,-0.0012,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0
18690000,0.71,2.6e-05,-0.012,0.71,0.014,-0.00027,0.0039,0.005,-0.0012,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00051,0.00051,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0
18790000,0.71,5.5e-05,-0.012,0.71,0.012,4.2e-05,0.0035,0.0038,-0.00092,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0
18890000,0.71,8.1e-05,-0.012,0.71,0.013,0.00053,0.0042,0.0051,-0.00085,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0
18990000,0.71,6.9e-05,-0.012,0.71,0.014,0.0014,0.0028,0.0064,-0.00069,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0
19090000,0.71,5.4e-05,-0.012,0.71,0.015,0.002,0.0059,0.0078,-0.00049,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0
19190000,0.71,5.7e-05,-0.012,0.71,0.015,0.002,0.0059,0.0086,-0.00044,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0
19290000,0.71,7.9e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00026,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0
19390000,0.71,9.2e-05,-0.012,0.71,0.012,0.00037,0.012,0.0081,-0.00028,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0
19490000,0.71,0.00012,-0.012,0.71,0.012,-0.00035,0.0088,0.0093,-0.00029,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0
19590000,0.71,0.00017,-0.012,0.71,0.0096,-0.0014,0.0081,0.0075,-0.00032,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0
19690000,0.71,0.00017,-0.012,0.71,0.01,-0.0036,0.0096,0.0085,-0.00059,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00045,0.00045,0.019,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0
19790000,0.71,0.00023,-0.012,0.71,0.0077,-0.0044,0.01,0.0069,-0.00049,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00044,0.019,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
19890000,0.71,0.00018,-0.012,0.71,0.0064,-0.0047,0.011,0.0076,-0.00096,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00044,0.00044,0.019,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
19990000,0.71,0.00017,-0.012,0.71,0.004,-0.0054,0.014,0.0061,-0.00082,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20090000,0.71,0.00017,-0.012,0.71,0.0038,-0.0073,0.014,0.0065,-0.0015,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20190000,0.71,0.00028,-0.012,0.71,0.0014,-0.008,0.017,0.0042,-0.0012,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20290000,0.71,0.00024,-0.012,0.71,0.00031,-0.0096,0.015,0.0043,-0.0021,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00043,0.00043,0.019,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20390000,0.71,0.00026,-0.012,0.71,-0.0022,-0.01,0.017,0.0024,-0.0016,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0015,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20490000,0.71,0.00031,-0.012,0.71,-0.0026,-0.011,0.016,0.0021,-0.0027,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0015,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00042,0.00042,0.019,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20590000,0.71,0.00033,-0.012,0.71,-0.0023,-0.011,0.013,0.0018,-0.0022,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20690000,0.71,0.00036,-0.012,0.71,-0.0023,-0.012,0.015,0.0016,-0.0033,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,2e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20790000,0.71,0.00039,-0.012,0.71,-0.0034,-0.011,0.015,0.0013,-0.0027,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.0004,0.019,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.00097,-0.0039,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0026,-0.0033,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00095,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
21090000,0.71,0.00038,-0.012,0.71,-0.0042,-0.017,0.015,0.0022,-0.0048,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00096,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
21190000,0.71,0.00042,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.004,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00071,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0033,-0.0056,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0007,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.0004,0.019,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21390000,0.71,0.00051,-0.012,0.71,-0.0047,-0.017,0.016,0.0028,-0.0036,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00032,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21490000,0.71,0.00052,-0.012,0.71,-0.0052,-0.018,0.015,0.0023,-0.0054,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00033,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21590000,0.71,0.00054,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0033,-3.7e+02,-0.0014,-0.006,4.4e-05,2.7e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00038,0.02,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21690000,0.71,0.00055,-0.012,0.71,-0.0057,-0.017,0.017,0.0013,-0.005,-3.7e+02,-0.0014,-0.006,4.4e-05,2.6e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00039,0.02,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,3.8e-05,-0.0009,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00055,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21890000,0.71,0.00058,-0.012,0.71,-0.0063,-0.012,0.016,-0.00059,-0.0021,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00055,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
21990000,0.71,0.00063,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00099,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22090000,0.71,0.00064,-0.012,0.71,-0.0071,-0.0082,0.015,-0.0022,0.00049,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22190000,0.71,0.00061,-0.012,0.71,-0.0069,-0.0073,0.015,-0.0018,0.00048,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22290000,0.71,0.00065,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0026,-0.00031,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00038,0.00037,0.02,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22390000,0.71,0.00063,-0.012,0.71,-0.0088,-0.0075,0.017,-0.0022,-0.00028,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22490000,0.71,0.00063,-0.012,0.71,-0.0095,-0.0075,0.018,-0.0032,-0.0011,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22590000,0.71,0.00061,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,3.9e-05,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22690000,0.71,0.00065,-0.012,0.71,-0.01,-0.0067,0.018,-0.0044,-0.00064,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00051,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00036,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0051,0.021,-0.0067,-0.001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
22990000,0.71,0.00063,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00093,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0015,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.00036,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23190000,0.71,0.00066,-0.012,0.71,-0.014,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23290000,0.71,0.0006,-0.012,0.71,-0.015,-0.0078,0.024,-0.014,-0.0021,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23390000,0.71,0.00069,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23490000,0.71,0.0031,-0.0096,0.71,-0.022,-0.0089,-0.012,-0.018,-0.0027,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23590000,0.71,0.0083,-0.0018,0.71,-0.031,-0.0073,-0.044,-0.017,-0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23690000,0.71,0.0079,0.004,0.71,-0.061,-0.015,-0.094,-0.021,-0.0025,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23790000,0.71,0.005,0.00066,0.71,-0.086,-0.026,-0.15,-0.021,-0.0019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.002,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23890000,0.71,0.0024,-0.0054,0.71,-0.1,-0.036,-0.2,-0.031,-0.0052,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.002,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
23990000,0.7,0.00098,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0084,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24090000,0.7,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.019,0.0078,0.045,0.045,0.035,6.8e-07,6.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24190000,0.7,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0077,0.04,0.04,0.035,6.5e-07,6.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24290000,0.7,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24190000,0.7,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.047,-0.014,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0077,0.04,0.04,0.035,6.5e-07,6.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24290000,0.7,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.019,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24390000,0.7,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24490000,0.7,0.0047,-0.0018,0.71,-0.14,-0.058,-0.51,-0.077,-0.036,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24590000,0.7,0.0052,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24690000,0.7,0.0052,0.0028,0.71,-0.18,-0.083,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24790000,0.7,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24890000,0.7,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.074,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24990000,0.7,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25090000,0.7,0.0088,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25190000,0.7,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25390000,0.7,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.00021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00035,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.0002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00036,0.02,0.017,0.019,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00035,0.02,0.016,0.018,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0029,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00037,0.02,0.017,0.02,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0037,-0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00039,0.019,0.016,0.019,0.0079,0.04,0.04,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
25890000,0.7,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0037,-0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00039,0.019,0.017,0.021,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
25990000,0.7,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00037,0.019,0.016,0.02,0.0079,0.04,0.04,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00042,0.019,0.017,0.023,0.008,0.044,0.044,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,4e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00046,0.018,0.016,0.022,0.0079,0.039,0.04,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,4e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00047,0.018,0.017,0.025,0.008,0.044,0.045,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26390000,0.7,0.023,0.043,0.71,-0.94,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00044,0.018,0.016,0.024,0.0079,0.039,0.04,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00056,0.018,0.018,0.027,0.008,0.043,0.045,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00096,-0.0059,4.7e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00067,0.017,0.016,0.027,0.008,0.039,0.041,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00096,-0.0059,4.7e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.0007,0.017,0.018,0.032,0.008,0.043,0.046,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26790000,0.7,0.036,0.072,0.71,-1.4,-0.74,-1.3,-1,-0.86,-3.7e+02,-0.00092,-0.006,2.9e-05,0.0021,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.0006,0.015,0.017,0.031,0.008,0.039,0.041,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26890000,0.7,0.044,0.094,0.7,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.006,2.9e-05,0.002,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00081,0.015,0.019,0.037,0.0081,0.043,0.046,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26990000,0.7,0.051,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.006,3e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00096,0.014,0.018,0.036,0.008,0.039,0.042,0.035,4.1e-07,4.3e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0
27090000,0.7,0.052,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.006,3e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.001,0.013,0.02,0.045,0.0081,0.043,0.047,0.035,4.1e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0
27190000,0.71,0.049,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00012,0.0028,-0.023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.0008,0.012,0.02,0.045,0.0081,0.046,0.05,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00012,0.0027,-0.023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00067,0.012,0.022,0.052,0.0081,0.051,0.057,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0
27390000,0.72,0.037,0.077,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00071,-0.0059,0.0002,0.0036,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.0005,0.011,0.021,0.048,0.0081,0.053,0.059,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0
27490000,0.72,0.031,0.062,0.69,-2.4,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00071,-0.0059,0.0002,0.0035,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00043,0.011,0.023,0.052,0.0082,0.058,0.067,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0
27590000,0.72,0.026,0.05,0.69,-2.5,-1.1,-1.2,-2.5,-1.6,-3.7e+02,-0.00072,-0.0059,0.00026,0.0024,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0094,0.021,0.045,0.0082,0.061,0.068,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0
27690000,0.72,0.026,0.048,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.00072,-0.0059,0.00026,0.0023,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0094,0.023,0.046,0.0082,0.067,0.077,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0
27790000,0.72,0.026,0.05,0.69,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00071,-0.0059,0.0003,0.0016,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00035,0.0084,0.021,0.04,0.0082,0.069,0.078,0.035,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0
27890000,0.72,0.025,0.048,0.69,-2.6,-1.2,-1.2,-3.3,-1.9,-3.7e+02,-0.00071,-0.0059,0.0003,0.0015,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00035,0.0084,0.023,0.042,0.0083,0.075,0.087,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0
27990000,0.72,0.025,0.044,0.69,-2.7,-1.2,-1.2,-3.6,-2,-3.7e+02,-0.00074,-0.0059,0.00033,0.00041,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0077,0.022,0.037,0.0083,0.078,0.088,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0
28090000,0.72,0.031,0.057,0.69,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00074,-0.0059,0.00033,0.00028,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0077,0.023,0.038,0.0084,0.085,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0
28190000,0.72,0.036,0.07,0.68,-2.8,-1.2,-0.95,-4.2,-2.2,-3.7e+02,-0.00076,-0.0059,0.00035,-0.00052,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00039,0.0071,0.022,0.034,0.0084,0.087,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0
28290000,0.73,0.028,0.054,0.68,-2.8,-1.2,-0.089,-4.5,-2.4,-3.7e+02,-0.00076,-0.0059,0.00035,-0.0007,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0072,0.022,0.035,0.0086,0.094,0.11,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0
28390000,0.73,0.011,0.023,0.68,-2.8,-1.2,0.77,-4.8,-2.5,-3.7e+02,-0.00076,-0.0059,0.00035,-0.001,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00031,0.0072,0.023,0.036,0.0087,0.1,0.12,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0
28490000,0.73,0.0015,0.0046,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00076,-0.0059,0.00035,-0.0013,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0072,0.024,0.036,0.0088,0.11,0.13,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0
28590000,0.73,-0.00034,0.0012,0.69,-2.7,-1.2,0.96,-5.3,-2.7,-3.7e+02,-0.00075,-0.0059,0.00035,-0.0017,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0073,0.025,0.035,0.0089,0.12,0.14,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0
28690000,0.73,-0.0011,0.00028,0.69,-2.6,-1.2,0.96,-5.6,-2.8,-3.7e+02,-0.00075,-0.0059,0.00035,-0.0021,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0073,0.026,0.035,0.009,0.13,0.15,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0
28790000,0.73,-0.0015,9.4e-05,0.68,-2.6,-1.2,0.97,-5.9,-2.9,-3.7e+02,-0.00081,-0.006,0.00038,-0.0039,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.007,0.025,0.03,0.0089,0.13,0.15,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0
28890000,0.73,-0.0015,0.00032,0.69,-2.5,-1.2,0.96,-6.1,-3.1,-3.7e+02,-0.00081,-0.006,0.00038,-0.0043,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.007,0.026,0.03,0.009,0.14,0.16,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0
28990000,0.73,-0.0014,0.00081,0.68,-2.5,-1.1,0.95,-6.5,-3.2,-3.7e+02,-0.00089,-0.006,0.0004,-0.0052,-0.03,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.14,0.16,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0
29090000,0.73,-0.0013,0.0012,0.68,-2.4,-1.1,0.94,-6.7,-3.3,-3.7e+02,-0.00089,-0.006,0.0004,-0.0057,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.009,0.15,0.17,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0
29190000,0.73,-0.0011,0.0017,0.68,-2.4,-1.1,0.93,-7,-3.4,-3.7e+02,-0.00093,-0.006,0.00041,-0.0067,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.15,0.17,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
29290000,0.73,-0.00074,0.0025,0.68,-2.3,-1.1,0.96,-7.3,-3.5,-3.7e+02,-0.00093,-0.006,0.00041,-0.0073,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.026,0.0091,0.16,0.18,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
29390000,0.73,-0.00021,0.004,0.68,-2.3,-1.1,0.97,-7.6,-3.6,-3.7e+02,-0.00099,-0.006,0.00041,-0.0081,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.16,0.18,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0
29490000,0.73,0.00032,0.0051,0.68,-2.2,-1.1,0.97,-7.8,-3.7,-3.7e+02,-0.00099,-0.006,0.00041,-0.0086,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.026,0.0091,0.17,0.19,0.037,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0
29590000,0.73,0.00073,0.0063,0.68,-2.2,-1.1,0.96,-8.1,-3.8,-3.7e+02,-0.001,-0.006,0.00039,-0.011,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.024,0.025,0.009,0.17,0.19,0.036,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0
29690000,0.73,0.001,0.0069,0.68,-2.2,-1.1,0.95,-8.3,-3.9,-3.7e+02,-0.001,-0.006,0.00039,-0.011,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.18,0.2,0.036,3.7e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0
29790000,0.73,0.0013,0.0075,0.68,-2.2,-1.1,0.94,-8.6,-4,-3.7e+02,-0.0011,-0.006,0.00038,-0.013,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.025,0.0091,0.18,0.2,0.037,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0
29890000,0.73,0.0014,0.0077,0.68,-2.1,-1.1,0.92,-8.8,-4.1,-3.7e+02,-0.0011,-0.006,0.00038,-0.013,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.19,0.21,0.037,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
29990000,0.73,0.0016,0.0079,0.68,-2.1,-1.1,0.91,-9,-4.2,-3.7e+02,-0.0011,-0.006,0.00035,-0.015,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.19,0.21,0.036,3.5e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
30090000,0.73,0.0015,0.0078,0.68,-2.1,-1.1,0.89,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,0.00035,-0.016,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.2,0.22,0.036,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
30190000,0.73,0.0016,0.0077,0.68,-2,-1.1,0.88,-9.5,-4.4,-3.7e+02,-0.0011,-0.0059,0.00032,-0.017,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.2,0.22,0.037,3.5e-07,4.1e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
30290000,0.73,0.0015,0.0075,0.68,-2,-1.1,0.87,-9.7,-4.5,-3.7e+02,-0.0011,-0.0059,0.00032,-0.018,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.0091,0.21,0.23,0.037,3.5e-07,4.1e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
30390000,0.73,0.0016,0.0074,0.68,-2,-1,0.85,-9.9,-4.6,-3.7e+02,-0.0012,-0.0059,0.0003,-0.019,-0.027,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.21,0.23,0.036,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
30490000,0.73,0.0014,0.0071,0.68,-2,-1,0.83,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.0003,-0.019,-0.027,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.029,0.0091,0.22,0.24,0.037,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
30590000,0.73,0.0014,0.0068,0.68,-1.9,-1,0.79,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00027,-0.02,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.025,0.028,0.009,0.22,0.24,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
30690000,0.73,0.0012,0.0065,0.68,-1.9,-1,0.79,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00027,-0.021,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.03,0.009,0.23,0.25,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
30790000,0.73,0.0013,0.0062,0.68,-1.9,-1,0.78,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00023,-0.022,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0067,0.025,0.029,0.009,0.23,0.25,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
30890000,0.73,0.0011,0.0058,0.68,-1.9,-1,0.77,-11,-5.1,-3.7e+02,-0.0012,-0.0059,0.00023,-0.022,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0067,0.026,0.031,0.009,0.24,0.26,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
30990000,0.73,0.0011,0.0053,0.68,-1.8,-1,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0059,0.00019,-0.023,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0066,0.025,0.03,0.0089,0.24,0.26,0.036,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
31090000,0.73,0.00088,0.0048,0.68,-1.8,-1,0.75,-11,-5.3,-3.7e+02,-0.0013,-0.0059,0.00019,-0.023,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0067,0.026,0.032,0.009,0.25,0.27,0.037,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
31190000,0.73,0.00089,0.0045,0.68,-1.8,-0.99,0.73,-12,-5.4,-3.7e+02,-0.0013,-0.0059,0.00016,-0.025,-0.019,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0065,0.025,0.03,0.0088,0.25,0.27,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
31290000,0.73,0.00064,0.004,0.68,-1.8,-0.99,0.74,-12,-5.5,-3.7e+02,-0.0013,-0.0059,0.00016,-0.025,-0.017,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0065,0.026,0.032,0.0089,0.26,0.28,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
31390000,0.73,0.00059,0.0035,0.68,-1.7,-0.98,0.73,-12,-5.6,-3.7e+02,-0.0013,-0.0059,0.00013,-0.026,-0.015,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0064,0.025,0.031,0.0088,0.25,0.28,0.036,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
31490000,0.73,0.00036,0.0029,0.68,-1.7,-0.98,0.73,-12,-5.7,-3.7e+02,-0.0013,-0.0059,0.00013,-0.027,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0064,0.026,0.033,0.0088,0.27,0.29,0.037,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
31590000,0.73,0.0004,0.0025,0.69,-1.7,-0.96,0.72,-12,-5.7,-3.7e+02,-0.0013,-0.0058,9.2e-05,-0.027,-0.012,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0062,0.025,0.031,0.0087,0.26,0.29,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31690000,0.73,0.00013,0.0019,0.69,-1.7,-0.95,0.73,-13,-5.8,-3.7e+02,-0.0013,-0.0058,9.1e-05,-0.028,-0.011,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0063,0.027,0.033,0.0088,0.28,0.3,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31790000,0.73,2.9e-05,0.0012,0.69,-1.6,-0.94,0.72,-13,-5.9,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.028,-0.0093,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0061,0.025,0.031,0.0087,0.27,0.3,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31890000,0.73,-0.00024,0.00056,0.69,-1.6,-0.93,0.72,-13,-6,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.029,-0.008,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0061,0.027,0.034,0.0087,0.29,0.31,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31990000,0.73,-0.00028,6.4e-05,0.69,-1.6,-0.91,0.71,-13,-6.1,-3.7e+02,-0.0014,-0.0058,2e-05,-0.03,-0.0061,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0059,0.025,0.032,0.0086,0.28,0.31,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
32090000,0.73,-0.00059,-0.00064,0.69,-1.5,-0.91,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,2e-05,-0.03,-0.0045,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0059,0.027,0.034,0.0087,0.29,0.32,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
32190000,0.72,-0.00071,-0.0015,0.69,-1.5,-0.89,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0058,-1.2e-05,-0.031,-0.0023,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0058,0.025,0.032,0.0086,0.29,0.32,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32290000,0.72,-0.00097,-0.0022,0.69,-1.5,-0.89,0.71,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-1.2e-05,-0.032,-0.00072,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0058,0.026,0.034,0.0086,0.3,0.33,0.037,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32390000,0.72,-0.0011,-0.0028,0.69,-1.5,-0.87,0.71,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.032,0.00022,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00034,0.0056,0.025,0.032,0.0085,0.3,0.33,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32490000,0.72,-0.0012,-0.0031,0.69,-1.4,-0.86,0.72,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.032,0.0014,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0056,0.026,0.034,0.0086,0.31,0.34,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32590000,0.72,-0.0011,-0.0033,0.69,-1.4,-0.85,0.71,-14,-6.6,-3.7e+02,-0.0014,-0.0058,-5.7e-05,-0.032,0.0022,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0054,0.025,0.032,0.0084,0.31,0.34,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32690000,0.72,-0.0012,-0.0034,0.69,-1.4,-0.84,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-5.7e-05,-0.033,0.0028,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00034,0.0055,0.026,0.034,0.0085,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32790000,0.72,-0.001,-0.0034,0.69,-1.3,-0.82,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.033,0.0038,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0053,0.025,0.032,0.0084,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32890000,0.72,-0.00095,-0.0033,0.69,-1.3,-0.82,0.71,-14,-6.8,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.033,0.0049,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0053,0.026,0.034,0.0084,0.33,0.36,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32990000,0.72,-0.00074,-0.0033,0.69,-1.3,-0.8,0.7,-15,-6.9,-3.7e+02,-0.0014,-0.0058,-9.7e-05,-0.034,0.0063,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0051,0.025,0.032,0.0083,0.33,0.36,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
33090000,0.72,-0.00078,-0.0033,0.69,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0058,-9.7e-05,-0.034,0.0068,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0052,0.026,0.034,0.0084,0.34,0.37,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
33190000,0.72,0.0027,-0.0024,0.7,-1.2,-0.78,0.64,-15,-7,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.0076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.005,0.025,0.031,0.0083,0.34,0.37,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
33290000,0.67,0.015,-0.0017,0.75,-1.2,-0.77,0.62,-15,-7.1,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.008,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.005,0.026,0.033,0.0083,0.35,0.38,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0.0025,9.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
33390000,0.56,0.013,-0.0019,0.83,-1.2,-0.75,0.81,-15,-7.2,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.009,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00029,0.00033,0.0049,0.025,0.03,0.0083,0.35,0.38,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0
33490000,0.43,0.0064,0.00074,0.9,-1.2,-0.75,0.83,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0049,0.026,0.032,0.0081,0.36,0.39,0.036,2.8e-07,2.9e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
33590000,0.27,0.00058,-0.0017,0.96,-1.2,-0.74,0.79,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0048,0.026,0.031,0.0078,0.35,0.39,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
33690000,0.1,-0.0027,-0.0046,0.99,-1.1,-0.74,0.8,-15,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00031,0.0049,0.028,0.035,0.0076,0.37,0.4,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
33790000,-0.067,-0.0042,-0.0065,1,-1.1,-0.72,0.78,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00016,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00029,0.0048,0.028,0.034,0.0074,0.36,0.4,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
33890000,-0.23,-0.0053,-0.0072,0.97,-1,-0.7,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00016,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00029,0.0048,0.032,0.039,0.0072,0.38,0.41,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
33990000,-0.38,-0.0035,-0.011,0.92,-0.97,-0.66,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00029,0.0047,0.032,0.039,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0
34090000,-0.49,-0.0024,-0.013,0.87,-0.92,-0.61,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.034,0.0091,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00029,0.0047,0.036,0.044,0.0069,0.39,0.42,0.036,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
34190000,-0.56,-0.0017,-0.011,0.83,-0.9,-0.57,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.0002,-0.037,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.0046,0.037,0.043,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
34290000,-0.6,-0.0026,-0.0085,0.8,-0.85,-0.52,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.0002,-0.037,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.0046,0.043,0.05,0.0066,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
34390000,-0.63,-0.0027,-0.0061,0.78,-0.84,-0.48,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.041,0.016,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00026,0.00026,0.0045,0.042,0.048,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
34490000,-0.65,-0.0036,-0.004,0.76,-0.79,-0.44,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.041,0.016,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00027,0.0045,0.049,0.056,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
34590000,-0.66,-0.003,-0.003,0.76,-0.79,-0.42,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.051,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00023,0.00024,0.0044,0.048,0.053,0.0063,0.4,0.44,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
34690000,-0.66,-0.0034,-0.0022,0.75,-0.73,-0.38,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.051,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00023,0.00024,0.0044,0.055,0.061,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
34790000,-0.67,-0.0023,-0.002,0.75,-0.74,-0.37,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.061,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.00022,0.0044,0.052,0.056,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0
34890000,-0.67,-0.0023,-0.0019,0.74,-0.69,-0.34,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.061,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.00022,0.0044,0.059,0.064,0.0062,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
34990000,-0.67,-0.0086,-0.0047,0.74,0.33,0.25,-0.13,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0043,0.059,0.07,0.0068,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
35090000,-0.67,-0.0087,-0.0047,0.74,0.46,0.27,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.064,0.077,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
35190000,-0.67,-0.0087,-0.0048,0.74,0.48,0.3,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.07,0.083,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
35290000,-0.67,-0.0087,-0.0048,0.74,0.5,0.34,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.075,0.089,0.0066,0.46,0.48,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
35390000,-0.67,-0.0088,-0.0048,0.74,0.53,0.37,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.081,0.095,0.0066,0.47,0.49,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
35490000,-0.67,-0.0088,-0.0048,0.74,0.55,0.4,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.088,0.1,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
35590000,-0.67,-0.0058,-0.005,0.74,0.44,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00017,0.0042,0.07,0.077,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
35690000,-0.67,-0.0058,-0.005,0.74,0.46,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.074,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00017,0.0042,0.075,0.082,0.0061,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
35790000,-0.67,-0.0036,-0.0051,0.74,0.38,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.076,0.053,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00015,0.0041,0.062,0.066,0.0059,0.49,0.51,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0
35890000,-0.67,-0.0036,-0.0051,0.74,0.39,0.33,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.076,0.053,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00015,0.0041,0.067,0.072,0.0059,0.5,0.53,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
35990000,-0.67,-0.0017,-0.0051,0.74,0.32,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.083,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00013,0.004,0.058,0.061,0.0057,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
36090000,-0.67,-0.0018,-0.0051,0.74,0.33,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.083,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00013,0.0041,0.063,0.066,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
36190000,-0.67,-0.0004,-0.005,0.74,0.27,0.26,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.094,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00012,0.004,0.055,0.057,0.0055,0.5,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
36290000,-0.67,-0.00052,-0.005,0.74,0.28,0.28,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.094,0.069,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00012,0.004,0.061,0.063,0.0056,0.52,0.54,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
36390000,-0.67,0.00054,-0.0049,0.74,0.24,0.24,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00011,0.004,0.054,0.055,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
36490000,-0.67,0.00044,-0.0049,0.74,0.24,0.26,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00011,0.0041,0.059,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
36590000,-0.67,0.0012,-0.0048,0.74,0.2,0.22,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9e-05,0.0001,0.0041,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
36690000,-0.67,0.0012,-0.0047,0.74,0.21,0.24,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9e-05,0.0001,0.0041,0.058,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
36790000,-0.67,0.0018,-0.0046,0.74,0.17,0.21,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.13,0.098,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,9.7e-05,0.0041,0.052,0.053,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
36890000,-0.67,0.0017,-0.0046,0.74,0.17,0.22,-0.16,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.13,0.098,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,9.8e-05,0.0041,0.057,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
36990000,-0.67,0.0022,-0.0044,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8e-05,9.3e-05,0.0041,0.051,0.053,0.0056,0.54,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
37090000,-0.67,0.0021,-0.0043,0.74,0.15,0.2,-0.15,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8e-05,9.3e-05,0.0041,0.056,0.058,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
37190000,-0.67,0.0025,-0.0042,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,8.9e-05,0.0041,0.051,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
37290000,-0.67,0.0024,-0.0042,0.74,0.12,0.18,-0.14,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,9e-05,0.0041,0.055,0.057,0.0059,0.56,0.59,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
37390000,-0.67,0.0027,-0.004,0.74,0.097,0.15,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,8.7e-05,0.0042,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
37490000,-0.67,0.0026,-0.004,0.74,0.096,0.16,-0.12,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.5e-05,8.7e-05,0.0042,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
37590000,-0.67,0.0028,-0.0039,0.74,0.076,0.14,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.5e-05,0.0042,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
37690000,-0.67,0.0027,-0.0039,0.74,0.074,0.14,-0.11,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.5e-05,0.0042,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
37790000,-0.67,0.0028,-0.0038,0.74,0.058,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.4e-05,0.0042,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
37890000,-0.67,0.0028,-0.0038,0.74,0.055,0.13,-0.093,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.4e-05,0.0042,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
37990000,-0.67,0.0029,-0.0038,0.74,0.041,0.11,-0.084,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.3e-05,0.0042,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,2.9e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
38090000,-0.67,0.0028,-0.0038,0.74,0.037,0.11,-0.074,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0042,0.05,0.052,0.0066,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
38190000,-0.67,0.0029,-0.0036,0.74,0.024,0.096,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.2e-05,0.0042,0.045,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
38290000,-0.67,0.0028,-0.0036,0.74,0.021,0.097,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0042,0.049,0.05,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
38390000,-0.67,0.0029,-0.0035,0.74,0.013,0.084,-0.051,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.2e-05,0.0042,0.044,0.045,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
38490000,-0.67,0.0028,-0.0035,0.74,0.0096,0.086,-0.044,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
38590000,-0.67,0.0029,-0.0034,0.74,0.0052,0.074,-0.037,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.2e-05,0.0043,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
38690000,-0.67,0.0028,-0.0034,0.74,0.00079,0.074,-0.03,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.046,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
38790000,-0.67,0.0028,-0.0033,0.74,-0.0042,0.062,-0.022,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
38890000,-0.67,0.0026,-0.0034,0.74,-0.014,0.051,0.48,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.22,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.3e-05,0.0043,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
24490000,0.7,0.0047,-0.0017,0.71,-0.14,-0.057,-0.51,-0.078,-0.036,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24590000,0.7,0.0052,0.0019,0.71,-0.15,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24690000,0.7,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.053,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24790000,0.7,0.0049,0.0015,0.71,-0.2,-0.094,-0.72,-0.11,-0.064,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24890000,0.7,0.0067,0.0032,0.71,-0.22,-0.11,-0.75,-0.13,-0.074,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
24990000,0.7,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.082,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25090000,0.7,0.0088,0.0041,0.71,-0.27,-0.12,-0.86,-0.16,-0.094,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25190000,0.7,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00033,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25290000,0.7,0.01,0.0096,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25390000,0.7,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0031,-7e-05,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00035,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25490000,0.7,0.012,0.017,0.71,-0.39,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0031,-5.1e-05,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00036,0.02,0.017,0.019,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25590000,0.7,0.011,0.015,0.71,-0.43,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0028,-0.00096,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00035,0.02,0.016,0.018,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25690000,0.7,0.015,0.022,0.71,-0.48,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0028,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00037,0.02,0.017,0.02,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0036,-0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00039,0.019,0.016,0.019,0.0079,0.04,0.04,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
25890000,0.7,0.017,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0036,-0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00039,0.019,0.017,0.021,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0
25990000,0.7,0.016,0.025,0.71,-0.65,-0.33,-1.3,-0.44,-0.35,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0032,-0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00037,0.019,0.016,0.02,0.0079,0.04,0.04,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26090000,0.7,0.021,0.035,0.71,-0.71,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0032,-0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00042,0.019,0.017,0.023,0.008,0.044,0.044,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26190000,0.7,0.023,0.045,0.71,-0.77,-0.39,-1.3,-0.54,-0.42,-3.7e+02,-0.0011,-0.0059,4e-05,0.0044,-0.0089,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00046,0.018,0.016,0.022,0.0079,0.039,0.04,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26290000,0.7,0.024,0.047,0.71,-0.86,-0.43,-1.3,-0.62,-0.47,-3.7e+02,-0.0011,-0.0059,4e-05,0.0044,-0.0089,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00047,0.018,0.017,0.025,0.008,0.044,0.045,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26390000,0.7,0.023,0.043,0.71,-0.94,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0031,-0.01,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00044,0.018,0.016,0.024,0.0079,0.039,0.04,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0031,-0.01,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00056,0.018,0.018,0.027,0.008,0.043,0.045,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26590000,0.7,0.037,0.075,0.71,-1.1,-0.58,-1.3,-0.83,-0.67,-3.7e+02,-0.00097,-0.0059,4.8e-05,0.0039,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00067,0.017,0.016,0.027,0.008,0.039,0.041,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.95,-0.73,-3.7e+02,-0.00097,-0.0059,4.8e-05,0.0038,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.0007,0.017,0.018,0.032,0.008,0.043,0.046,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26790000,0.7,0.036,0.073,0.71,-1.4,-0.73,-1.3,-1,-0.86,-3.7e+02,-0.00093,-0.006,3e-05,0.0018,-0.016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.0006,0.015,0.017,0.031,0.008,0.039,0.041,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26890000,0.7,0.044,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-0.00093,-0.006,3e-05,0.0017,-0.016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00036,0.00081,0.015,0.019,0.037,0.0081,0.043,0.046,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.3,-1,-3.7e+02,-0.00081,-0.006,3e-05,0.0025,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00096,0.014,0.018,0.036,0.008,0.039,0.042,0.035,4.1e-07,4.3e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-0.00081,-0.006,3e-05,0.0025,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0004,0.001,0.013,0.02,0.045,0.0081,0.043,0.047,0.035,4.1e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0
27190000,0.71,0.049,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.0008,-0.006,0.00012,0.0023,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00037,0.0008,0.012,0.02,0.045,0.0081,0.046,0.05,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.0008,-0.006,0.00012,0.0022,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00035,0.00067,0.012,0.022,0.052,0.0081,0.051,0.057,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0
27390000,0.72,0.037,0.077,0.69,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00073,-0.0059,0.0002,0.0031,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.0005,0.011,0.021,0.048,0.0081,0.053,0.059,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0
27490000,0.72,0.031,0.062,0.69,-2.4,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00073,-0.0059,0.0002,0.003,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00043,0.011,0.023,0.052,0.0082,0.058,0.067,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0
27590000,0.72,0.027,0.05,0.69,-2.5,-1.1,-1.2,-2.6,-1.6,-3.7e+02,-0.00074,-0.0059,0.00026,0.0019,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0094,0.021,0.045,0.0082,0.061,0.068,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0
27690000,0.72,0.026,0.048,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.00074,-0.0059,0.00026,0.0018,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0094,0.023,0.046,0.0082,0.067,0.077,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0
27790000,0.72,0.026,0.05,0.69,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00073,-0.0059,0.0003,0.0011,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00035,0.0084,0.021,0.04,0.0082,0.069,0.078,0.035,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0
27890000,0.72,0.026,0.048,0.69,-2.6,-1.2,-1.2,-3.3,-1.9,-3.7e+02,-0.00073,-0.0059,0.0003,0.00096,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00035,0.0085,0.023,0.042,0.0083,0.075,0.087,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0
27990000,0.72,0.025,0.044,0.69,-2.7,-1.2,-1.2,-3.6,-2,-3.7e+02,-0.00076,-0.0059,0.00033,-0.00012,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0077,0.022,0.037,0.0083,0.078,0.088,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0
28090000,0.72,0.031,0.058,0.69,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00076,-0.0059,0.00033,-0.00026,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00036,0.0077,0.023,0.038,0.0084,0.085,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0
28190000,0.72,0.036,0.071,0.68,-2.8,-1.2,-0.95,-4.2,-2.2,-3.7e+02,-0.00078,-0.006,0.00036,-0.0011,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00039,0.0071,0.022,0.034,0.0084,0.087,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0
28290000,0.73,0.028,0.054,0.68,-2.8,-1.2,-0.09,-4.5,-2.4,-3.7e+02,-0.00078,-0.006,0.00036,-0.0012,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0072,0.022,0.035,0.0086,0.094,0.11,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0
28390000,0.73,0.011,0.023,0.68,-2.8,-1.2,0.77,-4.8,-2.5,-3.7e+02,-0.00078,-0.006,0.00036,-0.0015,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00031,0.0072,0.023,0.036,0.0087,0.1,0.12,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0
28490000,0.73,0.0016,0.0048,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00078,-0.006,0.00036,-0.0018,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0073,0.024,0.036,0.0088,0.11,0.13,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0
28590000,0.73,-0.00027,0.0014,0.69,-2.7,-1.2,0.96,-5.3,-2.7,-3.7e+02,-0.00078,-0.006,0.00036,-0.0022,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0073,0.025,0.035,0.0089,0.12,0.14,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0
28690000,0.73,-0.001,0.00047,0.69,-2.6,-1.2,0.96,-5.6,-2.8,-3.7e+02,-0.00077,-0.006,0.00036,-0.0026,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0073,0.026,0.035,0.009,0.13,0.15,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0
28790000,0.73,-0.0014,0.00029,0.68,-2.6,-1.2,0.97,-5.9,-2.9,-3.7e+02,-0.00083,-0.006,0.00038,-0.0044,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.007,0.025,0.03,0.0089,0.13,0.15,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0
28890000,0.73,-0.0015,0.00052,0.69,-2.5,-1.2,0.96,-6.2,-3.1,-3.7e+02,-0.00083,-0.006,0.00038,-0.0048,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.007,0.026,0.03,0.009,0.14,0.16,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0
28990000,0.73,-0.0014,0.001,0.68,-2.5,-1.1,0.95,-6.5,-3.2,-3.7e+02,-0.00091,-0.006,0.0004,-0.0057,-0.029,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.14,0.16,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0
29090000,0.73,-0.0012,0.0014,0.68,-2.4,-1.1,0.94,-6.7,-3.3,-3.7e+02,-0.00091,-0.006,0.0004,-0.0062,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.009,0.15,0.17,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0
29190000,0.73,-0.001,0.0019,0.68,-2.4,-1.1,0.93,-7,-3.4,-3.7e+02,-0.00096,-0.006,0.00041,-0.0072,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.15,0.17,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
29290000,0.73,-0.00067,0.0027,0.68,-2.3,-1.1,0.96,-7.3,-3.5,-3.7e+02,-0.00095,-0.006,0.00041,-0.0078,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.026,0.0091,0.16,0.18,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0
29390000,0.73,-0.00013,0.0042,0.68,-2.3,-1.1,0.97,-7.6,-3.6,-3.7e+02,-0.001,-0.006,0.00041,-0.0086,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.16,0.18,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0
29490000,0.73,0.0004,0.0054,0.68,-2.2,-1.1,0.97,-7.8,-3.7,-3.7e+02,-0.001,-0.006,0.00041,-0.0091,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.17,0.19,0.037,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0
29590000,0.73,0.00081,0.0065,0.68,-2.2,-1.1,0.96,-8.1,-3.8,-3.7e+02,-0.0011,-0.006,0.00039,-0.011,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.024,0.025,0.009,0.17,0.19,0.036,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0
29690000,0.73,0.0011,0.0071,0.68,-2.2,-1.1,0.95,-8.3,-3.9,-3.7e+02,-0.0011,-0.006,0.00039,-0.012,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.18,0.2,0.036,3.7e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0
29790000,0.73,0.0014,0.0077,0.68,-2.2,-1.1,0.94,-8.6,-4,-3.7e+02,-0.0011,-0.006,0.00038,-0.013,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.025,0.0091,0.18,0.2,0.037,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0
29890000,0.73,0.0015,0.0079,0.68,-2.1,-1.1,0.92,-8.8,-4.1,-3.7e+02,-0.0011,-0.006,0.00038,-0.014,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.19,0.21,0.037,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
29990000,0.73,0.0016,0.0081,0.68,-2.1,-1.1,0.9,-9,-4.2,-3.7e+02,-0.0011,-0.006,0.00035,-0.016,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.19,0.21,0.036,3.5e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0
30090000,0.73,0.0016,0.008,0.68,-2.1,-1.1,0.89,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,0.00035,-0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.2,0.22,0.036,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
30190000,0.73,0.0017,0.0079,0.68,-2,-1.1,0.88,-9.5,-4.4,-3.7e+02,-0.0012,-0.006,0.00032,-0.018,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.2,0.22,0.037,3.5e-07,4.1e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
30290000,0.73,0.0016,0.0078,0.68,-2,-1.1,0.87,-9.7,-4.5,-3.7e+02,-0.0012,-0.006,0.00032,-0.018,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.0091,0.21,0.23,0.037,3.5e-07,4.1e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0
30390000,0.73,0.0017,0.0076,0.68,-2,-1.1,0.85,-9.9,-4.6,-3.7e+02,-0.0012,-0.0059,0.0003,-0.02,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.21,0.23,0.036,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
30490000,0.73,0.0015,0.0073,0.68,-2,-1,0.83,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.0003,-0.02,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.029,0.0091,0.22,0.24,0.037,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
30590000,0.73,0.0015,0.007,0.68,-1.9,-1,0.79,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00027,-0.021,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.025,0.028,0.009,0.22,0.24,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0
30690000,0.73,0.0013,0.0067,0.68,-1.9,-1,0.79,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00027,-0.021,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.03,0.009,0.23,0.25,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
30790000,0.73,0.0013,0.0064,0.68,-1.9,-1,0.78,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00023,-0.022,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0067,0.025,0.029,0.009,0.23,0.25,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
30890000,0.73,0.0011,0.006,0.68,-1.9,-1,0.77,-11,-5.1,-3.7e+02,-0.0012,-0.0059,0.00023,-0.023,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.031,0.009,0.24,0.26,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0
30990000,0.73,0.0012,0.0055,0.68,-1.8,-1,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0059,0.00019,-0.023,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0066,0.025,0.03,0.0089,0.24,0.26,0.037,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
31090000,0.73,0.00095,0.005,0.68,-1.8,-1,0.75,-11,-5.3,-3.7e+02,-0.0013,-0.0059,0.00019,-0.024,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0067,0.026,0.032,0.009,0.25,0.27,0.037,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
31190000,0.73,0.00096,0.0047,0.68,-1.8,-1,0.73,-12,-5.4,-3.7e+02,-0.0013,-0.0059,0.00016,-0.025,-0.018,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0065,0.025,0.03,0.0089,0.25,0.27,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0
31290000,0.73,0.00072,0.0042,0.68,-1.8,-0.99,0.73,-12,-5.5,-3.7e+02,-0.0013,-0.0059,0.00016,-0.026,-0.016,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0065,0.026,0.032,0.0089,0.26,0.28,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
31390000,0.73,0.00066,0.0037,0.68,-1.7,-0.98,0.73,-12,-5.6,-3.7e+02,-0.0013,-0.0059,0.00013,-0.026,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00033,0.0064,0.025,0.031,0.0088,0.25,0.28,0.036,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
31490000,0.73,0.00043,0.0031,0.68,-1.7,-0.98,0.73,-12,-5.7,-3.7e+02,-0.0013,-0.0059,0.00013,-0.027,-0.013,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0064,0.026,0.033,0.0088,0.27,0.29,0.037,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
31590000,0.73,0.00047,0.0027,0.69,-1.7,-0.96,0.72,-12,-5.7,-3.7e+02,-0.0013,-0.0058,9.1e-05,-0.028,-0.011,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0063,0.025,0.031,0.0087,0.26,0.29,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31690000,0.73,0.0002,0.0021,0.69,-1.7,-0.95,0.73,-12,-5.8,-3.7e+02,-0.0013,-0.0058,9.1e-05,-0.028,-0.01,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0063,0.027,0.033,0.0088,0.28,0.3,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31790000,0.73,9.7e-05,0.0014,0.69,-1.6,-0.94,0.72,-13,-5.9,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.029,-0.0083,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0061,0.025,0.031,0.0087,0.27,0.3,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31890000,0.73,-0.00017,0.00075,0.69,-1.6,-0.93,0.72,-13,-6,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.029,-0.007,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0061,0.027,0.034,0.0087,0.29,0.31,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
31990000,0.73,-0.00021,0.00025,0.69,-1.6,-0.92,0.71,-13,-6.1,-3.7e+02,-0.0014,-0.0058,2e-05,-0.03,-0.005,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0059,0.025,0.032,0.0086,0.28,0.31,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
32090000,0.73,-0.00052,-0.00046,0.69,-1.6,-0.91,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,1.9e-05,-0.031,-0.0035,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0059,0.027,0.034,0.0087,0.29,0.32,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0
32190000,0.72,-0.00065,-0.0013,0.69,-1.5,-0.9,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0058,-1.3e-05,-0.031,-0.0013,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0058,0.025,0.032,0.0086,0.29,0.32,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32290000,0.72,-0.0009,-0.002,0.69,-1.5,-0.89,0.71,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-1.3e-05,-0.032,0.00029,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0058,0.026,0.034,0.0086,0.3,0.33,0.037,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32390000,0.72,-0.001,-0.0027,0.69,-1.5,-0.87,0.71,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-3.6e-05,-0.032,0.0012,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00034,0.0056,0.025,0.032,0.0085,0.3,0.33,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32490000,0.72,-0.0011,-0.0029,0.69,-1.4,-0.86,0.72,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-3.6e-05,-0.033,0.0024,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00034,0.0056,0.026,0.034,0.0086,0.31,0.34,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32590000,0.72,-0.0011,-0.0031,0.69,-1.4,-0.85,0.71,-14,-6.6,-3.7e+02,-0.0014,-0.0058,-5.8e-05,-0.033,0.0032,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0054,0.025,0.032,0.0084,0.31,0.34,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32690000,0.72,-0.0011,-0.0032,0.69,-1.4,-0.84,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-5.8e-05,-0.033,0.0038,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00034,0.0055,0.026,0.034,0.0085,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32790000,0.72,-0.00098,-0.0032,0.69,-1.4,-0.83,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.033,0.0048,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0053,0.025,0.032,0.0084,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32890000,0.72,-0.0009,-0.0032,0.69,-1.3,-0.82,0.71,-14,-6.8,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.034,0.0059,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0053,0.026,0.034,0.0084,0.33,0.36,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
32990000,0.72,-0.00069,-0.0031,0.69,-1.3,-0.81,0.7,-15,-6.9,-3.7e+02,-0.0015,-0.0058,-9.8e-05,-0.034,0.0072,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0051,0.025,0.032,0.0083,0.33,0.36,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
33090000,0.72,-0.00072,-0.0032,0.69,-1.3,-0.8,0.69,-15,-7,-3.7e+02,-0.0015,-0.0058,-9.8e-05,-0.034,0.0078,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0052,0.026,0.034,0.0084,0.34,0.37,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
33190000,0.72,0.0028,-0.0023,0.7,-1.3,-0.79,0.64,-15,-7,-3.7e+02,-0.0015,-0.0058,-0.00012,-0.034,0.0086,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.005,0.025,0.031,0.0083,0.34,0.37,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0
33290000,0.67,0.015,-0.0016,0.75,-1.2,-0.77,0.62,-15,-7.1,-3.7e+02,-0.0015,-0.0058,-0.00012,-0.035,0.0089,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.005,0.026,0.033,0.0083,0.35,0.38,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0.0025,9.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
33390000,0.56,0.013,-0.0018,0.83,-1.3,-0.75,0.81,-15,-7.2,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.035,0.0099,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00029,0.00033,0.0049,0.025,0.03,0.0083,0.35,0.38,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0
33490000,0.43,0.0065,0.00085,0.9,-1.2,-0.75,0.83,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0003,0.00033,0.0049,0.026,0.032,0.0081,0.36,0.39,0.036,2.8e-07,2.9e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
33590000,0.27,0.0007,-0.0016,0.96,-1.2,-0.75,0.79,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00032,0.0048,0.026,0.031,0.0078,0.35,0.39,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
33690000,0.1,-0.0026,-0.0046,0.99,-1.1,-0.75,0.8,-15,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00031,0.0049,0.028,0.035,0.0076,0.37,0.4,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
33790000,-0.067,-0.004,-0.0065,1,-1.1,-0.73,0.78,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00017,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00029,0.0048,0.028,0.034,0.0074,0.36,0.4,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
33890000,-0.23,-0.0051,-0.0072,0.97,-1,-0.71,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00017,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00034,0.00029,0.0048,0.032,0.039,0.0072,0.38,0.41,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
33990000,-0.38,-0.0034,-0.011,0.92,-0.98,-0.67,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00029,0.0047,0.032,0.039,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0
34090000,-0.49,-0.0023,-0.013,0.87,-0.92,-0.63,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00031,0.00029,0.0047,0.036,0.044,0.0069,0.39,0.42,0.036,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
34190000,-0.56,-0.0017,-0.012,0.83,-0.9,-0.58,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00021,-0.037,0.012,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.0046,0.037,0.043,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
34290000,-0.6,-0.0026,-0.0087,0.8,-0.86,-0.54,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00021,-0.037,0.012,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00028,0.0046,0.043,0.05,0.0066,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
34390000,-0.63,-0.0027,-0.0063,0.78,-0.84,-0.49,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00023,-0.041,0.017,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00026,0.00026,0.0045,0.042,0.048,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
34490000,-0.65,-0.0037,-0.0041,0.76,-0.79,-0.45,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00023,-0.041,0.017,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00027,0.0045,0.049,0.056,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
34590000,-0.66,-0.0031,-0.0032,0.76,-0.79,-0.43,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00024,-0.05,0.027,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00023,0.00024,0.0044,0.048,0.053,0.0063,0.4,0.44,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
34690000,-0.66,-0.0035,-0.0024,0.75,-0.74,-0.39,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00024,-0.05,0.027,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00023,0.00024,0.0044,0.055,0.061,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
34790000,-0.67,-0.0024,-0.0022,0.75,-0.74,-0.38,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00024,-0.06,0.038,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.00022,0.0044,0.052,0.056,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0
34890000,-0.67,-0.0024,-0.0021,0.74,-0.69,-0.34,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00024,-0.06,0.038,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.00022,0.0044,0.059,0.064,0.0062,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
34990000,-0.67,-0.0088,-0.0049,0.74,0.33,0.24,-0.13,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00024,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.059,0.07,0.0068,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
35090000,-0.67,-0.0088,-0.0049,0.74,0.45,0.26,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00024,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.064,0.077,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
35190000,-0.67,-0.0088,-0.005,0.74,0.47,0.29,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00024,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.07,0.083,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
35290000,-0.67,-0.0089,-0.005,0.74,0.5,0.33,-0.19,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00024,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.075,0.089,0.0066,0.46,0.48,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
35390000,-0.67,-0.0089,-0.005,0.74,0.52,0.36,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00024,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.081,0.095,0.0066,0.47,0.49,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
35490000,-0.67,-0.009,-0.005,0.74,0.54,0.39,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00024,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0002,0.0044,0.088,0.1,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
35590000,-0.67,-0.006,-0.0053,0.74,0.43,0.32,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.00022,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00017,0.0042,0.07,0.077,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
35690000,-0.67,-0.006,-0.0052,0.74,0.45,0.35,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.00022,-0.073,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00017,0.0042,0.075,0.082,0.0061,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
35790000,-0.67,-0.0038,-0.0053,0.74,0.37,0.3,-0.2,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.075,0.053,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00015,0.0041,0.062,0.066,0.0059,0.49,0.51,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0
35890000,-0.67,-0.0039,-0.0053,0.74,0.39,0.33,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.075,0.053,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00015,0.0041,0.068,0.072,0.0059,0.5,0.53,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
35990000,-0.67,-0.002,-0.0053,0.74,0.32,0.28,-0.2,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.082,0.06,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00013,0.004,0.058,0.061,0.0057,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
36090000,-0.67,-0.0021,-0.0053,0.74,0.33,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.082,0.06,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00013,0.0041,0.063,0.066,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
36190000,-0.67,-0.00067,-0.0052,0.74,0.27,0.26,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.093,0.069,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00012,0.004,0.055,0.057,0.0055,0.5,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
36290000,-0.67,-0.00079,-0.0052,0.74,0.28,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.093,0.069,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00012,0.004,0.061,0.063,0.0056,0.52,0.54,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
36390000,-0.67,0.00026,-0.0051,0.74,0.23,0.24,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.1,0.079,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00011,0.004,0.054,0.055,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
36490000,-0.67,0.00017,-0.0051,0.74,0.24,0.26,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.11,0.079,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00011,0.0041,0.059,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
36590000,-0.67,0.00096,-0.0049,0.74,0.2,0.23,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.12,0.089,-0.092,0.37,0.0037,0.025,0,0,0,0,0,9e-05,0.0001,0.0041,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
36690000,-0.67,0.00094,-0.0049,0.74,0.21,0.24,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.12,0.089,-0.093,0.37,0.0037,0.025,0,0,0,0,0,9e-05,0.0001,0.0041,0.058,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
36790000,-0.67,0.0015,-0.0048,0.74,0.17,0.21,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.13,0.098,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,9.7e-05,0.0041,0.052,0.053,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
36890000,-0.67,0.0014,-0.0047,0.74,0.17,0.22,-0.16,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.13,0.098,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,9.8e-05,0.0041,0.057,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
36990000,-0.67,0.0019,-0.0045,0.74,0.14,0.19,-0.16,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.14,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8e-05,9.3e-05,0.0041,0.051,0.053,0.0056,0.54,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
37090000,-0.67,0.0018,-0.0045,0.74,0.15,0.21,-0.15,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.14,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,8e-05,9.3e-05,0.0041,0.056,0.058,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
37190000,-0.67,0.0022,-0.0043,0.74,0.12,0.18,-0.15,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,8.9e-05,0.0041,0.051,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
37290000,-0.67,0.0022,-0.0044,0.74,0.12,0.18,-0.14,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,8.9e-05,0.0041,0.055,0.057,0.0059,0.56,0.59,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
37390000,-0.67,0.0024,-0.0042,0.74,0.097,0.16,-0.13,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,8.7e-05,0.0042,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
37490000,-0.67,0.0023,-0.0041,0.74,0.096,0.17,-0.13,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,7.5e-05,8.7e-05,0.0042,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
37590000,-0.67,0.0025,-0.004,0.74,0.077,0.14,-0.12,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.5e-05,0.0042,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
37690000,-0.67,0.0024,-0.004,0.74,0.075,0.15,-0.11,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.5e-05,0.0042,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
37790000,-0.67,0.0026,-0.004,0.74,0.059,0.13,-0.1,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.4e-05,0.0042,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
37890000,-0.67,0.0025,-0.0039,0.74,0.056,0.13,-0.096,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.4e-05,0.0042,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
37990000,-0.67,0.0026,-0.0039,0.74,0.042,0.11,-0.086,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.2,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.3e-05,0.0042,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,2.9e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
38090000,-0.67,0.0026,-0.0039,0.74,0.038,0.12,-0.076,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.2,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0042,0.05,0.052,0.0066,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
38190000,-0.67,0.0026,-0.0038,0.74,0.025,0.1,-0.068,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.2e-05,0.0042,0.045,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
38290000,-0.67,0.0026,-0.0038,0.74,0.022,0.1,-0.061,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0042,0.049,0.05,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
38390000,-0.67,0.0026,-0.0036,0.74,0.014,0.089,-0.053,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,8.2e-05,0.0042,0.044,0.045,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
38490000,-0.67,0.0026,-0.0036,0.74,0.011,0.092,-0.046,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
38590000,-0.67,0.0026,-0.0035,0.74,0.0063,0.079,-0.039,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.2e-05,0.0043,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
38690000,-0.67,0.0025,-0.0035,0.74,0.002,0.08,-0.032,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.046,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
38790000,-0.67,0.0025,-0.0034,0.74,-0.003,0.066,-0.024,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.22,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,8.3e-05,0.0043,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
38890000,-0.67,0.0023,-0.0035,0.74,-0.013,0.056,0.48,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.22,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,8.3e-05,0.0043,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,5.4e-06,0.014,0.014,0.0005,0.0025,4.2e-05,0.0025,0.0025,0.0025,0.0025,0,0

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

View File

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

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