forked from Archive/PX4-Autopilot
ekf2: treat inhibited states as "consider states" and remove conservative covariance matrix fixes (#22597)
When a state stops to be estimated it becomes a "consider state". Its value and variance are frozen but its covariance with other states continue to evolve normally. - removes conservative accel bias variance limiting - force symmetry is skipped after fusion of NED vel/pos (a direct measurement) --------- Co-authored-by: bresch <brescianimathieu@gmail.com>
This commit is contained in:
parent
2c81c9fdea
commit
51155f7a29
|
@ -103,14 +103,14 @@ void Ekf::initialiseCovariance()
|
||||||
|
|
||||||
void Ekf::predictCovariance(const imuSample &imu_delayed)
|
void Ekf::predictCovariance(const imuSample &imu_delayed)
|
||||||
{
|
{
|
||||||
// Use average update interval to reduce accumulated covariance prediction errors due to small single frame dt values
|
// predict the covariance
|
||||||
const float dt = _dt_ekf_avg;
|
const float dt = 0.5f * (imu_delayed.delta_vel_dt + imu_delayed.delta_ang_dt);
|
||||||
|
|
||||||
// delta angle noise variance
|
// gyro noise variance
|
||||||
float gyro_noise = math::constrain(_params.gyro_noise, 0.f, 1.f);
|
float gyro_noise = math::constrain(_params.gyro_noise, 0.f, 1.f);
|
||||||
const float gyro_var = sq(gyro_noise);
|
const float gyro_var = sq(gyro_noise);
|
||||||
|
|
||||||
// delta velocity noise variance
|
// accel noise variance
|
||||||
float accel_noise = math::constrain(_params.accel_noise, 0.f, 1.f);
|
float accel_noise = math::constrain(_params.accel_noise, 0.f, 1.f);
|
||||||
Vector3f accel_var;
|
Vector3f accel_var;
|
||||||
|
|
||||||
|
@ -124,211 +124,112 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// predict the covariance
|
|
||||||
// calculate variances and upper diagonal covariances for quaternion, velocity, position and gyro bias states
|
// calculate variances and upper diagonal covariances for quaternion, velocity, position and gyro bias states
|
||||||
P = sym::PredictCovariance(_state.vector(), P,
|
P = sym::PredictCovariance(_state.vector(), P,
|
||||||
imu_delayed.delta_vel / math::max(imu_delayed.delta_vel_dt, FLT_EPSILON), accel_var,
|
imu_delayed.delta_vel / math::max(imu_delayed.delta_vel_dt, FLT_EPSILON), accel_var,
|
||||||
imu_delayed.delta_ang / math::max(imu_delayed.delta_ang_dt, FLT_EPSILON), gyro_var,
|
imu_delayed.delta_ang / math::max(imu_delayed.delta_ang_dt, FLT_EPSILON), gyro_var,
|
||||||
0.5f * (imu_delayed.delta_vel_dt + imu_delayed.delta_ang_dt));
|
dt);
|
||||||
|
|
||||||
// Construct the process noise variance diagonal for those states with a stationary process model
|
// Construct the process noise variance diagonal for those states with a stationary process model
|
||||||
// These are kinematic states and their error growth is controlled separately by the IMU noise variances
|
// These are kinematic states and their error growth is controlled separately by the IMU noise variances
|
||||||
|
|
||||||
// gyro bias: add process noise, or restore previous gyro bias var if state inhibited
|
// gyro bias: add process noise unless state is inhibited
|
||||||
const float gyro_bias_sig = dt * math::constrain(_params.gyro_bias_p_noise, 0.f, 1.f);
|
{
|
||||||
const float gyro_bias_process_noise = sq(gyro_bias_sig);
|
const float gyro_bias_sig = dt * math::constrain(_params.gyro_bias_p_noise, 0.f, 1.f);
|
||||||
for (unsigned index = 0; index < State::gyro_bias.dof; index++) {
|
const float gyro_bias_process_noise = sq(gyro_bias_sig);
|
||||||
const unsigned i = State::gyro_bias.idx + index;
|
|
||||||
|
|
||||||
if (!_gyro_bias_inhibit[index]) {
|
for (unsigned index = 0; index < State::gyro_bias.dof; index++) {
|
||||||
P(i, i) += gyro_bias_process_noise;
|
const unsigned i = State::gyro_bias.idx + index;
|
||||||
|
|
||||||
} else {
|
if (!_gyro_bias_inhibit[index]) {
|
||||||
P.uncorrelateCovarianceSetVariance<1>(i, _prev_gyro_bias_var(index));
|
P(i, i) += gyro_bias_process_noise;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// accel bias: add process noise, or restore previous accel bias var if state inhibited
|
// accel bias: add process noise unless state is inhibited
|
||||||
const float accel_bias_sig = dt * math::constrain(_params.accel_bias_p_noise, 0.f, 1.f);
|
{
|
||||||
const float accel_bias_process_noise = sq(accel_bias_sig);
|
const float accel_bias_sig = dt * math::constrain(_params.accel_bias_p_noise, 0.f, 1.f);
|
||||||
for (unsigned index = 0; index < State::accel_bias.dof; index++) {
|
const float accel_bias_process_noise = sq(accel_bias_sig);
|
||||||
const unsigned i = State::accel_bias.idx + index;
|
|
||||||
|
|
||||||
if (!_accel_bias_inhibit[index]) {
|
for (unsigned index = 0; index < State::accel_bias.dof; index++) {
|
||||||
P(i, i) += accel_bias_process_noise;
|
const unsigned i = State::accel_bias.idx + index;
|
||||||
|
|
||||||
} else {
|
if (!_accel_bias_inhibit[index]) {
|
||||||
P.uncorrelateCovarianceSetVariance<1>(i, _prev_accel_bias_var(index));
|
P(i, i) += accel_bias_process_noise;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
||||||
if (_control_status.flags.mag) {
|
if (_control_status.flags.mag) {
|
||||||
// Don't continue to grow the earth field variances if they are becoming too large or we are not doing 3-axis fusion as this can make the covariance matrix badly conditioned
|
// mag_I: add process noise
|
||||||
if (P.trace<State::mag_I.dof>(State::mag_I.idx) < 0.1f) {
|
float mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.f, 1.f);
|
||||||
|
P.slice<State::mag_I.dof, 1>(State::mag_I.idx, 0) += sq(mag_I_sig);
|
||||||
|
|
||||||
float mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.f, 1.f);
|
// mag_B: add process noise
|
||||||
float mag_I_process_noise = sq(mag_I_sig);
|
float mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.f, 1.f);
|
||||||
|
P.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) += sq(mag_B_sig);
|
||||||
for (unsigned index = 0; index < State::mag_I.dof; index++) {
|
|
||||||
unsigned i = State::mag_I.idx + index;
|
|
||||||
P(i, i) += mag_I_process_noise;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Don't continue to grow the body field variances if they are becoming too large or we are not doing 3-axis fusion as this can make the covariance matrix badly conditioned
|
|
||||||
if (P.trace<State::mag_B.dof>(State::mag_B.idx) < 0.1f) {
|
|
||||||
|
|
||||||
float mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.f, 1.f);
|
|
||||||
float mag_B_process_noise = sq(mag_B_sig);
|
|
||||||
|
|
||||||
for (unsigned index = 0; index < State::mag_B.dof; index++) {
|
|
||||||
unsigned i = State::mag_B.idx + index;
|
|
||||||
P(i, i) += mag_B_process_noise;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||||
|
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_WIND)
|
#if defined(CONFIG_EKF2_WIND)
|
||||||
if (_control_status.flags.wind) {
|
if (_control_status.flags.wind) {
|
||||||
// Don't continue to grow wind velocity state variances if they are becoming too large or we are not using wind velocity states as this can make the covariance matrix badly conditioned
|
// wind vel: add process noise
|
||||||
if (P.trace<State::wind_vel.dof>(State::wind_vel.idx) < sq(_params.initial_wind_uncertainty)) {
|
float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf));
|
||||||
|
P.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) += sq(wind_vel_nsd_scaled) * dt;
|
||||||
float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f) * (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf));
|
|
||||||
|
|
||||||
const float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt;
|
|
||||||
|
|
||||||
for (unsigned index = 0; index < State::wind_vel.dof; index++) {
|
|
||||||
unsigned i = State::wind_vel.idx + index;
|
|
||||||
P(i, i) += wind_vel_process_noise;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
#endif // CONFIG_EKF2_WIND
|
#endif // CONFIG_EKF2_WIND
|
||||||
|
|
||||||
|
|
||||||
// covariance matrix is symmetrical, so copy upper half to lower half
|
// covariance matrix is symmetrical, so copy upper half to lower half
|
||||||
for (unsigned row = 0; row < State::size; row++) {
|
for (unsigned row = 0; row < State::size; row++) {
|
||||||
for (unsigned column = 0 ; column < row; column++) {
|
for (unsigned column = 0; column < row; column++) {
|
||||||
P(row, column) = P(column, row);
|
P(row, column) = P(column, row);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// fix gross errors in the covariance matrix and ensure rows and
|
constrainStateVariances();
|
||||||
// columns for un-used states are zero
|
|
||||||
fixCovarianceErrors(false);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Ekf::fixCovarianceErrors(bool force_symmetry)
|
void Ekf::constrainStateVariances()
|
||||||
{
|
{
|
||||||
// NOTE: This limiting is a last resort and should not be relied on
|
// NOTE: This limiting is a last resort and should not be relied on
|
||||||
// TODO: Split covariance prediction into separate F*P*transpose(F) and Q contributions
|
// TODO: Split covariance prediction into separate F*P*transpose(F) and Q contributions
|
||||||
// and set corresponding entries in Q to zero when states exceed 50% of the limit
|
// and set corresponding entries in Q to zero when states exceed 50% of the limit
|
||||||
// Covariance diagonal limits. Use same values for states which
|
// Covariance diagonal limits. Use same values for states which
|
||||||
// belong to the same group (e.g. vel_x, vel_y, vel_z)
|
// belong to the same group (e.g. vel_x, vel_y, vel_z)
|
||||||
const float quat_var_max = 1.0f;
|
|
||||||
const float vel_var_max = 1e6f;
|
|
||||||
const float pos_var_max = 1e6f;
|
|
||||||
const float gyro_bias_var_max = 1.0f;
|
|
||||||
|
|
||||||
constrainStateVar(State::quat_nominal, 0.f, quat_var_max);
|
constrainStateVar(State::quat_nominal, 1e-9f, 1.f);
|
||||||
constrainStateVar(State::vel, 1e-6f, vel_var_max);
|
constrainStateVar(State::vel, 1e-6f, 1e6f);
|
||||||
constrainStateVar(State::pos, 1e-6f, pos_var_max);
|
constrainStateVar(State::pos, 1e-6f, 1e6f);
|
||||||
constrainStateVar(State::gyro_bias, 0.f, gyro_bias_var_max);
|
constrainStateVarLimitRatio(State::gyro_bias, kGyroBiasVarianceMin, 1.f);
|
||||||
|
constrainStateVarLimitRatio(State::accel_bias, kAccelBiasVarianceMin, 1.f);
|
||||||
// the following states are optional and are deactivated when not required
|
|
||||||
// by ensuring the corresponding covariance matrix values are kept at zero
|
|
||||||
|
|
||||||
// accelerometer bias states
|
|
||||||
if (!_accel_bias_inhibit[0] || !_accel_bias_inhibit[1] || !_accel_bias_inhibit[2]) {
|
|
||||||
// Find the maximum delta velocity bias state variance and request a covariance reset if any variance is below the safe minimum
|
|
||||||
const float minSafeStateVar = 1e-9f / sq(_dt_ekf_avg);
|
|
||||||
float maxStateVar = minSafeStateVar;
|
|
||||||
bool resetRequired = false;
|
|
||||||
|
|
||||||
for (unsigned axis = 0; axis < State::accel_bias.dof; axis++) {
|
|
||||||
const unsigned stateIndex = State::accel_bias.idx + axis;
|
|
||||||
|
|
||||||
if (_accel_bias_inhibit[axis]) {
|
|
||||||
// Skip the check for the inhibited axis
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (P(stateIndex, stateIndex) > maxStateVar) {
|
|
||||||
maxStateVar = P(stateIndex, stateIndex);
|
|
||||||
|
|
||||||
} else if (P(stateIndex, stateIndex) < minSafeStateVar) {
|
|
||||||
resetRequired = true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// To ensure stability of the covariance matrix operations, the ratio of a max and min variance must
|
|
||||||
// not exceed 100 and the minimum variance must not fall below the target minimum
|
|
||||||
// Also limit variance to a maximum equivalent to a 0.1g uncertainty
|
|
||||||
const float minStateVarTarget = 5E-8f / sq(_dt_ekf_avg);
|
|
||||||
float minAllowedStateVar = fmaxf(0.01f * maxStateVar, minStateVarTarget);
|
|
||||||
|
|
||||||
for (unsigned axis = 0; axis < State::accel_bias.dof; axis++) {
|
|
||||||
const unsigned stateIndex = State::accel_bias.idx + axis;
|
|
||||||
|
|
||||||
if (_accel_bias_inhibit[axis]) {
|
|
||||||
// Skip the check for the inhibited axis
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
P(stateIndex, stateIndex) = math::constrain(P(stateIndex, stateIndex), minAllowedStateVar, sq(0.1f * CONSTANTS_ONE_G));
|
|
||||||
}
|
|
||||||
|
|
||||||
// If any one axis has fallen below the safe minimum, all delta velocity covariance terms must be reset to zero
|
|
||||||
if (resetRequired) {
|
|
||||||
resetAccelBiasCov();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (force_symmetry) {
|
|
||||||
P.makeRowColSymmetric<State::quat_nominal.dof>(State::quat_nominal.idx);
|
|
||||||
P.makeRowColSymmetric<State::vel.dof>(State::vel.idx);
|
|
||||||
P.makeRowColSymmetric<State::pos.dof>(State::pos.idx);
|
|
||||||
P.makeRowColSymmetric<State::gyro_bias.dof>(State::gyro_bias.idx);
|
|
||||||
P.makeRowColSymmetric<State::accel_bias.dof>(State::accel_bias.idx);
|
|
||||||
}
|
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
||||||
// magnetic field states
|
if (_control_status.flags.mag) {
|
||||||
if (!_control_status.flags.mag) {
|
constrainStateVarLimitRatio(State::mag_I, kMagVarianceMin, 1.f);
|
||||||
P.uncorrelateCovarianceSetVariance<State::mag_I.dof>(State::mag_I.idx, 0.0f);
|
constrainStateVarLimitRatio(State::mag_B, kMagVarianceMin, 1.f);
|
||||||
P.uncorrelateCovarianceSetVariance<State::mag_B.dof>(State::mag_B.idx, 0.0f);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
const float mag_I_var_max = 1.f;
|
|
||||||
constrainStateVar(State::mag_I, 0.f, mag_I_var_max);
|
|
||||||
|
|
||||||
const float mag_B_var_max = 1.f;
|
|
||||||
constrainStateVar(State::mag_B, 0.f, mag_B_var_max);
|
|
||||||
|
|
||||||
if (force_symmetry) {
|
|
||||||
P.makeRowColSymmetric<State::mag_I.dof>(State::mag_I.idx);
|
|
||||||
P.makeRowColSymmetric<State::mag_B.dof>(State::mag_B.idx);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_WIND)
|
#if defined(CONFIG_EKF2_WIND)
|
||||||
// wind velocity states
|
if (_control_status.flags.wind) {
|
||||||
if (!_control_status.flags.wind) {
|
constrainStateVarLimitRatio(State::wind_vel, 1e-6f, 1e6f);
|
||||||
P.uncorrelateCovarianceSetVariance<State::wind_vel.dof>(State::wind_vel.idx, 0.0f);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
const float wind_vel_var_max = 1e6f;
|
|
||||||
constrainStateVar(State::wind_vel, 0.f, wind_vel_var_max);
|
|
||||||
|
|
||||||
if (force_symmetry) {
|
|
||||||
P.makeRowColSymmetric<State::wind_vel.dof>(State::wind_vel.idx);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
#endif // CONFIG_EKF2_WIND
|
#endif // CONFIG_EKF2_WIND
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Ekf::forceCovarianceSymmetry()
|
||||||
|
{
|
||||||
|
// DEBUG
|
||||||
|
// P.isBlockSymmetric(0, 1e-9f);
|
||||||
|
|
||||||
|
P.makeRowColSymmetric<State::size>(0);
|
||||||
|
}
|
||||||
|
|
||||||
void Ekf::constrainStateVar(const IdxDof &state, float min, float max)
|
void Ekf::constrainStateVar(const IdxDof &state, float min, float max)
|
||||||
{
|
{
|
||||||
for (unsigned i = state.idx; i < (state.idx + state.dof); i++) {
|
for (unsigned i = state.idx; i < (state.idx + state.dof); i++) {
|
||||||
|
@ -336,6 +237,25 @@ void Ekf::constrainStateVar(const IdxDof &state, float min, float max)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Ekf::constrainStateVarLimitRatio(const IdxDof &state, float min, float max, float max_ratio)
|
||||||
|
{
|
||||||
|
// the ratio of a max and min variance must not exceed max_ratio
|
||||||
|
float state_var_max = 0.f;
|
||||||
|
|
||||||
|
for (unsigned i = state.idx; i < (state.idx + state.dof); i++) {
|
||||||
|
if (P(i, i) > state_var_max) {
|
||||||
|
state_var_max = P(i, i);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
float limited_max = math::constrain(state_var_max, min, max);
|
||||||
|
float limited_min = math::constrain(limited_max / max_ratio, min, max);
|
||||||
|
|
||||||
|
for (unsigned i = state.idx; i < (state.idx + state.dof); i++) {
|
||||||
|
P(i, i) = math::constrain(P(i, i), limited_min, limited_max);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// if the covariance correction will result in a negative variance, then
|
// if the covariance correction will result in a negative variance, then
|
||||||
// the covariance matrix is unhealthy and must be corrected
|
// the covariance matrix is unhealthy and must be corrected
|
||||||
bool Ekf::checkAndFixCovarianceUpdate(const SquareMatrixState &KHP)
|
bool Ekf::checkAndFixCovarianceUpdate(const SquareMatrixState &KHP)
|
||||||
|
@ -344,7 +264,7 @@ bool Ekf::checkAndFixCovarianceUpdate(const SquareMatrixState &KHP)
|
||||||
|
|
||||||
for (int i = 0; i < State::size; i++) {
|
for (int i = 0; i < State::size; i++) {
|
||||||
if (P(i, i) < KHP(i, i)) {
|
if (P(i, i) < KHP(i, i)) {
|
||||||
P.uncorrelateCovarianceSetVariance<1>(i, 0.0f);
|
P.uncorrelateCovarianceSetVariance<1>(i, 0.f);
|
||||||
healthy = false;
|
healthy = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -382,14 +302,10 @@ void Ekf::resetMagCov()
|
||||||
|
|
||||||
P.uncorrelateCovarianceSetVariance<State::mag_I.dof>(State::mag_I.idx, sq(_params.mag_noise));
|
P.uncorrelateCovarianceSetVariance<State::mag_I.dof>(State::mag_I.idx, sq(_params.mag_noise));
|
||||||
P.uncorrelateCovarianceSetVariance<State::mag_B.dof>(State::mag_B.idx, sq(_params.mag_noise));
|
P.uncorrelateCovarianceSetVariance<State::mag_B.dof>(State::mag_B.idx, sq(_params.mag_noise));
|
||||||
|
|
||||||
saveMagCovData();
|
|
||||||
}
|
}
|
||||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||||
|
|
||||||
void Ekf::resetGyroBiasZCov()
|
void Ekf::resetGyroBiasZCov()
|
||||||
{
|
{
|
||||||
const float init_gyro_bias_var = sq(_params.switch_on_gyro_bias);
|
P.uncorrelateCovarianceSetVariance<1>(State::gyro_bias.idx + 2, sq(_params.switch_on_gyro_bias));
|
||||||
|
|
||||||
P.uncorrelateCovarianceSetVariance<1>(State::gyro_bias.idx + 2, init_gyro_bias_var);
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -89,9 +89,6 @@ void Ekf::reset()
|
||||||
_fault_status.value = 0;
|
_fault_status.value = 0;
|
||||||
_innov_check_fail_status.value = 0;
|
_innov_check_fail_status.value = 0;
|
||||||
|
|
||||||
_prev_gyro_bias_var.zero();
|
|
||||||
_prev_accel_bias_var.zero();
|
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_GNSS)
|
#if defined(CONFIG_EKF2_GNSS)
|
||||||
resetGpsDriftCheckFilters();
|
resetGpsDriftCheckFilters();
|
||||||
_gps_checks_passed = false;
|
_gps_checks_passed = false;
|
||||||
|
@ -312,8 +309,9 @@ void Ekf::predictState(const imuSample &imu_delayed)
|
||||||
// predict position states via trapezoidal integration of velocity
|
// predict position states via trapezoidal integration of velocity
|
||||||
_state.pos += (vel_last + _state.vel) * imu_delayed.delta_vel_dt * 0.5f;
|
_state.pos += (vel_last + _state.vel) * imu_delayed.delta_vel_dt * 0.5f;
|
||||||
|
|
||||||
constrainStates();
|
// constrain states
|
||||||
|
_state.vel = matrix::constrain(_state.vel, -1000.f, 1000.f);
|
||||||
|
_state.pos = matrix::constrain(_state.pos, -1.e6f, 1.e6f);
|
||||||
|
|
||||||
// some calculations elsewhere in code require a raw angular rate vector so calculate here to avoid duplication
|
// some calculations elsewhere in code require a raw angular rate vector so calculate here to avoid duplication
|
||||||
// protect against possible small timesteps resulting from timing slip on previous frame that can drive spikes into the rate
|
// protect against possible small timesteps resulting from timing slip on previous frame that can drive spikes into the rate
|
||||||
|
|
|
@ -345,14 +345,7 @@ public:
|
||||||
const Vector3f &getMagEarthField() const { return _state.mag_I; }
|
const Vector3f &getMagEarthField() const { return _state.mag_I; }
|
||||||
|
|
||||||
const Vector3f &getMagBias() const { return _state.mag_B; }
|
const Vector3f &getMagBias() const { return _state.mag_B; }
|
||||||
Vector3f getMagBiasVariance() const
|
Vector3f getMagBiasVariance() const { return getStateVariance<State::mag_B>(); } // get the mag bias variance in Gauss
|
||||||
{
|
|
||||||
if (_control_status.flags.mag) {
|
|
||||||
return getStateVariance<State::mag_B>();
|
|
||||||
}
|
|
||||||
|
|
||||||
return _saved_mag_bf_covmat.diag();
|
|
||||||
}
|
|
||||||
float getMagBiasLimit() const { return 0.5f; } // 0.5 Gauss
|
float getMagBiasLimit() const { return 0.5f; } // 0.5 Gauss
|
||||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||||
|
|
||||||
|
@ -496,7 +489,8 @@ public:
|
||||||
// apply the covariance corrections
|
// apply the covariance corrections
|
||||||
P -= KHP;
|
P -= KHP;
|
||||||
|
|
||||||
fixCovarianceErrors(true);
|
constrainStateVariances();
|
||||||
|
forceCovarianceSymmetry();
|
||||||
|
|
||||||
// apply the state corrections
|
// apply the state corrections
|
||||||
fuse(K, innovation);
|
fuse(K, innovation);
|
||||||
|
@ -523,6 +517,14 @@ private:
|
||||||
void updateHorizontalDeadReckoningstatus();
|
void updateHorizontalDeadReckoningstatus();
|
||||||
void updateVerticalDeadReckoningStatus();
|
void updateVerticalDeadReckoningStatus();
|
||||||
|
|
||||||
|
static constexpr float kGyroBiasVarianceMin{1e-9f};
|
||||||
|
static constexpr float kAccelBiasVarianceMin{1e-9f};
|
||||||
|
|
||||||
|
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
||||||
|
static constexpr float kMagVarianceMin = 1e-6f;
|
||||||
|
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||||
|
|
||||||
|
|
||||||
struct StateResetCounts {
|
struct StateResetCounts {
|
||||||
uint8_t velNE{0}; ///< number of horizontal position reset events (allow to wrap if count exceeds 255)
|
uint8_t velNE{0}; ///< number of horizontal position reset events (allow to wrap if count exceeds 255)
|
||||||
uint8_t velD{0}; ///< number of vertical velocity reset events (allow to wrap if count exceeds 255)
|
uint8_t velD{0}; ///< number of vertical velocity reset events (allow to wrap if count exceeds 255)
|
||||||
|
@ -720,8 +722,6 @@ private:
|
||||||
uint64_t _flt_mag_align_start_time{0}; ///< time that inflight magnetic field alignment started (uSec)
|
uint64_t _flt_mag_align_start_time{0}; ///< time that inflight magnetic field alignment started (uSec)
|
||||||
uint64_t _time_last_mov_3d_mag_suitable{0}; ///< last system time that sufficient movement to use 3-axis magnetometer fusion was detected (uSec)
|
uint64_t _time_last_mov_3d_mag_suitable{0}; ///< last system time that sufficient movement to use 3-axis magnetometer fusion was detected (uSec)
|
||||||
uint64_t _time_last_mag_check_failing{0};
|
uint64_t _time_last_mag_check_failing{0};
|
||||||
Matrix3f _saved_mag_ef_covmat{}; ///< NED magnetic field state covariance sub-matrix saved for use at the next initialisation (Gauss**2)
|
|
||||||
Matrix3f _saved_mag_bf_covmat{}; ///< magnetic field state covariance sub-matrix that has been saved for use at the next initialisation (Gauss**2)
|
|
||||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||||
|
|
||||||
// variables used to inhibit accel bias learning
|
// variables used to inhibit accel bias learning
|
||||||
|
@ -730,9 +730,6 @@ private:
|
||||||
float _accel_magnitude_filt{0.0f}; ///< acceleration magnitude after application of a decaying envelope filter (rad/sec)
|
float _accel_magnitude_filt{0.0f}; ///< acceleration magnitude after application of a decaying envelope filter (rad/sec)
|
||||||
float _ang_rate_magnitude_filt{0.0f}; ///< angular rate magnitude after application of a decaying envelope filter (rad/sec)
|
float _ang_rate_magnitude_filt{0.0f}; ///< angular rate magnitude after application of a decaying envelope filter (rad/sec)
|
||||||
|
|
||||||
Vector3f _prev_gyro_bias_var{}; ///< saved gyro XYZ bias variances
|
|
||||||
Vector3f _prev_accel_bias_var{}; ///< saved accel XYZ bias variances
|
|
||||||
|
|
||||||
// imu fault status
|
// imu fault status
|
||||||
uint64_t _time_bad_vert_accel{0}; ///< last time a bad vertical accel was detected (uSec)
|
uint64_t _time_bad_vert_accel{0}; ///< last time a bad vertical accel was detected (uSec)
|
||||||
uint64_t _time_good_vert_accel{0}; ///< last time a good vertical accel was detected (uSec)
|
uint64_t _time_good_vert_accel{0}; ///< last time a good vertical accel was detected (uSec)
|
||||||
|
@ -950,13 +947,12 @@ private:
|
||||||
bool checkAndFixCovarianceUpdate(const SquareMatrixState &KHP);
|
bool checkAndFixCovarianceUpdate(const SquareMatrixState &KHP);
|
||||||
|
|
||||||
// limit the diagonal of the covariance matrix
|
// limit the diagonal of the covariance matrix
|
||||||
// force symmetry when the argument is true
|
void constrainStateVariances();
|
||||||
void fixCovarianceErrors(bool force_symmetry);
|
|
||||||
|
void forceCovarianceSymmetry();
|
||||||
|
|
||||||
void constrainStateVar(const IdxDof &state, float min, float max);
|
void constrainStateVar(const IdxDof &state, float min, float max);
|
||||||
|
void constrainStateVarLimitRatio(const IdxDof &state, float min, float max, float max_ratio = 1.e6f);
|
||||||
// constrain the ekf states
|
|
||||||
void constrainStates();
|
|
||||||
|
|
||||||
// generic function which will perform a fusion step given a kalman gain K
|
// generic function which will perform a fusion step given a kalman gain K
|
||||||
// and a scalar innovation value
|
// and a scalar innovation value
|
||||||
|
@ -1062,10 +1058,6 @@ private:
|
||||||
void stopMagHdgFusion();
|
void stopMagHdgFusion();
|
||||||
void stopMagFusion();
|
void stopMagFusion();
|
||||||
|
|
||||||
// load and save mag field state covariance data for re-use
|
|
||||||
void loadMagCovData();
|
|
||||||
void saveMagCovData();
|
|
||||||
|
|
||||||
// calculate a synthetic value for the magnetometer Z component, given the 3D magnetomter
|
// calculate a synthetic value for the magnetometer Z component, given the 3D magnetomter
|
||||||
// sensor measurement
|
// sensor measurement
|
||||||
float calculate_synthetic_mag_z_measurement(const Vector3f &mag_meas, const Vector3f &mag_earth_predicted);
|
float calculate_synthetic_mag_z_measurement(const Vector3f &mag_meas, const Vector3f &mag_earth_predicted);
|
||||||
|
|
|
@ -233,28 +233,6 @@ void Ekf::resetVerticalVelocityToZero()
|
||||||
resetVerticalVelocityTo(0.0f, 10.f);
|
resetVerticalVelocityTo(0.0f, 10.f);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Ekf::constrainStates()
|
|
||||||
{
|
|
||||||
_state.quat_nominal = matrix::constrain(_state.quat_nominal, -1.0f, 1.0f);
|
|
||||||
_state.vel = matrix::constrain(_state.vel, -1000.0f, 1000.0f);
|
|
||||||
_state.pos = matrix::constrain(_state.pos, -1.e6f, 1.e6f);
|
|
||||||
|
|
||||||
const float gyro_bias_limit = getGyroBiasLimit();
|
|
||||||
_state.gyro_bias = matrix::constrain(_state.gyro_bias, -gyro_bias_limit, gyro_bias_limit);
|
|
||||||
|
|
||||||
const float accel_bias_limit = getAccelBiasLimit();
|
|
||||||
_state.accel_bias = matrix::constrain(_state.accel_bias, -accel_bias_limit, accel_bias_limit);
|
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
|
||||||
_state.mag_I = matrix::constrain(_state.mag_I, -1.0f, 1.0f);
|
|
||||||
_state.mag_B = matrix::constrain(_state.mag_B, -getMagBiasLimit(), getMagBiasLimit());
|
|
||||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_WIND)
|
|
||||||
_state.wind_vel = matrix::constrain(_state.wind_vel, -100.0f, 100.0f);
|
|
||||||
#endif // CONFIG_EKF2_WIND
|
|
||||||
}
|
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_BARO_COMPENSATION)
|
#if defined(CONFIG_EKF2_BARO_COMPENSATION)
|
||||||
float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const
|
float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const
|
||||||
{
|
{
|
||||||
|
@ -548,9 +526,6 @@ void Ekf::resetGyroBiasCov()
|
||||||
// Zero the corresponding covariances and set
|
// Zero the corresponding covariances and set
|
||||||
// variances to the values use for initial alignment
|
// variances to the values use for initial alignment
|
||||||
P.uncorrelateCovarianceSetVariance<State::gyro_bias.dof>(State::gyro_bias.idx, sq(_params.switch_on_gyro_bias));
|
P.uncorrelateCovarianceSetVariance<State::gyro_bias.dof>(State::gyro_bias.idx, sq(_params.switch_on_gyro_bias));
|
||||||
|
|
||||||
// Set previous frame values
|
|
||||||
_prev_gyro_bias_var = getStateVariance<State::gyro_bias>();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Ekf::resetAccelBias()
|
void Ekf::resetAccelBias()
|
||||||
|
@ -566,9 +541,6 @@ void Ekf::resetAccelBiasCov()
|
||||||
// Zero the corresponding covariances and set
|
// Zero the corresponding covariances and set
|
||||||
// variances to the values use for initial alignment
|
// variances to the values use for initial alignment
|
||||||
P.uncorrelateCovarianceSetVariance<State::accel_bias.dof>(State::accel_bias.idx, sq(_params.switch_on_accel_bias));
|
P.uncorrelateCovarianceSetVariance<State::accel_bias.dof>(State::accel_bias.idx, sq(_params.switch_on_accel_bias));
|
||||||
|
|
||||||
// Set previous frame values
|
|
||||||
_prev_accel_bias_var = getStateVariance<State::accel_bias>();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// get EKF innovation consistency check status information comprising of:
|
// get EKF innovation consistency check status information comprising of:
|
||||||
|
@ -755,23 +727,39 @@ void Ekf::get_ekf_soln_status(uint16_t *status) const
|
||||||
|
|
||||||
void Ekf::fuse(const VectorState &K, float innovation)
|
void Ekf::fuse(const VectorState &K, float innovation)
|
||||||
{
|
{
|
||||||
|
// quat_nominal
|
||||||
Quatf delta_quat(matrix::AxisAnglef(K.slice<State::quat_nominal.dof, 1>(State::quat_nominal.idx, 0) * (-1.f * innovation)));
|
Quatf delta_quat(matrix::AxisAnglef(K.slice<State::quat_nominal.dof, 1>(State::quat_nominal.idx, 0) * (-1.f * innovation)));
|
||||||
_state.quat_nominal *= delta_quat;
|
_state.quat_nominal *= delta_quat;
|
||||||
_state.quat_nominal.normalize();
|
_state.quat_nominal.normalize();
|
||||||
_R_to_earth = Dcmf(_state.quat_nominal);
|
_R_to_earth = Dcmf(_state.quat_nominal);
|
||||||
|
|
||||||
_state.vel -= K.slice<State::vel.dof, 1>(State::vel.idx, 0) * innovation;
|
// vel
|
||||||
_state.pos -= K.slice<State::pos.dof, 1>(State::pos.idx, 0) * innovation;
|
_state.vel = matrix::constrain(_state.vel - K.slice<State::vel.dof, 1>(State::vel.idx, 0) * innovation, -1.e3f, 1.e3f);
|
||||||
_state.gyro_bias -= K.slice<State::gyro_bias.dof, 1>(State::gyro_bias.idx, 0) * innovation;
|
|
||||||
_state.accel_bias -= K.slice<State::accel_bias.dof, 1>(State::accel_bias.idx, 0) * innovation;
|
// pos
|
||||||
|
_state.pos = matrix::constrain(_state.pos - K.slice<State::pos.dof, 1>(State::pos.idx, 0) * innovation, -1.e6f, 1.e6f);
|
||||||
|
|
||||||
|
// gyro_bias
|
||||||
|
_state.gyro_bias = matrix::constrain(_state.gyro_bias - K.slice<State::gyro_bias.dof, 1>(State::gyro_bias.idx, 0) * innovation,
|
||||||
|
-getGyroBiasLimit(), getGyroBiasLimit());
|
||||||
|
|
||||||
|
// accel_bias
|
||||||
|
_state.accel_bias = matrix::constrain(_state.accel_bias - K.slice<State::accel_bias.dof, 1>(State::accel_bias.idx, 0) * innovation,
|
||||||
|
-getAccelBiasLimit(), getAccelBiasLimit());
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
||||||
_state.mag_I -= K.slice<State::mag_I.dof, 1>(State::mag_I.idx, 0) * innovation;
|
// mag_I, mag_B
|
||||||
_state.mag_B -= K.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) * innovation;
|
if (_control_status.flags.mag) {
|
||||||
|
_state.mag_I = matrix::constrain(_state.mag_I - K.slice<State::mag_I.dof, 1>(State::mag_I.idx, 0) * innovation, -1.f, 1.f);
|
||||||
|
_state.mag_B = matrix::constrain(_state.mag_B - K.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) * innovation, -getMagBiasLimit(), getMagBiasLimit());
|
||||||
|
}
|
||||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||||
|
|
||||||
#if defined(CONFIG_EKF2_WIND)
|
#if defined(CONFIG_EKF2_WIND)
|
||||||
_state.wind_vel -= K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) * innovation;
|
// wind_vel
|
||||||
|
if (_control_status.flags.wind) {
|
||||||
|
_state.wind_vel = matrix::constrain(_state.wind_vel - K.slice<State::wind_vel.dof, 1>(State::wind_vel.idx, 0) * innovation, -1.e2f, 1.e2f);
|
||||||
|
}
|
||||||
#endif // CONFIG_EKF2_WIND
|
#endif // CONFIG_EKF2_WIND
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -996,32 +984,13 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed)
|
||||||
const bool is_manoeuvre_level_high = (_ang_rate_magnitude_filt > _params.acc_bias_learn_gyr_lim)
|
const bool is_manoeuvre_level_high = (_ang_rate_magnitude_filt > _params.acc_bias_learn_gyr_lim)
|
||||||
|| (_accel_magnitude_filt > _params.acc_bias_learn_acc_lim);
|
|| (_accel_magnitude_filt > _params.acc_bias_learn_acc_lim);
|
||||||
|
|
||||||
|
|
||||||
// gyro bias inhibit
|
// gyro bias inhibit
|
||||||
const bool do_inhibit_all_gyro_axes = !(_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::GyroBias));
|
const bool do_inhibit_all_gyro_axes = !(_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::GyroBias));
|
||||||
|
|
||||||
for (unsigned index = 0; index < State::gyro_bias.dof; index++) {
|
for (unsigned index = 0; index < State::gyro_bias.dof; index++) {
|
||||||
const unsigned stateIndex = State::gyro_bias.idx + index;
|
bool is_bias_observable = true; // TODO: gyro bias conditions
|
||||||
|
_gyro_bias_inhibit[index] = do_inhibit_all_gyro_axes || !is_bias_observable;
|
||||||
bool is_bias_observable = true;
|
|
||||||
|
|
||||||
// TODO: gyro bias conditions
|
|
||||||
|
|
||||||
const bool do_inhibit_axis = do_inhibit_all_gyro_axes || !is_bias_observable;
|
|
||||||
|
|
||||||
if (do_inhibit_axis) {
|
|
||||||
// store the bias state variances to be reinstated later
|
|
||||||
if (!_gyro_bias_inhibit[index]) {
|
|
||||||
_prev_gyro_bias_var(index) = P(stateIndex, stateIndex);
|
|
||||||
_gyro_bias_inhibit[index] = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
if (_gyro_bias_inhibit[index]) {
|
|
||||||
// reinstate the bias state variances
|
|
||||||
P(stateIndex, stateIndex) = _prev_gyro_bias_var(index);
|
|
||||||
_gyro_bias_inhibit[index] = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// accel bias inhibit
|
// accel bias inhibit
|
||||||
|
@ -1030,8 +999,6 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed)
|
||||||
|| _fault_status.flags.bad_acc_vertical;
|
|| _fault_status.flags.bad_acc_vertical;
|
||||||
|
|
||||||
for (unsigned index = 0; index < State::accel_bias.dof; index++) {
|
for (unsigned index = 0; index < State::accel_bias.dof; index++) {
|
||||||
const unsigned stateIndex = State::accel_bias.idx + index;
|
|
||||||
|
|
||||||
bool is_bias_observable = true;
|
bool is_bias_observable = true;
|
||||||
|
|
||||||
if (_control_status.flags.vehicle_at_rest) {
|
if (_control_status.flags.vehicle_at_rest) {
|
||||||
|
@ -1045,22 +1012,6 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed)
|
||||||
is_bias_observable = (fabsf(_R_to_earth(2, index)) > 0.966f); // cos 15 degrees ~= 0.966
|
is_bias_observable = (fabsf(_R_to_earth(2, index)) > 0.966f); // cos 15 degrees ~= 0.966
|
||||||
}
|
}
|
||||||
|
|
||||||
const bool do_inhibit_axis = do_inhibit_all_accel_axes || imu_delayed.delta_vel_clipping[index] || !is_bias_observable;
|
_accel_bias_inhibit[index] = do_inhibit_all_accel_axes || imu_delayed.delta_vel_clipping[index] || !is_bias_observable;
|
||||||
|
|
||||||
if (do_inhibit_axis) {
|
|
||||||
// store the bias state variances to be reinstated later
|
|
||||||
if (!_accel_bias_inhibit[index]) {
|
|
||||||
_prev_accel_bias_var(index) = P(stateIndex, stateIndex);
|
|
||||||
_accel_bias_inhibit[index] = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
if (_accel_bias_inhibit[index]) {
|
|
||||||
// reinstate the bias state variances
|
|
||||||
P(stateIndex, stateIndex) = _prev_accel_bias_var(index);
|
|
||||||
_accel_bias_inhibit[index] = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -159,15 +159,13 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star
|
||||||
|
|
||||||
_control_status.flags.mag = true;
|
_control_status.flags.mag = true;
|
||||||
|
|
||||||
loadMagCovData();
|
|
||||||
|
|
||||||
// activate fusion, reset mag states and initialize variance if first init or in flight reset
|
// activate fusion, reset mag states and initialize variance if first init or in flight reset
|
||||||
if (!_control_status.flags.yaw_align
|
if (!_control_status.flags.yaw_align
|
||||||
|| wmm_updated
|
|| wmm_updated
|
||||||
|| !_mag_decl_cov_reset
|
|| !_mag_decl_cov_reset
|
||||||
|| !_state.mag_I.longerThan(0.f)
|
|| !_state.mag_I.longerThan(0.f)
|
||||||
|| (getStateVariance<State::mag_I>().min() < sq(0.0001f))
|
|| (getStateVariance<State::mag_I>().min() < kMagVarianceMin)
|
||||||
|| (getStateVariance<State::mag_B>().min() < sq(0.0001f))
|
|| (getStateVariance<State::mag_B>().min() < kMagVarianceMin)
|
||||||
) {
|
) {
|
||||||
ECL_INFO("starting %s fusion, resetting states", AID_SRC_NAME);
|
ECL_INFO("starting %s fusion, resetting states", AID_SRC_NAME);
|
||||||
|
|
||||||
|
@ -209,25 +207,5 @@ void Ekf::stopMagFusion()
|
||||||
_fault_status.flags.bad_mag_z = false;
|
_fault_status.flags.bad_mag_z = false;
|
||||||
|
|
||||||
_fault_status.flags.bad_mag_decl = false;
|
_fault_status.flags.bad_mag_decl = false;
|
||||||
|
|
||||||
saveMagCovData();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Ekf::saveMagCovData()
|
|
||||||
{
|
|
||||||
// save the NED axis covariance sub-matrix
|
|
||||||
_saved_mag_ef_covmat = getStateCovariance<State::mag_I>();
|
|
||||||
|
|
||||||
// save the XYZ body covariance sub-matrix
|
|
||||||
_saved_mag_bf_covmat = getStateCovariance<State::mag_B>();
|
|
||||||
}
|
|
||||||
|
|
||||||
void Ekf::loadMagCovData()
|
|
||||||
{
|
|
||||||
// re-instate the NED axis covariance sub-matrix
|
|
||||||
resetStateCovariance<State::mag_I>(_saved_mag_ef_covmat);
|
|
||||||
|
|
||||||
// re-instate the XYZ body axis covariance sub-matrix
|
|
||||||
resetStateCovariance<State::mag_B>(_saved_mag_bf_covmat);
|
|
||||||
}
|
|
||||||
|
|
|
@ -220,7 +220,7 @@ bool Ekf::fuseVelPosHeight(const float innov, const float innov_var, const int s
|
||||||
// apply the covariance corrections
|
// apply the covariance corrections
|
||||||
P -= KHP;
|
P -= KHP;
|
||||||
|
|
||||||
fixCovarianceErrors(true);
|
constrainStateVariances();
|
||||||
|
|
||||||
// apply the state corrections
|
// apply the state corrections
|
||||||
fuse(Kfusion, innov);
|
fuse(Kfusion, innov);
|
||||||
|
|
|
@ -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]
|
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.2e-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.00023,7.3e-05,-0.011,7.2e-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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
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.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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-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.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.9e-13,0,0,-5e-08,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
290000,1,-0.0094,-0.011,6.3e-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.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-2.8e-11,0,0,-2.5e-06,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,7.7e-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.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,7.7e-11,0,0,-1.5e-05,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-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,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,1.4e-08,0,0,-4.1e-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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
590000,1,-0.0095,-0.012,2.6e-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.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,1.4e-08,0,0,-7.3e-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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.06,0.0005,0.00055,-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.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,1.1e-07,0,0,-0.00012,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-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.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,1.1e-07,0,0,-0.00016,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,3.3e-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.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,3.3e-07,0,0,-0.00016,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,3.3e-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.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,3.3e-07,0,0,-0.00016,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1090000,1,-0.01,-0.014,0.00012,0.016,0.0051,-0.11,0.0018,0.00086,-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
|
1090000,1,-0.01,-0.014,0.00012,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,9.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00046,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1190000,1,-0.01,-0.014,9.8e-05,0.02,0.0053,-0.12,0.0035,0.0014,-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
|
1190000,1,-0.01,-0.014,9.8e-05,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,9.3e-07,0,0,-0.00016,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1290000,1,-0.01,-0.014,0.00015,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-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.00015,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,2.3e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00041,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1390000,1,-0.01,-0.014,0.00016,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-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.00016,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,2.3e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00047,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1490000,1,-0.01,-0.014,0.00014,0.024,0.003,-0.16,0.0038,0.00084,-0.093,0.00015,-0.00046,4.6e-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.00014,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,4.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1590000,1,-0.01,-0.014,0.00013,0.031,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00046,4.6e-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.01,-0.014,0.00013,0.031,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,4.5e-06,0,0,-0.00016,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1690000,1,-0.011,-0.014,9.6e-05,0.028,-8.3e-05,-0.19,0.0045,0.00063,-0.13,0.00021,-0.00088,7.8e-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,9.6e-05,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,7.8e-06,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00033,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1790000,1,-0.011,-0.014,6.5e-05,0.035,-0.0019,-0.2,0.0076,0.00055,-0.15,0.00021,-0.00088,7.8e-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,6.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,7.8e-06,0,0,-0.00017,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1890000,1,-0.011,-0.015,4.4e-05,0.043,-0.0031,-0.22,0.011,0.0003,-0.17,0.00021,-0.00088,7.8e-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,4.4e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,7.8e-06,0,0,-0.00017,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1990000,1,-0.011,-0.014,3.6e-05,0.036,-0.0047,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,1.2e-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,3.6e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,1.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2090000,1,-0.011,-0.014,-4.6e-06,0.041,-0.0072,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,1.2e-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,-4.4e-06,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,1.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00037,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2190000,1,-0.011,-0.014,-1.3e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,1.7e-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.3e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,1.7e-05,0,0,-0.00017,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2290000,1,-0.011,-0.014,-3e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,1.7e-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,-2.9e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,1.7e-05,0,0,-0.00017,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2390000,1,-0.011,-0.013,-3.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9.2e-05,-0.0025,2.1e-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,-3.1e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9.2e-05,-0.0025,2.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00027,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2490000,1,-0.011,-0.013,-5.3e-05,0.034,-0.011,-0.3,0.011,-0.0024,-0.32,9.2e-05,-0.0025,2.1e-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,-5.3e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9.2e-05,-0.0025,2.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.0003,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2590000,1,-0.011,-0.013,-5.7e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.2e-05,-0.003,2.5e-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,-5.6e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.2e-05,-0.0029,2.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2690000,1,-0.011,-0.013,-6.4e-05,0.03,-0.011,-0.33,0.0096,-0.0028,-0.39,-1.2e-05,-0.003,2.5e-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,-6.4e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.2e-05,-0.0029,2.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2790000,1,-0.011,-0.013,-8.6e-05,0.023,-0.0093,-0.34,0.0061,-0.0019,-0.42,-0.00012,-0.0033,2.7e-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,-8.5e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,2.7e-05,0,0,-0.00018,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2890000,1,-0.011,-0.013,-0.00014,0.027,-0.011,-0.35,0.0086,-0.0029,-0.46,-0.00012,-0.0033,2.7e-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.00014,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,2.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2990000,1,-0.011,-0.013,-0.00011,0.022,-0.0095,-0.36,0.0056,-0.0021,-0.49,-0.00023,-0.0036,3e-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,-0.00011,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,2.9e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3090000,1,-0.011,-0.013,-0.00011,0.024,-0.011,-0.38,0.0079,-0.0031,-0.53,-0.00023,-0.0036,3e-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,-0.00011,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,2.9e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3190000,1,-0.011,-0.013,-0.00018,0.019,-0.0086,-0.39,0.0052,-0.0021,-0.57,-0.00034,-0.0039,3.2e-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.00018,0.02,-0.0086,-0.39,0.0052,-0.0021,-0.57,-0.00034,-0.0039,3.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0087,0.0087,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3290000,1,-0.011,-0.013,-0.00014,0.023,-0.011,-0.4,0.0073,-0.0031,-0.61,-0.00034,-0.0039,3.2e-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.00014,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,3.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0096,0.0096,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3390000,1,-0.011,-0.012,-0.00018,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,3.3e-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.00018,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,2.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3490000,1,-0.011,-0.013,-0.0002,0.021,-0.012,-0.43,0.0068,-0.0031,-0.69,-0.00044,-0.0041,3.3e-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.0002,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0085,0.0002,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,2.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3590000,1,-0.011,-0.012,-0.00018,0.016,-0.011,-0.44,0.0046,-0.0023,-0.73,-0.00054,-0.0044,3.5e-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.00018,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,3.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3690000,1,-0.011,-0.012,-6.8e-05,0.019,-0.014,-0.46,0.0064,-0.0035,-0.78,-0.00054,-0.0044,3.5e-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,-6.8e-05,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,3.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3790000,1,-0.011,-0.012,-3.3e-05,0.015,-0.013,-0.47,0.0043,-0.0026,-0.83,-0.00066,-0.0045,3.6e-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,-3.3e-05,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00066,-0.0046,3.6e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3890000,1,-0.011,-0.012,-7.2e-05,0.017,-0.014,-0.48,0.0059,-0.004,-0.87,-0.00066,-0.0045,3.6e-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,-7.2e-05,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00066,-0.0046,3.6e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3990000,1,-0.011,-0.012,-7.3e-05,0.02,-0.016,-0.5,0.0078,-0.0055,-0.92,-0.00066,-0.0045,3.6e-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,-7.3e-05,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00066,-0.0046,3.6e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.67,2.5,0.23,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4090000,1,-0.011,-0.012,-8.9e-05,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00078,-0.0047,3.8e-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,-8.9e-05,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,3.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4190000,1,-0.011,-0.012,-0.00012,0.02,-0.017,-0.53,0.0075,-0.0056,-1,-0.00078,-0.0047,3.8e-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,-0.00012,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,3.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4290000,1,-0.01,-0.012,-0.00017,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,4e-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.00017,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,4e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0055,0.00016,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4390000,1,-0.01,-0.012,-0.00016,0.018,-0.013,-0.55,0.0072,-0.0054,-1.1,-0.00091,-0.0049,4e-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.00016,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,4e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4490000,1,-0.01,-0.012,-0.00011,0.015,-0.01,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,4.2e-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,-0.00011,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,4.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00015,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4590000,1,-0.01,-0.012,-8.5e-05,0.018,-0.012,-0.58,0.0068,-0.0048,-1.2,-0.001,-0.005,4.2e-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,-8.5e-05,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,4.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00016,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4690000,1,-0.01,-0.012,-9.2e-05,0.014,-0.0099,-0.6,0.0049,-0.0034,-1.3,-0.0011,-0.0052,4.3e-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,-9.2e-05,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,4.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4790000,1,-0.01,-0.012,-0.00011,0.016,-0.011,-0.61,0.0064,-0.0044,-1.4,-0.0011,-0.0052,4.3e-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,-0.00011,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,4.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.48,2.7,0.18,0.18,40,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4890000,1,-0.01,-0.012,-0.00013,0.013,-0.01,-0.63,0.0046,-0.0032,-1.4,-0.0012,-0.0053,4.5e-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.011,-0.00013,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,4.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.37,2.8,0.13,0.13,42,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4990000,1,-0.01,-0.012,-0.00016,0.015,-0.011,-0.64,0.006,-0.0043,-1.5,-0.0012,-0.0053,4.5e-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.00016,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,4.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.43,0.44,2.8,0.17,0.17,44,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5090000,1,-0.01,-0.011,-0.00012,0.012,-0.0085,-0.66,0.0043,-0.0031,-1.6,-0.0013,-0.0054,4.6e-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,-0.00012,0.011,-0.0081,-0.66,0.0042,-0.003,-1.6,-0.0013,-0.0054,4.5e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.33,0.33,2.8,0.12,0.12,47,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5190000,1,-0.01,-0.011,-9.9e-05,0.013,-0.0099,-0.67,0.0056,-0.004,-1.6,-0.0013,-0.0054,4.6e-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,-9.9e-05,0.013,-0.0095,-0.67,0.0054,-0.0039,-1.6,-0.0013,-0.0054,4.5e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5290000,1,-0.01,-0.011,-0.00012,0.0093,-0.0073,-0.68,0.0039,-0.0029,-1.7,-0.0013,-0.0055,4.7e-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.0099,-0.011,-0.00012,0.0086,-0.007,-0.68,0.0038,-0.0027,-1.7,-0.0013,-0.0055,4.6e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00035,0.00034,9.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5390000,1,-0.0099,-0.011,-6.7e-05,0.0089,-0.0082,-0.7,0.0048,-0.0036,-1.8,-0.0013,-0.0055,4.7e-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,-6.7e-05,0.0081,-0.0078,-0.7,0.0046,-0.0035,-1.8,-0.0013,-0.0055,4.6e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,3,0.16,0.16,54,0.00035,0.00034,9.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5490000,1,-0.0098,-0.011,-6.4e-05,0.0062,-0.0063,-0.71,0.0033,-0.0026,-1.8,-0.0014,-0.0055,4.7e-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,-6.4e-05,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,4.7e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00012,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5590000,1,-0.0098,-0.011,-9e-05,0.0069,-0.0067,-0.73,0.0039,-0.0032,-1.9,-0.0014,-0.0055,4.7e-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.0097,-0.011,-9e-05,0.0062,-0.0063,-0.73,0.0036,-0.0031,-1.9,-0.0014,-0.0055,4.7e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5690000,1,-0.0096,-0.011,-2.5e-05,0.0049,-0.004,-0.74,0.0027,-0.0022,-2,-0.0014,-0.0056,4.8e-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,-2.5e-05,0.0042,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00012,0.25,0.26,3.1,0.11,0.11,61,0.00022,0.00022,7.5e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5790000,1,-0.0096,-0.011,-3.5e-05,0.0053,-0.003,-0.75,0.0031,-0.0026,-2,-0.0014,-0.0056,4.8e-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.0095,-0.011,-3.4e-05,0.0045,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5890000,1,-0.0095,-0.011,-6.5e-05,0.0045,-0.0012,0.0028,0.0022,-0.0017,-3.7e+02,-0.0014,-0.0056,4.9e-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,-6.5e-05,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5990000,1,-0.0095,-0.011,-4.8e-05,0.0049,0.00023,0.015,0.0026,-0.0017,-3.7e+02,-0.0014,-0.0056,4.9e-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,-4.8e-05,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,4.8e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6090000,1,-0.0094,-0.011,-6.9e-05,0.006,0.0013,-0.011,0.0032,-0.0016,-3.7e+02,-0.0014,-0.0056,4.9e-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,-6.8e-05,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6190000,0.78,-0.014,-0.0027,-0.63,0.0055,0.003,-0.005,0.0024,-0.00067,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-8.8e-05,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0014,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,1,-0.0094,-0.011,-0.00015,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6290000,0.78,-0.014,-0.0027,-0.63,0.0057,0.0017,-0.012,0.0029,-0.00046,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-9.5e-05,-0.017,-0.0037,0.57,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,1,-0.0094,-0.011,-0.00018,0.0051,0.0042,-0.012,0.0025,-6.9e-05,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6390000,0.78,-0.014,-0.0028,-0.63,0.0068,0.0013,-0.05,0.0035,-0.00031,-3.7e+02,-0.0015,-0.0057,4.9e-05,2.1e-08,-1.8e-08,-3.6e-05,-0.017,-0.0037,0.57,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,1,-0.0093,-0.011,-0.00017,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,4.8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6490000,0.78,-0.014,-0.0028,-0.63,0.0071,0.00057,-0.052,0.0042,-0.00023,-3.7e+02,-0.0015,-0.0057,4.9e-05,-1.8e-07,1.5e-07,-8.6e-05,-0.017,-0.0037,0.57,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,1,-0.0093,-0.011,-0.00018,0.0049,0.0053,-0.052,0.0024,0.00093,-3.7e+02,-0.0015,-0.0057,4.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6590000,0.78,-0.014,-0.0028,-0.63,0.00058,0.00014,-0.099,0.0047,-0.0002,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,9.5e-05,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,1.1,1e+02,1e+02,0.23,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
6590000,1,-0.0094,-0.011,-0.00025,0.0038,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0014,-0.0057,4.8e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6690000,0.78,-0.014,-0.0029,-0.63,0.00032,-0.0011,-0.076,0.0048,-0.00025,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.00022,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.78,1e+02,1e+02,0.21,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
6690000,1,-0.0093,-0.011,-0.00033,0.0047,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0014,-0.0057,4.8e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6790000,0.78,-0.014,-0.0029,-0.63,0.0015,-0.00089,-0.11,0.0048,-0.0003,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,8.3e-06,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.6,50,50,0.2,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
6790000,0.78,-0.014,-0.0027,-0.63,0.004,0.0049,-0.11,0.0017,0.0013,-3.7e+02,-0.0014,-0.0057,4.7e-05,0,0,-5.8e-05,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.022,0.18,0.18,0.6,0.11,0.11,0.2,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6890000,0.78,-0.014,-0.0029,-0.63,0.0035,-0.0012,-0.12,0.0051,-0.0004,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-4.3e-05,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.46,51,51,0.18,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
6890000,0.78,-0.014,-0.0027,-0.63,0.0059,0.005,-0.12,0.0022,0.0018,-3.7e+02,-0.0014,-0.0057,4.7e-05,0,0,-0.00011,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.18,0.18,0.46,0.14,0.14,0.18,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6990000,0.78,-0.014,-0.0029,-0.63,0.0036,-0.0022,-0.12,0.0052,-0.00047,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.00034,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.36,35,35,0.16,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
6990000,0.78,-0.014,-0.0028,-0.63,-0.00012,7.4e-05,-0.12,0.0027,0.0022,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.00041,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.36,1e+02,1e+02,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7090000,0.78,-0.014,-0.0029,-0.63,0.004,-0.0019,-0.13,0.0056,-0.00065,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.0007,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.29,36,36,0.16,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
7090000,0.78,-0.014,-0.0028,-0.63,9.7e-05,0.00068,-0.13,0.0027,0.0022,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.00077,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.29,1e+02,1e+02,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7190000,0.78,-0.014,-0.0029,-0.63,0.0055,-0.0019,-0.15,0.0057,-0.00068,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.00049,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.24,27,27,0.15,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
7190000,0.78,-0.014,-0.0028,-0.63,0.0015,0.00099,-0.15,0.0027,0.0022,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.00056,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.24,50,50,0.15,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7290000,0.78,-0.014,-0.0029,-0.63,0.0069,-0.0021,-0.15,0.0063,-0.00086,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.0012,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,24,24,0.2,29,29,0.14,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0
|
7290000,0.78,-0.014,-0.0028,-0.63,0.0027,0.0012,-0.15,0.0029,0.0023,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.0012,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.2,51,51,0.14,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7390000,0.78,-0.014,-0.003,-0.63,0.0072,-0.0037,-0.16,0.007,-0.0012,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.0013,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,24,24,0.18,31,31,0.13,0.00015,0.00015,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
7390000,0.78,-0.014,-0.0028,-0.63,0.0028,-0.00021,-0.16,0.0031,0.0023,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.0014,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,24,24,0.18,34,34,0.13,8e-05,8e-05,4.9e-06,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7490000,0.78,-0.014,-0.003,-0.63,0.0085,-0.004,-0.16,0.0073,-0.0013,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.0021,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.15,26,26,0.12,0.00015,0.00015,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
7490000,0.78,-0.014,-0.0029,-0.63,0.0042,-0.00026,-0.16,0.0034,0.0023,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.0022,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.15,36,36,0.12,8e-05,8e-05,4.9e-06,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7590000,0.78,-0.014,-0.003,-0.63,0.01,-0.0052,-0.17,0.0082,-0.0018,-3.7e+02,-0.0015,-0.0057,4.9e-05,6.7e-07,-5.6e-07,-0.003,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,23,23,0.14,28,28,0.12,0.00015,0.00015,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
7590000,0.78,-0.014,-0.0029,-0.63,0.006,-0.0011,-0.17,0.0039,0.0022,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.003,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.14,37,37,0.12,8e-05,8e-05,4.9e-06,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7690000,0.78,-0.014,-0.0031,-0.63,0.012,-0.0057,-0.16,0.0085,-0.0019,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.005,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,21,21,0.13,24,24,0.11,0.00015,0.00015,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
7690000,0.78,-0.014,-0.003,-0.63,0.0075,-0.0014,-0.16,0.0042,0.0021,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.0051,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,24,24,0.13,29,29,0.11,8e-05,8e-05,4.9e-06,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7790000,0.78,-0.014,-0.0031,-0.63,0.013,-0.0067,-0.16,0.0097,-0.0025,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.007,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,21,21,0.12,27,27,0.11,0.00015,0.00015,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0
|
7790000,0.78,-0.014,-0.003,-0.63,0.0087,-0.0021,-0.16,0.005,0.0019,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.0071,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.12,31,31,0.11,8e-05,8e-05,4.9e-06,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7890000,0.78,-0.014,-0.0031,-0.63,0.016,-0.008,-0.16,0.01,-0.0027,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.0096,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,19,19,0.11,24,24,0.1,0.00015,0.00015,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0
|
7890000,0.78,-0.014,-0.003,-0.63,0.011,-0.0034,-0.16,0.0054,0.0017,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.0096,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,23,23,0.11,26,26,0.1,8e-05,8e-05,4.9e-06,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7990000,0.78,-0.014,-0.0032,-0.63,0.018,-0.0091,-0.16,0.012,-0.0035,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.011,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,19,19,0.1,27,27,0.099,0.00015,0.00015,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0
|
7990000,0.78,-0.014,-0.003,-0.63,0.013,-0.0042,-0.16,0.0066,0.0013,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.011,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,23,23,0.1,28,28,0.099,8e-05,8e-05,4.9e-06,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8090000,0.78,-0.014,-0.0032,-0.63,0.019,-0.01,-0.17,0.012,-0.0036,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.011,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,17,17,0.1,23,23,0.097,0.00015,0.00015,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0
|
8090000,0.78,-0.014,-0.003,-0.63,0.014,-0.0051,-0.17,0.007,0.0011,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.011,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,21,21,0.1,24,24,0.097,8e-05,8e-05,4.9e-06,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8190000,0.78,-0.014,-0.0032,-0.63,0.021,-0.011,-0.18,0.014,-0.0047,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.013,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,17,17,0.099,26,26,0.094,0.00015,0.00015,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0
|
8190000,0.78,-0.014,-0.003,-0.63,0.017,-0.0061,-0.18,0.0085,0.00049,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.013,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,21,21,0.099,27,27,0.094,8e-05,8e-05,4.9e-06,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8290000,0.78,-0.014,-0.0032,-0.63,0.022,-0.012,-0.17,0.014,-0.0047,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.017,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,15,15,0.097,23,23,0.091,0.00015,0.00015,6.3e-06,0.04,0.04,0.036,0,0,0,0,0,0,0,0
|
8290000,0.78,-0.014,-0.0031,-0.63,0.017,-0.0065,-0.17,0.0088,0.00026,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.017,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,19,19,0.097,23,23,0.091,8e-05,8e-05,4.9e-06,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8390000,0.78,-0.014,-0.0033,-0.63,0.024,-0.013,-0.17,0.016,-0.0059,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.021,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,15,15,0.097,26,26,0.091,0.00015,0.00015,6.3e-06,0.04,0.04,0.035,0,0,0,0,0,0,0,0
|
8390000,0.78,-0.014,-0.0031,-0.63,0.019,-0.0074,-0.17,0.011,-0.00047,-3.7e+02,-0.0014,-0.0057,4.7e-05,-1.5e-06,1.3e-06,-0.021,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,19,19,0.097,26,26,0.091,8e-05,8e-05,4.9e-06,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8490000,0.78,-0.014,-0.0033,-0.63,0.024,-0.014,-0.17,0.016,-0.0058,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.025,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,13,13,0.096,23,23,0.089,0.00015,0.00015,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0
|
8490000,0.78,-0.014,-0.0031,-0.63,0.02,-0.0085,-0.17,0.011,-0.0006,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.025,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,17,17,0.096,23,23,0.089,8e-05,8e-05,4.9e-06,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8590000,0.78,-0.014,-0.0033,-0.63,0.027,-0.016,-0.17,0.018,-0.0071,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.029,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,14,14,0.095,26,26,0.088,0.00015,0.00015,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0
|
8590000,0.78,-0.014,-0.0031,-0.63,0.022,-0.01,-0.17,0.013,-0.0015,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.029,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,17,17,0.095,26,26,0.088,8e-05,8e-05,4.9e-06,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8690000,0.78,-0.014,-0.0034,-0.63,0.028,-0.016,-0.16,0.018,-0.0069,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.035,-0.017,-0.0037,0.57,0,0,0,0,0,0.0023,0.0023,0.018,12,12,0.096,22,22,0.088,0.00015,0.00015,6.3e-06,0.04,0.04,0.033,0,0,0,0,0,0,0,0
|
8690000,0.78,-0.014,-0.0032,-0.63,0.024,-0.011,-0.16,0.013,-0.0016,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.035,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,15,15,0.096,23,23,0.088,8e-05,8e-05,4.9e-06,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8790000,0.78,-0.014,-0.0033,-0.63,0.031,-0.018,-0.15,0.021,-0.0085,-3.7e+02,-0.0015,-0.0056,4.9e-05,6.7e-07,-5.6e-07,-0.041,-0.017,-0.0037,0.57,0,0,0,0,0,0.0024,0.0024,0.018,12,12,0.095,25,25,0.087,0.00015,0.00015,6.3e-06,0.04,0.04,0.032,0,0,0,0,0,0,0,0
|
8790000,0.78,-0.014,-0.0031,-0.63,0.026,-0.012,-0.15,0.015,-0.0028,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.041,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,15,15,0.095,26,26,0.087,8e-05,8e-05,4.9e-06,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8890000,0.78,-0.014,-0.0034,-0.63,0.031,-0.018,-0.15,0.02,-0.0082,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.045,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,10,10,0.095,22,22,0.086,0.00015,0.00015,6.3e-06,0.04,0.04,0.03,0,0,0,0,0,0,0,0
|
8890000,0.78,-0.014,-0.0032,-0.63,0.026,-0.012,-0.15,0.015,-0.0028,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.045,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,13,13,0.095,23,23,0.086,8e-05,8e-05,4.9e-06,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8990000,0.78,-0.014,-0.0034,-0.63,0.033,-0.018,-0.14,0.024,-0.0098,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.051,-0.017,-0.0037,0.57,0,0,0,0,0,0.0026,0.0025,0.018,10,10,0.096,24,24,0.087,0.00015,0.00015,6.3e-06,0.04,0.04,0.029,0,0,0,0,0,0,0,0
|
8990000,0.78,-0.014,-0.0032,-0.63,0.028,-0.013,-0.14,0.017,-0.004,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.051,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,14,14,0.096,25,25,0.087,8e-05,8e-05,4.9e-06,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9090000,0.78,-0.014,-0.0035,-0.63,0.034,-0.018,-0.14,0.022,-0.0093,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.053,-0.017,-0.0037,0.57,0,0,0,0,0,0.0026,0.0026,0.018,8.8,8.8,0.095,21,21,0.086,0.00015,0.00015,6.3e-06,0.04,0.04,0.028,0,0,0,0,0,0,0,0
|
9090000,0.78,-0.014,-0.0033,-0.63,0.028,-0.012,-0.14,0.017,-0.0038,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.053,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,12,12,0.095,22,22,0.086,8e-05,8e-05,4.9e-06,0.04,0.04,0.028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9190000,0.78,-0.014,-0.0035,-0.63,0.035,-0.019,-0.14,0.026,-0.011,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.057,-0.017,-0.0037,0.57,0,0,0,0,0,0.0027,0.0027,0.018,8.9,8.9,0.094,24,24,0.085,0.00015,0.00015,6.3e-06,0.04,0.04,0.027,0,0,0,0,0,0,0,0
|
9190000,0.78,-0.014,-0.0033,-0.63,0.03,-0.013,-0.14,0.02,-0.0051,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.057,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,12,12,0.094,25,25,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9290000,0.78,-0.014,-0.0035,-0.63,0.035,-0.02,-0.14,0.025,-0.01,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.061,-0.017,-0.0037,0.57,0,0,0,0,0,0.0028,0.0028,0.018,7.7,7.7,0.093,21,21,0.085,0.00015,0.00015,6.3e-06,0.04,0.04,0.025,0,0,0,0,0,0,0,0
|
9290000,0.78,-0.014,-0.0033,-0.63,0.029,-0.014,-0.14,0.018,-0.0047,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.061,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,10,10,0.093,22,22,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9390000,0.78,-0.014,-0.0035,-0.63,0.036,-0.022,-0.14,0.028,-0.012,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.065,-0.017,-0.0037,0.57,0,0,0,0,0,0.0029,0.0029,0.018,7.8,7.8,0.093,23,23,0.086,0.00015,0.00015,6.3e-06,0.04,0.04,0.024,0,0,0,0,0,0,0,0
|
9390000,0.78,-0.014,-0.0033,-0.63,0.03,-0.016,-0.14,0.021,-0.0062,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.065,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,10,10,0.093,24,24,0.086,8e-05,8e-05,4.9e-06,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9490000,0.78,-0.014,-0.0035,-0.63,0.039,-0.023,-0.13,0.032,-0.015,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.068,-0.017,-0.0037,0.57,0,0,0,0,0,0.003,0.003,0.018,7.9,7.9,0.091,25,25,0.085,0.00015,0.00015,6.3e-06,0.04,0.04,0.023,0,0,0,0,0,0,0,0
|
9490000,0.78,-0.014,-0.0033,-0.63,0.03,-0.015,-0.13,0.02,-0.0057,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.068,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,8.9,8.9,0.091,21,21,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9590000,0.78,-0.014,-0.0035,-0.63,0.039,-0.023,-0.13,0.03,-0.014,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.072,-0.017,-0.0037,0.57,0,0,0,0,0,0.0031,0.0031,0.018,6.9,6.9,0.09,22,22,0.085,0.00015,0.00015,6.3e-06,0.04,0.04,0.021,0,0,0,0,0,0,0,0
|
9590000,0.78,-0.014,-0.0033,-0.63,0.033,-0.016,-0.13,0.023,-0.0073,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.072,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,8.9,8.9,0.09,23,23,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9690000,0.78,-0.014,-0.0036,-0.63,0.042,-0.026,-0.12,0.035,-0.016,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.077,-0.017,-0.0037,0.57,0,0,0,0,0,0.0032,0.0032,0.018,7,7,0.089,24,24,0.086,0.00015,0.00015,6.3e-06,0.04,0.04,0.02,0,0,0,0,0,0,0,0
|
9690000,0.78,-0.014,-0.0034,-0.63,0.035,-0.019,-0.12,0.027,-0.009,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.077,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,9,9,0.089,26,26,0.086,8e-05,8e-05,4.9e-06,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9790000,0.78,-0.014,-0.0036,-0.63,0.04,-0.027,-0.11,0.033,-0.015,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.082,-0.017,-0.0037,0.57,0,0,0,0,0,0.0033,0.0033,0.018,6.1,6.1,0.087,21,21,0.085,0.00015,0.00014,6.3e-06,0.04,0.04,0.019,0,0,0,0,0,0,0,0
|
9790000,0.78,-0.014,-0.0034,-0.63,0.033,-0.02,-0.11,0.025,-0.0086,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.082,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,7.8,7.8,0.087,23,23,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9890000,0.78,-0.014,-0.0036,-0.63,0.043,-0.028,-0.11,0.037,-0.018,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.085,-0.017,-0.0037,0.57,0,0,0,0,0,0.0034,0.0034,0.018,6.2,6.2,0.084,23,23,0.085,0.00015,0.00014,6.3e-06,0.04,0.04,0.018,0,0,0,0,0,0,0,0
|
9890000,0.78,-0.014,-0.0034,-0.63,0.035,-0.021,-0.11,0.028,-0.011,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.085,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0021,0.018,7.9,7.9,0.084,25,25,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9990000,0.78,-0.014,-0.0037,-0.63,0.042,-0.028,-0.1,0.035,-0.017,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.089,-0.017,-0.0037,0.57,0,0,0,0,0,0.0035,0.0035,0.018,5.5,5.5,0.083,20,20,0.086,0.00014,0.00014,6.3e-06,0.04,0.04,0.017,0,0,0,0,0,0,0,0
|
9990000,0.78,-0.014,-0.0034,-0.63,0.035,-0.02,-0.1,0.026,-0.01,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.089,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,6.8,6.8,0.083,22,22,0.086,8e-05,8e-05,4.9e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10090000,0.78,-0.014,-0.0037,-0.63,0.044,-0.029,-0.096,0.039,-0.02,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.091,-0.017,-0.0037,0.57,0,0,0,0,0,0.0036,0.0036,0.018,5.6,5.6,0.08,22,22,0.085,0.00014,0.00014,6.3e-06,0.04,0.04,0.016,0,0,0,0,0,0,0,0
|
10090000,0.78,-0.014,-0.0035,-0.63,0.036,-0.021,-0.096,0.03,-0.012,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.091,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,6.9,6.9,0.08,24,24,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10190000,0.78,-0.014,-0.0037,-0.63,0.043,-0.03,-0.096,0.037,-0.019,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.093,-0.017,-0.0037,0.57,0,0,0,0,0,0.0037,0.0037,0.018,5,5,0.078,20,20,0.084,0.00014,0.00014,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0
|
10190000,0.78,-0.014,-0.0035,-0.63,0.036,-0.022,-0.096,0.028,-0.011,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.093,-0.017,-0.0037,0.57,0,0,0,0,0,0.0023,0.0023,0.018,6.1,6.1,0.078,21,21,0.084,8e-05,8e-05,4.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10290000,0.78,-0.014,-0.0037,-0.63,0.045,-0.031,-0.083,0.042,-0.022,-3.7e+02,-0.0015,-0.0056,4.8e-05,6.7e-07,-5.6e-07,-0.098,-0.017,-0.0037,0.57,0,0,0,0,0,0.0038,0.0038,0.018,5.1,5.1,0.076,21,21,0.085,0.00014,0.00014,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0
|
10290000,0.78,-0.014,-0.0035,-0.63,0.037,-0.023,-0.084,0.032,-0.014,-3.7e+02,-0.0014,-0.0057,4.8e-05,-1.5e-06,1.3e-06,-0.098,-0.017,-0.0037,0.57,0,0,0,0,0,0.0024,0.0024,0.018,6.2,6.2,0.076,23,23,0.085,8e-05,8e-05,4.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10390000,0.78,-0.014,-0.0037,-0.63,0.011,-0.021,0.0096,0.00095,-0.0019,-3.7e+02,-0.0015,-0.0056,4.8e-05,6e-07,-5.1e-07,-0.1,-0.017,-0.0037,0.57,0,0,0,0,0,0.0039,0.0039,0.018,0.25,0.25,0.56,0.25,0.25,0.078,0.00014,0.00014,6.3e-06,0.04,0.04,0.013,0,0,0,0,0,0,0,0
|
10390000,0.78,-0.014,-0.0034,-0.63,0.011,-0.021,0.0096,0.00094,-0.0019,-3.7e+02,-0.0014,-0.0057,4.9e-05,-7.7e-05,6.1e-05,-0.1,-0.017,-0.0037,0.57,0,0,0,0,0,0.0024,0.0024,0.018,0.25,0.25,0.56,0.25,0.25,0.078,8e-05,8e-05,4.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10490000,0.78,-0.014,-0.0037,-0.63,0.013,-0.024,0.023,0.0021,-0.0041,-3.7e+02,-0.0015,-0.0056,4.8e-05,-1.1e-06,7.2e-07,-0.1,-0.017,-0.0037,0.57,0,0,0,0,0,0.0041,0.0041,0.018,0.27,0.27,0.55,0.26,0.26,0.08,0.00014,0.00014,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
|
10490000,0.78,-0.014,-0.0035,-0.63,0.012,-0.023,0.023,0.0021,-0.004,-3.7e+02,-0.0014,-0.0057,4.9e-05,-0.00018,0.00014,-0.1,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,0.26,0.26,0.55,0.26,0.26,0.08,8e-05,8e-05,4.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10590000,0.78,-0.014,-0.0037,-0.63,0.013,-0.013,0.026,0.002,-0.00088,-3.7e+02,-0.0015,-0.0057,4.8e-05,0.00037,-3.4e-05,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0041,0.0041,0.018,0.14,0.14,0.27,0.13,0.13,0.073,0.00014,0.00014,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0
|
10590000,0.78,-0.013,-0.0035,-0.63,0.012,-0.012,0.026,0.002,-0.00088,-3.7e+02,-0.0014,-0.0057,4.8e-05,8.3e-05,0.00014,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,0.13,0.13,0.27,0.13,0.13,0.073,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10690000,0.78,-0.014,-0.0037,-0.63,0.015,-0.013,0.03,0.0033,-0.0021,-3.7e+02,-0.0015,-0.0057,4.8e-05,0.00037,-3.2e-05,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0042,0.0042,0.018,0.16,0.16,0.26,0.14,0.14,0.078,0.00014,0.00014,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
10690000,0.78,-0.013,-0.0035,-0.63,0.014,-0.012,0.03,0.0033,-0.0021,-3.7e+02,-0.0014,-0.0057,4.8e-05,4.9e-05,0.00017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,0.15,0.15,0.26,0.14,0.14,0.078,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10790000,0.78,-0.013,-0.0035,-0.63,0.015,-0.0072,0.024,0.003,-0.00081,-3.7e+02,-0.0015,-0.0058,4.7e-05,0.00077,4.1e-05,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.004,0.004,0.018,0.11,0.11,0.17,0.092,0.092,0.072,0.00013,0.00013,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
10790000,0.78,-0.013,-0.0034,-0.63,0.014,-0.0066,0.024,0.003,-0.00083,-3.7e+02,-0.0014,-0.0058,4.8e-05,0.00038,0.00022,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,0.1,0.1,0.17,0.091,0.091,0.072,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10890000,0.78,-0.013,-0.0035,-0.63,0.016,-0.0077,0.02,0.0046,-0.0016,-3.7e+02,-0.0015,-0.0058,4.7e-05,0.00077,4e-05,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0041,0.0041,0.018,0.14,0.14,0.16,0.098,0.098,0.075,0.00013,0.00013,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0
|
10890000,0.78,-0.013,-0.0033,-0.63,0.016,-0.0068,0.02,0.0045,-0.0015,-3.7e+02,-0.0014,-0.0058,4.8e-05,0.00038,0.00022,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,0.12,0.12,0.16,0.098,0.098,0.075,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10990000,0.78,-0.013,-0.0033,-0.63,0.021,-0.00075,0.014,0.0069,0.0002,-3.7e+02,-0.0015,-0.0059,4.7e-05,0.0014,-0.00021,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0036,0.0036,0.018,0.11,0.11,0.12,0.1,0.1,0.071,0.00012,0.00012,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
|
10990000,0.78,-0.013,-0.0033,-0.63,0.02,-0.00091,0.014,0.0068,0.0001,-3.7e+02,-0.0015,-0.0058,4.8e-05,0.00091,-2.9e-05,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0024,0.0024,0.018,0.097,0.097,0.12,0.1,0.1,0.071,7.4e-05,7.4e-05,4.9e-06,0.039,0.039,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11090000,0.78,-0.013,-0.0033,-0.63,0.023,-0.0012,0.019,0.0091,0.00014,-3.7e+02,-0.0015,-0.0059,4.7e-05,0.0014,-0.0002,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0037,0.0037,0.018,0.15,0.15,0.11,0.11,0.11,0.074,0.00012,0.00012,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0
|
11090000,0.78,-0.013,-0.0033,-0.63,0.022,-0.0014,0.019,0.009,2.6e-05,-3.7e+02,-0.0015,-0.0058,4.8e-05,0.00088,-7.9e-06,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0024,0.0024,0.018,0.12,0.12,0.11,0.11,0.11,0.074,7.4e-05,7.4e-05,4.9e-06,0.039,0.039,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11190000,0.78,-0.013,-0.0031,-0.63,0.023,0.0036,0.0076,0.011,0.002,-3.7e+02,-0.0015,-0.0059,4.6e-05,0.0018,-0.00017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0031,0.0031,0.018,0.12,0.12,0.084,0.11,0.11,0.069,0.00011,0.00011,6.3e-06,0.039,0.039,0.01,0,0,0,0,0,0,0,0
|
11190000,0.78,-0.013,-0.0031,-0.63,0.022,0.0027,0.0076,0.011,0.0018,-3.7e+02,-0.0015,-0.0058,4.7e-05,0.0014,-1.9e-05,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.098,0.098,0.084,0.11,0.11,0.069,7e-05,7e-05,4.9e-06,0.039,0.039,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11290000,0.78,-0.013,-0.0032,-0.63,0.025,0.0038,0.0073,0.013,0.0023,-3.7e+02,-0.0015,-0.0059,4.6e-05,0.0018,-0.00017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0032,0.0032,0.018,0.15,0.15,0.078,0.12,0.12,0.072,0.00011,0.00011,6.3e-06,0.039,0.039,0.01,0,0,0,0,0,0,0,0
|
11290000,0.78,-0.013,-0.0032,-0.63,0.024,0.0028,0.0073,0.013,0.002,-3.7e+02,-0.0015,-0.0058,4.7e-05,0.0013,-1.4e-05,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.12,0.12,0.078,0.12,0.12,0.072,7e-05,7e-05,4.9e-06,0.039,0.039,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11390000,0.78,-0.013,-0.0028,-0.63,0.015,0.0022,0.0017,0.0068,0.0012,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0019,0.00073,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,0.11,0.11,0.063,0.084,0.084,0.068,9.2e-05,9.1e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
11390000,0.78,-0.013,-0.003,-0.63,0.016,0.0016,0.0017,0.007,0.0011,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0014,0.00094,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.095,0.095,0.063,0.083,0.083,0.068,6.5e-05,6.5e-05,4.9e-06,0.038,0.038,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11490000,0.78,-0.013,-0.0028,-0.63,0.017,0.002,0.0025,0.0084,0.0014,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0019,0.00073,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0026,0.0026,0.018,0.14,0.14,0.058,0.093,0.093,0.069,9.2e-05,9.1e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
11490000,0.78,-0.013,-0.003,-0.63,0.018,0.0012,0.0025,0.0087,0.0013,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0014,0.00095,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,0.12,0.12,0.058,0.092,0.092,0.069,6.5e-05,6.5e-05,4.9e-06,0.038,0.038,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11590000,0.78,-0.014,-0.0026,-0.63,0.012,0.00078,-0.0034,0.005,0.00089,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0019,0.0013,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.11,0.11,0.049,0.07,0.07,0.066,8e-05,8e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
11590000,0.78,-0.014,-0.0027,-0.63,0.014,0.00027,-0.0034,0.0053,0.00084,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0015,0.0016,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.094,0.094,0.049,0.07,0.07,0.066,6.1e-05,6.1e-05,4.9e-06,0.038,0.038,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11690000,0.78,-0.014,-0.0025,-0.63,0.014,-0.00017,-0.0079,0.0063,0.00096,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0019,0.0013,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.13,0.13,0.046,0.079,0.079,0.066,8e-05,8e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
11690000,0.78,-0.014,-0.0027,-0.63,0.016,-0.00077,-0.008,0.0068,0.00085,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0016,0.0016,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.11,0.11,0.046,0.078,0.078,0.066,6.1e-05,6.1e-05,4.9e-06,0.038,0.038,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11790000,0.78,-0.014,-0.0021,-0.63,0.0061,0.0048,-0.0098,0.0022,0.0025,-3.7e+02,-0.0011,-0.006,3.6e-05,0.0023,0.0018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.1,0.1,0.039,0.062,0.062,0.063,7.1e-05,7.1e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
11790000,0.78,-0.014,-0.0023,-0.63,0.0086,0.0039,-0.0098,0.0028,0.0024,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.002,0.0023,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.091,0.091,0.039,0.062,0.062,0.063,5.7e-05,5.7e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11890000,0.78,-0.014,-0.0021,-0.63,0.0053,0.0057,-0.011,0.0028,0.003,-3.7e+02,-0.0011,-0.006,3.6e-05,0.0023,0.0018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,0.12,0.12,0.037,0.071,0.071,0.063,7.1e-05,7.1e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0
|
11890000,0.78,-0.014,-0.0023,-0.63,0.0083,0.0046,-0.011,0.0036,0.0028,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.002,0.0023,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.037,0.07,0.07,0.063,5.7e-05,5.7e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11990000,0.78,-0.014,-0.0019,-0.63,-0.0007,0.0075,-0.016,0.00013,0.0037,-3.7e+02,-0.0011,-0.006,3.4e-05,0.0024,0.002,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.096,0.096,0.033,0.057,0.057,0.061,6.3e-05,6.4e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
11990000,0.78,-0.014,-0.0022,-0.63,0.0021,0.0066,-0.016,0.00072,0.0035,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0023,0.0028,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.087,0.087,0.033,0.057,0.057,0.061,5.3e-05,5.3e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12090000,0.78,-0.014,-0.0019,-0.63,-0.0019,0.0072,-0.022,-3e-06,0.0044,-3.7e+02,-0.0011,-0.006,3.4e-05,0.0024,0.002,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.031,0.066,0.066,0.061,6.3e-05,6.4e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
12090000,0.78,-0.014,-0.0022,-0.63,0.0013,0.0061,-0.022,0.00088,0.0042,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0023,0.0027,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.1,0.1,0.031,0.065,0.065,0.061,5.3e-05,5.3e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12190000,0.78,-0.014,-0.0021,-0.63,0.0016,0.0037,-0.017,0.0018,0.003,-3.7e+02,-0.0011,-0.006,3.5e-05,0.0022,0.002,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.089,0.089,0.028,0.054,0.054,0.059,5.8e-05,5.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
12190000,0.78,-0.014,-0.0023,-0.63,0.0038,0.003,-0.017,0.0022,0.0029,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.002,0.0027,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.082,0.082,0.028,0.054,0.054,0.059,5e-05,5e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12290000,0.78,-0.014,-0.002,-0.63,0.0025,0.0038,-0.016,0.002,0.0034,-3.7e+02,-0.0011,-0.006,3.5e-05,0.0022,0.002,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.11,0.11,0.028,0.063,0.063,0.059,5.8e-05,5.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
12290000,0.78,-0.014,-0.0023,-0.63,0.005,0.003,-0.016,0.0027,0.0032,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.002,0.0027,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.097,0.097,0.028,0.062,0.062,0.059,5e-05,5e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12390000,0.78,-0.014,-0.0021,-0.63,0.004,0.002,-0.015,0.0031,0.0024,-3.7e+02,-0.0011,-0.006,3.6e-05,0.0021,0.002,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.082,0.082,0.026,0.053,0.053,0.057,5.4e-05,5.4e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
12390000,0.78,-0.014,-0.0023,-0.63,0.0058,0.0014,-0.015,0.0034,0.0024,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0019,0.0027,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.001,0.001,0.018,0.077,0.077,0.026,0.052,0.052,0.057,4.8e-05,4.8e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12490000,0.78,-0.014,-0.0021,-0.63,0.0043,0.001,-0.018,0.0035,0.0026,-3.7e+02,-0.0011,-0.006,3.6e-05,0.0021,0.002,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.096,0.096,0.026,0.061,0.061,0.057,5.4e-05,5.4e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0
|
12490000,0.78,-0.014,-0.0023,-0.63,0.0064,0.00036,-0.018,0.004,0.0025,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0019,0.0027,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.09,0.09,0.026,0.06,0.06,0.057,4.8e-05,4.8e-05,4.9e-06,0.037,0.037,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12590000,0.78,-0.014,-0.0018,-0.63,-0.007,-0.00068,-0.023,-0.0026,0.002,-3.7e+02,-0.001,-0.006,3.3e-05,0.0021,0.0021,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.001,0.001,0.018,0.076,0.076,0.025,0.051,0.051,0.055,5e-05,5e-05,6.3e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0
|
12590000,0.78,-0.014,-0.002,-0.63,-0.0047,-0.0012,-0.023,-0.0021,0.0019,-3.7e+02,-0.0011,-0.0059,3.6e-05,0.002,0.003,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00096,0.00096,0.018,0.072,0.072,0.025,0.051,0.051,0.055,4.6e-05,4.6e-05,4.9e-06,0.037,0.037,0.0099,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12690000,0.78,-0.014,-0.0018,-0.63,-0.0087,-0.0016,-0.027,-0.0033,0.0018,-3.7e+02,-0.001,-0.006,3.3e-05,0.0022,0.0021,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.088,0.088,0.025,0.06,0.06,0.055,5e-05,5e-05,6.3e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0
|
12690000,0.78,-0.014,-0.002,-0.63,-0.0062,-0.0023,-0.027,-0.0026,0.0017,-3.7e+02,-0.0011,-0.0059,3.6e-05,0.002,0.003,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00099,0.00099,0.018,0.083,0.083,0.025,0.059,0.059,0.055,4.6e-05,4.6e-05,4.9e-06,0.037,0.037,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12790000,0.78,-0.014,-0.0017,-0.63,-0.015,-0.0012,-0.03,-0.0072,0.0016,-3.7e+02,-0.00095,-0.006,3.1e-05,0.0022,0.0022,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00097,0.00097,0.018,0.071,0.071,0.024,0.05,0.05,0.053,4.7e-05,4.7e-05,6.3e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0
|
12790000,0.78,-0.014,-0.0019,-0.63,-0.013,-0.0018,-0.03,-0.0067,0.0015,-3.7e+02,-0.0011,-0.0059,3.4e-05,0.002,0.0032,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.067,0.067,0.024,0.05,0.05,0.053,4.4e-05,4.4e-05,4.9e-06,0.037,0.037,0.0097,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12890000,0.78,-0.014,-0.0016,-0.63,-0.017,-0.00081,-0.029,-0.0088,0.0015,-3.7e+02,-0.00095,-0.006,3.1e-05,0.0021,0.0022,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.001,0.001,0.018,0.081,0.081,0.025,0.059,0.059,0.054,4.7e-05,4.7e-05,6.3e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0
|
12890000,0.78,-0.014,-0.0018,-0.63,-0.015,-0.0015,-0.029,-0.0081,0.0014,-3.7e+02,-0.0011,-0.0059,3.4e-05,0.002,0.0032,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00093,0.00093,0.018,0.078,0.077,0.025,0.058,0.058,0.054,4.4e-05,4.4e-05,4.9e-06,0.037,0.037,0.0096,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12990000,0.78,-0.014,-0.0019,-0.63,-0.0099,-0.00047,-0.03,-0.0044,0.0016,-3.7e+02,-0.001,-0.006,3.4e-05,0.002,0.0023,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00093,0.00093,0.018,0.07,0.07,0.025,0.06,0.06,0.052,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
|
12990000,0.78,-0.014,-0.002,-0.63,-0.0081,-0.0011,-0.03,-0.0039,0.0015,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0019,0.0032,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.067,0.067,0.025,0.059,0.059,0.052,4.2e-05,4.2e-05,4.9e-06,0.037,0.037,0.0094,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13090000,0.78,-0.014,-0.0019,-0.63,-0.011,-0.00043,-0.03,-0.0055,0.0015,-3.7e+02,-0.001,-0.006,3.4e-05,0.002,0.0024,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00096,0.00096,0.018,0.08,0.08,0.025,0.07,0.07,0.052,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0
|
13090000,0.78,-0.014,-0.002,-0.63,-0.0089,-0.0011,-0.03,-0.0048,0.0014,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0019,0.0032,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.077,0.077,0.025,0.069,0.069,0.052,4.2e-05,4.2e-05,4.9e-06,0.037,0.037,0.0094,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13190000,0.78,-0.014,-0.002,-0.63,-0.0048,-0.0015,-0.027,-0.0008,0.0014,-3.7e+02,-0.0011,-0.006,3.6e-05,0.0018,0.0026,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.069,0.069,0.025,0.07,0.07,0.051,4.3e-05,4.3e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
|
13190000,0.78,-0.014,-0.0022,-0.63,-0.0033,-0.0022,-0.027,-0.00042,0.0014,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0017,0.0033,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00085,0.00085,0.018,0.067,0.067,0.025,0.069,0.069,0.051,4e-05,4e-05,4.9e-06,0.037,0.037,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13290000,0.78,-0.014,-0.0021,-0.63,-0.0052,-0.0022,-0.024,-0.0013,0.0012,-3.7e+02,-0.0011,-0.006,3.6e-05,0.0017,0.0028,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00093,0.00093,0.018,0.078,0.078,0.027,0.08,0.08,0.051,4.3e-05,4.3e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0
|
13290000,0.78,-0.014,-0.0022,-0.63,-0.0035,-0.003,-0.024,-0.00077,0.0011,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0016,0.0034,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.075,0.075,0.027,0.08,0.08,0.051,4e-05,4.1e-05,4.9e-06,0.037,0.037,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13390000,0.78,-0.014,-0.0021,-0.63,-0.0023,-0.0024,-0.02,0.0012,0.0015,-3.7e+02,-0.0012,-0.006,3.7e-05,0.0015,0.003,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.067,0.067,0.026,0.08,0.08,0.05,4.1e-05,4.1e-05,6.3e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0
|
13390000,0.78,-0.014,-0.0022,-0.63,-0.001,-0.0031,-0.02,0.0016,0.0014,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0015,0.0036,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00083,0.00083,0.018,0.065,0.065,0.026,0.079,0.079,0.05,3.9e-05,3.9e-05,4.9e-06,0.037,0.037,0.0088,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13490000,0.78,-0.014,-0.0021,-0.63,-0.0024,-0.0022,-0.019,0.00097,0.0012,-3.7e+02,-0.0012,-0.006,3.7e-05,0.0014,0.0031,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.076,0.076,0.028,0.091,0.091,0.05,4.1e-05,4.1e-05,6.3e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0
|
13490000,0.78,-0.014,-0.0022,-0.63,-0.00087,-0.0031,-0.019,0.0014,0.0011,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0015,0.0036,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00085,0.00085,0.018,0.073,0.073,0.028,0.09,0.09,0.05,3.9e-05,3.9e-05,4.9e-06,0.037,0.037,0.0087,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13590000,0.78,-0.014,-0.0021,-0.63,0.00073,-0.0033,-0.021,0.0034,0.0015,-3.7e+02,-0.0012,-0.006,3.8e-05,0.0015,0.0032,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00085,0.00085,0.018,0.065,0.065,0.028,0.089,0.089,0.05,3.9e-05,3.9e-05,6.3e-06,0.037,0.037,0.0084,0,0,0,0,0,0,0,0
|
13590000,0.78,-0.014,-0.0023,-0.63,0.0019,-0.0041,-0.021,0.0037,0.0014,-3.7e+02,-0.0013,-0.0059,4e-05,0.0015,0.0037,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.064,0.064,0.028,0.089,0.089,0.05,3.7e-05,3.7e-05,4.9e-06,0.037,0.037,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13690000,0.78,-0.014,-0.0021,-0.63,0.00017,-0.0053,-0.025,0.0035,0.0011,-3.7e+02,-0.0012,-0.006,3.8e-05,0.0015,0.0031,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00088,0.00088,0.018,0.073,0.073,0.029,0.1,0.1,0.05,3.9e-05,3.9e-05,6.3e-06,0.037,0.037,0.0083,0,0,0,0,0,0,0,0
|
13690000,0.78,-0.014,-0.0023,-0.63,0.0015,-0.0061,-0.025,0.0039,0.00089,-3.7e+02,-0.0013,-0.0059,4e-05,0.0015,0.0037,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.071,0.071,0.029,0.1,0.1,0.05,3.7e-05,3.7e-05,4.9e-06,0.037,0.037,0.0083,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13790000,0.78,-0.014,-0.0022,-0.63,0.0027,-0.0062,-0.027,0.0048,-0.00081,-3.7e+02,-0.0012,-0.006,3.9e-05,0.0015,0.0033,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00083,0.00083,0.018,0.056,0.056,0.029,0.074,0.074,0.049,3.7e-05,3.7e-05,6.3e-06,0.037,0.037,0.0079,0,0,0,0,0,0,0,0
|
13790000,0.78,-0.014,-0.0023,-0.63,0.0038,-0.0069,-0.027,0.0049,-0.00082,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0015,0.0038,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.054,0.054,0.029,0.074,0.074,0.049,3.6e-05,3.6e-05,4.9e-06,0.037,0.037,0.0079,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13890000,0.78,-0.014,-0.0022,-0.63,0.0022,-0.0065,-0.031,0.0051,-0.0014,-3.7e+02,-0.0012,-0.006,3.9e-05,0.0016,0.0033,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00086,0.00086,0.018,0.063,0.063,0.03,0.084,0.084,0.05,3.7e-05,3.7e-05,6.3e-06,0.037,0.037,0.0078,0,0,0,0,0,0,0,0
|
13890000,0.78,-0.014,-0.0023,-0.63,0.0034,-0.0073,-0.031,0.0053,-0.0015,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0015,0.0037,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.061,0.061,0.03,0.083,0.083,0.05,3.6e-05,3.6e-05,4.9e-06,0.037,0.037,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13990000,0.78,-0.014,-0.0023,-0.63,0.0041,-0.0074,-0.03,0.0055,-0.0023,-3.7e+02,-0.0012,-0.006,3.9e-05,0.0016,0.0034,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.051,0.051,0.03,0.065,0.065,0.05,3.5e-05,3.5e-05,6.3e-06,0.037,0.037,0.0074,0,0,0,0,0,0,0,0
|
13990000,0.78,-0.014,-0.0024,-0.63,0.0052,-0.0081,-0.03,0.0055,-0.0023,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0015,0.0039,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.049,0.049,0.03,0.065,0.065,0.05,3.4e-05,3.4e-05,4.9e-06,0.037,0.037,0.0074,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14090000,0.78,-0.014,-0.0023,-0.63,0.0043,-0.0081,-0.031,0.0059,-0.0031,-3.7e+02,-0.0012,-0.006,3.9e-05,0.0016,0.0034,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00085,0.00085,0.018,0.057,0.057,0.031,0.073,0.073,0.05,3.5e-05,3.5e-05,6.3e-06,0.037,0.037,0.0073,0,0,0,0,0,0,0,0
|
14090000,0.78,-0.014,-0.0024,-0.63,0.0055,-0.0089,-0.031,0.0061,-0.0032,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0015,0.0039,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.056,0.056,0.031,0.073,0.073,0.05,3.4e-05,3.4e-05,4.9e-06,0.037,0.037,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14190000,0.78,-0.013,-0.0023,-0.63,0.0063,-0.0063,-0.033,0.0077,-0.0019,-3.7e+02,-0.0013,-0.006,4e-05,0.0015,0.0037,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.048,0.048,0.031,0.059,0.059,0.05,3.3e-05,3.3e-05,6.3e-06,0.037,0.037,0.0069,0,0,0,0,0,0,0,0
|
14190000,0.78,-0.013,-0.0024,-0.63,0.0073,-0.0071,-0.033,0.0077,-0.0019,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0015,0.0041,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.047,0.047,0.031,0.059,0.059,0.05,3.3e-05,3.3e-05,4.9e-06,0.037,0.037,0.0069,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14290000,0.78,-0.013,-0.0023,-0.63,0.0063,-0.0076,-0.032,0.0083,-0.0026,-3.7e+02,-0.0013,-0.006,4e-05,0.0014,0.0038,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.054,0.054,0.032,0.067,0.067,0.051,3.3e-05,3.3e-05,6.3e-06,0.037,0.037,0.0067,0,0,0,0,0,0,0,0
|
14290000,0.78,-0.013,-0.0024,-0.63,0.0074,-0.0085,-0.032,0.0084,-0.0027,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0014,0.0042,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.053,0.053,0.032,0.066,0.066,0.051,3.3e-05,3.3e-05,4.9e-06,0.037,0.037,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14390000,0.78,-0.013,-0.0023,-0.63,0.0085,-0.0074,-0.034,0.0094,-0.0017,-3.7e+02,-0.0013,-0.006,4.1e-05,0.0013,0.0041,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.046,0.046,0.031,0.055,0.055,0.05,3.2e-05,3.2e-05,6.3e-06,0.037,0.037,0.0063,0,0,0,0,0,0,0,0
|
14390000,0.78,-0.013,-0.0024,-0.63,0.0095,-0.0082,-0.034,0.0094,-0.0017,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0013,0.0045,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.045,0.045,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,4.9e-06,0.037,0.037,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14490000,0.78,-0.013,-0.0023,-0.63,0.0096,-0.009,-0.037,0.01,-0.0025,-3.7e+02,-0.0013,-0.006,4.1e-05,0.0014,0.0041,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00083,0.00083,0.018,0.052,0.052,0.032,0.062,0.062,0.051,3.2e-05,3.2e-05,6.3e-06,0.037,0.037,0.0062,0,0,0,0,0,0,0,0
|
14490000,0.78,-0.013,-0.0024,-0.63,0.011,-0.0099,-0.037,0.01,-0.0026,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0013,0.0044,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.051,0.051,0.032,0.062,0.062,0.051,3.1e-05,3.1e-05,4.9e-06,0.037,0.037,0.0062,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14590000,0.78,-0.013,-0.0021,-0.63,0.005,-0.01,-0.037,0.0064,-0.0031,-3.7e+02,-0.0013,-0.006,4e-05,0.0013,0.0037,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.045,0.045,0.031,0.052,0.052,0.051,3e-05,3e-05,6.3e-06,0.037,0.037,0.0058,0,0,0,0,0,0,0,0
|
14590000,0.78,-0.013,-0.0023,-0.63,0.0061,-0.011,-0.037,0.0065,-0.0032,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0012,0.004,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.044,0.044,0.031,0.052,0.052,0.051,3e-05,3e-05,4.9e-06,0.036,0.036,0.0058,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14690000,0.78,-0.013,-0.0021,-0.63,0.0036,-0.0081,-0.034,0.0068,-0.004,-3.7e+02,-0.0013,-0.006,4e-05,0.0012,0.0037,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00083,0.00083,0.018,0.051,0.051,0.032,0.059,0.059,0.051,3e-05,3e-05,6.3e-06,0.037,0.037,0.0056,0,0,0,0,0,0,0,0
|
14690000,0.78,-0.013,-0.0022,-0.63,0.0048,-0.0091,-0.034,0.007,-0.0042,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0011,0.0041,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.05,0.05,0.032,0.059,0.059,0.051,3e-05,3e-05,4.9e-06,0.036,0.036,0.0056,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14790000,0.78,-0.013,-0.002,-0.63,0.00046,-0.0084,-0.03,0.004,-0.0043,-3.7e+02,-0.0012,-0.006,3.9e-05,0.001,0.0035,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.044,0.044,0.031,0.05,0.05,0.051,2.8e-05,2.8e-05,6.3e-06,0.037,0.037,0.0053,0,0,0,0,0,0,0,0
|
14790000,0.78,-0.013,-0.0021,-0.63,0.0016,-0.0093,-0.03,0.0041,-0.0045,-3.7e+02,-0.0013,-0.006,4e-05,0.00096,0.0039,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.043,0.043,0.031,0.05,0.05,0.051,2.8e-05,2.8e-05,4.9e-06,0.036,0.036,0.0053,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14890000,0.78,-0.013,-0.002,-0.63,-0.0007,-0.01,-0.033,0.004,-0.0053,-3.7e+02,-0.0012,-0.006,3.9e-05,0.001,0.0035,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.05,0.05,0.031,0.057,0.057,0.052,2.8e-05,2.8e-05,6.3e-06,0.037,0.037,0.0051,0,0,0,0,0,0,0,0
|
14890000,0.78,-0.013,-0.0021,-0.63,0.00058,-0.011,-0.033,0.0042,-0.0055,-3.7e+02,-0.0013,-0.006,4e-05,0.00098,0.0039,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.049,0.049,0.031,0.057,0.057,0.052,2.8e-05,2.8e-05,4.9e-06,0.036,0.036,0.0051,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14990000,0.78,-0.013,-0.0019,-0.63,-0.001,-0.0079,-0.029,0.0033,-0.0039,-3.7e+02,-0.0012,-0.006,3.8e-05,0.00065,0.0037,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00078,0.018,0.043,0.043,0.03,0.049,0.049,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0
|
14990000,0.78,-0.013,-0.002,-0.63,9.5e-05,-0.0088,-0.029,0.0035,-0.0041,-3.7e+02,-0.0013,-0.006,4e-05,0.00061,0.004,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.03,0.049,0.049,0.051,2.6e-05,2.6e-05,4.9e-06,0.036,0.036,0.0048,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15090000,0.78,-0.013,-0.0019,-0.63,-0.0014,-0.0084,-0.032,0.0032,-0.0048,-3.7e+02,-0.0012,-0.006,3.8e-05,0.0007,0.0036,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.019,0.049,0.049,0.031,0.056,0.056,0.052,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0
|
15090000,0.78,-0.013,-0.002,-0.63,-0.00011,-0.0094,-0.032,0.0035,-0.005,-3.7e+02,-0.0013,-0.006,4e-05,0.00065,0.004,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.048,0.048,0.031,0.055,0.055,0.052,2.6e-05,2.6e-05,4.9e-06,0.036,0.036,0.0046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15190000,0.78,-0.013,-0.0018,-0.63,-0.0017,-0.0077,-0.029,0.0026,-0.0036,-3.7e+02,-0.0012,-0.0061,3.8e-05,0.0004,0.0038,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.019,0.043,0.043,0.03,0.048,0.048,0.052,2.4e-05,2.4e-05,6.3e-06,0.036,0.036,0.0043,0,0,0,0,0,0,0,0
|
15190000,0.78,-0.013,-0.0019,-0.63,-0.00053,-0.0087,-0.029,0.0028,-0.0038,-3.7e+02,-0.0013,-0.006,4e-05,0.00034,0.004,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.042,0.042,0.03,0.048,0.048,0.052,2.4e-05,2.4e-05,4.9e-06,0.036,0.036,0.0043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15290000,0.78,-0.013,-0.0018,-0.63,-0.0021,-0.0085,-0.027,0.0025,-0.0044,-3.7e+02,-0.0012,-0.0061,3.8e-05,0.00031,0.0038,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.019,0.048,0.048,0.03,0.055,0.055,0.052,2.4e-05,2.4e-05,6.3e-06,0.036,0.036,0.0042,0,0,0,0,0,0,0,0
|
15290000,0.78,-0.013,-0.0019,-0.63,-0.00087,-0.0096,-0.027,0.0028,-0.0047,-3.7e+02,-0.0013,-0.006,4e-05,0.00026,0.0041,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.048,0.048,0.03,0.054,0.054,0.052,2.4e-05,2.4e-05,4.9e-06,0.036,0.036,0.0042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15390000,0.78,-0.013,-0.0017,-0.63,-0.0031,-0.0078,-0.024,0.0025,-0.0042,-3.7e+02,-0.0012,-0.0061,3.9e-05,3.7e-05,0.004,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.019,0.046,0.046,0.029,0.057,0.057,0.051,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0039,0,0,0,0,0,0,0,0
|
15390000,0.78,-0.013,-0.0018,-0.63,-0.0019,-0.0088,-0.024,0.0028,-0.0044,-3.7e+02,-0.0013,-0.006,4e-05,-3e-05,0.0042,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.045,0.045,0.029,0.057,0.057,0.051,2.3e-05,2.3e-05,4.9e-06,0.036,0.036,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15490000,0.78,-0.013,-0.0018,-0.63,-0.0044,-0.0081,-0.024,0.0021,-0.0049,-3.7e+02,-0.0012,-0.0061,3.9e-05,5.7e-05,0.004,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.019,0.051,0.051,0.029,0.064,0.064,0.053,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0037,0,0,0,0,0,0,0,0
|
15490000,0.78,-0.013,-0.0019,-0.63,-0.0031,-0.0093,-0.024,0.0025,-0.0053,-3.7e+02,-0.0013,-0.006,4e-05,-1.3e-05,0.0042,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.051,0.051,0.029,0.064,0.064,0.053,2.3e-05,2.3e-05,4.9e-06,0.036,0.036,0.0037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15590000,0.78,-0.013,-0.0017,-0.63,-0.0037,-0.0068,-0.023,0.0023,-0.0045,-3.7e+02,-0.0013,-0.0061,3.9e-05,-0.00017,0.0042,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00075,0.00075,0.019,0.048,0.048,0.028,0.066,0.066,0.052,2.1e-05,2.1e-05,6.3e-06,0.036,0.036,0.0035,0,0,0,0,0,0,0,0
|
15590000,0.78,-0.013,-0.0018,-0.63,-0.0026,-0.0079,-0.023,0.0027,-0.0048,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.00026,0.0044,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.047,0.047,0.028,0.066,0.066,0.052,2.1e-05,2.1e-05,4.9e-06,0.036,0.036,0.0035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15690000,0.78,-0.013,-0.0017,-0.63,-0.0041,-0.0072,-0.023,0.002,-0.0052,-3.7e+02,-0.0013,-0.0061,3.9e-05,-0.00017,0.0042,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.019,0.053,0.053,0.028,0.075,0.075,0.052,2.1e-05,2.1e-05,6.3e-06,0.036,0.036,0.0033,0,0,0,0,0,0,0,0
|
15690000,0.78,-0.013,-0.0018,-0.63,-0.0029,-0.0083,-0.023,0.0024,-0.0056,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.00026,0.0044,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.053,0.053,0.028,0.075,0.075,0.052,2.1e-05,2.1e-05,4.9e-06,0.036,0.036,0.0033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15790000,0.78,-0.013,-0.0017,-0.63,-0.0045,-0.0072,-0.026,0.0018,-0.0053,-3.7e+02,-0.0013,-0.0061,3.9e-05,-5.7e-05,0.0042,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.019,0.044,0.044,0.027,0.06,0.06,0.051,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0
|
15790000,0.78,-0.013,-0.0018,-0.63,-0.0034,-0.0082,-0.026,0.0021,-0.0055,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0002,0.0044,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.044,0.044,0.027,0.06,0.06,0.051,1.9e-05,1.9e-05,4.9e-06,0.035,0.035,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15890000,0.78,-0.013,-0.0017,-0.63,-0.0055,-0.0074,-0.024,0.0013,-0.006,-3.7e+02,-0.0013,-0.0061,3.9e-05,-8e-05,0.0043,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00075,0.00075,0.019,0.049,0.049,0.027,0.068,0.068,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0
|
15890000,0.78,-0.013,-0.0018,-0.63,-0.0043,-0.0085,-0.024,0.0017,-0.0063,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.00022,0.0044,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.049,0.049,0.027,0.068,0.068,0.052,1.9e-05,1.9e-05,4.9e-06,0.035,0.035,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15990000,0.78,-0.013,-0.0017,-0.63,-0.0051,-0.0077,-0.019,0.0014,-0.0059,-3.7e+02,-0.0013,-0.0061,3.9e-05,-0.00011,0.0045,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.019,0.042,0.042,0.026,0.056,0.056,0.051,1.8e-05,1.8e-05,6.3e-06,0.035,0.035,0.0028,0,0,0,0,0,0,0,0
|
15990000,0.78,-0.013,-0.0018,-0.63,-0.0041,-0.0086,-0.019,0.0016,-0.0061,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.00028,0.0046,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.042,0.042,0.026,0.056,0.056,0.051,1.8e-05,1.8e-05,4.9e-06,0.035,0.035,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16090000,0.78,-0.013,-0.0017,-0.63,-0.0068,-0.0084,-0.016,0.00079,-0.0066,-3.7e+02,-0.0013,-0.0061,3.9e-05,-0.00018,0.0045,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.019,0.047,0.047,0.025,0.063,0.063,0.052,1.8e-05,1.8e-05,6.3e-06,0.035,0.035,0.0027,0,0,0,0,0,0,0,0
|
16090000,0.78,-0.013,-0.0018,-0.63,-0.0057,-0.0094,-0.016,0.0011,-0.007,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.00034,0.0047,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.047,0.047,0.026,0.063,0.063,0.052,1.8e-05,1.8e-05,4.9e-06,0.035,0.035,0.0027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16190000,0.78,-0.013,-0.0017,-0.63,-0.0066,-0.0067,-0.014,0.00099,-0.0049,-3.7e+02,-0.0013,-0.0061,4e-05,-0.00045,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0007,0.0007,0.019,0.04,0.04,0.025,0.053,0.053,0.051,1.6e-05,1.6e-05,6.3e-06,0.035,0.035,0.0025,0,0,0,0,0,0,0,0
|
16190000,0.78,-0.013,-0.0018,-0.63,-0.0057,-0.0077,-0.014,0.0012,-0.0051,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.00064,0.0049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00069,0.00069,0.018,0.04,0.04,0.025,0.053,0.053,0.051,1.6e-05,1.6e-05,4.9e-06,0.035,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16290000,0.78,-0.013,-0.0017,-0.63,-0.0083,-0.0067,-0.016,0.00024,-0.0055,-3.7e+02,-0.0013,-0.0061,4e-05,-0.00044,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.019,0.045,0.045,0.024,0.06,0.06,0.052,1.6e-05,1.6e-05,6.3e-06,0.035,0.035,0.0024,0,0,0,0,0,0,0,0
|
16290000,0.78,-0.013,-0.0018,-0.63,-0.0073,-0.0077,-0.016,0.00054,-0.0059,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.00062,0.0049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.045,0.045,0.024,0.06,0.06,0.052,1.6e-05,1.6e-05,4.9e-06,0.035,0.035,0.0024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16390000,0.78,-0.013,-0.0016,-0.63,-0.0072,-0.0043,-0.015,0.00056,-0.0042,-3.7e+02,-0.0013,-0.0061,4e-05,-0.00063,0.0051,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00068,0.00068,0.019,0.039,0.039,0.023,0.051,0.051,0.051,1.5e-05,1.5e-05,6.3e-06,0.035,0.035,0.0022,0,0,0,0,0,0,0,0
|
16390000,0.78,-0.013,-0.0017,-0.63,-0.0063,-0.0052,-0.015,0.00076,-0.0044,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.00084,0.0052,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.039,0.039,0.023,0.051,0.051,0.051,1.5e-05,1.5e-05,4.9e-06,0.035,0.035,0.0022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16490000,0.78,-0.013,-0.0017,-0.63,-0.0063,-0.0049,-0.018,-8.1e-05,-0.0047,-3.7e+02,-0.0013,-0.0061,4e-05,-0.00059,0.0051,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0007,0.0007,0.019,0.044,0.044,0.023,0.057,0.057,0.052,1.5e-05,1.5e-05,6.3e-06,0.035,0.035,0.0022,0,0,0,0,0,0,0,0
|
16490000,0.78,-0.013,-0.0017,-0.63,-0.0053,-0.0059,-0.018,0.00021,-0.005,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.00081,0.0051,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00069,0.00069,0.018,0.044,0.044,0.023,0.057,0.057,0.052,1.5e-05,1.5e-05,4.9e-06,0.035,0.035,0.0021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16590000,0.78,-0.013,-0.0016,-0.63,-0.0089,0.00029,-0.018,-0.0026,-0.00084,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0014,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00066,0.00066,0.019,0.039,0.039,0.022,0.049,0.049,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.002,0,0,0,0,0,0,0,0
|
16590000,0.78,-0.013,-0.0016,-0.63,-0.008,-0.0006,-0.018,-0.0024,-0.0011,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.0016,0.0049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00066,0.00066,0.018,0.038,0.038,0.022,0.049,0.049,0.051,1.4e-05,1.4e-05,4.9e-06,0.034,0.034,0.002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16690000,0.78,-0.013,-0.0015,-0.63,-0.0093,-0.0002,-0.015,-0.0035,-0.00084,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0015,0.0049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00068,0.00068,0.019,0.043,0.043,0.022,0.056,0.056,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0019,0,0,0,0,0,0,0,0
|
16690000,0.78,-0.013,-0.0016,-0.63,-0.0083,-0.0012,-0.015,-0.0032,-0.0012,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.0017,0.0049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.043,0.043,0.022,0.056,0.056,0.051,1.4e-05,1.4e-05,4.9e-06,0.034,0.034,0.0019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16790000,0.78,-0.013,-0.0014,-0.63,-0.011,0.004,-0.014,-0.0053,0.0021,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0021,0.0047,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00065,0.00065,0.019,0.038,0.038,0.021,0.048,0.048,0.05,1.2e-05,1.2e-05,6.3e-06,0.034,0.034,0.0018,0,0,0,0,0,0,0,0
|
16790000,0.78,-0.013,-0.0015,-0.63,-0.0099,0.0031,-0.014,-0.0051,0.0018,-3.7e+02,-0.0013,-0.0062,4.1e-05,-0.0023,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.038,0.038,0.021,0.048,0.048,0.05,1.2e-05,1.2e-05,4.9e-06,0.034,0.034,0.0018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16890000,0.78,-0.013,-0.0014,-0.63,-0.011,0.0035,-0.011,-0.0064,0.0025,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0021,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00066,0.00066,0.019,0.042,0.042,0.021,0.055,0.055,0.051,1.2e-05,1.2e-05,6.3e-06,0.034,0.034,0.0017,0,0,0,0,0,0,0,0
|
16890000,0.78,-0.013,-0.0015,-0.63,-0.0099,0.0026,-0.011,-0.0061,0.0021,-3.7e+02,-0.0013,-0.0062,4.1e-05,-0.0024,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00066,0.00066,0.019,0.042,0.042,0.021,0.054,0.054,0.051,1.2e-05,1.2e-05,4.9e-06,0.034,0.034,0.0017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16990000,0.78,-0.013,-0.0014,-0.63,-0.011,0.0012,-0.01,-0.0062,0.00053,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0017,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00063,0.00063,0.019,0.037,0.037,0.02,0.047,0.047,0.05,1.1e-05,1.1e-05,6.3e-06,0.034,0.034,0.0016,0,0,0,0,0,0,0,0
|
16990000,0.78,-0.013,-0.0015,-0.63,-0.011,0.00043,-0.01,-0.006,0.00029,-3.7e+02,-0.0013,-0.0062,4.1e-05,-0.002,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00063,0.00063,0.019,0.037,0.037,0.02,0.047,0.047,0.05,1.1e-05,1.1e-05,4.9e-06,0.034,0.034,0.0016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17090000,0.78,-0.013,-0.0014,-0.63,-0.012,0.00024,-0.01,-0.0074,0.00063,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0017,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00064,0.00064,0.019,0.042,0.042,0.02,0.054,0.054,0.05,1.1e-05,1.1e-05,6.3e-06,0.034,0.034,0.0016,0,0,0,0,0,0,0,0
|
17090000,0.78,-0.013,-0.0015,-0.63,-0.012,-0.00064,-0.01,-0.0071,0.00031,-3.7e+02,-0.0013,-0.0062,4.1e-05,-0.002,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00064,0.00064,0.019,0.042,0.042,0.02,0.054,0.054,0.05,1.1e-05,1.1e-05,4.9e-06,0.034,0.034,0.0016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17190000,0.78,-0.013,-0.0015,-0.63,-0.013,-0.0032,-0.011,-0.0071,-0.00091,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0014,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00062,0.00061,0.019,0.037,0.037,0.019,0.047,0.047,0.049,1e-05,1e-05,6.3e-06,0.034,0.034,0.0015,0,0,0,0,0,0,0,0
|
17190000,0.78,-0.013,-0.0015,-0.63,-0.012,-0.004,-0.011,-0.0069,-0.0011,-3.7e+02,-0.0013,-0.0062,4.1e-05,-0.0017,0.0048,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00061,0.00061,0.019,0.037,0.037,0.019,0.047,0.047,0.049,1e-05,1e-05,5e-06,0.034,0.034,0.0015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17290000,0.78,-0.013,-0.0014,-0.63,-0.015,-0.0047,-0.0066,-0.0085,-0.0013,-3.7e+02,-0.0013,-0.0062,3.9e-05,-0.0015,0.0049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00063,0.00063,0.019,0.041,0.041,0.019,0.053,0.053,0.049,1e-05,1e-05,6.3e-06,0.034,0.034,0.0014,0,0,0,0,0,0,0,0
|
17290000,0.78,-0.013,-0.0015,-0.63,-0.014,-0.0056,-0.0067,-0.0082,-0.0016,-3.7e+02,-0.0013,-0.0062,4.1e-05,-0.0018,0.0049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00062,0.00063,0.019,0.041,0.041,0.019,0.053,0.053,0.049,1e-05,1e-05,5e-06,0.034,0.034,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17390000,0.78,-0.013,-0.0015,-0.63,-0.013,-0.0064,-0.0047,-0.0066,-0.0023,-3.7e+02,-0.0013,-0.0062,4e-05,-0.0013,0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0006,0.0006,0.019,0.036,0.036,0.018,0.046,0.046,0.048,9.2e-06,9.2e-06,6.3e-06,0.033,0.033,0.0013,0,0,0,0,0,0,0,0
|
17390000,0.78,-0.013,-0.0016,-0.63,-0.012,-0.0072,-0.0047,-0.0064,-0.0025,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.0016,0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0006,0.0006,0.019,0.036,0.036,0.018,0.046,0.046,0.048,9.3e-06,9.3e-06,5e-06,0.033,0.033,0.0013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17490000,0.78,-0.013,-0.0015,-0.63,-0.014,-0.0063,-0.003,-0.0079,-0.0029,-3.7e+02,-0.0013,-0.0062,4e-05,-0.0013,0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00061,0.00061,0.019,0.04,0.04,0.018,0.053,0.053,0.049,9.2e-06,9.2e-06,6.3e-06,0.033,0.033,0.0013,0,0,0,0,0,0,0,0
|
17490000,0.78,-0.013,-0.0016,-0.63,-0.013,-0.0071,-0.003,-0.0076,-0.0032,-3.7e+02,-0.0013,-0.0061,4.2e-05,-0.0016,0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00061,0.00061,0.019,0.04,0.04,0.018,0.053,0.053,0.049,9.3e-06,9.3e-06,5e-06,0.033,0.033,0.0013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17590000,0.78,-0.013,-0.0016,-0.63,-0.013,-0.0072,0.0025,-0.0062,-0.0035,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.0012,0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.035,0.035,0.017,0.046,0.046,0.048,8.3e-06,8.4e-06,6.3e-06,0.033,0.033,0.0012,0,0,0,0,0,0,0,0
|
17590000,0.78,-0.013,-0.0016,-0.63,-0.012,-0.0079,0.0025,-0.0059,-0.0038,-3.7e+02,-0.0014,-0.0061,4.3e-05,-0.0015,0.0057,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.035,0.035,0.017,0.046,0.046,0.048,8.4e-06,8.4e-06,5e-06,0.033,0.033,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17690000,0.78,-0.013,-0.0015,-0.63,-0.013,-0.0084,0.0019,-0.0075,-0.0043,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.0012,0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00059,0.00059,0.019,0.039,0.039,0.017,0.052,0.052,0.048,8.4e-06,8.4e-06,6.3e-06,0.033,0.033,0.0012,0,0,0,0,0,0,0,0
|
17690000,0.78,-0.013,-0.0016,-0.63,-0.013,-0.0092,0.0019,-0.0072,-0.0046,-3.7e+02,-0.0014,-0.0061,4.3e-05,-0.0015,0.0057,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00059,0.00059,0.019,0.039,0.039,0.017,0.052,0.052,0.048,8.4e-06,8.4e-06,5e-06,0.033,0.033,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17790000,0.78,-0.012,-0.0016,-0.63,-0.01,-0.0073,0.0006,-0.0045,-0.004,-3.7e+02,-0.0014,-0.0061,4.2e-05,-0.0012,0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.038,0.038,0.016,0.055,0.055,0.048,7.7e-06,7.7e-06,6.3e-06,0.033,0.033,0.0011,0,0,0,0,0,0,0,0
|
17790000,0.78,-0.012,-0.0016,-0.63,-0.0096,-0.008,0.00058,-0.0042,-0.0043,-3.7e+02,-0.0014,-0.0061,4.4e-05,-0.0016,0.0065,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.038,0.038,0.016,0.055,0.055,0.048,7.8e-06,7.8e-06,5e-06,0.033,0.033,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17890000,0.78,-0.012,-0.0016,-0.63,-0.012,-0.0071,0.0007,-0.0056,-0.0048,-3.7e+02,-0.0014,-0.0061,4.2e-05,-0.0012,0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.042,0.042,0.016,0.062,0.062,0.048,7.7e-06,7.7e-06,6.3e-06,0.033,0.033,0.0011,0,0,0,0,0,0,0,0
|
17890000,0.78,-0.012,-0.0016,-0.63,-0.011,-0.0079,0.00067,-0.0053,-0.0052,-3.7e+02,-0.0014,-0.0061,4.4e-05,-0.0016,0.0065,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.042,0.042,0.016,0.062,0.062,0.048,7.8e-06,7.8e-06,5e-06,0.033,0.033,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17990000,0.78,-0.012,-0.0017,-0.63,-0.0087,-0.0045,0.0019,-0.0021,-0.0044,-3.7e+02,-0.0015,-0.0061,4.3e-05,-0.0012,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00056,0.00056,0.019,0.039,0.039,0.016,0.064,0.064,0.047,7e-06,7e-06,6.3e-06,0.033,0.033,0.001,0,0,0,0,0,0,0,0
|
17990000,0.78,-0.012,-0.0017,-0.63,-0.008,-0.0053,0.0019,-0.0018,-0.0047,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0016,0.0072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00056,0.00056,0.019,0.04,0.04,0.016,0.064,0.064,0.047,7.1e-06,7.1e-06,5e-06,0.033,0.033,0.001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18090000,0.78,-0.012,-0.0017,-0.63,-0.009,-0.0047,0.0043,-0.003,-0.0048,-3.7e+02,-0.0015,-0.0061,4.3e-05,-0.0012,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.044,0.044,0.016,0.072,0.072,0.047,7e-06,7e-06,6.3e-06,0.033,0.033,0.00097,0,0,0,0,0,0,0,0
|
18090000,0.78,-0.012,-0.0017,-0.63,-0.0083,-0.0054,0.0043,-0.0026,-0.0052,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0016,0.0073,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.044,0.044,0.016,0.072,0.072,0.047,7.1e-06,7.1e-06,5e-06,0.033,0.033,0.00097,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18190000,0.78,-0.012,-0.0017,-0.63,-0.0061,-0.0042,0.0056,-0.0001,-0.0035,-3.7e+02,-0.0015,-0.0062,4.4e-05,-0.0013,0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.036,0.036,0.015,0.058,0.058,0.047,6.2e-06,6.3e-06,6.3e-06,0.033,0.033,0.00092,0,0,0,0,0,0,0,0
|
18190000,0.78,-0.012,-0.0017,-0.63,-0.0055,-0.0049,0.0056,0.00016,-0.0038,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0017,0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.036,0.036,0.015,0.058,0.058,0.047,6.3e-06,6.3e-06,5e-06,0.033,0.033,0.00092,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18290000,0.78,-0.012,-0.0016,-0.63,-0.0058,-0.0038,0.0068,-0.00069,-0.0039,-3.7e+02,-0.0015,-0.0062,4.4e-05,-0.0013,0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00055,0.00055,0.019,0.04,0.04,0.015,0.066,0.066,0.046,6.2e-06,6.3e-06,6.3e-06,0.033,0.033,0.00089,0,0,0,0,0,0,0,0
|
18290000,0.78,-0.012,-0.0017,-0.63,-0.0051,-0.0045,0.0068,-0.00036,-0.0043,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0017,0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00055,0.00055,0.019,0.04,0.04,0.015,0.066,0.066,0.046,6.3e-06,6.3e-06,5e-06,0.033,0.033,0.00089,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18390000,0.78,-0.012,-0.0017,-0.63,-0.0045,-0.0045,0.008,0.0012,-0.003,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0013,0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.034,0.034,0.014,0.055,0.055,0.046,5.6e-06,5.6e-06,6.3e-06,0.032,0.032,0.00084,0,0,0,0,0,0,0,0
|
18390000,0.78,-0.012,-0.0017,-0.63,-0.0039,-0.0051,0.008,0.0015,-0.0033,-3.7e+02,-0.0015,-0.0061,4.7e-05,-0.0018,0.0081,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.034,0.034,0.014,0.055,0.055,0.046,5.7e-06,5.7e-06,5e-06,0.033,0.033,0.00084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18490000,0.77,-0.012,-0.0017,-0.63,-0.0047,-0.0051,0.0076,0.00073,-0.0035,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0013,0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.037,0.037,0.014,0.061,0.061,0.046,5.6e-06,5.6e-06,6.3e-06,0.032,0.032,0.00082,0,0,0,0,0,0,0,0
|
18490000,0.78,-0.012,-0.0017,-0.63,-0.004,-0.0057,0.0076,0.001,-0.0038,-3.7e+02,-0.0015,-0.0061,4.7e-05,-0.0018,0.0081,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.037,0.037,0.014,0.061,0.061,0.046,5.7e-06,5.7e-06,5e-06,0.033,0.033,0.00082,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18590000,0.77,-0.012,-0.0016,-0.63,-0.0048,-0.0045,0.0058,0.00074,-0.0026,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0014,0.0084,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.032,0.032,0.014,0.052,0.052,0.045,5.1e-06,5.1e-06,6.3e-06,0.032,0.032,0.00078,0,0,0,0,0,0,0,0
|
18590000,0.78,-0.012,-0.0017,-0.63,-0.0042,-0.005,0.0057,0.00095,-0.0028,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.0019,0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.032,0.032,0.014,0.052,0.052,0.045,5.1e-06,5.1e-06,5e-06,0.032,0.032,0.00078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18690000,0.77,-0.012,-0.0016,-0.63,-0.0047,-0.0039,0.0039,0.00028,-0.0031,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0014,0.0084,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.035,0.035,0.013,0.058,0.058,0.045,5.1e-06,5.1e-06,6.3e-06,0.032,0.032,0.00075,0,0,0,0,0,0,0,0
|
18690000,0.78,-0.012,-0.0016,-0.63,-0.0041,-0.0045,0.0038,0.00054,-0.0033,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.0019,0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.036,0.036,0.013,0.058,0.058,0.045,5.1e-06,5.1e-06,5e-06,0.032,0.032,0.00075,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18790000,0.77,-0.012,-0.0016,-0.63,-0.0041,-0.0034,0.0035,0.00039,-0.0024,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0015,0.0085,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.031,0.031,0.013,0.05,0.05,0.045,4.6e-06,4.6e-06,6.3e-06,0.032,0.032,0.00072,0,0,0,0,0,0,0,0
|
18790000,0.78,-0.012,-0.0016,-0.63,-0.0036,-0.0039,0.0035,0.00058,-0.0026,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.002,0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.031,0.031,0.013,0.05,0.05,0.045,4.6e-06,4.6e-06,5e-06,0.032,0.032,0.00072,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18890000,0.77,-0.012,-0.0016,-0.63,-0.0041,-0.004,0.0042,-1.8e-05,-0.0028,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0015,0.0085,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.034,0.034,0.013,0.056,0.056,0.045,4.6e-06,4.6e-06,6.3e-06,0.032,0.032,0.0007,0,0,0,0,0,0,0,0
|
18890000,0.78,-0.012,-0.0017,-0.63,-0.0035,-0.0045,0.0041,0.00023,-0.003,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.002,0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.034,0.034,0.013,0.056,0.056,0.045,4.6e-06,4.6e-06,5e-06,0.032,0.032,0.0007,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18990000,0.78,-0.012,-0.0017,-0.63,-0.0012,-0.0043,0.0028,0.0027,-0.0022,-3.7e+02,-0.0015,-0.0062,4.6e-05,-0.0015,0.0089,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.012,0.048,0.048,0.044,4.2e-06,4.2e-06,6.3e-06,0.032,0.032,0.00067,0,0,0,0,0,0,0,0
|
18990000,0.78,-0.012,-0.0017,-0.63,-0.00067,-0.0047,0.0028,0.0029,-0.0024,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.002,0.0087,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.012,0.048,0.048,0.044,4.2e-06,4.2e-06,5e-06,0.032,0.032,0.00066,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19090000,0.78,-0.012,-0.0017,-0.63,-0.001,-0.005,0.0058,0.0026,-0.0027,-3.7e+02,-0.0015,-0.0062,4.6e-05,-0.0015,0.009,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.033,0.033,0.012,0.054,0.054,0.044,4.2e-06,4.2e-06,6.3e-06,0.032,0.032,0.00065,0,0,0,0,0,0,0,0
|
19090000,0.78,-0.012,-0.0017,-0.63,-0.00049,-0.0055,0.0058,0.0028,-0.0029,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.002,0.0087,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.033,0.033,0.012,0.054,0.054,0.044,4.2e-06,4.2e-06,5e-06,0.032,0.032,0.00065,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19190000,0.78,-0.012,-0.0017,-0.63,0.0019,-0.0043,0.0059,0.0047,-0.0021,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0015,0.0093,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.012,0.047,0.047,0.044,3.8e-06,3.8e-06,6.3e-06,0.032,0.032,0.00062,0,0,0,0,0,0,0,0
|
19190000,0.78,-0.012,-0.0017,-0.63,0.0024,-0.0047,0.0058,0.0049,-0.0023,-3.7e+02,-0.0016,-0.0062,4.9e-05,-0.002,0.0091,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.012,0.047,0.047,0.044,3.9e-06,3.9e-06,5e-06,0.032,0.032,0.00062,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19290000,0.78,-0.012,-0.0017,-0.63,0.0022,-0.0035,0.0086,0.0049,-0.0025,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0015,0.0093,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.032,0.032,0.012,0.053,0.053,0.044,3.8e-06,3.8e-06,6.3e-06,0.032,0.032,0.0006,0,0,0,0,0,0,0,0
|
19290000,0.78,-0.012,-0.0018,-0.63,0.0028,-0.004,0.0086,0.0052,-0.0027,-3.7e+02,-0.0016,-0.0062,4.9e-05,-0.002,0.0091,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.032,0.032,0.012,0.053,0.053,0.044,3.9e-06,3.9e-06,5e-06,0.032,0.032,0.0006,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19390000,0.78,-0.012,-0.0017,-0.63,0.002,-0.0021,0.012,0.004,-0.0019,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0016,0.0093,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.028,0.012,0.046,0.046,0.043,3.5e-06,3.5e-06,6.3e-06,0.032,0.032,0.00058,0,0,0,0,0,0,0,0
|
19390000,0.78,-0.012,-0.0017,-0.63,0.0024,-0.0025,0.012,0.0042,-0.0021,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.009,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.028,0.012,0.046,0.046,0.043,3.5e-06,3.5e-06,5e-06,0.032,0.032,0.00058,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19490000,0.78,-0.012,-0.0017,-0.63,0.0035,-0.0011,0.0088,0.0043,-0.0021,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0016,0.0093,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.031,0.031,0.011,0.052,0.052,0.043,3.5e-06,3.5e-06,6.3e-06,0.032,0.032,0.00056,0,0,0,0,0,0,0,0
|
19490000,0.78,-0.012,-0.0017,-0.63,0.004,-0.0016,0.0088,0.0045,-0.0023,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.009,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.031,0.031,0.011,0.052,0.052,0.043,3.5e-06,3.5e-06,5e-06,0.032,0.032,0.00056,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19590000,0.78,-0.012,-0.0017,-0.63,0.003,0.00028,0.0081,0.0035,-0.0016,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0017,0.0092,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.011,0.046,0.046,0.042,3.2e-06,3.2e-06,6.3e-06,0.032,0.032,0.00054,0,0,0,0,0,0,0,0
|
19590000,0.78,-0.012,-0.0017,-0.63,0.0034,-9.9e-05,0.0081,0.0037,-0.0018,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.0089,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.011,0.046,0.046,0.042,3.2e-06,3.2e-06,5e-06,0.032,0.032,0.00054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19690000,0.78,-0.012,-0.0017,-0.63,0.0028,0.0024,0.0096,0.0038,-0.0015,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0017,0.0092,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.03,0.03,0.011,0.051,0.051,0.042,3.2e-06,3.2e-06,6.3e-06,0.032,0.032,0.00052,0,0,0,0,0,0,0,0
|
19690000,0.78,-0.012,-0.0017,-0.63,0.0033,0.002,0.0096,0.004,-0.0017,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.0089,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.011,0.051,0.051,0.042,3.2e-06,3.2e-06,5e-06,0.032,0.032,0.00052,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19790000,0.78,-0.012,-0.0017,-0.63,0.003,0.0037,0.01,0.0031,-0.0012,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0017,0.0091,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00045,0.019,0.027,0.027,0.011,0.045,0.045,0.042,2.9e-06,2.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
19790000,0.78,-0.012,-0.0017,-0.63,0.0034,0.0033,0.01,0.0033,-0.0014,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.0088,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.027,0.027,0.011,0.045,0.045,0.042,2.9e-06,2.9e-06,5e-06,0.032,0.032,0.0005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19890000,0.78,-0.012,-0.0017,-0.63,0.0047,0.0043,0.011,0.0035,-0.00083,-3.7e+02,-0.0016,-0.0062,4.6e-05,-0.0017,0.0091,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.011,0.051,0.051,0.042,2.9e-06,2.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
19890000,0.78,-0.012,-0.0017,-0.63,0.0051,0.0039,0.011,0.0037,-0.001,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.0088,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.011,0.051,0.051,0.042,2.9e-06,2.9e-06,5e-06,0.032,0.032,0.00049,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19990000,0.78,-0.012,-0.0016,-0.63,0.0052,0.0054,0.014,0.0029,-0.00068,-3.7e+02,-0.0015,-0.0062,4.6e-05,-0.0017,0.009,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.027,0.027,0.01,0.045,0.045,0.041,2.7e-06,2.7e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
19990000,0.78,-0.012,-0.0016,-0.63,0.0056,0.0051,0.014,0.003,-0.00085,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.0087,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.027,0.027,0.01,0.045,0.045,0.041,2.7e-06,2.7e-06,5e-06,0.032,0.032,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20090000,0.78,-0.012,-0.0016,-0.63,0.0056,0.0074,0.014,0.0034,-5.4e-05,-3.7e+02,-0.0015,-0.0062,4.6e-05,-0.0017,0.009,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.029,0.029,0.01,0.05,0.05,0.042,2.7e-06,2.7e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
20090000,0.78,-0.012,-0.0016,-0.63,0.0059,0.0071,0.014,0.0036,-0.00025,-3.7e+02,-0.0016,-0.0062,4.8e-05,-0.0022,0.0087,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.029,0.029,0.01,0.05,0.05,0.042,2.7e-06,2.7e-06,5e-06,0.032,0.032,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20190000,0.78,-0.012,-0.0017,-0.63,0.004,0.0083,0.017,0.0016,-0.00011,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0016,0.0087,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
20190000,0.78,-0.012,-0.0017,-0.63,0.0044,0.008,0.017,0.0018,-0.00027,-3.7e+02,-0.0015,-0.0062,4.8e-05,-0.0022,0.0085,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,5e-06,0.032,0.032,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20290000,0.78,-0.012,-0.0016,-0.63,0.0052,0.01,0.015,0.0021,0.00081,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0016,0.0087,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.028,0.028,0.0099,0.05,0.05,0.041,2.5e-06,2.5e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
20290000,0.78,-0.012,-0.0016,-0.63,0.0055,0.0098,0.015,0.0023,0.00061,-3.7e+02,-0.0015,-0.0062,4.8e-05,-0.0022,0.0085,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.028,0.028,0.0099,0.05,0.05,0.041,2.5e-06,2.5e-06,5e-06,0.032,0.032,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20390000,0.78,-0.012,-0.0016,-0.63,0.0044,0.011,0.017,0.00055,0.00057,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0015,0.0085,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.025,0.025,0.0097,0.044,0.044,0.041,2.3e-06,2.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20390000,0.78,-0.012,-0.0016,-0.63,0.0047,0.011,0.017,0.00071,0.00041,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.0021,0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.025,0.025,0.0097,0.044,0.044,0.041,2.3e-06,2.3e-06,5e-06,0.032,0.032,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20490000,0.78,-0.012,-0.0016,-0.63,0.005,0.012,0.016,0.001,0.0017,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0015,0.0085,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.028,0.028,0.0096,0.049,0.049,0.041,2.3e-06,2.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20490000,0.78,-0.012,-0.0016,-0.63,0.0053,0.011,0.016,0.0012,0.0015,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.0021,0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.028,0.028,0.0096,0.049,0.049,0.041,2.3e-06,2.3e-06,5e-06,0.032,0.032,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20590000,0.78,-0.012,-0.0017,-0.63,0.0041,0.012,0.013,0.00079,0.0013,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0014,0.0084,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.025,0.025,0.0094,0.044,0.044,0.04,2.1e-06,2.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20590000,0.78,-0.012,-0.0017,-0.63,0.0043,0.011,0.013,0.00094,0.0012,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.0019,0.0081,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.025,0.025,0.0093,0.044,0.044,0.04,2.1e-06,2.1e-06,5e-06,0.032,0.032,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20690000,0.78,-0.012,-0.0017,-0.63,0.004,0.013,0.015,0.0012,0.0025,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0014,0.0084,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.027,0.027,0.0093,0.049,0.049,0.04,2.1e-06,2.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20690000,0.78,-0.012,-0.0017,-0.63,0.0043,0.013,0.015,0.0014,0.0024,-3.7e+02,-0.0015,-0.0062,4.7e-05,-0.0019,0.0081,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.027,0.027,0.0093,0.049,0.049,0.04,2.1e-06,2.1e-06,5e-06,0.032,0.032,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20790000,0.78,-0.012,-0.0017,-0.63,0.0048,0.012,0.015,0.00098,0.002,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0012,0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.024,0.024,0.0091,0.044,0.044,0.04,1.9e-06,1.9e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20790000,0.78,-0.012,-0.0017,-0.63,0.005,0.012,0.015,0.0011,0.0018,-3.7e+02,-0.0015,-0.0061,4.7e-05,-0.0018,0.008,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.024,0.024,0.0091,0.044,0.044,0.04,1.9e-06,1.9e-06,5e-06,0.032,0.032,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20890000,0.77,-0.012,-0.0017,-0.63,0.0049,0.015,0.014,0.0015,0.0033,-3.7e+02,-0.0015,-0.0062,4.5e-05,-0.0012,0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00042,0.019,0.026,0.026,0.0091,0.049,0.049,0.04,1.9e-06,1.9e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20890000,0.78,-0.012,-0.0017,-0.63,0.0052,0.014,0.014,0.0016,0.0031,-3.7e+02,-0.0015,-0.0061,4.7e-05,-0.0018,0.008,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.026,0.009,0.049,0.049,0.04,1.9e-06,1.9e-06,5e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20990000,0.77,-0.012,-0.0017,-0.63,0.0056,0.016,0.015,0.0014,0.0033,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.001,0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.026,0.026,0.0089,0.051,0.051,0.039,1.8e-06,1.8e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20990000,0.78,-0.012,-0.0017,-0.63,0.0058,0.016,0.015,0.0016,0.0031,-3.7e+02,-0.0015,-0.0061,4.7e-05,-0.0016,0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.026,0.026,0.0088,0.051,0.051,0.039,1.8e-06,1.8e-06,5e-06,0.031,0.031,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21090000,0.77,-0.012,-0.0017,-0.63,0.0055,0.018,0.015,0.002,0.005,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.001,0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.028,0.028,0.0089,0.057,0.057,0.039,1.8e-06,1.8e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21090000,0.78,-0.012,-0.0017,-0.63,0.0057,0.018,0.015,0.0022,0.0048,-3.7e+02,-0.0015,-0.0061,4.7e-05,-0.0016,0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00042,0.019,0.028,0.028,0.0088,0.057,0.057,0.039,1.8e-06,1.8e-06,5e-06,0.031,0.031,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21190000,0.77,-0.012,-0.0017,-0.63,0.0054,0.017,0.014,0.0018,0.0045,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00086,0.0081,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.027,0.027,0.0087,0.06,0.06,0.039,1.7e-06,1.7e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21190000,0.78,-0.012,-0.0017,-0.63,0.0056,0.017,0.014,0.002,0.0043,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0014,0.0078,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.027,0.027,0.0086,0.06,0.06,0.039,1.7e-06,1.7e-06,5e-06,0.031,0.031,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21290000,0.77,-0.012,-0.0018,-0.63,0.0057,0.02,0.016,0.0024,0.0064,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00085,0.0081,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.03,0.03,0.0086,0.067,0.067,0.039,1.7e-06,1.7e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21290000,0.78,-0.012,-0.0018,-0.63,0.0059,0.019,0.016,0.0026,0.0062,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0014,0.0078,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.03,0.03,0.0085,0.067,0.067,0.039,1.7e-06,1.7e-06,5e-06,0.031,0.031,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21390000,0.77,-0.012,-0.0018,-0.63,0.0055,0.02,0.016,0.0017,0.0057,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00071,0.008,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0085,0.055,0.055,0.039,1.6e-06,1.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21390000,0.78,-0.012,-0.0018,-0.63,0.0057,0.02,0.016,0.0018,0.0055,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0013,0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0084,0.055,0.055,0.039,1.6e-06,1.6e-06,5e-06,0.031,0.031,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21490000,0.77,-0.012,-0.0018,-0.63,0.006,0.022,0.015,0.0023,0.0078,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00072,0.008,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.027,0.027,0.0085,0.061,0.061,0.038,1.6e-06,1.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21490000,0.78,-0.012,-0.0018,-0.63,0.0062,0.021,0.015,0.0024,0.0076,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0013,0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.027,0.027,0.0083,0.061,0.061,0.038,1.6e-06,1.6e-06,5e-06,0.031,0.031,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21590000,0.77,-0.012,-0.0018,-0.63,0.0061,0.02,0.015,0.0017,0.0069,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00057,0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.0004,0.019,0.023,0.023,0.0083,0.052,0.052,0.038,1.4e-06,1.4e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21590000,0.78,-0.012,-0.0018,-0.63,0.0062,0.02,0.015,0.0018,0.0068,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0012,0.0076,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.023,0.023,0.0081,0.052,0.052,0.038,1.4e-06,1.4e-06,5e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21690000,0.77,-0.012,-0.0018,-0.63,0.0059,0.021,0.017,0.0023,0.009,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00057,0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.02,0.025,0.025,0.0084,0.058,0.058,0.038,1.4e-06,1.4e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21690000,0.78,-0.012,-0.0018,-0.63,0.0061,0.021,0.017,0.0024,0.0088,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0012,0.0076,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0081,0.058,0.058,0.038,1.4e-06,1.4e-06,5e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21790000,0.77,-0.012,-0.0017,-0.63,0.0046,0.021,0.015,0.00058,0.01,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00064,0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.02,0.022,0.022,0.0082,0.049,0.049,0.038,1.3e-06,1.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21790000,0.78,-0.012,-0.0017,-0.63,0.0047,0.021,0.015,0.00069,0.01,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0012,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.022,0.022,0.008,0.049,0.049,0.038,1.3e-06,1.3e-06,5e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21890000,0.77,-0.012,-0.0017,-0.63,0.0046,0.022,0.016,0.001,0.013,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00065,0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.02,0.024,0.024,0.0082,0.055,0.055,0.038,1.3e-06,1.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21890000,0.78,-0.012,-0.0017,-0.63,0.0047,0.021,0.016,0.0012,0.012,-3.7e+02,-0.0015,-0.0061,4.6e-05,-0.0012,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.024,0.024,0.0079,0.055,0.055,0.038,1.3e-06,1.3e-06,5e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21990000,0.77,-0.012,-0.0016,-0.63,0.0032,0.023,0.016,-0.00037,0.013,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00069,0.0076,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.00039,0.02,0.021,0.021,0.0081,0.048,0.048,0.038,1.2e-06,1.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21990000,0.78,-0.012,-0.0016,-0.63,0.0034,0.022,0.016,-0.00027,0.013,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.0013,0.0073,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.021,0.021,0.0078,0.048,0.048,0.038,1.2e-06,1.2e-06,5e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22090000,0.77,-0.012,-0.0016,-0.63,0.0037,0.022,0.015,-2.7e-05,0.016,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.0007,0.0076,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.02,0.023,0.023,0.0081,0.053,0.053,0.038,1.2e-06,1.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22090000,0.78,-0.012,-0.0016,-0.63,0.0039,0.022,0.015,8.1e-05,0.016,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.0013,0.0073,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.023,0.023,0.0078,0.053,0.053,0.037,1.2e-06,1.2e-06,5e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22190000,0.77,-0.012,-0.0017,-0.63,0.004,0.019,0.015,-4.6e-05,0.013,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00043,0.0075,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.021,0.021,0.008,0.046,0.046,0.037,1.2e-06,1.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22190000,0.78,-0.012,-0.0017,-0.63,0.0041,0.019,0.015,4.1e-05,0.013,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.001,0.0072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.021,0.021,0.0076,0.046,0.046,0.037,1.2e-06,1.2e-06,5e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22290000,0.77,-0.012,-0.0017,-0.63,0.0052,0.021,0.015,0.0004,0.015,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00043,0.0075,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.022,0.022,0.008,0.051,0.051,0.037,1.2e-06,1.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22290000,0.78,-0.012,-0.0017,-0.63,0.0053,0.021,0.015,0.0005,0.015,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.001,0.0072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.022,0.022,0.0076,0.051,0.051,0.037,1.2e-06,1.2e-06,5e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22390000,0.77,-0.012,-0.0017,-0.63,0.0061,0.019,0.017,0.00035,0.012,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00019,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.02,0.02,0.0079,0.045,0.045,0.037,1.1e-06,1.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22390000,0.78,-0.012,-0.0017,-0.63,0.0062,0.018,0.017,0.00043,0.012,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00079,0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.02,0.02,0.0075,0.045,0.045,0.037,1.1e-06,1.1e-06,5e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22490000,0.77,-0.012,-0.0017,-0.63,0.0068,0.019,0.018,0.00098,0.014,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00018,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.022,0.022,0.0079,0.05,0.05,0.037,1.1e-06,1.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22490000,0.78,-0.012,-0.0017,-0.63,0.0069,0.019,0.018,0.0011,0.014,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00079,0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0074,0.05,0.05,0.037,1.1e-06,1.1e-06,5e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22590000,0.77,-0.012,-0.0017,-0.63,0.0075,0.02,0.017,0.002,0.015,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00012,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.021,0.021,0.0078,0.052,0.052,0.036,1e-06,1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22590000,0.78,-0.012,-0.0017,-0.63,0.0076,0.019,0.017,0.0021,0.015,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00072,0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0073,0.052,0.052,0.036,1e-06,1e-06,5e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22690000,0.77,-0.012,-0.0017,-0.63,0.0088,0.02,0.018,0.0028,0.017,-3.7e+02,-0.0015,-0.0061,4.4e-05,-0.00012,0.0074,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.023,0.023,0.0079,0.058,0.058,0.037,1e-06,1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22690000,0.78,-0.012,-0.0017,-0.63,0.0089,0.02,0.018,0.0029,0.017,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00072,0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0073,0.058,0.058,0.036,1e-06,1e-06,5e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22790000,0.77,-0.012,-0.0017,-0.63,0.009,0.018,0.019,0.0027,0.017,-3.7e+02,-0.0015,-0.0061,4.4e-05,3e-05,0.0073,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.023,0.023,0.0078,0.06,0.06,0.036,1e-06,1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22790000,0.78,-0.012,-0.0017,-0.63,0.0091,0.018,0.019,0.0028,0.017,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00058,0.007,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0072,0.06,0.06,0.036,1e-06,1e-06,5e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22890000,0.77,-0.012,-0.0017,-0.63,0.01,0.018,0.021,0.0037,0.019,-3.7e+02,-0.0015,-0.0061,4.4e-05,3e-05,0.0073,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.025,0.025,0.0078,0.067,0.067,0.036,1e-06,1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22890000,0.78,-0.012,-0.0017,-0.63,0.011,0.018,0.021,0.0038,0.018,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00058,0.007,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.025,0.025,0.0072,0.067,0.067,0.036,1e-06,1e-06,5e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22990000,0.77,-0.012,-0.0017,-0.63,0.0099,0.018,0.022,0.0034,0.018,-3.7e+02,-0.0015,-0.0061,4.4e-05,0.00016,0.0072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.024,0.024,0.0078,0.069,0.069,0.036,9.6e-07,9.6e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
22990000,0.78,-0.012,-0.0017,-0.63,0.01,0.018,0.022,0.0035,0.018,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00045,0.0069,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.024,0.024,0.0071,0.069,0.069,0.036,9.6e-07,9.6e-07,5e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23090000,0.77,-0.012,-0.0017,-0.63,0.011,0.018,0.022,0.0044,0.02,-3.7e+02,-0.0015,-0.0061,4.4e-05,0.00017,0.0072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.026,0.026,0.0078,0.076,0.076,0.036,9.6e-07,9.6e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23090000,0.78,-0.012,-0.0017,-0.63,0.011,0.018,0.022,0.0046,0.02,-3.7e+02,-0.0015,-0.0061,4.5e-05,-0.00045,0.0069,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.026,0.026,0.007,0.076,0.076,0.036,9.6e-07,9.6e-07,5e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23190000,0.77,-0.012,-0.0017,-0.63,0.0064,0.018,0.024,-0.0003,0.019,-3.7e+02,-0.0014,-0.0061,4.3e-05,0.00026,0.0069,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00038,0.02,0.025,0.025,0.0077,0.078,0.078,0.036,9.2e-07,9.2e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23190000,0.78,-0.012,-0.0017,-0.63,0.0065,0.018,0.024,-0.00019,0.019,-3.7e+02,-0.0014,-0.0061,4.4e-05,-0.00037,0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.025,0.025,0.0069,0.078,0.078,0.035,9.2e-07,9.2e-07,5e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23290000,0.77,-0.012,-0.0016,-0.63,0.0067,0.02,0.024,0.00035,0.021,-3.7e+02,-0.0014,-0.0061,4.3e-05,0.00025,0.0069,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.027,0.027,0.0078,0.086,0.086,0.036,9.2e-07,9.2e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23290000,0.78,-0.012,-0.0016,-0.63,0.0068,0.02,0.024,0.00046,0.021,-3.7e+02,-0.0014,-0.0061,4.4e-05,-0.00037,0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.027,0.027,0.0069,0.086,0.086,0.036,9.2e-07,9.2e-07,5e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23390000,0.77,-0.012,-0.0016,-0.63,0.0026,0.019,0.022,-0.0047,0.02,-3.7e+02,-0.0014,-0.0061,4.3e-05,0.00033,0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00038,0.02,0.026,0.026,0.0077,0.087,0.087,0.036,8.8e-07,8.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23390000,0.78,-0.012,-0.0016,-0.63,0.0027,0.019,0.022,-0.0046,0.02,-3.7e+02,-0.0014,-0.0061,4.4e-05,-0.00029,0.0063,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.026,0.026,0.0068,0.087,0.087,0.035,8.8e-07,8.8e-07,5e-06,0.031,0.031,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23490000,0.77,-0.0092,-0.0038,-0.63,0.0091,0.022,-0.012,-0.0042,0.022,-3.7e+02,-0.0014,-0.0061,4.3e-05,0.00032,0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00038,0.02,0.028,0.028,0.0078,0.096,0.096,0.036,8.8e-07,8.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23490000,0.78,-0.0092,-0.0038,-0.63,0.0091,0.022,-0.012,-0.0041,0.022,-3.7e+02,-0.0014,-0.0061,4.4e-05,-0.0003,0.0063,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00038,0.019,0.028,0.028,0.0068,0.096,0.096,0.035,8.8e-07,8.8e-07,5e-06,0.031,0.031,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23590000,0.78,-0.00092,-0.0082,-0.63,0.02,0.021,-0.044,-0.005,0.016,-3.7e+02,-0.0014,-0.0061,4.3e-05,0.00054,0.0064,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0077,0.072,0.072,0.035,8e-07,8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23590000,0.78,-0.00089,-0.0081,-0.63,0.02,0.021,-0.043,-0.005,0.016,-3.7e+02,-0.0014,-0.0061,4.4e-05,-9e-05,0.0061,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.022,0.022,0.0067,0.072,0.072,0.035,8e-07,8e-07,5e-06,0.031,0.031,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23690000,0.78,0.0048,-0.0072,-0.63,0.048,0.036,-0.094,-0.0017,0.019,-3.7e+02,-0.0014,-0.0061,4.3e-05,0.00053,0.0064,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.02,0.024,0.024,0.0078,0.079,0.079,0.036,8e-07,8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23690000,0.78,0.0048,-0.0072,-0.63,0.048,0.036,-0.094,-0.0017,0.019,-3.7e+02,-0.0014,-0.0061,4.4e-05,-9.5e-05,0.0061,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.024,0.024,0.0067,0.079,0.079,0.035,8e-07,8e-07,5e-06,0.031,0.031,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23790000,0.78,0.0011,-0.0047,-0.63,0.069,0.051,-0.15,-0.0036,0.015,-3.7e+02,-0.0014,-0.006,4.2e-05,0.00077,0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0077,0.062,0.062,0.035,7.5e-07,7.5e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23790000,0.78,0.0012,-0.0046,-0.63,0.069,0.051,-0.15,-0.0036,0.015,-3.7e+02,-0.0014,-0.006,4.3e-05,0.00013,0.0055,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.02,0.02,0.0066,0.062,0.062,0.035,7.5e-07,7.5e-07,5e-06,0.031,0.031,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23890000,0.78,-0.0052,-0.0027,-0.63,0.083,0.063,-0.2,0.0041,0.021,-3.7e+02,-0.0014,-0.006,4.2e-05,0.00076,0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.022,0.022,0.0078,0.068,0.068,0.035,7.5e-07,7.5e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23890000,0.78,-0.0052,-0.0026,-0.63,0.083,0.064,-0.2,0.0041,0.021,-3.7e+02,-0.0014,-0.006,4.3e-05,0.00013,0.0055,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.022,0.022,0.0066,0.068,0.068,0.035,7.5e-07,7.5e-07,5e-06,0.031,0.031,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23990000,0.78,-0.01,-0.0016,-0.63,0.073,0.061,-0.25,-0.007,0.018,-3.7e+02,-0.0013,-0.006,4e-05,0.0012,0.0042,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.021,0.022,0.0077,0.071,0.071,0.035,7.3e-07,7.2e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
23990000,0.78,-0.01,-0.0016,-0.63,0.073,0.062,-0.25,-0.007,0.018,-3.7e+02,-0.0013,-0.006,4e-05,0.00057,0.004,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.021,0.022,0.0066,0.071,0.071,0.035,7.3e-07,7.3e-07,5e-06,0.031,0.031,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24090000,0.78,-0.0087,-0.0028,-0.63,0.074,0.062,-0.3,0.00031,0.024,-3.7e+02,-0.0013,-0.006,4e-05,0.0012,0.0042,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.023,0.023,0.0078,0.077,0.077,0.035,7.3e-07,7.3e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24090000,0.78,-0.0087,-0.0028,-0.63,0.074,0.063,-0.3,0.00032,0.024,-3.7e+02,-0.0013,-0.006,4e-05,0.00058,0.004,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00037,0.019,0.023,0.023,0.0065,0.077,0.077,0.035,7.3e-07,7.3e-07,5e-06,0.031,0.031,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24190000,0.78,-0.0066,-0.0035,-0.63,0.067,0.059,-0.35,-0.012,0.019,-3.7e+02,-0.0013,-0.006,3.8e-05,0.0018,0.0026,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.023,0.023,0.0077,0.079,0.079,0.035,7e-07,7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24190000,0.78,-0.0066,-0.0035,-0.63,0.067,0.059,-0.35,-0.012,0.019,-3.7e+02,-0.0013,-0.006,3.8e-05,0.0011,0.0023,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.023,0.023,0.0065,0.079,0.079,0.034,7e-07,7e-07,5e-06,0.031,0.031,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24290000,0.78,-0.0057,-0.0039,-0.63,0.076,0.065,-0.41,-0.0053,0.026,-3.7e+02,-0.0013,-0.006,3.8e-05,0.0018,0.0026,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.024,0.024,0.0078,0.087,0.087,0.036,7e-07,7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24290000,0.78,-0.0057,-0.0039,-0.63,0.076,0.065,-0.41,-0.0053,0.026,-3.7e+02,-0.0013,-0.006,3.8e-05,0.0011,0.0023,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.024,0.024,0.0065,0.087,0.087,0.034,7e-07,7e-07,5e-06,0.031,0.031,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24390000,0.78,-0.0063,-0.004,-0.63,0.068,0.059,-0.46,-0.024,0.014,-3.7e+02,-0.0012,-0.006,3.7e-05,0.0027,0.00033,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.024,0.024,0.0077,0.089,0.089,0.035,6.8e-07,6.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24390000,0.78,-0.0063,-0.004,-0.63,0.068,0.059,-0.46,-0.024,0.014,-3.7e+02,-0.0012,-0.006,3.6e-05,0.0021,0.00014,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.024,0.024,0.0064,0.089,0.089,0.034,6.8e-07,6.8e-07,5e-06,0.031,0.031,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24490000,0.78,-0.0021,-0.0044,-0.63,0.079,0.067,-0.51,-0.017,0.02,-3.7e+02,-0.0012,-0.006,3.7e-05,0.0028,0.00032,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.025,0.026,0.0078,0.096,0.096,0.035,6.8e-07,6.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24490000,0.78,-0.0021,-0.0044,-0.63,0.079,0.067,-0.51,-0.017,0.02,-3.7e+02,-0.0012,-0.006,3.6e-05,0.0021,0.00014,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.025,0.026,0.0064,0.096,0.096,0.034,6.8e-07,6.8e-07,5e-06,0.031,0.031,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24590000,0.78,0.0012,-0.0044,-0.63,0.078,0.067,-0.56,-0.038,0.0077,-3.7e+02,-0.0012,-0.006,3.6e-05,0.0038,-0.0021,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.02,0.025,0.025,0.0078,0.098,0.098,0.035,6.6e-07,6.5e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24590000,0.78,0.0012,-0.0044,-0.63,0.077,0.068,-0.56,-0.038,0.0077,-3.7e+02,-0.0012,-0.006,3.4e-05,0.0031,-0.0023,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.025,0.025,0.0063,0.098,0.098,0.034,6.6e-07,6.6e-07,5e-06,0.031,0.031,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24690000,0.78,0.0021,-0.0044,-0.63,0.098,0.085,-0.64,-0.029,0.015,-3.7e+02,-0.0012,-0.006,3.6e-05,0.0038,-0.0021,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.02,0.027,0.027,0.0078,0.11,0.11,0.035,6.6e-07,6.6e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24690000,0.78,0.0021,-0.0043,-0.63,0.097,0.086,-0.64,-0.029,0.015,-3.7e+02,-0.0012,-0.006,3.4e-05,0.0031,-0.0022,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.027,0.027,0.0063,0.11,0.11,0.034,6.6e-07,6.6e-07,5e-06,0.031,0.031,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24790000,0.78,0.00033,-0.0041,-0.63,0.093,0.09,-0.73,-0.059,0.0051,-3.7e+02,-0.0011,-0.0059,3.1e-05,0.0048,-0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0078,0.11,0.11,0.035,6.3e-07,6.3e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24790000,0.78,0.00036,-0.004,-0.63,0.092,0.09,-0.73,-0.059,0.0051,-3.7e+02,-0.0011,-0.0059,2.9e-05,0.004,-0.0054,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.026,0.026,0.0062,0.11,0.11,0.034,6.3e-07,6.3e-07,5e-06,0.031,0.031,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24890000,0.78,0.0022,-0.0056,-0.63,0.11,0.1,-0.75,-0.049,0.015,-3.7e+02,-0.0011,-0.0059,3.1e-05,0.0047,-0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.02,0.028,0.028,0.0078,0.12,0.12,0.035,6.3e-07,6.3e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24890000,0.78,0.0022,-0.0056,-0.63,0.11,0.1,-0.75,-0.049,0.015,-3.7e+02,-0.0011,-0.0059,2.9e-05,0.004,-0.0054,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.019,0.028,0.028,0.0062,0.12,0.12,0.034,6.3e-07,6.3e-07,5e-06,0.031,0.031,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24990000,0.78,0.0036,-0.0071,-0.63,0.11,0.11,-0.81,-0.082,0.0018,-3.7e+02,-0.001,-0.0059,2.6e-05,0.0059,-0.0088,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.027,0.027,0.0078,0.12,0.12,0.035,6.1e-07,6.1e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
24990000,0.78,0.0037,-0.0071,-0.63,0.11,0.11,-0.81,-0.082,0.0018,-3.7e+02,-0.001,-0.0059,2.4e-05,0.0052,-0.0088,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.027,0.027,0.0062,0.12,0.12,0.034,6.1e-07,6.1e-07,5e-06,0.031,0.031,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25090000,0.78,0.0031,-0.0075,-0.63,0.13,0.12,-0.86,-0.07,0.013,-3.7e+02,-0.001,-0.0059,2.6e-05,0.0059,-0.0088,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.02,0.028,0.029,0.0079,0.13,0.13,0.035,6.1e-07,6.1e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25090000,0.78,0.0031,-0.0074,-0.63,0.13,0.12,-0.86,-0.07,0.013,-3.7e+02,-0.001,-0.0059,2.4e-05,0.0052,-0.0088,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.019,0.028,0.029,0.0062,0.13,0.13,0.034,6.1e-07,6.1e-07,5e-06,0.031,0.031,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25190000,0.78,0.0007,-0.0069,-0.63,0.11,0.11,-0.91,-0.13,-0.018,-3.7e+02,-0.00087,-0.0059,2e-05,0.0081,-0.014,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.027,0.028,0.0078,0.13,0.13,0.035,5.9e-07,5.9e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25190000,0.78,0.00074,-0.0068,-0.63,0.11,0.11,-0.91,-0.13,-0.018,-3.7e+02,-0.00087,-0.0059,1.7e-05,0.0074,-0.014,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.027,0.028,0.0061,0.13,0.13,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25290000,0.78,0.0077,-0.008,-0.63,0.14,0.12,-0.96,-0.12,-0.0064,-3.7e+02,-0.00087,-0.0059,2e-05,0.0081,-0.014,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.02,0.029,0.03,0.0079,0.14,0.14,0.035,5.9e-07,5.9e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25290000,0.78,0.0077,-0.008,-0.63,0.14,0.12,-0.96,-0.12,-0.0063,-3.7e+02,-0.00087,-0.0059,1.7e-05,0.0074,-0.014,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00037,0.019,0.029,0.03,0.0061,0.14,0.14,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25390000,0.78,0.013,-0.0085,-0.63,0.13,0.12,-1,-0.18,-0.039,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00038,0.02,0.028,0.028,0.0078,0.14,0.14,0.035,5.7e-07,5.7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25390000,0.78,0.013,-0.0084,-0.63,0.13,0.12,-1,-0.18,-0.039,-3.7e+02,-0.00075,-0.0058,1e-05,0.0096,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00038,0.019,0.028,0.028,0.0061,0.14,0.14,0.033,5.7e-07,5.7e-07,5e-06,0.031,0.031,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25490000,0.78,0.015,-0.0086,-0.63,0.17,0.15,-1.1,-0.17,-0.025,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00038,0.02,0.03,0.031,0.0079,0.15,0.15,0.035,5.7e-07,5.7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25490000,0.78,0.015,-0.0085,-0.63,0.17,0.15,-1.1,-0.17,-0.025,-3.7e+02,-0.00075,-0.0058,1e-05,0.0096,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00038,0.019,0.03,0.031,0.0061,0.15,0.15,0.033,5.7e-07,5.7e-07,5e-06,0.031,0.031,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25590000,0.78,0.013,-0.0084,-0.63,0.2,0.18,-1.1,-0.15,-0.0086,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00038,0.02,0.032,0.033,0.008,0.16,0.16,0.035,5.7e-07,5.7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25590000,0.78,0.013,-0.0083,-0.63,0.2,0.18,-1.1,-0.15,-0.0083,-3.7e+02,-0.00075,-0.0058,1e-05,0.0096,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00038,0.019,0.032,0.033,0.0061,0.16,0.16,0.033,5.7e-07,5.7e-07,5e-06,0.031,0.031,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25690000,0.78,0.02,-0.011,-0.63,0.24,0.21,-1.2,-0.13,0.011,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.0004,0.02,0.034,0.035,0.008,0.17,0.17,0.035,5.7e-07,5.7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25690000,0.78,0.02,-0.011,-0.63,0.24,0.21,-1.2,-0.13,0.011,-3.7e+02,-0.00075,-0.0058,1e-05,0.0096,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.0004,0.019,0.034,0.035,0.0061,0.17,0.17,0.033,5.7e-07,5.7e-07,5e-06,0.031,0.031,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25790000,0.78,0.026,-0.013,-0.63,0.29,0.24,-1.2,-0.099,0.033,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00043,0.02,0.036,0.038,0.0081,0.18,0.18,0.035,5.7e-07,5.7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25790000,0.78,0.027,-0.013,-0.63,0.29,0.25,-1.2,-0.1,0.034,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00043,0.019,0.036,0.038,0.0061,0.18,0.18,0.033,5.7e-07,5.7e-07,5e-06,0.031,0.031,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25890000,0.78,0.027,-0.013,-0.63,0.35,0.28,-1.3,-0.067,0.06,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00043,0.02,0.039,0.042,0.0081,0.2,0.2,0.036,5.7e-07,5.7e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25890000,0.78,0.027,-0.013,-0.63,0.35,0.29,-1.3,-0.067,0.06,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00043,0.019,0.039,0.041,0.0061,0.2,0.2,0.033,5.7e-07,5.7e-07,5e-06,0.031,0.031,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25990000,0.78,0.024,-0.013,-0.63,0.41,0.32,-1.3,-0.028,0.09,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00042,0.02,0.042,0.045,0.0082,0.21,0.21,0.036,5.7e-07,5.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
25990000,0.78,0.024,-0.013,-0.63,0.41,0.32,-1.3,-0.029,0.091,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00042,0.019,0.042,0.045,0.0061,0.21,0.21,0.033,5.7e-07,5.8e-07,5e-06,0.031,0.031,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26090000,0.78,0.034,-0.017,-0.62,0.46,0.36,-1.4,0.015,0.12,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00048,0.02,0.044,0.049,0.0082,0.23,0.23,0.036,5.8e-07,5.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26090000,0.78,0.034,-0.016,-0.62,0.46,0.36,-1.4,0.014,0.12,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00047,0.019,0.044,0.048,0.0061,0.23,0.23,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26190000,0.78,0.044,-0.018,-0.62,0.53,0.41,-1.3,0.065,0.16,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00054,0.02,0.047,0.052,0.0083,0.25,0.25,0.036,5.8e-07,5.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26190000,0.78,0.044,-0.018,-0.62,0.53,0.41,-1.3,0.063,0.16,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00053,0.019,0.047,0.052,0.0061,0.25,0.25,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26290000,0.78,0.046,-0.019,-0.62,0.61,0.46,-1.3,0.12,0.21,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00056,0.02,0.051,0.057,0.0083,0.27,0.27,0.036,5.8e-07,5.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26290000,0.78,0.046,-0.019,-0.62,0.61,0.47,-1.3,0.12,0.21,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00054,0.019,0.051,0.057,0.0061,0.27,0.27,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26390000,0.78,0.043,-0.018,-0.62,0.69,0.52,-1.3,0.19,0.25,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00053,0.02,0.054,0.062,0.0084,0.29,0.29,0.036,5.8e-07,5.8e-07,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26390000,0.78,0.043,-0.018,-0.62,0.68,0.52,-1.3,0.18,0.26,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00052,0.019,0.054,0.061,0.0061,0.29,0.29,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26490000,0.78,0.059,-0.024,-0.62,0.77,0.57,-1.3,0.26,0.31,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00068,0.02,0.058,0.068,0.0084,0.31,0.32,0.036,5.8e-07,5.8e-07,6.4e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26490000,0.78,0.059,-0.024,-0.62,0.77,0.58,-1.3,0.26,0.31,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00066,0.019,0.058,0.067,0.0061,0.31,0.31,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26590000,0.78,0.076,-0.029,-0.63,0.88,0.65,-1.3,0.34,0.37,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00086,0.02,0.063,0.075,0.0085,0.33,0.34,0.037,5.8e-07,5.8e-07,6.4e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26590000,0.78,0.076,-0.029,-0.62,0.88,0.66,-1.3,0.34,0.37,-3.7e+02,-0.00075,-0.0058,1e-05,0.0095,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00083,0.019,0.063,0.074,0.0061,0.34,0.34,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26690000,0.78,0.079,-0.03,-0.63,1,0.74,-1.3,0.44,0.44,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00089,0.02,0.068,0.083,0.0085,0.36,0.37,0.037,5.8e-07,5.8e-07,6.4e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26690000,0.78,0.079,-0.03,-0.62,1,0.75,-1.3,0.43,0.44,-3.7e+02,-0.00075,-0.0058,1.1e-05,0.0094,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00087,0.019,0.068,0.082,0.0061,0.36,0.37,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26790000,0.77,0.073,-0.029,-0.63,1.1,0.82,-1.3,0.54,0.52,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00083,0.02,0.074,0.092,0.0085,0.39,0.4,0.037,5.8e-07,5.8e-07,6.4e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26790000,0.78,0.074,-0.029,-0.63,1.1,0.83,-1.3,0.54,0.52,-3.7e+02,-0.00075,-0.0058,1.1e-05,0.0094,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00081,0.019,0.074,0.091,0.0061,0.39,0.4,0.033,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26890000,0.77,0.096,-0.035,-0.63,1.3,0.9,-1.3,0.66,0.6,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.0011,0.019,0.08,0.1,0.0086,0.42,0.43,0.037,5.8e-07,5.8e-07,6.4e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26890000,0.77,0.096,-0.035,-0.62,1.3,0.91,-1.3,0.66,0.61,-3.7e+02,-0.00075,-0.0058,1.1e-05,0.0093,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.0011,0.019,0.08,0.1,0.0061,0.42,0.43,0.034,5.8e-07,5.8e-07,5e-06,0.031,0.031,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26990000,0.77,0.12,-0.04,-0.63,1.4,1,-1.3,0.8,0.7,-3.7e+02,-0.00075,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00052,0.0015,0.019,0.087,0.12,0.0086,0.45,0.47,0.037,5.8e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
26990000,0.77,0.12,-0.04,-0.62,1.4,1,-1.3,0.79,0.7,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0093,-0.02,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00052,0.0014,0.018,0.087,0.11,0.0061,0.45,0.47,0.033,5.8e-07,5.9e-07,5e-06,0.031,0.031,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27090000,0.77,0.12,-0.041,-0.63,1.6,1.1,-1.3,0.95,0.81,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.1,-0.022,0.51,0.0047,-0.1,-0.04,0,0,0.00054,0.0015,0.019,0.096,0.13,0.0087,0.49,0.51,0.037,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0013,0.00033,0.0013,0.00053,0.0013,0.0013,0,0
|
27090000,0.77,0.12,-0.04,-0.63,1.6,1.2,-1.3,0.94,0.81,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0093,-0.02,-0.13,-0.1,-0.022,0.51,0.0048,-0.1,-0.04,0,0,0.00053,0.0015,0.018,0.096,0.13,0.0062,0.49,0.51,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00015,0.0013,0.00033,0.0013,0.00053,0.0013,0.0013,1,1
|
||||||
27190000,0.77,0.11,-0.038,-0.63,1.8,1.3,-1.2,1.1,0.93,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.01,-0.02,-0.13,-0.11,-0.022,0.5,0.0048,-0.1,-0.041,0,0,0.00051,0.0014,0.019,0.11,0.15,0.0087,0.53,0.55,0.037,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0012,0.00022,0.0013,0.00033,0.0013,0.0013,0,0
|
27190000,0.77,0.11,-0.038,-0.63,1.8,1.3,-1.2,1.1,0.94,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0093,-0.019,-0.13,-0.11,-0.023,0.5,0.0049,-0.1,-0.041,0,0,0.0005,0.0013,0.019,0.11,0.14,0.0062,0.53,0.55,0.034,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00015,0.0012,0.00022,0.0013,0.00033,0.0013,0.0013,1,1
|
||||||
27290000,0.77,0.096,-0.034,-0.63,1.9,1.4,-1.2,1.3,1.1,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.01,-0.019,-0.13,-0.11,-0.023,0.5,0.0051,-0.1,-0.042,0,0,0.00047,0.0011,0.02,0.11,0.16,0.0088,0.57,0.6,0.037,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0012,0.00016,0.0013,0.00023,0.0013,0.0013,0,0
|
27290000,0.77,0.097,-0.034,-0.63,1.9,1.4,-1.2,1.3,1.1,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0092,-0.019,-0.13,-0.11,-0.023,0.5,0.0051,-0.1,-0.042,0,0,0.00047,0.0011,0.019,0.11,0.16,0.0062,0.57,0.6,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00014,0.0012,0.00017,0.0013,0.00023,0.0013,0.0013,1,1
|
||||||
27390000,0.77,0.08,-0.029,-0.63,2,1.4,-1.2,1.5,1.2,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0099,-0.019,-0.12,-0.11,-0.023,0.5,0.0049,-0.1,-0.043,0,0,0.00043,0.0009,0.02,0.12,0.18,0.0088,0.61,0.66,0.037,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0012,0.00014,0.0013,0.00018,0.0013,0.0012,0,0
|
27390000,0.77,0.08,-0.029,-0.63,2,1.5,-1.2,1.5,1.2,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0092,-0.019,-0.13,-0.11,-0.023,0.5,0.005,-0.1,-0.043,0,0,0.00044,0.00087,0.019,0.12,0.17,0.0063,0.61,0.65,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00014,0.0012,0.00014,0.0013,0.00018,0.0013,0.0012,1,1
|
||||||
27490000,0.77,0.065,-0.025,-0.63,2.1,1.5,-1.2,1.7,1.3,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0098,-0.019,-0.12,-0.11,-0.023,0.5,0.0044,-0.1,-0.043,0,0,0.00041,0.00073,0.02,0.13,0.19,0.0088,0.66,0.72,0.037,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0012,0.00012,0.0012,0.00014,0.0012,0.0012,0,0
|
27490000,0.77,0.065,-0.025,-0.63,2.1,1.5,-1.2,1.7,1.4,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.009,-0.019,-0.13,-0.11,-0.024,0.5,0.0044,-0.1,-0.043,0,0,0.00041,0.00071,0.019,0.13,0.18,0.0063,0.66,0.71,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00014,0.0012,0.00012,0.0012,0.00014,0.0012,0.0012,1,1
|
||||||
27590000,0.77,0.052,-0.022,-0.63,2.2,1.5,-1.2,1.9,1.5,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0097,-0.019,-0.12,-0.11,-0.024,0.5,0.0039,-0.099,-0.044,0,0,0.0004,0.00062,0.02,0.14,0.2,0.0089,0.71,0.78,0.038,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0012,0.00011,0.0012,0.00012,0.0012,0.0012,0,0
|
27590000,0.77,0.052,-0.022,-0.63,2.2,1.5,-1.2,1.9,1.5,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0089,-0.019,-0.13,-0.11,-0.024,0.5,0.004,-0.099,-0.044,0,0,0.0004,0.0006,0.02,0.14,0.19,0.0063,0.71,0.78,0.034,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00014,0.0012,0.00011,0.0012,0.00012,0.0012,0.0012,1,1
|
||||||
27690000,0.77,0.05,-0.021,-0.63,2.2,1.6,-1.2,2.1,1.7,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0096,-0.019,-0.12,-0.11,-0.024,0.5,0.0033,-0.096,-0.044,0,0,0.0004,0.0006,0.02,0.14,0.2,0.009,0.77,0.85,0.038,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0011,0.0001,0.0012,0.00011,0.0012,0.0012,0,0
|
27690000,0.78,0.05,-0.021,-0.63,2.2,1.6,-1.2,2.1,1.7,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0088,-0.018,-0.13,-0.11,-0.025,0.5,0.0034,-0.096,-0.044,0,0,0.0004,0.00059,0.02,0.14,0.2,0.0063,0.77,0.84,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00014,0.0011,0.0001,0.0012,0.00011,0.0012,0.0012,1,1
|
||||||
27790000,0.77,0.052,-0.021,-0.63,2.2,1.6,-1.2,2.4,1.8,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0096,-0.018,-0.12,-0.12,-0.025,0.49,0.0027,-0.094,-0.044,0,0,0.0004,0.00062,0.02,0.15,0.21,0.009,0.83,0.93,0.038,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0011,9.5e-05,0.0011,9.5e-05,0.0012,0.0011,0,0
|
27790000,0.78,0.052,-0.021,-0.63,2.2,1.6,-1.2,2.3,1.8,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0088,-0.018,-0.13,-0.12,-0.025,0.49,0.0028,-0.094,-0.044,0,0,0.0004,0.0006,0.02,0.15,0.21,0.0064,0.83,0.92,0.033,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00014,0.0011,9.7e-05,0.0011,9.5e-05,0.0012,0.0011,1,1
|
||||||
27890000,0.77,0.05,-0.021,-0.63,2.3,1.6,-1.2,2.6,2,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0094,-0.018,-0.12,-0.12,-0.025,0.49,0.0027,-0.092,-0.044,0,0,0.0004,0.0006,0.02,0.15,0.22,0.0091,0.89,1,0.038,5.9e-07,5.9e-07,6.4e-06,0.031,0.031,0.0005,0.0011,9.1e-05,0.0011,8.6e-05,0.0011,0.0011,0,0
|
27890000,0.78,0.05,-0.021,-0.63,2.3,1.6,-1.2,2.6,2,-3.7e+02,-0.00074,-0.0058,1.1e-05,0.0086,-0.018,-0.13,-0.12,-0.025,0.49,0.0028,-0.092,-0.044,0,0,0.0004,0.00059,0.02,0.15,0.21,0.0064,0.89,1,0.034,5.9e-07,5.9e-07,5e-06,0.031,0.031,0.00014,0.0011,9.3e-05,0.0011,8.6e-05,0.0011,0.0011,1,1
|
||||||
27990000,0.77,0.046,-0.02,-0.63,2.3,1.6,-1.2,2.8,2.1,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0092,-0.018,-0.12,-0.12,-0.025,0.49,0.0025,-0.091,-0.044,0,0,0.0004,0.00057,0.02,0.16,0.23,0.0091,0.96,1.1,0.038,5.9e-07,6e-07,6.4e-06,0.031,0.031,0.0005,0.0011,8.6e-05,0.0011,7.8e-05,0.0011,0.0011,0,0
|
27990000,0.78,0.046,-0.02,-0.63,2.3,1.6,-1.2,2.8,2.1,-3.7e+02,-0.00073,-0.0058,1.1e-05,0.0084,-0.017,-0.13,-0.12,-0.026,0.49,0.0026,-0.091,-0.044,0,0,0.0004,0.00056,0.02,0.16,0.22,0.0064,0.96,1.1,0.034,5.9e-07,6e-07,5e-06,0.031,0.031,0.00014,0.0011,8.8e-05,0.0011,7.8e-05,0.0011,0.0011,1,1
|
||||||
28090000,0.77,0.06,-0.024,-0.63,2.3,1.6,-1.2,3,2.3,-3.7e+02,-0.00074,-0.0058,1.5e-05,0.0091,-0.017,-0.12,-0.12,-0.025,0.49,0.0022,-0.09,-0.044,0,0,0.00041,0.00069,0.02,0.16,0.23,0.0091,1,1.2,0.038,6e-07,6e-07,6.4e-06,0.031,0.031,0.0005,0.0011,8.3e-05,0.0011,7.2e-05,0.0011,0.0011,0,0
|
28090000,0.77,0.06,-0.024,-0.63,2.3,1.6,-1.2,3,2.3,-3.7e+02,-0.00073,-0.0058,1.1e-05,0.0082,-0.017,-0.12,-0.12,-0.026,0.49,0.0023,-0.09,-0.044,0,0,0.00041,0.00068,0.02,0.16,0.23,0.0065,1,1.2,0.033,5.9e-07,6e-07,5e-06,0.031,0.031,0.00014,0.0011,8.5e-05,0.0011,7.1e-05,0.0011,0.0011,1,1
|
||||||
28190000,0.77,0.073,-0.028,-0.63,2.4,1.7,-0.95,3.3,2.4,-3.7e+02,-0.00073,-0.0058,1.5e-05,0.0089,-0.017,-0.12,-0.12,-0.025,0.49,0.0022,-0.09,-0.044,0,0,0.00043,0.00083,0.02,0.17,0.24,0.0092,1.1,1.3,0.038,6e-07,6e-07,6.4e-06,0.031,0.031,0.0005,0.0011,8.1e-05,0.0011,6.7e-05,0.0011,0.0011,0,0
|
28190000,0.77,0.073,-0.028,-0.63,2.3,1.7,-0.94,3.2,2.5,-3.7e+02,-0.00073,-0.0058,1.1e-05,0.008,-0.016,-0.12,-0.12,-0.026,0.49,0.0023,-0.09,-0.044,0,0,0.00043,0.00081,0.019,0.17,0.24,0.0066,1.1,1.3,0.034,6e-07,6e-07,5e-06,0.031,0.031,0.00013,0.0011,8.3e-05,0.0011,6.7e-05,0.0011,0.0011,1,1
|
||||||
28290000,0.77,0.055,-0.022,-0.63,2.4,1.7,-0.089,3.5,2.6,-3.7e+02,-0.00073,-0.0058,1.5e-05,0.0087,-0.016,-0.12,-0.12,-0.025,0.49,0.0021,-0.09,-0.044,0,0,0.00041,0.00065,0.02,0.17,0.24,0.0093,1.2,1.4,0.038,6e-07,6e-07,6.4e-06,0.031,0.031,0.0005,0.0011,7.8e-05,0.0011,6.2e-05,0.0011,0.0011,0,0
|
28290000,0.77,0.056,-0.022,-0.63,2.3,1.7,-0.078,3.5,2.6,-3.7e+02,-0.00073,-0.0058,1.2e-05,0.0077,-0.016,-0.12,-0.12,-0.026,0.49,0.0022,-0.09,-0.044,0,0,0.00041,0.00064,0.02,0.17,0.24,0.0066,1.2,1.4,0.034,6e-07,6e-07,5e-06,0.031,0.031,0.00013,0.0011,8.1e-05,0.0011,6.2e-05,0.0011,0.0011,1,1
|
||||||
28390000,0.77,0.023,-0.0093,-0.63,2.4,1.7,0.77,3.7,2.8,-3.7e+02,-0.00073,-0.0058,1.5e-05,0.0083,-0.015,-0.12,-0.12,-0.025,0.49,0.0019,-0.089,-0.043,0,0,0.00039,0.00043,0.021,0.17,0.24,0.0094,1.3,1.5,0.038,6e-07,6e-07,6.4e-06,0.031,0.031,0.0005,0.0011,7.5e-05,0.0011,5.8e-05,0.0011,0.0011,0,0
|
28390000,0.77,0.023,-0.0092,-0.63,2.3,1.7,0.78,3.7,2.8,-3.7e+02,-0.00073,-0.0058,1.2e-05,0.0073,-0.015,-0.12,-0.12,-0.026,0.49,0.002,-0.089,-0.043,0,0,0.00039,0.00043,0.02,0.17,0.24,0.0067,1.3,1.5,0.034,6e-07,6e-07,5e-06,0.031,0.031,0.00013,0.0011,7.8e-05,0.0011,5.8e-05,0.0011,0.0011,1,1
|
||||||
28490000,0.77,0.0035,-0.0024,-0.63,2.3,1.7,1.1,4,2.9,-3.7e+02,-0.00073,-0.0058,1.5e-05,0.0081,-0.015,-0.12,-0.12,-0.026,0.49,0.0017,-0.086,-0.041,0,0,0.00039,0.00039,0.021,0.17,0.24,0.0094,1.4,1.6,0.038,6e-07,6e-07,6.4e-06,0.031,0.031,0.0005,0.001,7.2e-05,0.001,5.4e-05,0.0011,0.001,0,0
|
28490000,0.77,0.0035,-0.0023,-0.63,2.3,1.7,1.1,3.9,3,-3.7e+02,-0.00072,-0.0058,1.2e-05,0.007,-0.014,-0.12,-0.12,-0.026,0.49,0.0018,-0.086,-0.041,0,0,0.00039,0.00039,0.02,0.17,0.24,0.0067,1.4,1.6,0.034,6e-07,6e-07,5e-06,0.031,0.031,0.00013,0.001,7.4e-05,0.001,5.4e-05,0.0011,0.001,1,1
|
||||||
28590000,0.77,-0.00022,-0.00094,-0.63,2.2,1.6,0.96,4.2,3.1,-3.7e+02,-0.00072,-0.0058,1.5e-05,0.0077,-0.014,-0.12,-0.13,-0.027,0.49,0.0016,-0.081,-0.04,0,0,0.00039,0.00039,0.021,0.18,0.24,0.0095,1.5,1.7,0.038,6e-07,6e-07,6.4e-06,0.031,0.03,0.0005,0.00096,6.8e-05,0.00098,5.1e-05,0.001,0.00098,0,0
|
28590000,0.78,-0.00017,-0.00092,-0.63,2.2,1.6,0.97,4.2,3.1,-3.7e+02,-0.00072,-0.0058,1.2e-05,0.0065,-0.013,-0.12,-0.13,-0.028,0.49,0.0017,-0.081,-0.04,0,0,0.00039,0.0004,0.02,0.17,0.23,0.0068,1.5,1.7,0.034,6e-07,6e-07,5e-06,0.031,0.031,0.00013,0.00096,7e-05,0.00098,5.1e-05,0.001,0.00098,1,1
|
||||||
28690000,0.77,-0.0012,-0.00033,-0.63,2.2,1.6,0.96,4.4,3.3,-3.7e+02,-0.00072,-0.0058,1.5e-05,0.0072,-0.013,-0.12,-0.13,-0.028,0.48,0.0013,-0.077,-0.038,0,0,0.00039,0.00039,0.021,0.18,0.24,0.0095,1.6,1.9,0.038,6e-07,6e-07,6.4e-06,0.031,0.03,0.0005,0.00092,6.5e-05,0.00093,4.8e-05,0.00095,0.00093,0,0
|
28690000,0.78,-0.0012,-0.00031,-0.63,2.2,1.6,0.98,4.4,3.3,-3.7e+02,-0.00072,-0.0058,1.3e-05,0.0059,-0.011,-0.12,-0.13,-0.028,0.48,0.0014,-0.076,-0.038,0,0,0.00039,0.0004,0.02,0.18,0.23,0.0068,1.6,1.8,0.034,6e-07,6e-07,5.1e-06,0.031,0.031,0.00013,0.00091,6.7e-05,0.00093,4.8e-05,0.00095,0.00093,1,1
|
||||||
28790000,0.77,-0.0016,-4.3e-05,-0.63,2.1,1.6,0.97,4.6,3.4,-3.7e+02,-0.00072,-0.0058,1.5e-05,0.0067,-0.011,-0.12,-0.13,-0.028,0.48,0.0011,-0.073,-0.037,0,0,0.00039,0.0004,0.021,0.18,0.24,0.0095,1.7,2,0.038,6e-07,6e-07,6.4e-06,0.031,0.03,0.0005,0.00088,6.2e-05,0.0009,4.6e-05,0.00092,0.00089,0,0
|
28790000,0.78,-0.0015,-3e-05,-0.63,2.1,1.6,0.98,4.6,3.4,-3.7e+02,-0.00071,-0.0058,1.3e-05,0.0053,-0.0096,-0.12,-0.13,-0.029,0.48,0.0012,-0.073,-0.037,0,0,0.0004,0.0004,0.02,0.18,0.23,0.0068,1.7,2,0.034,6e-07,6e-07,5.1e-06,0.031,0.031,0.00013,0.00088,6.4e-05,0.0009,4.6e-05,0.00092,0.00089,1,1
|
||||||
28890000,0.78,-0.0013,8e-06,-0.63,2,1.5,0.95,4.8,3.6,-3.7e+02,-0.00072,-0.0058,1.5e-05,0.0062,-0.01,-0.12,-0.13,-0.029,0.48,0.00096,-0.071,-0.036,0,0,0.00039,0.0004,0.021,0.18,0.24,0.0096,1.8,2.1,0.039,6e-07,6e-07,6.4e-06,0.031,0.03,0.0005,0.00085,6e-05,0.00087,4.4e-05,0.00089,0.00087,0,0
|
28890000,0.78,-0.0013,1.8e-05,-0.63,2,1.5,0.97,4.8,3.6,-3.7e+02,-0.00071,-0.0058,1.4e-05,0.0047,-0.0081,-0.12,-0.13,-0.029,0.48,0.001,-0.071,-0.036,0,0,0.0004,0.0004,0.02,0.18,0.23,0.0069,1.8,2.1,0.034,6e-07,6e-07,5.1e-06,0.031,0.031,0.00013,0.00085,6.2e-05,0.00087,4.4e-05,0.00089,0.00087,1,1
|
||||||
28990000,0.78,-0.00098,-7.2e-05,-0.63,2,1.5,0.95,5,3.7,-3.7e+02,-0.00071,-0.0058,1.5e-05,0.0057,-0.0085,-0.12,-0.14,-0.029,0.48,0.00073,-0.069,-0.034,0,0,0.0004,0.0004,0.021,0.19,0.23,0.0096,1.9,2.2,0.039,6e-07,6.1e-07,6.4e-06,0.031,0.03,0.0005,0.00083,5.8e-05,0.00084,4.2e-05,0.00086,0.00084,0,0
|
28990000,0.78,-0.00089,-6.6e-05,-0.63,1.9,1.5,0.97,5,3.7,-3.7e+02,-0.00071,-0.0058,1.4e-05,0.004,-0.0062,-0.12,-0.14,-0.03,0.48,0.00082,-0.069,-0.034,0,0,0.0004,0.0004,0.02,0.19,0.23,0.0069,1.9,2.2,0.034,6e-07,6.1e-07,5.1e-06,0.031,0.031,0.00013,0.00082,6e-05,0.00084,4.2e-05,0.00086,0.00084,1,1
|
||||||
29090000,0.78,-0.00057,-0.00017,-0.63,1.9,1.5,0.94,5.2,3.9,-3.7e+02,-0.00071,-0.0058,1.5e-05,0.0051,-0.0072,-0.12,-0.14,-0.029,0.48,0.00061,-0.067,-0.033,0,0,0.0004,0.0004,0.021,0.19,0.23,0.0097,2,2.4,0.039,6e-07,6.1e-07,6.4e-06,0.031,0.03,0.0005,0.0008,5.6e-05,0.00082,4e-05,0.00084,0.00082,0,0
|
29090000,0.78,-0.00047,-0.00017,-0.63,1.9,1.5,0.96,5.2,3.9,-3.7e+02,-0.0007,-0.0058,1.4e-05,0.0033,-0.0045,-0.12,-0.14,-0.03,0.48,0.0007,-0.067,-0.034,0,0,0.0004,0.0004,0.02,0.19,0.23,0.007,2,2.4,0.034,6e-07,6.1e-07,5.1e-06,0.031,0.031,0.00012,0.0008,5.8e-05,0.00082,4e-05,0.00084,0.00082,1,1
|
||||||
29190000,0.78,-0.00025,-0.00027,-0.63,1.8,1.4,0.93,5.4,4,-3.7e+02,-0.00071,-0.0058,1.5e-05,0.0046,-0.0057,-0.12,-0.14,-0.03,0.48,0.00061,-0.065,-0.034,0,0,0.0004,0.0004,0.021,0.19,0.24,0.0097,2.1,2.5,0.039,6.1e-07,6.1e-07,6.4e-06,0.031,0.03,0.0005,0.00079,5.5e-05,0.0008,3.9e-05,0.00082,0.0008,0,0
|
29190000,0.78,-0.00013,-0.00027,-0.63,1.8,1.4,0.95,5.3,4,-3.7e+02,-0.0007,-0.0058,1.5e-05,0.0026,-0.0026,-0.12,-0.14,-0.03,0.48,0.0007,-0.065,-0.034,0,0,0.0004,0.0004,0.02,0.19,0.23,0.007,2.1,2.5,0.034,6e-07,6.1e-07,5.1e-06,0.031,0.031,0.00012,0.00079,5.6e-05,0.0008,3.9e-05,0.00082,0.0008,1,1
|
||||||
29290000,0.78,0.00063,-0.00052,-0.63,1.8,1.4,0.96,5.6,4.2,-3.7e+02,-0.00071,-0.0058,1.5e-05,0.0039,-0.004,-0.11,-0.14,-0.03,0.47,0.00049,-0.063,-0.033,0,0,0.0004,0.0004,0.021,0.2,0.24,0.0098,2.2,2.7,0.039,6.1e-07,6.1e-07,6.4e-06,0.031,0.03,0.0005,0.00077,5.3e-05,0.00078,3.7e-05,0.0008,0.00078,0,0
|
29290000,0.78,0.00076,-0.00052,-0.63,1.8,1.4,0.98,5.5,4.2,-3.7e+02,-0.0007,-0.0058,1.5e-05,0.0017,-0.00038,-0.12,-0.14,-0.031,0.47,0.00058,-0.063,-0.033,0,0,0.0004,0.00041,0.02,0.2,0.23,0.0071,2.2,2.7,0.034,6.1e-07,6.1e-07,5.1e-06,0.031,0.03,0.00012,0.00077,5.5e-05,0.00078,3.7e-05,0.0008,0.00078,1,1
|
||||||
29390000,0.78,0.002,-0.0008,-0.63,1.7,1.4,0.97,5.7,4.3,-3.7e+02,-0.00071,-0.0058,1.5e-05,0.0032,-0.0022,-0.11,-0.14,-0.03,0.47,0.00029,-0.062,-0.033,0,0,0.0004,0.0004,0.021,0.2,0.24,0.0098,2.4,2.8,0.039,6.1e-07,6.1e-07,6.4e-06,0.031,0.03,0.0005,0.00076,5.2e-05,0.00077,3.6e-05,0.00079,0.00077,0,0
|
29390000,0.78,0.0022,-0.0008,-0.63,1.7,1.4,0.99,5.7,4.3,-3.7e+02,-0.00069,-0.0058,1.6e-05,0.00081,0.002,-0.12,-0.14,-0.031,0.47,0.00038,-0.062,-0.033,0,0,0.0004,0.00041,0.02,0.2,0.23,0.0071,2.4,2.8,0.034,6.1e-07,6.1e-07,5.1e-06,0.031,0.03,0.00012,0.00076,5.4e-05,0.00077,3.6e-05,0.00079,0.00077,1,1
|
||||||
29490000,0.78,0.0032,-0.0012,-0.63,1.7,1.4,0.96,5.9,4.4,-3.7e+02,-0.0007,-0.0058,1.5e-05,0.0027,-0.00094,-0.11,-0.14,-0.03,0.47,0.00026,-0.061,-0.032,0,0,0.0004,0.00041,0.021,0.21,0.24,0.0098,2.5,3,0.039,6.1e-07,6.1e-07,6.4e-06,0.031,0.03,0.0005,0.00075,5.1e-05,0.00076,3.5e-05,0.00078,0.00076,0,0
|
29490000,0.78,0.0034,-0.0012,-0.63,1.7,1.4,0.99,5.9,4.4,-3.7e+02,-0.00069,-0.0058,1.6e-05,0.00012,0.0038,-0.12,-0.14,-0.031,0.47,0.00036,-0.061,-0.032,0,0,0.0004,0.00041,0.02,0.21,0.24,0.0072,2.5,3,0.034,6.1e-07,6.1e-07,5.1e-06,0.031,0.03,0.00012,0.00075,5.3e-05,0.00076,3.5e-05,0.00078,0.00076,1,1
|
||||||
29590000,0.78,0.0042,-0.0014,-0.63,1.6,1.3,0.96,6.1,4.6,-3.7e+02,-0.0007,-0.0058,1.5e-05,0.0019,0.0012,-0.11,-0.14,-0.031,0.47,0.00023,-0.06,-0.032,0,0,0.0004,0.00041,0.021,0.21,0.24,0.0099,2.6,3.2,0.039,6.1e-07,6.1e-07,6.4e-06,0.031,0.03,0.0005,0.00074,5e-05,0.00075,3.4e-05,0.00077,0.00075,0,0
|
29590000,0.78,0.0044,-0.0014,-0.63,1.6,1.3,0.98,6,4.6,-3.7e+02,-0.00069,-0.0058,1.7e-05,-0.00097,0.0066,-0.12,-0.14,-0.031,0.47,0.00033,-0.06,-0.032,0,0,0.0004,0.00041,0.02,0.21,0.24,0.0072,2.6,3.1,0.034,6.1e-07,6.1e-07,5.1e-06,0.031,0.03,0.00012,0.00074,5.2e-05,0.00075,3.3e-05,0.00077,0.00075,1,1
|
||||||
29690000,0.78,0.0049,-0.0016,-0.63,1.6,1.3,0.95,6.2,4.7,-3.7e+02,-0.0007,-0.0058,1.5e-05,0.0013,0.0026,-0.11,-0.14,-0.031,0.47,0.00017,-0.059,-0.032,0,0,0.0004,0.00041,0.021,0.22,0.25,0.0099,2.8,3.3,0.039,6.1e-07,6.1e-07,6.4e-06,0.03,0.03,0.0005,0.00073,5e-05,0.00074,3.2e-05,0.00076,0.00074,0,0
|
29690000,0.78,0.0051,-0.0016,-0.63,1.6,1.3,0.98,6.2,4.7,-3.7e+02,-0.00069,-0.0058,1.8e-05,-0.0018,0.0087,-0.12,-0.14,-0.032,0.47,0.00027,-0.059,-0.032,0,0,0.00041,0.00041,0.02,0.22,0.24,0.0072,2.8,3.3,0.034,6.1e-07,6.1e-07,5.1e-06,0.031,0.03,0.00012,0.00073,5.1e-05,0.00074,3.2e-05,0.00076,0.00074,1,1
|
||||||
29790000,0.78,0.0053,-0.0017,-0.63,1.5,1.3,0.94,6.4,4.8,-3.7e+02,-0.0007,-0.0058,1.5e-05,0.00069,0.0043,-0.11,-0.14,-0.031,0.47,0.0002,-0.059,-0.031,0,0,0.0004,0.00041,0.021,0.22,0.25,0.0099,2.9,3.5,0.039,6.1e-07,6.1e-07,6.4e-06,0.03,0.03,0.0005,0.00072,4.9e-05,0.00073,3.2e-05,0.00075,0.00073,0,0
|
29790000,0.78,0.0055,-0.0017,-0.63,1.5,1.3,0.97,6.3,4.8,-3.7e+02,-0.00068,-0.0058,1.8e-05,-0.0027,0.011,-0.12,-0.14,-0.032,0.47,0.0003,-0.059,-0.031,0,0,0.00041,0.00041,0.02,0.22,0.25,0.0073,2.9,3.5,0.035,6.1e-07,6.1e-07,5.1e-06,0.031,0.03,0.00012,0.00072,5e-05,0.00073,3.2e-05,0.00076,0.00073,1,1
|
||||||
29890000,0.78,0.0055,-0.0017,-0.63,1.5,1.3,0.92,6.5,4.9,-3.7e+02,-0.0007,-0.0058,1.5e-05,-0.00029,0.0069,-0.11,-0.14,-0.031,0.47,0.00011,-0.058,-0.031,0,0,0.00041,0.00041,0.021,0.23,0.25,0.0099,3.1,3.7,0.039,6.1e-07,6.1e-07,6.4e-06,0.03,0.03,0.0005,0.00072,4.8e-05,0.00073,3.1e-05,0.00075,0.00073,0,0
|
29890000,0.78,0.0058,-0.0018,-0.63,1.5,1.3,0.95,6.5,5,-3.7e+02,-0.00068,-0.0058,1.9e-05,-0.0041,0.015,-0.12,-0.14,-0.032,0.47,0.00022,-0.058,-0.031,0,0,0.00041,0.00041,0.02,0.23,0.25,0.0073,3.1,3.7,0.035,6.1e-07,6.1e-07,5.1e-06,0.031,0.03,0.00012,0.00072,5e-05,0.00073,3.1e-05,0.00075,0.00073,1,1
|
||||||
29990000,0.78,0.0056,-0.0018,-0.63,1.4,1.3,0.91,6.7,5.1,-3.7e+02,-0.0007,-0.0058,1.5e-05,-0.0011,0.0088,-0.11,-0.14,-0.031,0.47,8.6e-05,-0.058,-0.031,0,0,0.00041,0.00041,0.021,0.24,0.26,0.0099,3.3,3.9,0.039,6.1e-07,6.2e-07,6.4e-06,0.03,0.03,0.0005,0.00071,4.7e-05,0.00072,3e-05,0.00074,0.00072,0,0
|
29990000,0.78,0.006,-0.0018,-0.63,1.4,1.3,0.94,6.6,5.1,-3.7e+02,-0.00068,-0.0058,1.9e-05,-0.0052,0.017,-0.12,-0.14,-0.032,0.47,0.00019,-0.058,-0.031,0,0,0.00041,0.00042,0.02,0.24,0.26,0.0073,3.3,3.8,0.035,6.1e-07,6.2e-07,5.1e-06,0.031,0.03,0.00012,0.00071,4.9e-05,0.00072,3e-05,0.00074,0.00072,1,1
|
||||||
30090000,0.78,0.0056,-0.0017,-0.63,1.4,1.3,0.89,6.8,5.2,-3.7e+02,-0.0007,-0.0058,1.5e-05,-0.0018,0.011,-0.11,-0.15,-0.031,0.47,2.5e-05,-0.057,-0.031,0,0,0.00041,0.00041,0.021,0.24,0.26,0.0099,3.4,4.1,0.039,6.1e-07,6.2e-07,6.4e-06,0.03,0.03,0.0005,0.00071,4.7e-05,0.00071,2.9e-05,0.00074,0.00071,0,0
|
30090000,0.78,0.0059,-0.0018,-0.63,1.4,1.2,0.93,6.7,5.2,-3.7e+02,-0.00068,-0.0058,2e-05,-0.0063,0.02,-0.12,-0.15,-0.032,0.47,0.00013,-0.057,-0.031,0,0,0.00041,0.00042,0.02,0.24,0.26,0.0073,3.4,4,0.035,6.1e-07,6.2e-07,5.1e-06,0.031,0.03,0.00011,0.00071,4.8e-05,0.00072,2.9e-05,0.00074,0.00072,1,1
|
||||||
30190000,0.77,0.0053,-0.0017,-0.63,1.4,1.2,0.88,7,5.3,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0023,0.012,-0.11,-0.15,-0.031,0.47,5.6e-05,-0.056,-0.031,0,0,0.00041,0.00042,0.021,0.25,0.27,0.01,3.6,4.3,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.03,0.0005,0.0007,4.6e-05,0.00071,2.8e-05,0.00073,0.00071,0,0
|
30190000,0.78,0.0057,-0.0018,-0.63,1.3,1.2,0.91,6.9,5.3,-3.7e+02,-0.00068,-0.0058,2.1e-05,-0.007,0.022,-0.12,-0.15,-0.032,0.47,0.00017,-0.056,-0.031,0,0,0.00041,0.00042,0.02,0.25,0.27,0.0074,3.6,4.2,0.035,6.1e-07,6.2e-07,5.1e-06,0.031,0.03,0.00011,0.0007,4.8e-05,0.00071,2.8e-05,0.00073,0.00071,1,1
|
||||||
30290000,0.77,0.0051,-0.0016,-0.63,1.3,1.2,0.87,7.1,5.4,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0027,0.013,-0.11,-0.15,-0.032,0.47,3.5e-05,-0.056,-0.031,0,0,0.00041,0.00042,0.021,0.26,0.27,0.01,3.8,4.5,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.03,0.0005,0.0007,4.6e-05,0.00071,2.8e-05,0.00073,0.0007,0,0
|
30290000,0.78,0.0056,-0.0017,-0.63,1.3,1.2,0.9,7,5.4,-3.7e+02,-0.00068,-0.0058,2.1e-05,-0.0078,0.024,-0.12,-0.15,-0.032,0.47,0.00015,-0.055,-0.032,0,0,0.00041,0.00042,0.02,0.26,0.27,0.0074,3.8,4.4,0.035,6.1e-07,6.2e-07,5.1e-06,0.031,0.03,0.00011,0.0007,4.7e-05,0.00071,2.7e-05,0.00073,0.00071,1,1
|
||||||
30390000,0.77,0.0049,-0.0015,-0.63,1.3,1.2,0.85,7.2,5.6,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0034,0.015,-0.11,-0.15,-0.032,0.47,2.7e-05,-0.055,-0.031,0,0,0.00041,0.00042,0.021,0.26,0.28,0.01,4,4.7,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.03,0.0005,0.00069,4.5e-05,0.0007,2.7e-05,0.00072,0.0007,0,0
|
30390000,0.78,0.0054,-0.0017,-0.63,1.3,1.2,0.89,7.1,5.6,-3.7e+02,-0.00067,-0.0058,2.2e-05,-0.009,0.027,-0.12,-0.15,-0.032,0.47,0.00014,-0.055,-0.031,0,0,0.00041,0.00042,0.02,0.26,0.28,0.0074,4,4.7,0.035,6.2e-07,6.2e-07,5.1e-06,0.031,0.03,0.00011,0.00069,4.7e-05,0.0007,2.7e-05,0.00072,0.0007,1,1
|
||||||
30490000,0.77,0.0046,-0.0014,-0.63,1.3,1.2,0.84,7.3,5.7,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0038,0.016,-0.11,-0.15,-0.032,0.47,4.7e-05,-0.055,-0.031,0,0,0.00041,0.00042,0.021,0.27,0.29,0.01,4.2,4.9,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.03,0.0005,0.00069,4.5e-05,0.0007,2.6e-05,0.00072,0.0007,0,0
|
30490000,0.78,0.0051,-0.0016,-0.63,1.2,1.2,0.87,7.3,5.7,-3.7e+02,-0.00067,-0.0058,2.2e-05,-0.0097,0.029,-0.12,-0.15,-0.032,0.47,0.00017,-0.055,-0.031,0,0,0.00041,0.00042,0.02,0.27,0.28,0.0074,4.2,4.9,0.035,6.2e-07,6.2e-07,5.1e-06,0.031,0.03,0.00011,0.00069,4.6e-05,0.0007,2.6e-05,0.00072,0.0007,1,1
|
||||||
30590000,0.77,0.0042,-0.0013,-0.63,1.2,1.2,0.8,7.5,5.8,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0045,0.018,-0.11,-0.15,-0.032,0.47,9.3e-05,-0.055,-0.031,0,0,0.00041,0.00042,0.021,0.28,0.29,0.01,4.4,5.2,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.03,0.0005,0.00068,4.4e-05,0.00069,2.6e-05,0.00071,0.00069,0,0
|
30590000,0.78,0.0048,-0.0014,-0.63,1.2,1.2,0.83,7.4,5.8,-3.7e+02,-0.00067,-0.0058,2.3e-05,-0.011,0.032,-0.12,-0.15,-0.032,0.47,0.00022,-0.055,-0.031,0,0,0.00041,0.00042,0.02,0.28,0.29,0.0074,4.4,5.1,0.035,6.2e-07,6.2e-07,5.1e-06,0.031,0.029,0.00011,0.00068,4.6e-05,0.00069,2.6e-05,0.00071,0.00069,1,1
|
||||||
30690000,0.77,0.0039,-0.0012,-0.63,1.2,1.2,0.79,7.6,5.9,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0052,0.019,-0.11,-0.15,-0.032,0.47,9.1e-05,-0.054,-0.031,0,0,0.00041,0.00042,0.021,0.29,0.3,0.01,4.6,5.4,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.029,0.0005,0.00068,4.4e-05,0.00069,2.5e-05,0.00071,0.00069,0,0
|
30690000,0.78,0.0045,-0.0013,-0.63,1.1,1.1,0.83,7.5,5.9,-3.7e+02,-0.00067,-0.0058,2.3e-05,-0.012,0.035,-0.12,-0.15,-0.033,0.47,0.00022,-0.054,-0.031,0,0,0.00041,0.00043,0.02,0.29,0.3,0.0074,4.6,5.3,0.035,6.2e-07,6.2e-07,5.1e-06,0.031,0.029,0.00011,0.00068,4.5e-05,0.00069,2.5e-05,0.00071,0.00069,1,1
|
||||||
30790000,0.77,0.0035,-0.001,-0.63,1.1,1.1,0.78,7.7,6,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0055,0.02,-0.11,-0.15,-0.032,0.47,5.1e-05,-0.054,-0.031,0,0,0.00041,0.00042,0.021,0.29,0.3,0.01,4.8,5.7,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.029,0.0005,0.00068,4.4e-05,0.00068,2.5e-05,0.00071,0.00068,0,0
|
30790000,0.78,0.0041,-0.0012,-0.63,1.1,1.1,0.82,7.6,6,-3.7e+02,-0.00067,-0.0058,2.4e-05,-0.013,0.037,-0.12,-0.15,-0.033,0.47,0.00018,-0.054,-0.031,0,0,0.00041,0.00043,0.02,0.29,0.3,0.0074,4.8,5.6,0.035,6.2e-07,6.2e-07,5.1e-06,0.031,0.029,0.00011,0.00068,4.5e-05,0.00069,2.5e-05,0.00071,0.00069,1,1
|
||||||
30890000,0.77,0.003,-0.00088,-0.63,1.1,1.1,0.77,7.8,6.1,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.006,0.022,-0.11,-0.15,-0.032,0.47,6.1e-05,-0.053,-0.031,0,0,0.00041,0.00043,0.021,0.3,0.31,0.01,5.1,5.9,0.04,6.2e-07,6.2e-07,6.4e-06,0.03,0.029,0.0005,0.00067,4.3e-05,0.00068,2.4e-05,0.0007,0.00068,0,0
|
30890000,0.78,0.0037,-0.0011,-0.63,1.1,1.1,0.81,7.7,6.1,-3.7e+02,-0.00067,-0.0058,2.4e-05,-0.014,0.039,-0.12,-0.15,-0.033,0.47,0.0002,-0.053,-0.031,0,0,0.00041,0.00043,0.02,0.3,0.31,0.0074,5.1,5.8,0.035,6.2e-07,6.2e-07,5.1e-06,0.031,0.029,0.00011,0.00067,4.5e-05,0.00068,2.4e-05,0.0007,0.00068,1,1
|
||||||
30990000,0.77,0.0024,-0.00076,-0.63,1.1,1.1,0.76,7.9,6.3,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0067,0.023,-0.11,-0.15,-0.032,0.47,6.2e-05,-0.053,-0.031,0,0,0.00042,0.00043,0.021,0.31,0.32,0.0099,5.3,6.2,0.04,6.2e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0.00067,4.3e-05,0.00068,2.4e-05,0.0007,0.00068,0,0
|
30990000,0.78,0.0032,-0.00098,-0.63,1,1.1,0.8,7.8,6.2,-3.7e+02,-0.00067,-0.0058,2.5e-05,-0.015,0.042,-0.12,-0.15,-0.033,0.47,0.0002,-0.053,-0.031,0,0,0.00041,0.00043,0.021,0.31,0.32,0.0074,5.3,6.1,0.035,6.2e-07,6.3e-07,5.1e-06,0.031,0.029,0.00011,0.00067,4.4e-05,0.00068,2.3e-05,0.0007,0.00068,1,1
|
||||||
31090000,0.77,0.0019,-0.00059,-0.63,1,1.1,0.75,8,6.4,-3.7e+02,-0.0007,-0.0058,1.4e-05,-0.0074,0.025,-0.11,-0.15,-0.032,0.47,4.1e-05,-0.053,-0.031,0,0,0.00042,0.00043,0.021,0.32,0.33,0.01,5.6,6.4,0.04,6.2e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0.00067,4.2e-05,0.00067,2.3e-05,0.00069,0.00067,0,0
|
31090000,0.78,0.0028,-0.00083,-0.63,0.99,1.1,0.79,7.9,6.3,-3.7e+02,-0.00067,-0.0058,2.5e-05,-0.016,0.045,-0.12,-0.15,-0.033,0.47,0.00019,-0.053,-0.031,0,0,0.00041,0.00043,0.021,0.32,0.32,0.0074,5.6,6.4,0.035,6.2e-07,6.3e-07,5.1e-06,0.031,0.029,0.00011,0.00067,4.4e-05,0.00068,2.3e-05,0.0007,0.00068,1,1
|
||||||
31190000,0.77,0.0016,-0.00047,-0.63,0.99,1.1,0.74,8.1,6.5,-3.7e+02,-0.0007,-0.0058,1.3e-05,-0.0085,0.028,-0.1,-0.15,-0.032,0.47,4.7e-05,-0.053,-0.031,0,0,0.00042,0.00043,0.021,0.33,0.34,0.0099,5.8,6.7,0.04,6.2e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0.00066,4.2e-05,0.00067,2.3e-05,0.00069,0.00067,0,0
|
31190000,0.78,0.0026,-0.00073,-0.63,0.96,1.1,0.78,8,6.4,-3.7e+02,-0.00067,-0.0058,2.6e-05,-0.018,0.049,-0.12,-0.15,-0.033,0.47,0.0002,-0.052,-0.031,0,0,0.00041,0.00043,0.021,0.33,0.33,0.0074,5.8,6.6,0.035,6.2e-07,6.3e-07,5.1e-06,0.03,0.029,0.0001,0.00066,4.3e-05,0.00067,2.3e-05,0.00069,0.00067,1,1
|
||||||
31290000,0.77,0.0011,-0.00028,-0.63,0.95,1.1,0.74,8.2,6.6,-3.7e+02,-0.0007,-0.0058,1.3e-05,-0.0093,0.03,-0.1,-0.15,-0.032,0.47,5.7e-05,-0.052,-0.031,0,0,0.00042,0.00043,0.022,0.34,0.34,0.0099,6.1,7,0.04,6.3e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0.00066,4.2e-05,0.00067,2.2e-05,0.00069,0.00067,0,0
|
31290000,0.78,0.0021,-0.00058,-0.63,0.92,1,0.78,8.1,6.6,-3.7e+02,-0.00067,-0.0058,2.7e-05,-0.019,0.053,-0.12,-0.15,-0.033,0.47,0.00021,-0.052,-0.032,0,0,0.00041,0.00043,0.021,0.34,0.34,0.0074,6.1,6.9,0.035,6.2e-07,6.3e-07,5.1e-06,0.03,0.029,0.0001,0.00066,4.3e-05,0.00067,2.2e-05,0.00069,0.00067,1,1
|
||||||
31390000,0.77,0.00045,-9.2e-05,-0.63,0.91,1,0.74,8.3,6.7,-3.7e+02,-0.0007,-0.0058,1.3e-05,-0.0099,0.031,-0.1,-0.15,-0.032,0.47,5.7e-05,-0.052,-0.031,0,0,0.00042,0.00043,0.022,0.35,0.35,0.0099,6.4,7.3,0.04,6.3e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0.00066,4.1e-05,0.00066,2.2e-05,0.00068,0.00066,0,0
|
31390000,0.78,0.0015,-0.00041,-0.63,0.88,1,0.78,8.2,6.7,-3.7e+02,-0.00068,-0.0058,2.7e-05,-0.02,0.056,-0.12,-0.15,-0.033,0.47,0.00022,-0.052,-0.032,0,0,0.00041,0.00044,0.021,0.35,0.35,0.0074,6.4,7.2,0.035,6.3e-07,6.3e-07,5.1e-06,0.03,0.028,0.0001,0.00066,4.3e-05,0.00067,2.2e-05,0.00069,0.00067,1,1
|
||||||
31490000,0.77,-0.00017,6.2e-05,-0.63,0.87,1,0.74,8.4,6.8,-3.7e+02,-0.0007,-0.0058,1.3e-05,-0.011,0.033,-0.1,-0.15,-0.032,0.47,1.6e-05,-0.051,-0.031,0,0,0.00042,0.00044,0.022,0.36,0.36,0.0099,6.7,7.6,0.04,6.3e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0.00065,4.1e-05,0.00066,2.1e-05,0.00068,0.00066,0,0
|
31490000,0.78,0.00098,-0.00028,-0.63,0.84,1,0.78,8.3,6.8,-3.7e+02,-0.00068,-0.0058,2.8e-05,-0.022,0.059,-0.11,-0.15,-0.033,0.47,0.00018,-0.051,-0.032,0,0,0.00042,0.00044,0.021,0.36,0.36,0.0074,6.7,7.5,0.036,6.3e-07,6.3e-07,5.1e-06,0.03,0.028,0.0001,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
31590000,0.77,-0.00058,0.0002,-0.63,0.84,1,0.73,8.5,6.9,-3.7e+02,-0.0007,-0.0058,1.3e-05,-0.011,0.035,-0.1,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00042,0.00044,0.022,0.37,0.37,0.0098,7,7.9,0.04,6.3e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0,0,0,0,0,0,0,0
|
31590000,0.78,0.00065,-0.00017,-0.63,0.8,1,0.77,8.4,6.9,-3.7e+02,-0.00068,-0.0058,2.9e-05,-0.023,0.062,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00044,0.021,0.37,0.37,0.0073,7,7.8,0.035,6.3e-07,6.3e-07,5.1e-06,0.03,0.028,0.0001,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
31690000,0.77,-0.0013,0.00039,-0.63,0.8,1,0.74,8.6,7,-3.7e+02,-0.00071,-0.0058,1.2e-05,-0.012,0.037,-0.1,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00042,0.00044,0.022,0.38,0.38,0.0098,7.3,8.2,0.04,6.3e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0,0,0,0,0,0,0,0
|
31690000,0.78,5.2e-05,-1.7e-06,-0.63,0.76,0.98,0.78,8.5,7,-3.7e+02,-0.00068,-0.0058,2.9e-05,-0.024,0.066,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00044,0.021,0.38,0.38,0.0073,7.3,8.1,0.035,6.3e-07,6.3e-07,5.1e-06,0.03,0.028,0.0001,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
31790000,0.77,-0.002,0.00065,-0.63,0.76,0.98,0.74,8.7,7.1,-3.7e+02,-0.00071,-0.0058,1.2e-05,-0.013,0.038,-0.1,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00042,0.00044,0.022,0.39,0.39,0.0098,7.6,8.6,0.04,6.3e-07,6.3e-07,6.4e-06,0.03,0.029,0.0005,0,0,0,0,0,0,0,0
|
31790000,0.78,-0.00062,0.00023,-0.63,0.73,0.96,0.78,8.5,7.1,-3.7e+02,-0.00068,-0.0058,3e-05,-0.026,0.069,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00044,0.021,0.39,0.39,0.0073,7.6,8.5,0.036,6.3e-07,6.3e-07,5.1e-06,0.03,0.028,9.9e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
31890000,0.77,-0.0027,0.00083,-0.63,0.72,0.96,0.73,8.8,7.2,-3.7e+02,-0.00071,-0.0058,1.2e-05,-0.013,0.04,-0.1,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00042,0.00044,0.022,0.4,0.4,0.0098,7.9,8.9,0.04,6.3e-07,6.3e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
31890000,0.78,-0.0012,0.00038,-0.63,0.69,0.94,0.77,8.6,7.2,-3.7e+02,-0.00068,-0.0058,3.1e-05,-0.027,0.073,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00045,0.021,0.4,0.4,0.0073,7.9,8.8,0.036,6.3e-07,6.3e-07,5.1e-06,0.03,0.028,9.8e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
31990000,0.77,-0.0032,0.001,-0.63,0.68,0.95,0.73,8.8,7.3,-3.7e+02,-0.00071,-0.0058,1.2e-05,-0.014,0.042,-0.1,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00042,0.00045,0.022,0.41,0.41,0.0097,8.3,9.3,0.04,6.3e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
31990000,0.78,-0.0017,0.00051,-0.63,0.65,0.93,0.77,8.7,7.2,-3.7e+02,-0.00069,-0.0058,3.1e-05,-0.029,0.076,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00045,0.021,0.41,0.41,0.0072,8.3,9.2,0.035,6.3e-07,6.4e-07,5.1e-06,0.03,0.028,9.8e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32090000,0.77,-0.0039,0.0012,-0.63,0.65,0.93,0.73,8.9,7.4,-3.7e+02,-0.00071,-0.0058,1.1e-05,-0.015,0.044,-0.1,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00042,0.00045,0.022,0.42,0.42,0.0097,8.6,9.6,0.04,6.3e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32090000,0.78,-0.0023,0.0007,-0.63,0.61,0.91,0.78,8.8,7.3,-3.7e+02,-0.00069,-0.0058,3.2e-05,-0.03,0.08,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00045,0.021,0.42,0.42,0.0072,8.6,9.5,0.036,6.3e-07,6.4e-07,5.1e-06,0.03,0.027,9.7e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32190000,0.77,-0.0048,0.0014,-0.63,0.61,0.91,0.73,9,7.5,-3.7e+02,-0.00072,-0.0058,1.1e-05,-0.016,0.047,-0.099,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00045,0.022,0.43,0.43,0.0097,9,10,0.04,6.3e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32190000,0.78,-0.0031,0.0009,-0.63,0.57,0.89,0.78,8.8,7.4,-3.7e+02,-0.00069,-0.0058,3.3e-05,-0.032,0.085,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00046,0.021,0.43,0.43,0.0072,9,9.9,0.036,6.3e-07,6.4e-07,5.1e-06,0.03,0.027,9.6e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32290000,0.77,-0.0055,0.0016,-0.63,0.57,0.9,0.73,9.1,7.6,-3.7e+02,-0.00072,-0.0058,1.1e-05,-0.017,0.049,-0.099,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00045,0.022,0.45,0.44,0.0096,9.4,10,0.04,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32290000,0.78,-0.0037,0.001,-0.63,0.53,0.87,0.77,8.9,7.5,-3.7e+02,-0.0007,-0.0058,3.4e-05,-0.034,0.089,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00046,0.021,0.44,0.44,0.0072,9.4,10,0.036,6.3e-07,6.4e-07,5.1e-06,0.03,0.027,9.5e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32390000,0.77,-0.0062,0.0018,-0.63,0.53,0.88,0.73,9.1,7.7,-3.7e+02,-0.00072,-0.0058,1.1e-05,-0.017,0.05,-0.098,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00046,0.022,0.46,0.46,0.0097,9.8,11,0.04,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32390000,0.78,-0.0043,0.0012,-0.63,0.49,0.85,0.77,9,7.6,-3.7e+02,-0.0007,-0.0058,3.4e-05,-0.035,0.091,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00046,0.021,0.46,0.45,0.0072,9.8,11,0.036,6.4e-07,6.4e-07,5.1e-06,0.03,0.027,9.5e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32490000,0.77,-0.0065,0.0019,-0.63,0.49,0.86,0.73,9.2,7.8,-3.7e+02,-0.00072,-0.0058,1e-05,-0.018,0.052,-0.098,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00046,0.022,0.47,0.47,0.0096,10,11,0.04,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32490000,0.78,-0.0044,0.0012,-0.63,0.45,0.83,0.78,9,7.7,-3.7e+02,-0.0007,-0.0058,3.5e-05,-0.036,0.095,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00046,0.021,0.47,0.47,0.0071,10,11,0.036,6.4e-07,6.4e-07,5.1e-06,0.03,0.027,9.4e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32590000,0.77,-0.0068,0.0019,-0.63,-1.6,-0.84,0.64,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,1e-05,-0.018,0.052,-0.098,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00046,0.022,0.25,0.25,0.56,0.25,0.25,0.042,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32590000,0.78,-0.0047,0.0013,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0007,-0.0058,3.5e-05,-0.037,0.096,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00047,0.021,0.25,0.25,0.56,0.25,0.25,0.038,6.4e-07,6.4e-07,5.1e-06,0.03,0.027,9.3e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32690000,0.77,-0.0069,0.002,-0.63,-1.6,-0.86,0.63,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,1e-05,-0.019,0.053,-0.098,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00046,0.022,0.25,0.25,0.55,0.26,0.26,0.052,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32690000,0.78,-0.0047,0.0013,-0.63,-1.6,-0.86,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0007,-0.0058,3.5e-05,-0.038,0.098,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00047,0.021,0.25,0.25,0.55,0.26,0.26,0.049,6.4e-07,6.4e-07,5.1e-06,0.03,0.027,9.3e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32790000,0.77,-0.0068,0.002,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,8.9e-06,-0.019,0.054,-0.097,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00047,0.022,0.13,0.13,0.27,0.26,0.26,0.052,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32790000,0.78,-0.0046,0.0013,-0.63,-1.6,-0.84,0.62,-1e+06,1.2e+04,-3.7e+02,-0.00071,-0.0058,3.5e-05,-0.038,0.1,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00047,0.021,0.13,0.13,0.27,0.26,0.26,0.049,6.4e-07,6.4e-07,5.1e-06,0.03,0.027,9.2e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32890000,0.77,-0.0068,0.0019,-0.63,-1.6,-0.85,0.62,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,8.7e-06,-0.019,0.055,-0.097,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00047,0.022,0.13,0.13,0.26,0.27,0.27,0.061,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32890000,0.78,-0.0045,0.0012,-0.63,-1.6,-0.85,0.6,-1e+06,1.2e+04,-3.7e+02,-0.00071,-0.0058,3.5e-05,-0.039,0.1,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00047,0.021,0.13,0.13,0.26,0.27,0.27,0.059,6.4e-07,6.4e-07,5.1e-06,0.03,0.026,9.2e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
32990000,0.78,-0.0068,0.0018,-0.63,-1.6,-0.84,0.62,-1e+06,1.2e+04,-3.7e+02,-0.00074,-0.0058,6.7e-06,-0.02,0.056,-0.097,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00047,0.022,0.085,0.085,0.17,0.27,0.27,0.059,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
32990000,0.78,-0.0044,0.0011,-0.63,-1.6,-0.85,0.6,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,3.4e-05,-0.04,0.1,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00047,0.021,0.085,0.085,0.17,0.27,0.27,0.057,6.4e-07,6.4e-07,5.1e-06,0.03,0.026,9.2e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
33090000,0.78,-0.0068,0.0019,-0.63,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.00074,-0.0058,6.6e-06,-0.02,0.056,-0.097,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00043,0.00047,0.022,0.086,0.086,0.16,0.28,0.28,0.067,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
33090000,0.78,-0.0044,0.0011,-0.63,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,3.4e-05,-0.04,0.11,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00047,0.021,0.086,0.086,0.16,0.28,0.28,0.065,6.4e-07,6.4e-07,5.1e-06,0.03,0.026,9.2e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
33190000,0.78,-0.0054,-0.0014,-0.63,-1.6,-0.85,0.55,-1e+06,1.2e+04,-3.7e+02,-0.00077,-0.0058,1e-06,-0.02,0.056,-0.097,-0.15,-0.032,0.47,4e-05,-0.051,-0.031,0,0,0.00044,0.00047,0.022,0.065,0.065,0.11,0.28,0.28,0.063,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0,0,0,0,0,0,0,0
|
33190000,0.78,-0.0029,-0.0022,-0.63,-1.6,-0.85,0.53,-1e+06,1.2e+04,-3.7e+02,-0.00075,-0.0058,2.9e-05,-0.04,0.11,-0.11,-0.15,-0.033,0.47,0.00021,-0.051,-0.032,0,0,0.00042,0.00047,0.021,0.065,0.065,0.11,0.28,0.28,0.062,6.4e-07,6.4e-07,5.1e-06,0.03,0.026,9.1e-05,0.00065,4.2e-05,0.00066,2.1e-05,0.00068,0.00066,1,1
|
||||||
33290000,0.82,-0.0031,-0.013,-0.57,-1.6,-0.87,0.54,-1e+06,1.2e+04,-3.7e+02,-0.00077,-0.0058,1e-06,-0.02,0.056,-0.097,-0.15,-0.032,0.47,-8.3e-05,-0.052,-0.033,0,0,0.00045,0.00047,0.022,0.066,0.067,0.11,0.29,0.29,0.068,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0.0004,3e-05,0.00041,2e-05,0.00042,0.00041,0,0
|
33290000,0.82,-0.00069,-0.014,-0.57,-1.6,-0.87,0.51,-1e+06,1.2e+04,-3.7e+02,-0.00076,-0.0058,2.9e-05,-0.041,0.11,-0.11,-0.15,-0.033,0.47,0.00012,-0.05,-0.032,0,0,0.00043,0.00047,0.021,0.066,0.067,0.11,0.29,0.29,0.067,6.4e-07,6.4e-07,5.1e-06,0.03,0.026,9.1e-05,0.00064,4.2e-05,0.00066,2.1e-05,0.00067,0.00066,1,1
|
||||||
33390000,0.89,-0.0031,-0.011,-0.46,-1.5,-0.86,0.74,-1e+06,1.2e+04,-3.7e+02,-0.00081,-0.0058,-4.8e-06,-0.02,0.057,-0.097,-0.15,-0.033,0.47,-0.00059,-0.049,-0.032,0,0,0.00045,0.00047,0.022,0.053,0.054,0.083,0.29,0.29,0.066,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0.00035,2.8e-05,0.00037,1.9e-05,0.00036,0.00037,0,0
|
33390000,0.89,-0.00079,-0.012,-0.46,-1.5,-0.86,0.71,-1e+06,1.2e+04,-3.7e+02,-0.00079,-0.0058,2.5e-05,-0.041,0.11,-0.11,-0.16,-0.034,0.47,-0.00012,-0.045,-0.031,0,0,0.00043,0.00048,0.021,0.053,0.054,0.083,0.29,0.29,0.065,6.4e-07,6.4e-07,5.1e-06,0.03,0.026,9.1e-05,0.00057,3.8e-05,0.00066,2e-05,0.00059,0.00066,1,1
|
||||||
33490000,0.95,-0.0009,-0.0037,-0.31,-1.6,-0.87,0.75,-1e+06,1.2e+04,-3.7e+02,-0.00081,-0.0058,-4.9e-06,-0.02,0.057,-0.097,-0.16,-0.034,0.47,-0.0015,-0.039,-0.031,0,0,0.00044,0.00048,0.022,0.055,0.056,0.076,0.3,0.3,0.068,6.4e-07,6.4e-07,6.4e-06,0.03,0.028,0.0005,0.00027,2.5e-05,0.00036,1.9e-05,0.00028,0.00036,0,0
|
33490000,0.95,0.0011,-0.0053,-0.31,-1.6,-0.88,0.73,-1e+06,1.2e+04,-3.7e+02,-0.00079,-0.0058,2.5e-05,-0.041,0.11,-0.11,-0.17,-0.038,0.47,-0.00055,-0.03,-0.032,0,0,0.00043,0.00048,0.021,0.055,0.056,0.075,0.3,0.3,0.068,6.4e-07,6.4e-07,5.1e-06,0.03,0.026,9.1e-05,0.00038,2.9e-05,0.00065,2e-05,0.00039,0.00066,1,1
|
||||||
33590000,0.99,-0.003,0.0018,-0.15,-1.5,-0.84,0.71,-1e+06,1.2e+04,-3.7e+02,-0.00086,-0.0059,-1e-05,-0.02,0.057,-0.097,-0.18,-0.036,0.47,-0.0019,-0.027,-0.032,0,0,0.00046,0.00047,0.022,0.047,0.048,0.062,0.3,0.3,0.065,6.3e-07,6.3e-07,6.4e-06,0.03,0.028,0.0005,0.00019,2.2e-05,0.00035,1.9e-05,0.0002,0.00035,0,0
|
33590000,0.99,-0.0013,4.4e-05,-0.15,-1.5,-0.85,0.69,-1e+06,1.2e+04,-3.7e+02,-0.00084,-0.0058,2.3e-05,-0.041,0.11,-0.11,-0.18,-0.041,0.47,-0.00072,-0.017,-0.032,0,0,0.00045,0.00047,0.021,0.047,0.048,0.061,0.3,0.3,0.065,6.3e-07,6.4e-07,5.1e-06,0.03,0.026,9.1e-05,0.00021,2.1e-05,0.00065,1.9e-05,0.00022,0.00065,1,1
|
||||||
33690000,1,-0.0052,0.0075,0.039,-1.6,-0.87,0.72,-1e+06,1.2e+04,-3.7e+02,-0.00078,-0.0059,-0.00033,-0.02,0.057,-0.097,-0.18,-0.038,0.47,-0.002,-0.022,-0.032,0,0,0.00047,0.00038,0.011,0.049,0.052,0.057,0.31,0.31,0.068,6e-07,6.3e-07,5.8e-06,0.03,0.028,0.0005,0.00014,1.9e-05,0.00035,1.9e-05,0.00016,0.00035,0,0
|
33690000,1,-0.0045,0.0029,0.019,-1.6,-0.87,0.7,-1e+06,1.2e+04,-3.7e+02,-0.00084,-0.0058,2.3e-05,-0.041,0.11,-0.11,-0.19,-0.042,0.47,-0.0009,-0.011,-0.033,0,0,0.00049,0.00046,0.021,0.05,0.052,0.056,0.31,0.31,0.068,6.3e-07,6.4e-07,5.1e-06,0.03,0.026,9.1e-05,0.00013,1.6e-05,0.00065,1.9e-05,0.00013,0.00065,1,1
|
||||||
33790000,0.98,-0.0056,0.0098,0.21,-1.6,-0.87,0.7,-1e+06,1.2e+04,-3.7e+02,-0.00078,-0.0059,-0.00035,-0.02,0.057,-0.097,-0.19,-0.039,0.47,-0.002,-0.018,-0.032,0,0,0.00048,0.00032,0.0078,0.043,0.047,0.047,0.31,0.31,0.064,5.8e-07,6.2e-07,5.6e-06,0.03,0.028,0.0005,0.00011,1.7e-05,0.00034,1.8e-05,0.00013,0.00034,0,0
|
33790000,0.98,-0.0054,0.0036,0.19,-1.6,-0.87,0.69,-1e+06,1.2e+04,-3.7e+02,-0.00091,-0.0059,2.7e-05,-0.041,0.11,-0.11,-0.19,-0.043,0.47,-0.00094,-0.0069,-0.034,0,0,0.0005,0.00044,0.021,0.046,0.048,0.047,0.31,0.31,0.064,6.2e-07,6.3e-07,5.1e-06,0.03,0.026,9.1e-05,7.7e-05,1.3e-05,0.00065,1.8e-05,8e-05,0.00065,1,1
|
||||||
33890000,0.93,-0.0053,0.011,0.37,-1.7,-0.91,0.69,-1e+06,1.2e+04,-3.7e+02,-0.00074,-0.0059,-0.0003,-0.02,0.057,-0.097,-0.19,-0.04,0.47,-0.0018,-0.015,-0.032,0,0,0.00047,0.00032,0.0065,0.046,0.053,0.043,0.32,0.32,0.065,5.8e-07,6.2e-07,5.5e-06,0.03,0.028,0.0005,9.1e-05,1.5e-05,0.00034,1.8e-05,0.00011,0.00034,0,0
|
33890000,0.94,-0.0063,0.0044,0.35,-1.6,-0.91,0.67,-1e+06,1.2e+04,-3.7e+02,-0.00092,-0.0059,2.7e-05,-0.041,0.11,-0.11,-0.2,-0.043,0.47,-0.00092,-0.0049,-0.034,0,0,0.00052,0.00044,0.021,0.052,0.055,0.043,0.32,0.32,0.065,6.3e-07,6.3e-07,5.1e-06,0.03,0.026,9.1e-05,5.2e-05,1.1e-05,0.00065,1.6e-05,5.3e-05,0.00065,1,1
|
||||||
33990000,0.87,-0.0077,0.0098,0.5,-1.8,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-0.00019,-0.02,0.057,-0.097,-0.19,-0.041,0.47,-0.0015,-0.011,-0.032,0,0,0.00042,0.00035,0.0056,0.05,0.059,0.04,0.33,0.33,0.065,5.8e-07,6.2e-07,5.5e-06,0.03,0.028,0.0005,7.6e-05,1.4e-05,0.00034,1.8e-05,8.9e-05,0.00034,0,0
|
33990000,0.87,-0.0083,0.00065,0.49,-1.6,-0.91,0.65,-1e+06,1.2e+04,-3.7e+02,-0.001,-0.0059,4e-05,-0.041,0.11,-0.11,-0.2,-0.044,0.47,-0.0011,-0.0032,-0.034,0,0,0.00048,0.00043,0.02,0.05,0.054,0.036,0.32,0.32,0.062,6.1e-07,6.2e-07,5e-06,0.03,0.026,9.1e-05,3.7e-05,1e-05,0.00065,1.5e-05,3.8e-05,0.00065,1,1
|
||||||
34090000,0.8,-0.0085,0.0082,0.59,-1.8,-1,0.67,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-0.00011,-0.02,0.057,-0.097,-0.19,-0.041,0.47,-0.0013,-0.0086,-0.032,0,0,0.00038,0.00038,0.005,0.055,0.067,0.036,0.34,0.34,0.066,5.8e-07,6.2e-07,5.5e-06,0.03,0.028,0.0005,6.7e-05,1.3e-05,0.00034,1.8e-05,7.4e-05,0.00034,0,0
|
34090000,0.81,-0.0099,-0.00092,0.59,-1.6,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.001,-0.0059,4e-05,-0.041,0.11,-0.11,-0.2,-0.044,0.47,-0.0013,-0.0022,-0.034,0,0,0.00047,0.00044,0.02,0.059,0.064,0.034,0.33,0.33,0.063,6.2e-07,6.2e-07,5e-06,0.03,0.026,9.1e-05,2.9e-05,9.2e-06,0.00065,1.4e-05,2.9e-05,0.00065,1,1
|
||||||
34190000,0.75,-0.0066,0.0084,0.66,-1.9,-1.1,0.68,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-6.6e-05,-0.02,0.057,-0.097,-0.2,-0.041,0.47,-0.0011,-0.0069,-0.032,0,0,0.00035,0.00041,0.0045,0.061,0.076,0.033,0.35,0.36,0.066,5.8e-07,6.2e-07,5.4e-06,0.03,0.028,0.0005,6.1e-05,1.3e-05,0.00034,1.7e-05,6.2e-05,0.00034,0,0
|
34190000,0.76,-0.0074,-0.0036,0.65,-1.6,-0.95,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0011,-0.006,5.9e-05,-0.077,0.13,-0.11,-0.2,-0.045,0.47,-0.0014,-0.0012,-0.034,0,0,0.00042,0.00041,0.02,0.057,0.062,0.029,0.33,0.33,0.06,6e-07,6e-07,5e-06,0.028,0.025,9.1e-05,2.3e-05,8.4e-06,0.00065,1.3e-05,2.3e-05,0.00065,1,1
|
||||||
34290000,0.72,-0.0036,0.0094,0.69,-1.9,-1.2,0.68,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-3.5e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00085,-0.0057,-0.032,0,0,0.00033,0.00043,0.0041,0.068,0.087,0.03,0.37,0.37,0.065,5.7e-07,6.2e-07,5.4e-06,0.03,0.028,0.0005,5.7e-05,1.2e-05,0.00034,1.7e-05,5.4e-05,0.00034,0,0
|
34290000,0.72,-0.0049,-0.0025,0.69,-1.6,-0.99,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0011,-0.006,5.9e-05,-0.077,0.13,-0.11,-0.2,-0.045,0.47,-0.0015,-0.00051,-0.034,0,0,0.00041,0.00042,0.02,0.068,0.075,0.027,0.34,0.34,0.06,6e-07,6.1e-07,5e-06,0.028,0.025,9.1e-05,1.9e-05,7.8e-06,0.00065,1.2e-05,1.9e-05,0.00065,1,1
|
||||||
34390000,0.7,-0.0007,0.011,0.72,-2,-1.2,0.68,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-1.1e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.0007,-0.0049,-0.032,0,0,0.00031,0.00045,0.0039,0.076,0.1,0.028,0.38,0.39,0.065,5.8e-07,6.2e-07,5.4e-06,0.03,0.028,0.0005,5.5e-05,1.2e-05,0.00034,1.6e-05,4.9e-05,0.00034,0,0
|
34390000,0.7,-0.0011,-0.0052,0.72,-1.5,-0.93,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,9.1e-05,-0.12,0.16,-0.11,-0.2,-0.045,0.47,-0.0017,0.00017,-0.034,0,0,0.00036,0.00037,0.02,0.064,0.069,0.024,0.34,0.34,0.059,5.9e-07,5.9e-07,5e-06,0.026,0.023,9.1e-05,1.6e-05,7.3e-06,0.00065,1.1e-05,1.6e-05,0.00065,1,1
|
||||||
34490000,0.68,0.0014,0.012,0.73,-2.1,-1.3,0.68,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,3.8e-06,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00063,-0.0045,-0.032,0,0,0.0003,0.00046,0.0037,0.085,0.11,0.026,0.4,0.41,0.064,5.8e-07,6.3e-07,5.4e-06,0.03,0.028,0.0005,5.2e-05,1.2e-05,0.00034,1.6e-05,4.4e-05,0.00034,0,0
|
34490000,0.68,0.00076,-0.0041,0.73,-1.5,-0.95,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,9.1e-05,-0.12,0.16,-0.11,-0.2,-0.046,0.47,-0.002,0.00057,-0.034,0,0,0.00035,0.00037,0.02,0.077,0.083,0.022,0.35,0.35,0.058,5.9e-07,5.9e-07,5e-06,0.026,0.023,9.1e-05,1.4e-05,6.9e-06,0.00065,1.1e-05,1.4e-05,0.00065,1,1
|
||||||
34590000,0.67,0.0027,0.012,0.74,-2.1,-1.3,0.68,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,2.2e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00058,-0.0041,-0.032,0,0,0.0003,0.00047,0.0036,0.095,0.13,0.024,0.42,0.43,0.062,5.8e-07,6.3e-07,5.4e-06,0.03,0.028,0.0005,5.1e-05,1.2e-05,0.00033,1.6e-05,4.1e-05,0.00034,0,0
|
34590000,0.67,0.0027,-0.0069,0.74,-1.5,-0.87,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0013,-0.0061,0.00012,-0.17,0.19,-0.11,-0.2,-0.046,0.47,-0.0023,0.001,-0.034,0,0,0.0003,0.00031,0.019,0.07,0.074,0.019,0.35,0.35,0.056,5.8e-07,5.8e-07,5e-06,0.022,0.02,9e-05,1.3e-05,6.5e-06,0.00065,1e-05,1.2e-05,0.00065,1,1
|
||||||
34690000,0.67,0.0034,0.013,0.74,-2.2,-1.4,0.69,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,2.2e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00044,-0.0037,-0.032,0,0,0.00029,0.00047,0.0035,0.11,0.15,0.022,0.44,0.46,0.062,5.8e-07,6.3e-07,5.4e-06,0.03,0.028,0.0005,5e-05,1.2e-05,0.00033,1.6e-05,3.9e-05,0.00034,0,0
|
34690000,0.67,0.0033,-0.0065,0.75,-1.5,-0.89,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0013,-0.0061,0.00012,-0.17,0.19,-0.11,-0.2,-0.046,0.47,-0.0024,0.0016,-0.034,0,0,0.0003,0.00031,0.019,0.082,0.088,0.018,0.36,0.36,0.056,5.8e-07,5.8e-07,5e-06,0.022,0.02,9e-05,1.2e-05,6.2e-06,0.00065,9.7e-06,1.1e-05,0.00065,1,1
|
||||||
34790000,0.66,0.004,0.013,0.75,-2.2,-1.4,0.69,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,1.1e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00034,-0.0036,-0.033,0,0,0.00029,0.00047,0.0034,0.12,0.17,0.02,0.47,0.49,0.061,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.9e-05,1.1e-05,0.00033,1.5e-05,3.7e-05,0.00034,0,0
|
34790000,0.66,0.0041,-0.0099,0.75,-1.4,-0.8,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0061,0.00014,-0.2,0.23,-0.11,-0.2,-0.047,0.47,-0.0026,0.0021,-0.033,0,0,0.00025,0.00025,0.019,0.073,0.077,0.016,0.36,0.36,0.054,5.7e-07,5.8e-07,4.9e-06,0.019,0.018,9e-05,1.1e-05,6e-06,0.00065,9.2e-06,1e-05,0.00065,1,1
|
||||||
34890000,0.66,0.0041,0.013,0.75,-2.3,-1.5,0.69,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,2e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00033,-0.0035,-0.033,0,0,0.00029,0.00047,0.0034,0.13,0.19,0.019,0.5,0.52,0.059,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.8e-05,1.1e-05,0.00033,1.5e-05,3.6e-05,0.00033,0,0
|
34890000,0.66,0.0042,-0.0099,0.75,-1.4,-0.8,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0061,0.00014,-0.2,0.23,-0.11,-0.2,-0.047,0.47,-0.0029,0.0024,-0.033,0,0,0.00025,0.00025,0.019,0.085,0.09,0.015,0.37,0.37,0.053,5.7e-07,5.8e-07,5e-06,0.019,0.018,9e-05,9.7e-06,5.7e-06,0.00064,8.8e-06,9.6e-06,0.00064,1,1
|
||||||
34990000,0.66,0.00072,0.02,0.75,-3.3,-2.4,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,5.3e-06,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00028,-0.0035,-0.032,0,0,0.00029,0.00049,0.0033,0.16,0.25,0.018,0.53,0.57,0.059,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.7e-05,1.1e-05,0.00033,1.5e-05,3.5e-05,0.00033,0,0
|
34990000,0.66,0.00075,-0.0051,0.75,-2.2,-1.5,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.047,0.47,-0.0031,0.0027,-0.033,0,0,0.0002,0.00021,0.019,0.096,0.11,0.014,0.37,0.37,0.052,5.6e-07,5.7e-07,4.9e-06,0.017,0.016,8.9e-05,9.1e-06,5.5e-06,0.00064,8.5e-06,9e-06,0.00064,1,1
|
||||||
35090000,0.66,0.00065,0.02,0.75,-3.4,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,3.5e-06,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00027,-0.0035,-0.032,0,0,0.00028,0.00048,0.0033,0.17,0.28,0.017,0.57,0.62,0.057,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.7e-05,1.1e-05,0.00033,1.5e-05,3.4e-05,0.00033,0,0
|
35090000,0.66,0.00069,-0.0051,0.75,-2.3,-1.5,-0.24,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.047,0.47,-0.0033,0.003,-0.033,0,0,0.0002,0.00021,0.019,0.11,0.12,0.013,0.38,0.38,0.051,5.7e-07,5.7e-07,4.9e-06,0.017,0.016,8.9e-05,8.6e-06,5.3e-06,0.00064,8.2e-06,8.4e-06,0.00064,1,1
|
||||||
35190000,0.66,0.00052,0.02,0.75,-3.4,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-2e-06,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00022,-0.0034,-0.032,0,0,0.00028,0.00048,0.0032,0.19,0.3,0.016,0.61,0.67,0.056,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.6e-05,1.1e-05,0.00033,1.5e-05,3.3e-05,0.00033,0,0
|
35190000,0.66,0.00063,-0.0051,0.75,-2.3,-1.5,-0.24,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.0035,0.0033,-0.033,0,0,0.0002,0.00021,0.019,0.12,0.14,0.013,0.39,0.4,0.05,5.7e-07,5.7e-07,4.9e-06,0.017,0.016,8.9e-05,8.1e-06,5.1e-06,0.00064,7.9e-06,7.9e-06,0.00064,1,1
|
||||||
35290000,0.66,0.0004,0.02,0.75,-3.5,-2.6,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-1e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00019,-0.0033,-0.032,0,0,0.00028,0.00048,0.0032,0.2,0.32,0.015,0.65,0.74,0.055,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.6e-05,1.1e-05,0.00033,1.5e-05,3.2e-05,0.00033,0,0
|
35290000,0.66,0.00054,-0.0051,0.75,-2.2,-1.5,-0.23,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.0036,0.0035,-0.032,0,0,0.0002,0.00021,0.019,0.14,0.15,0.012,0.41,0.41,0.049,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,8.9e-05,7.7e-06,4.9e-06,0.00064,7.6e-06,7.5e-06,0.00064,1,1
|
||||||
35390000,0.66,0.00039,0.02,0.75,-3.5,-2.6,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-2.5e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00017,-0.0034,-0.032,0,0,0.00028,0.00048,0.0032,0.21,0.34,0.014,0.7,0.81,0.054,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.6e-05,1.1e-05,0.00033,1.5e-05,3.1e-05,0.00033,0,0
|
35390000,0.66,0.00053,-0.005,0.75,-2.2,-1.5,-0.22,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.0037,0.0037,-0.032,0,0,0.0002,0.00021,0.019,0.15,0.17,0.011,0.43,0.43,0.049,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,8.9e-05,7.3e-06,4.8e-06,0.00064,7.4e-06,7.2e-06,0.00064,1,1
|
||||||
35490000,0.66,0.00035,0.02,0.75,-3.5,-2.7,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-3.9e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00015,-0.0035,-0.032,0,0,0.00028,0.00048,0.0032,0.22,0.37,0.013,0.76,0.89,0.053,5.8e-07,6.3e-07,5.3e-06,0.03,0.028,0.0005,4.5e-05,1.1e-05,0.00033,1.5e-05,3.1e-05,0.00033,0,0
|
35490000,0.66,0.0005,-0.005,0.75,-2.2,-1.5,-0.21,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.0038,0.0038,-0.032,0,0,0.0002,0.00021,0.019,0.17,0.18,0.011,0.45,0.46,0.048,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,8.9e-05,7e-06,4.7e-06,0.00064,7.1e-06,6.8e-06,0.00064,1,1
|
||||||
35590000,0.66,0.00029,0.02,0.75,-3.6,-2.7,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-3.1e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00014,-0.0034,-0.032,0,0,0.00028,0.00048,0.0031,0.24,0.39,0.013,0.82,0.98,0.052,5.8e-07,6.4e-07,5.3e-06,0.03,0.028,0.0005,4.5e-05,1.1e-05,0.00033,1.5e-05,3e-05,0.00033,0,0
|
35590000,0.66,0.00047,-0.005,0.75,-2.2,-1.5,-0.21,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.004,0.004,-0.032,0,0,0.0002,0.0002,0.019,0.18,0.2,0.01,0.48,0.49,0.047,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,8.9e-05,6.7e-06,4.5e-06,0.00064,6.9e-06,6.6e-06,0.00064,1,1
|
||||||
35690000,0.66,0.00031,0.021,0.75,-3.6,-2.8,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-4.5e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-0.00011,-0.0034,-0.032,0,0,0.00028,0.00047,0.0031,0.25,0.41,0.012,0.89,1.1,0.051,5.8e-07,6.4e-07,5.3e-06,0.03,0.028,0.0005,4.5e-05,1.1e-05,0.00033,1.5e-05,3e-05,0.00033,0,0
|
35690000,0.66,0.00049,-0.005,0.75,-2.2,-1.5,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.0041,0.0041,-0.032,0,0,0.0002,0.0002,0.019,0.2,0.22,0.0096,0.51,0.52,0.047,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,8.9e-05,6.5e-06,4.4e-06,0.00064,6.7e-06,6.3e-06,0.00064,1,1
|
||||||
35790000,0.66,0.00025,0.021,0.75,-3.7,-2.8,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-4.9e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-9.8e-05,-0.0034,-0.032,0,0,0.00028,0.00047,0.0031,0.27,0.44,0.012,0.96,1.2,0.05,5.8e-07,6.4e-07,5.3e-06,0.03,0.028,0.0005,4.4e-05,1.1e-05,0.00033,1.5e-05,3e-05,0.00033,0,0
|
35790000,0.66,0.00045,-0.0049,0.75,-2.2,-1.5,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.0042,0.0043,-0.032,0,0,0.0002,0.0002,0.019,0.22,0.24,0.0091,0.55,0.56,0.046,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,9e-05,6.3e-06,4.3e-06,0.00064,6.6e-06,6.1e-06,0.00064,1,1
|
||||||
35890000,0.66,0.00015,0.021,0.75,-3.7,-2.9,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-5.1e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-8.9e-05,-0.0034,-0.032,0,0,0.00027,0.00047,0.0031,0.29,0.47,0.011,1,1.3,0.049,5.8e-07,6.4e-07,5.3e-06,0.03,0.028,0.0005,4.4e-05,1e-05,0.00033,1.5e-05,2.9e-05,0.00033,0,0
|
35890000,0.66,0.00038,-0.0049,0.75,-2.2,-1.4,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.048,0.47,-0.0043,0.0044,-0.032,0,0,0.0002,0.0002,0.019,0.24,0.26,0.0087,0.59,0.6,0.045,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,9e-05,6e-06,4.2e-06,0.00064,6.4e-06,5.9e-06,0.00064,1,1
|
||||||
35990000,0.66,0.00012,0.02,0.75,-3.7,-2.9,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-4.4e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-9e-05,-0.0034,-0.032,0,0,0.00027,0.00047,0.0031,0.3,0.5,0.011,1.1,1.5,0.048,5.9e-07,6.4e-07,5.3e-06,0.03,0.028,0.0005,4.4e-05,1e-05,0.00033,1.5e-05,2.9e-05,0.00033,0,0
|
35990000,0.66,0.00037,-0.0049,0.75,-2.2,-1.4,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.049,0.47,-0.0044,0.0045,-0.032,0,0,0.0002,0.0002,0.019,0.26,0.28,0.0084,0.64,0.66,0.045,5.7e-07,5.8e-07,4.9e-06,0.017,0.016,9e-05,5.9e-06,4.1e-06,0.00064,6.2e-06,5.7e-06,0.00064,1,1
|
||||||
36090000,0.66,8e-05,0.021,0.75,-3.8,-3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-5.3e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-8e-05,-0.0034,-0.032,0,0,0.00027,0.00047,0.003,0.32,0.53,0.01,1.2,1.6,0.047,5.9e-07,6.4e-07,5.3e-06,0.03,0.028,0.0005,4.4e-05,1e-05,0.00033,1.5e-05,2.9e-05,0.00033,0,0
|
36090000,0.66,0.00036,-0.0048,0.75,-2.2,-1.4,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00016,-0.23,0.26,-0.11,-0.2,-0.049,0.46,-0.0045,0.0045,-0.032,0,0,0.0002,0.0002,0.019,0.29,0.31,0.008,0.69,0.72,0.044,5.8e-07,5.8e-07,4.9e-06,0.017,0.016,9e-05,5.7e-06,4.1e-06,0.00064,6.1e-06,5.5e-06,0.00064,1,1
|
||||||
36190000,0.66,2.6e-05,0.021,0.75,-3.8,-3,-0.096,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-8.1e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-5.3e-05,-0.0034,-0.032,0,0,0.00027,0.00047,0.003,0.34,0.56,0.0099,1.3,1.8,0.046,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.3e-05,1e-05,0.00033,1.4e-05,2.8e-05,0.00033,0,0
|
36190000,0.66,0.00033,-0.0048,0.75,-2.1,-1.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.23,0.26,-0.11,-0.2,-0.049,0.46,-0.0045,0.0046,-0.032,0,0,0.0002,0.0002,0.019,0.31,0.33,0.0077,0.76,0.78,0.043,5.8e-07,5.8e-07,4.9e-06,0.017,0.016,9e-05,5.5e-06,4e-06,0.00064,6e-06,5.4e-06,0.00064,1,1
|
||||||
36290000,0.66,2.8e-05,0.021,0.75,-3.9,-3.1,-0.088,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-8.7e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-4.1e-05,-0.0034,-0.032,0,0,0.00027,0.00046,0.003,0.36,0.59,0.0097,1.4,1.9,0.046,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.3e-05,1e-05,0.00033,1.4e-05,2.8e-05,0.00033,0,0
|
36290000,0.66,0.00034,-0.0047,0.75,-2.1,-1.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.2,-0.049,0.46,-0.0046,0.0047,-0.032,0,0,0.00019,0.0002,0.019,0.34,0.36,0.0075,0.83,0.86,0.043,5.8e-07,5.9e-07,5e-06,0.017,0.016,9e-05,5.4e-06,3.9e-06,0.00064,5.8e-06,5.3e-06,0.00064,1,1
|
||||||
36390000,0.66,-5.5e-05,0.021,0.75,-3.9,-3.2,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-8.6e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-1.8e-05,-0.0034,-0.032,0,0,0.00027,0.00046,0.003,0.38,0.62,0.0094,1.6,2.1,0.045,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.3e-05,1e-05,0.00033,1.4e-05,2.8e-05,0.00033,0,0
|
36390000,0.66,0.0003,-0.0047,0.75,-2.1,-1.4,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.2,-0.049,0.46,-0.0047,0.0048,-0.032,0,0,0.00019,0.0002,0.02,0.36,0.39,0.0072,0.91,0.95,0.042,5.8e-07,5.9e-07,5e-06,0.017,0.016,9e-05,5.3e-06,3.8e-06,0.00064,5.7e-06,5.1e-06,0.00064,1,1
|
||||||
36490000,0.66,-0.00014,0.021,0.75,-3.9,-3.2,-0.078,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0059,-7.6e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,-1.4e-05,-0.0033,-0.032,0,0,0.00027,0.00046,0.003,0.41,0.66,0.0092,1.7,2.3,0.044,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.3e-05,1e-05,0.00033,1.4e-05,2.8e-05,0.00033,0,0
|
36490000,0.66,0.00025,-0.0046,0.75,-2.1,-1.4,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.2,-0.049,0.46,-0.0048,0.0049,-0.032,0,0,0.00019,0.0002,0.02,0.39,0.42,0.0069,1,1,0.041,5.8e-07,5.9e-07,5e-06,0.017,0.016,9e-05,5.2e-06,3.8e-06,0.00064,5.6e-06,5e-06,0.00064,1,1
|
||||||
36590000,0.66,-0.00016,0.021,0.75,-4,-3.3,-0.069,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0059,-9.4e-05,-0.02,0.057,-0.097,-0.2,-0.042,0.47,1.5e-05,-0.0033,-0.032,0,0,0.00027,0.00046,0.003,0.43,0.69,0.009,1.9,2.6,0.044,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.3e-05,1e-05,0.00033,1.4e-05,2.8e-05,0.00033,0,0
|
36590000,0.66,0.00026,-0.0045,0.75,-2.1,-1.4,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.2,-0.049,0.46,-0.0048,0.005,-0.032,0,0,0.00019,0.0002,0.02,0.42,0.45,0.0067,1.1,1.1,0.041,5.8e-07,5.9e-07,5e-06,0.017,0.016,9e-05,5e-06,3.7e-06,0.00064,5.5e-06,4.9e-06,0.00064,1,1
|
||||||
36690000,0.66,-0.00019,0.021,0.75,-4,-3.3,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,-0.00011,-0.02,0.057,-0.097,-0.2,-0.042,0.47,3.1e-05,-0.0033,-0.032,0,0,0.00027,0.00046,0.003,0.46,0.73,0.0089,2,2.8,0.043,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.3e-05,1e-05,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
36690000,0.66,0.00027,-0.0045,0.75,-2.1,-1.4,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0049,0.0051,-0.032,0,0,0.00019,0.0002,0.02,0.45,0.48,0.0066,1.2,1.3,0.04,5.8e-07,5.9e-07,5e-06,0.017,0.016,9e-05,4.9e-06,3.6e-06,0.00064,5.4e-06,4.8e-06,0.00064,1,1
|
||||||
36790000,0.66,-0.00024,0.021,0.75,-4,-3.4,-0.055,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,-0.00013,-0.02,0.057,-0.097,-0.2,-0.042,0.47,3.2e-05,-0.0034,-0.032,0,0,0.00027,0.00046,0.003,0.48,0.77,0.0088,2.2,3.1,0.043,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.3e-05,9.9e-06,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
36790000,0.66,0.00024,-0.0044,0.75,-2.1,-1.4,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0049,0.0051,-0.032,0,0,0.00019,0.0002,0.02,0.48,0.51,0.0064,1.3,1.4,0.04,5.8e-07,5.9e-07,5e-06,0.017,0.016,9.1e-05,4.8e-06,3.6e-06,0.00064,5.3e-06,4.7e-06,0.00064,1,1
|
||||||
36890000,0.66,-0.00029,0.021,0.75,-4.1,-3.5,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,-0.00014,-0.02,0.057,-0.097,-0.2,-0.042,0.47,4.5e-05,-0.0034,-0.032,0,0,0.00027,0.00046,0.003,0.51,0.81,0.0087,2.4,3.4,0.042,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.2e-05,9.8e-06,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
36890000,0.66,0.00023,-0.0043,0.75,-2.1,-1.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0049,0.0051,-0.032,0,0,0.00019,0.0002,0.02,0.51,0.54,0.0062,1.5,1.6,0.039,5.8e-07,5.9e-07,5e-06,0.017,0.016,9.1e-05,4.7e-06,3.5e-06,0.00064,5.2e-06,4.6e-06,0.00064,1,1
|
||||||
36990000,0.66,-0.00028,0.021,0.75,-4.1,-3.5,-0.043,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,-0.00015,-0.02,0.057,-0.097,-0.2,-0.042,0.47,5.7e-05,-0.0034,-0.032,0,0,0.00026,0.00045,0.0029,0.54,0.85,0.0086,2.6,3.7,0.042,5.9e-07,6.4e-07,5.2e-06,0.03,0.028,0.0005,4.2e-05,9.8e-06,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
36990000,0.66,0.00027,-0.0043,0.75,-2.1,-1.4,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.005,0.0052,-0.032,0,0,0.00019,0.0002,0.02,0.55,0.58,0.0061,1.6,1.7,0.039,5.8e-07,5.9e-07,5e-06,0.017,0.016,9.1e-05,4.7e-06,3.5e-06,0.00064,5.1e-06,4.5e-06,0.00064,1,1
|
||||||
37090000,0.66,-0.0003,0.021,0.75,-4.2,-3.6,-0.036,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,-0.00016,-0.02,0.057,-0.097,-0.2,-0.042,0.47,7.6e-05,-0.0033,-0.032,0,0,0.00026,0.00045,0.0029,0.57,0.9,0.0086,2.8,4,0.041,5.9e-07,6.4e-07,5.1e-06,0.03,0.028,0.0005,4.2e-05,9.7e-06,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
37090000,0.66,0.00029,-0.0042,0.75,-2,-1.4,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.005,0.0053,-0.032,0,0,0.00019,0.0002,0.02,0.58,0.61,0.006,1.8,1.9,0.038,5.8e-07,5.9e-07,5e-06,0.017,0.016,9.1e-05,4.6e-06,3.4e-06,0.00064,5e-06,4.4e-06,0.00064,1,1
|
||||||
37190000,0.66,-0.00033,0.021,0.75,-4.2,-3.6,-0.029,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,-0.00016,-0.02,0.057,-0.097,-0.2,-0.042,0.47,8.3e-05,-0.0033,-0.032,0,0,0.00026,0.00045,0.0029,0.6,0.94,0.0085,3,4.4,0.041,5.9e-07,6.4e-07,5.1e-06,0.03,0.028,0.0005,4.2e-05,9.7e-06,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
37190000,0.66,0.00028,-0.0042,0.75,-2,-1.3,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0051,0.0053,-0.032,0,0,0.00019,0.0002,0.02,0.62,0.65,0.0059,2,2.1,0.038,5.9e-07,5.9e-07,5e-06,0.017,0.016,9.1e-05,4.5e-06,3.4e-06,0.00064,5e-06,4.4e-06,0.00064,1,1
|
||||||
37290000,0.66,-0.00042,0.021,0.75,-4.2,-3.7,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.00072,-0.0058,-0.00016,-0.02,0.057,-0.097,-0.2,-0.042,0.47,8.9e-05,-0.0033,-0.032,0,0,0.00026,0.00045,0.0029,0.63,0.98,0.0086,3.3,4.7,0.04,5.9e-07,6.4e-07,5.1e-06,0.03,0.028,0.0005,4.2e-05,9.6e-06,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
37290000,0.66,0.00023,-0.0041,0.75,-2,-1.3,-0.086,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0051,0.0053,-0.032,0,0,0.00019,0.0002,0.02,0.65,0.69,0.0058,2.2,2.3,0.037,5.9e-07,5.9e-07,5e-06,0.017,0.016,9.1e-05,4.4e-06,3.3e-06,0.00064,4.9e-06,4.3e-06,0.00064,1,1
|
||||||
37390000,0.66,-0.00039,0.021,0.76,-4.3,-3.7,-0.017,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00018,-0.02,0.057,-0.097,-0.2,-0.042,0.47,0.0001,-0.0033,-0.032,0,0,0.00026,0.00045,0.0029,0.66,1,0.0086,3.5,5.1,0.04,5.9e-07,6.4e-07,5.1e-06,0.03,0.028,0.0005,4.2e-05,9.6e-06,0.00033,1.4e-05,2.7e-05,0.00033,0,0
|
37390000,0.66,0.00027,-0.0041,0.75,-2,-1.3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0051,0.0054,-0.032,0,0,0.00019,0.0002,0.02,0.69,0.73,0.0057,2.4,2.5,0.037,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4.4e-06,3.3e-06,0.00064,4.8e-06,4.2e-06,0.00064,1,1
|
||||||
37490000,0.66,-0.00043,0.021,0.76,-4.3,-3.8,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.0002,-0.02,0.056,-0.097,-0.2,-0.042,0.47,0.00013,-0.0033,-0.032,0,0,0.00026,0.00045,0.0029,0.7,1.1,0.0086,3.8,5.6,0.039,5.9e-07,6.4e-07,5.1e-06,0.03,0.028,0.0005,4.2e-05,9.5e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
37490000,0.66,0.00026,-0.004,0.75,-2,-1.3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0015,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0051,0.0055,-0.032,0,0,0.00019,0.0002,0.02,0.73,0.77,0.0056,2.6,2.8,0.036,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4.3e-06,3.2e-06,0.00064,4.7e-06,4.2e-06,0.00064,1,1
|
||||||
37590000,0.65,-0.00045,0.021,0.76,-4.3,-3.9,-0.0036,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00021,-0.019,0.056,-0.097,-0.2,-0.042,0.47,0.00014,-0.0033,-0.032,0,0,0.00026,0.00044,0.0029,0.73,1.1,0.0087,4.1,6,0.039,5.9e-07,6.4e-07,5.1e-06,0.03,0.028,0.0005,4.1e-05,9.5e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
37590000,0.66,0.00027,-0.004,0.75,-2,-1.3,-0.065,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0051,0.0055,-0.032,0,0,0.00019,0.0002,0.02,0.77,0.81,0.0056,2.9,3.1,0.036,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4.2e-06,3.2e-06,0.00064,4.7e-06,4.1e-06,0.00064,1,1
|
||||||
37690000,0.65,-0.00056,0.022,0.76,-4.4,-3.9,0.0048,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00022,-0.019,0.056,-0.097,-0.2,-0.042,0.47,0.00014,-0.0033,-0.032,0,0,0.00026,0.00044,0.0029,0.77,1.2,0.0087,4.4,6.5,0.039,5.9e-07,6.4e-07,5e-06,0.03,0.028,0.0005,4.1e-05,9.4e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
37690000,0.66,0.00021,-0.0039,0.75,-2,-1.3,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0052,0.0055,-0.032,0,0,0.00019,0.0002,0.02,0.81,0.85,0.0055,3.2,3.4,0.036,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4.2e-06,3.2e-06,0.00064,4.6e-06,4e-06,0.00064,1,1
|
||||||
37790000,0.65,-0.00063,0.022,0.76,-4.4,-4,0.012,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00023,-0.019,0.056,-0.097,-0.2,-0.042,0.47,0.00015,-0.0033,-0.032,0,0,0.00026,0.00044,0.0029,0.8,1.2,0.0087,4.8,7,0.039,5.9e-07,6.4e-07,5e-06,0.03,0.028,0.0005,4.1e-05,9.3e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
37790000,0.66,0.00015,-0.0039,0.75,-2,-1.3,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0052,0.0056,-0.032,0,0,0.00019,0.0002,0.02,0.85,0.9,0.0055,3.5,3.7,0.035,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4.1e-06,3.1e-06,0.00064,4.6e-06,4e-06,0.00064,1,1
|
||||||
37890000,0.65,-0.00067,0.022,0.76,-4.5,-4,0.018,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00023,-0.019,0.056,-0.097,-0.2,-0.042,0.47,0.00015,-0.0033,-0.032,0,0,0.00026,0.00044,0.0029,0.84,1.3,0.0088,5.1,7.6,0.038,5.9e-07,6.4e-07,5e-06,0.03,0.028,0.0005,4.1e-05,9.3e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
37890000,0.66,0.00013,-0.0039,0.75,-2,-1.3,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0052,0.0056,-0.032,0,0,0.00019,0.0002,0.02,0.9,0.94,0.0054,3.8,4,0.035,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4.1e-06,3.1e-06,0.00064,4.5e-06,3.9e-06,0.00064,1,1
|
||||||
37990000,0.65,-0.00074,0.022,0.76,-4.5,-4.1,0.027,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00024,-0.019,0.056,-0.098,-0.2,-0.042,0.47,0.00015,-0.0033,-0.032,0,0,0.00026,0.00044,0.0028,0.88,1.3,0.0089,5.5,8.2,0.038,5.9e-07,6.4e-07,5e-06,0.03,0.028,0.0005,4.1e-05,9.2e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
37990000,0.66,7.6e-05,-0.0039,0.75,-1.9,-1.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0052,0.0056,-0.032,0,0,0.00019,0.0002,0.02,0.94,0.99,0.0054,4.2,4.4,0.035,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4e-06,3.1e-06,0.00064,4.5e-06,3.9e-06,0.00064,1,1
|
||||||
38090000,0.65,-0.00081,0.022,0.76,-4.5,-4.2,0.036,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00025,-0.019,0.055,-0.098,-0.2,-0.042,0.47,0.00017,-0.0033,-0.032,0,0,0.00026,0.00043,0.0028,0.92,1.4,0.009,5.9,8.8,0.038,5.9e-07,6.4e-07,5e-06,0.03,0.028,0.0005,4.1e-05,9.2e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
38090000,0.66,4.8e-05,-0.0038,0.75,-1.9,-1.3,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0053,0.0056,-0.032,0,0,0.00019,0.0002,0.02,0.99,1,0.0054,4.6,4.8,0.034,5.9e-07,6e-07,5e-06,0.017,0.016,9.1e-05,4e-06,3e-06,0.00064,4.4e-06,3.8e-06,0.00064,1,1
|
||||||
38190000,0.65,-0.00081,0.022,0.76,-4.6,-4.2,0.042,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00026,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.00017,-0.0033,-0.032,0,0,0.00026,0.00043,0.0028,0.96,1.4,0.009,6.4,9.4,0.038,5.9e-07,6.4e-07,4.9e-06,0.03,0.028,0.0005,4.1e-05,9.1e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
38190000,0.66,6e-05,-0.0038,0.75,-1.9,-1.3,-0.016,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0053,0.0057,-0.032,0,0,0.00019,0.0002,0.02,1,1.1,0.0053,5,5.3,0.034,6e-07,6e-07,5e-06,0.017,0.016,9.2e-05,3.9e-06,3e-06,0.00064,4.3e-06,3.8e-06,0.00064,1,1
|
||||||
38290000,0.65,-0.00085,0.022,0.76,-4.6,-4.3,0.049,-1e+06,1.2e+04,-3.7e+02,-0.00073,-0.0058,-0.00026,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.00017,-0.0033,-0.032,0,0,0.00026,0.00043,0.0028,1,1.5,0.0092,6.8,10,0.038,5.9e-07,6.4e-07,4.9e-06,0.03,0.028,0.0005,4.1e-05,9.1e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
38290000,0.66,3.8e-05,-0.0038,0.75,-1.9,-1.3,-0.0091,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0053,0.0057,-0.032,0,0,0.00019,0.0002,0.02,1.1,1.1,0.0053,5.4,5.7,0.034,6e-07,6e-07,5e-06,0.017,0.016,9.2e-05,3.9e-06,3e-06,0.00064,4.3e-06,3.8e-06,0.00064,1,1
|
||||||
38390000,0.65,-0.00084,0.022,0.76,-4.6,-4.3,0.055,-1e+06,1.2e+04,-3.7e+02,-0.00074,-0.0058,-0.00026,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.00018,-0.0032,-0.032,0,0,0.00025,0.00043,0.0028,1,1.5,0.0092,7.3,11,0.038,5.9e-07,6.4e-07,4.9e-06,0.03,0.028,0.0005,4.1e-05,9.1e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
38390000,0.66,5.4e-05,-0.0038,0.75,-1.9,-1.3,-0.0023,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0053,0.0057,-0.032,0,0,0.00019,0.0002,0.02,1.1,1.2,0.0053,5.9,6.2,0.034,6e-07,6.1e-07,5e-06,0.017,0.016,9.2e-05,3.9e-06,2.9e-06,0.00064,4.3e-06,3.7e-06,0.00064,1,1
|
||||||
38490000,0.65,-0.00087,0.022,0.76,-4.7,-4.4,0.06,-1e+06,1.2e+04,-3.7e+02,-0.00075,-0.0058,-0.00027,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.0002,-0.0032,-0.032,0,0,0.00025,0.00043,0.0028,1.1,1.6,0.0093,7.8,12,0.038,5.9e-07,6.4e-07,4.9e-06,0.03,0.028,0.0005,4e-05,9e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
38490000,0.66,3.3e-05,-0.0037,0.75,-1.9,-1.3,0.0042,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.049,0.46,-0.0053,0.0058,-0.032,0,0,0.00019,0.0002,0.02,1.2,1.2,0.0053,6.4,6.7,0.033,6e-07,6.1e-07,5e-06,0.017,0.016,9.2e-05,3.8e-06,2.9e-06,0.00064,4.2e-06,3.7e-06,0.00064,1,1
|
||||||
38590000,0.65,-0.00084,0.022,0.76,-4.7,-4.4,0.066,-1e+06,1.2e+04,-3.7e+02,-0.00075,-0.0058,-0.00026,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.0002,-0.0032,-0.032,0,0,0.00025,0.00042,0.0028,1.1,1.7,0.0094,8.4,12,0.038,5.9e-07,6.4e-07,4.9e-06,0.03,0.028,0.0005,4e-05,9e-06,0.00033,1.4e-05,2.6e-05,0.00033,0,0
|
38590000,0.66,7.4e-05,-0.0037,0.75,-1.9,-1.3,0.01,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.05,0.46,-0.0054,0.0058,-0.032,0,0,0.00019,0.0002,0.02,1.2,1.3,0.0053,6.9,7.3,0.033,6e-07,6.1e-07,5e-06,0.017,0.016,9.2e-05,3.8e-06,2.9e-06,0.00064,4.2e-06,3.6e-06,0.00064,1,1
|
||||||
38690000,0.65,-0.00089,0.022,0.76,-4.8,-4.5,0.071,-1e+06,1.2e+04,-3.7e+02,-0.00075,-0.0058,-0.00028,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.00022,-0.0032,-0.032,0,0,0.00025,0.00042,0.0028,1.2,1.7,0.0095,9,13,0.038,5.9e-07,6.4e-07,4.8e-06,0.03,0.028,0.0005,4e-05,8.9e-06,0.00033,1.4e-05,2.5e-05,0.00033,0,0
|
38690000,0.66,3.3e-05,-0.0036,0.75,-1.9,-1.3,0.017,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.05,0.46,-0.0054,0.0058,-0.032,0,0,0.00019,0.0002,0.02,1.3,1.3,0.0053,7.5,7.9,0.033,6e-07,6.1e-07,5e-06,0.017,0.016,9.2e-05,3.7e-06,2.9e-06,0.00064,4.1e-06,3.6e-06,0.00064,1,1
|
||||||
38790000,0.65,-0.00091,0.022,0.76,-4.8,-4.6,0.077,-1e+06,1.2e+04,-3.7e+02,-0.00076,-0.0058,-0.00029,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.00022,-0.0032,-0.032,0,0,0.00025,0.00042,0.0028,1.2,1.8,0.0096,9.6,14,0.038,5.9e-07,6.4e-07,4.8e-06,0.03,0.028,0.0005,4e-05,8.9e-06,0.00033,1.4e-05,2.5e-05,0.00033,0,0
|
38790000,0.66,1.7e-05,-0.0036,0.75,-1.9,-1.2,0.023,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.05,0.46,-0.0054,0.0058,-0.032,0,0,0.00019,0.0002,0.02,1.3,1.4,0.0053,8.1,8.6,0.033,6e-07,6.1e-07,5e-06,0.017,0.016,9.2e-05,3.7e-06,2.8e-06,0.00064,4.1e-06,3.6e-06,0.00064,1,1
|
||||||
38890000,0.65,-0.001,0.022,0.76,-4.8,-4.6,0.58,-1e+06,1.2e+04,-3.7e+02,-0.00075,-0.0058,-0.00029,-0.018,0.055,-0.098,-0.2,-0.042,0.47,0.00021,-0.0032,-0.032,0,0,0.00025,0.00042,0.0028,1.3,1.8,0.0097,10,15,0.038,5.9e-07,6.4e-07,4.8e-06,0.03,0.028,0.0005,4e-05,8.8e-06,0.00033,1.4e-05,2.5e-05,0.00033,0,0
|
38890000,0.66,-8.6e-05,-0.0034,0.75,-1.8,-1.2,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0014,-0.0062,0.00017,-0.22,0.26,-0.11,-0.21,-0.05,0.46,-0.0054,0.0058,-0.032,0,0,0.00019,0.0002,0.02,1.4,1.4,0.0053,8.8,9.2,0.033,6e-07,6.1e-07,5e-06,0.017,0.016,9.2e-05,3.7e-06,2.8e-06,0.00064,4e-06,3.5e-06,0.00064,1,1
|
||||||
|
|
|
|
@ -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]
|
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.9e-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.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
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.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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
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.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-1.5e-11,0,0,-1.1e-06,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-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.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-4.7e-10,0,0,-1e-05,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-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.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,-1.3e-09,0,0,2.2e-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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-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.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.5e-07,-1.7e-07,0,0,-1e-06,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-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.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.8e-07,-1.8e-07,0,0,7.8e-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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
690000,1,-0.012,-0.012,0.0006,5.3e-05,-0.0088,-0.05,-8e-05,-0.00078,-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.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,-5.2e-07,0,0,-0.00016,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-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.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,-5.1e-07,0,0,-0.0002,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1.2e-06,-7.4e-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.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1.2e-06,-7.4e-07,0,0,-8.1e-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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1.2e-06,-7.4e-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.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1.2e-06,-7.4e-07,0,0,-2.6e-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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-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.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,-1.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00045,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.7e-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.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.7e-05,-1.3e-05,-2.2e-07,0,0,-0.00056,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1290000,1,-0.012,-0.014,0.00041,0.019,-0.018,-0.11,0.002,-0.0024,-0.048,-0.00016,-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.00041,0.019,-0.018,-0.11,0.002,-0.0024,-0.048,-0.00016,-9.5e-05,3e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.025,0.026,0.0004,0.88,0.88,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1390000,1,-0.012,-0.014,0.00038,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.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9e-05,2.8e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00046,1.2,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1490000,1,-0.012,-0.014,0.00037,0.024,-0.02,-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.00037,0.024,-0.02,-0.12,0.0034,-0.0033,-0.053,-0.00039,-0.00033,1.1e-05,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.95,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1590000,1,-0.012,-0.014,0.00039,0.031,-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
|
1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.1e-05,0,0,-0.0015,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1690000,1,-0.012,-0.014,0.00042,0.028,-0.02,-0.13,0.0044,-0.0037,-0.068,-0.00073,-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.00042,0.028,-0.019,-0.13,0.0044,-0.0037,-0.068,-0.00073,-0.00073,2.4e-05,0,0,-0.0019,0,0,0,0,0,0,0,0,0.025,0.026,0.00033,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1790000,1,-0.012,-0.014,0.00038,0.036,-0.024,-0.13,0.0076,-0.006,-0.067,-0.00072,-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.00038,0.036,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00072,-0.00072,2.4e-05,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1890000,1,-0.012,-0.014,0.00037,0.043,-0.025,-0.14,0.012,-0.0084,-0.075,-0.00072,-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.00037,0.043,-0.025,-0.14,0.012,-0.0084,-0.075,-0.00072,-0.00071,2.4e-05,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
1990000,1,-0.011,-0.014,0.00036,0.035,-0.018,-0.14,0.0082,-0.0054,-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
|
1990000,1,-0.011,-0.014,0.00036,0.035,-0.018,-0.14,0.0082,-0.0054,-0.074,-0.0011,-0.0012,3.8e-05,0,0,-0.0047,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.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2090000,1,-0.011,-0.014,0.00039,0.042,-0.02,-0.14,0.012,-0.0074,-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.00039,0.042,-0.02,-0.14,0.012,-0.0074,-0.071,-0.0011,-0.0012,3.8e-05,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00037,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2190000,1,-0.011,-0.014,0.00032,0.033,-0.014,-0.14,0.0081,-0.0044,-0.077,-0.0014,-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.00032,0.033,-0.014,-0.14,0.0081,-0.0044,-0.077,-0.0014,-0.0018,5.1e-05,0,0,-0.0076,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2290000,1,-0.011,-0.014,0.00031,0.038,-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
|
2290000,1,-0.011,-0.014,0.00031,0.038,-0.014,-0.14,0.012,-0.0058,-0.075,-0.0014,-0.0018,5e-05,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,0.11,0.3,0.29,0.1,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2390000,1,-0.011,-0.013,0.00031,0.029,-0.0099,-0.14,0.0075,-0.0034,-0.072,-0.0017,-0.0023,5.9e-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.00031,0.03,-0.01,-0.14,0.0076,-0.0034,-0.072,-0.0017,-0.0023,5.9e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00027,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2490000,1,-0.011,-0.014,0.00039,0.033,-0.0088,-0.14,0.011,-0.0043,-0.079,-0.0017,-0.0023,5.9e-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.00039,0.033,-0.009,-0.14,0.011,-0.0044,-0.079,-0.0017,-0.0023,5.9e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.0003,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2590000,1,-0.01,-0.013,0.00028,0.023,-0.0059,-0.15,0.0066,-0.0024,-0.085,-0.0018,-0.0027,6.4e-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.00028,0.023,-0.006,-0.15,0.0066,-0.0024,-0.084,-0.0018,-0.0027,6.4e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2690000,1,-0.01,-0.013,0.00032,0.027,-0.0051,-0.15,0.0091,-0.003,-0.084,-0.0018,-0.0027,6.4e-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.00032,0.027,-0.0052,-0.15,0.0092,-0.003,-0.084,-0.0018,-0.0027,6.4e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2790000,1,-0.01,-0.013,0.00025,0.022,-0.0028,-0.14,0.0059,-0.0016,-0.081,-0.0019,-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.00025,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,6.7e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2890000,1,-0.01,-0.013,0.00017,0.026,-0.0046,-0.14,0.0083,-0.002,-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
|
2890000,1,-0.01,-0.013,0.00017,0.026,-0.0046,-0.14,0.0083,-0.0021,-0.081,-0.0019,-0.003,6.7e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
2990000,1,-0.01,-0.013,0.00017,0.02,-0.0035,-0.15,0.0054,-0.0012,-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.00017,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,6.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3090000,1,-0.01,-0.013,0.00037,0.025,-0.0064,-0.15,0.0077,-0.0018,-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.00037,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,6.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.82,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,3.9e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3190000,1,-0.01,-0.013,0.00041,0.021,-0.0062,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,6.8e-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.00041,0.02,-0.006,-0.15,0.0052,-0.0013,-0.097,-0.0021,-0.0036,6.8e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0087,0.0087,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3290000,1,-0.01,-0.013,0.00043,0.024,-0.0063,-0.15,0.0074,-0.002,-0.11,-0.002,-0.0036,6.8e-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.00042,0.023,-0.0061,-0.15,0.0073,-0.002,-0.11,-0.0021,-0.0036,6.8e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,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.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3390000,1,-0.0098,-0.013,0.00043,0.019,-0.0034,-0.15,0.005,-0.0013,-0.1,-0.0021,-0.0038,6.8e-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.0097,-0.013,0.00043,0.019,-0.0031,-0.15,0.005,-0.0013,-0.1,-0.0021,-0.0038,6.8e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,2.8e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3490000,1,-0.0097,-0.013,0.00041,0.025,-0.0021,-0.15,0.0073,-0.0016,-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
|
3490000,1,-0.0097,-0.013,0.00041,0.025,-0.0017,-0.15,0.0072,-0.0015,-0.1,-0.0021,-0.0038,6.8e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.0002,0.65,0.65,0.095,0.19,0.19,0.086,0.002,0.002,2.8e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3590000,1,-0.0095,-0.013,0.00035,0.022,-0.0016,-0.15,0.0051,-0.00096,-0.11,-0.0021,-0.004,6.7e-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.0095,-0.012,0.00035,0.021,-0.0012,-0.15,0.0051,-0.0009,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,2.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3690000,1,-0.0096,-0.013,0.00033,0.024,-0.001,-0.15,0.0075,-0.0012,-0.11,-0.0021,-0.004,6.7e-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.0095,-0.013,0.00033,0.024,-0.0005,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,2.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3790000,1,-0.0095,-0.012,0.00035,0.02,0.0033,-0.15,0.0052,-0.00053,-0.11,-0.0022,-0.0042,6.5e-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.0094,-0.012,0.00034,0.02,0.0039,-0.15,0.0051,-0.00044,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3890000,1,-0.0094,-0.013,0.00042,0.022,0.0045,-0.14,0.0074,-0.00015,-0.11,-0.0022,-0.0042,6.5e-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.0093,-0.013,0.00042,0.021,0.0052,-0.14,0.0072,1.4e-05,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
3990000,1,-0.0094,-0.013,0.00048,0.027,0.0041,-0.14,0.0099,0.00021,-0.11,-0.0022,-0.0042,6.5e-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.0093,-0.013,0.00048,0.026,0.005,-0.14,0.0096,0.00046,-0.11,-0.0022,-0.0042,6.6e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,2.1e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4090000,1,-0.0094,-0.012,0.00054,0.023,0.0034,-0.12,0.0074,0.00042,-0.098,-0.0021,-0.0044,6.3e-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.0093,-0.012,0.00054,0.022,0.0043,-0.12,0.0071,0.00064,-0.098,-0.0022,-0.0045,6.4e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.8e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4190000,1,-0.0094,-0.012,0.0005,0.025,0.003,-0.12,0.0098,0.00073,-0.1,-0.0021,-0.0044,6.3e-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.0094,-0.012,0.00049,0.024,0.0041,-0.12,0.0094,0.0011,-0.1,-0.0022,-0.0045,6.4e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1.8e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4290000,1,-0.0095,-0.012,0.0005,0.023,0.0029,-0.12,0.0071,0.00062,-0.11,-0.0021,-0.0046,6.1e-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.0094,-0.012,0.0005,0.021,0.0039,-0.12,0.0068,0.00087,-0.11,-0.0022,-0.0047,6.2e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.46,0.46,0.084,0.15,0.15,0.085,0.00097,0.00097,1.6e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4390000,1,-0.0094,-0.012,0.00045,0.026,0.0013,-0.11,0.0097,0.00073,-0.094,-0.0021,-0.0046,6.1e-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.0093,-0.012,0.00045,0.025,0.0025,-0.11,0.0092,0.0011,-0.094,-0.0022,-0.0046,6.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,1.6e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4490000,1,-0.0095,-0.012,0.00051,0.022,0.003,-0.11,0.0071,0.00061,-0.095,-0.0021,-0.0048,5.8e-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.0094,-0.012,0.0005,0.021,0.0042,-0.11,0.0067,0.0009,-0.095,-0.0021,-0.0048,6e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00015,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,1.4e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4590000,1,-0.0095,-0.012,0.00057,0.025,0.0018,-0.11,0.0095,0.00084,-0.098,-0.0021,-0.0048,5.8e-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.0094,-0.012,0.00056,0.023,0.0031,-0.11,0.0089,0.0013,-0.098,-0.0021,-0.0048,6e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00016,0.51,0.51,0.077,0.19,0.19,0.084,0.0008,0.0008,1.4e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4690000,1,-0.0095,-0.012,0.00049,0.019,0.0021,-0.1,0.0069,0.0006,-0.09,-0.0021,-0.005,5.6e-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.0094,-0.012,0.00049,0.017,0.0032,-0.1,0.0065,0.00092,-0.09,-0.0021,-0.005,5.7e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.39,0.39,0.074,0.14,0.14,0.083,0.00065,0.00065,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4790000,1,-0.0093,-0.012,0.00059,0.017,0.0041,-0.099,0.0087,0.00095,-0.092,-0.0021,-0.005,5.6e-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.0092,-0.012,0.00058,0.015,0.0055,-0.099,0.0081,0.0014,-0.092,-0.0021,-0.005,5.7e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4890000,1,-0.0093,-0.012,0.00062,0.012,0.0017,-0.093,0.0059,0.00073,-0.088,-0.0021,-0.0051,5.4e-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.0092,-0.012,0.00061,0.01,0.003,-0.093,0.0053,0.0011,-0.088,-0.0021,-0.0051,5.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,1.1e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
4990000,1,-0.0093,-0.012,0.0006,0.016,0.0023,-0.085,0.0073,0.00095,-0.083,-0.0021,-0.0051,5.4e-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.0092,-0.012,0.00059,0.013,0.0037,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,5.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.1e-05,0.04,0.04,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5090000,1,-0.0091,-0.012,0.00066,0.012,0.0027,-0.082,0.0051,0.00068,-0.081,-0.0021,-0.0052,5.2e-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.0091,-0.011,0.00066,0.01,0.004,-0.082,0.0045,0.001,-0.081,-0.0021,-0.0053,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00013,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5190000,1,-0.009,-0.012,0.0007,0.012,0.0062,-0.08,0.0063,0.0011,-0.079,-0.0021,-0.0052,5.2e-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.0089,-0.012,0.0007,0.0098,0.0076,-0.08,0.0055,0.0016,-0.079,-0.0021,-0.0053,5.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5290000,1,-0.0089,-0.012,0.00075,0.01,0.0064,-0.068,0.0044,0.001,-0.072,-0.002,-0.0053,5e-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.0088,-0.011,0.00075,0.0081,0.0076,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.1e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5390000,1,-0.0088,-0.012,0.00075,0.0099,0.0099,-0.065,0.0054,0.0018,-0.067,-0.002,-0.0053,5e-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.0087,-0.011,0.00074,0.0075,0.011,-0.065,0.0046,0.0023,-0.067,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.15,0.16,0.079,0.00035,0.00035,9.2e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5490000,1,-0.0089,-0.012,0.00074,0.0091,0.011,-0.06,0.0037,0.0017,-0.065,-0.002,-0.0054,4.8e-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.0088,-0.011,0.00073,0.007,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,5e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00012,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5590000,1,-0.0089,-0.012,0.00066,0.011,0.015,-0.053,0.0048,0.003,-0.058,-0.002,-0.0054,4.8e-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.0088,-0.011,0.00066,0.0082,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5690000,1,-0.0089,-0.011,0.00056,0.0095,0.015,-0.052,0.0034,0.0027,-0.055,-0.0019,-0.0055,4.7e-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.00055,0.0074,0.016,-0.052,0.0028,0.0031,-0.055,-0.0019,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.5e-06,0.04,0.04,0.0062,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5790000,1,-0.0088,-0.011,0.0005,0.011,0.017,-0.049,0.0045,0.0043,-0.053,-0.0019,-0.0055,4.7e-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.0087,-0.011,0.0005,0.0087,0.018,-0.049,0.0036,0.0048,-0.053,-0.0019,-0.0055,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.5e-06,0.04,0.04,0.0058,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5890000,1,-0.0088,-0.011,0.00053,0.011,0.015,-0.048,0.0034,0.0035,-0.056,-0.0019,-0.0055,4.5e-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.00053,0.0092,0.016,-0.048,0.0027,0.0039,-0.056,-0.0019,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
5990000,1,-0.0088,-0.012,0.0005,0.013,0.016,-0.041,0.0046,0.005,-0.05,-0.0019,-0.0055,4.5e-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.011,0.00049,0.011,0.017,-0.041,0.0037,0.0055,-0.05,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.046,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6090000,1,-0.0088,-0.012,0.00031,0.013,0.017,-0.039,0.0059,0.0067,-0.047,-0.0019,-0.0055,4.5e-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.0087,-0.011,0.0003,0.011,0.019,-0.039,0.0048,0.0073,-0.047,-0.0019,-0.0055,4.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6190000,-0.29,0.013,-0.0053,0.96,0.012,0.013,-0.037,0.0046,0.0053,-0.047,-0.0018,-0.0056,4.3e-05,0,0,-0.12,-0.017,-0.0037,0.57,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,1,-0.0089,-0.011,0.0003,0.0083,0.017,-0.038,0.0037,0.0059,-0.047,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6290000,-0.29,0.013,-0.0052,0.96,0.014,0.011,-0.041,0.0058,0.0066,-0.053,-0.0018,-0.0056,4.3e-05,0,0,-0.12,-0.017,-0.0037,0.57,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,1,-0.0088,-0.011,0.00032,0.0075,0.02,-0.041,0.0045,0.0077,-0.053,-0.0018,-0.0055,4.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.041,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6390000,-0.29,0.013,-0.0052,0.96,0.012,0.0091,-0.042,0.0072,0.0076,-0.056,-0.0018,-0.0056,4.3e-05,1.4e-09,-1.1e-09,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.22,0.22,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,1,-0.0089,-0.011,0.00033,0.0077,0.017,-0.042,0.0033,0.0062,-0.056,-0.0017,-0.0056,4.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6490000,-0.29,0.013,-0.0051,0.96,0.0015,0.00057,-0.039,0.0077,0.008,-0.053,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.038,1e+02,1e+02,0.07,0.00015,0.00015,6.3e-06,0.04,0.04,0.0036,0,0,0,0,0,0,0,0
|
6490000,1,-0.0088,-0.011,0.00022,0.0051,0.017,-0.039,0.004,0.0078,-0.053,-0.0017,-0.0056,4.3e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6590000,-0.29,0.013,-0.0051,0.96,0.0026,-0.0022,-0.042,0.0079,0.008,-0.056,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.036,1e+02,1e+02,0.069,0.00015,0.00015,6.3e-06,0.04,0.04,0.0033,0,0,0,0,0,0,0,0
|
6590000,1,-0.0089,-0.011,0.00014,0.0034,0.015,-0.042,0.0027,0.006,-0.056,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6690000,-0.29,0.013,-0.005,0.96,0.0057,-0.0045,-0.044,0.0081,0.0077,-0.057,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.035,51,51,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0031,0,0,0,0,0,0,0,0
|
6690000,1,-0.0088,-0.011,9.4e-05,0.0016,0.019,-0.044,0.003,0.0077,-0.057,-0.0017,-0.0056,4.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6790000,-0.29,0.013,-0.005,0.96,0.0043,-0.007,-0.042,0.0087,0.0072,-0.058,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.034,52,52,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0029,0,0,0,0,0,0,0,0
|
6790000,1,-0.0089,-0.011,5.3e-05,0.0023,0.016,-0.042,0.0019,0.0061,-0.058,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6890000,-0.29,0.013,-0.0048,0.96,0.0047,-0.0074,-0.038,0.0087,0.0069,-0.055,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.032,35,35,0.067,0.00015,0.00015,6.3e-06,0.04,0.04,0.0027,0,0,0,0,0,0,0,0
|
6890000,1,-0.0087,-0.011,-3.7e-05,0.0016,0.016,-0.039,0.0021,0.0076,-0.055,-0.0016,-0.0056,3.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8.1e-05,8.1e-05,4.9e-06,0.04,0.04,0.0027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
6990000,-0.29,0.013,-0.0047,0.96,0.005,-0.0092,-0.037,0.0092,0.0061,-0.055,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.031,36,36,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.29,0.013,-0.0052,0.96,0.0011,0.012,-0.037,0.0014,0.0059,-0.055,-0.0016,-0.0057,3.8e-05,0,0,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.022,0.16,0.16,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7090000,-0.29,0.013,-0.0046,0.96,0.0068,-0.015,-0.037,0.0093,0.0056,-0.056,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.03,28,28,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.29,0.013,-0.0051,0.96,0.0031,0.0076,-0.038,0.0017,0.0067,-0.056,-0.0016,-0.0057,3.8e-05,0,0,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.16,0.16,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7190000,-0.29,0.013,-0.0045,0.96,0.0077,-0.017,-0.036,0.01,0.0039,-0.058,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.029,30,30,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.29,0.013,-0.0051,0.96,0.004,0.0062,-0.037,0.0021,0.0074,-0.058,-0.0016,-0.0057,3.8e-05,-1.3e-05,1.1e-05,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.17,0.17,0.029,0.16,0.16,0.065,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7290000,-0.29,0.013,-0.0045,0.96,0.0074,-0.022,-0.034,0.01,0.0033,-0.054,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.028,24,24,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.29,0.013,-0.0051,0.96,0.004,0.0026,-0.034,0.0025,0.0078,-0.054,-0.0016,-0.0057,3.8e-05,-0.00013,0.00011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.18,0.18,0.028,0.19,0.19,0.064,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7390000,-0.29,0.013,-0.0043,0.96,0.0098,-0.025,-0.032,0.011,0.00094,-0.052,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.027,27,27,0.064,0.00015,0.00015,6.3e-06,0.04,0.04,0.002,0,0,0,0,0,0,0,0
|
7390000,-0.29,0.013,-0.0049,0.96,0.0063,0.00064,-0.032,0.0031,0.008,-0.052,-0.0016,-0.0057,3.8e-05,-0.00021,0.00019,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.19,0.19,0.027,0.22,0.22,0.064,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7490000,-0.29,0.013,-0.0043,0.96,0.0077,-0.028,-0.026,0.011,0.00035,-0.046,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,21,21,0.026,23,23,0.063,0.00015,0.00015,6.3e-06,0.04,0.04,0.0019,0,0,0,0,0,0,0,0
|
7490000,-0.29,0.013,-0.0049,0.96,0.0046,-0.0022,-0.026,0.0036,0.0079,-0.046,-0.0016,-0.0057,3.8e-05,-0.00036,0.00032,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.2,0.2,0.026,0.26,0.26,0.063,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7590000,-0.29,0.013,-0.0044,0.96,0.0074,-0.032,-0.023,0.012,-0.0026,-0.041,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,21,21,0.025,25,25,0.062,0.00015,0.00015,6.3e-06,0.04,0.04,0.0018,0,0,0,0,0,0,0,0
|
7590000,-0.29,0.013,-0.005,0.96,0.0041,-0.0048,-0.023,0.004,0.0076,-0.041,-0.0016,-0.0057,3.8e-05,-0.00049,0.00043,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.22,0.22,0.025,0.3,0.3,0.062,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7690000,-0.29,0.013,-0.0044,0.96,0.0079,-0.035,-0.022,0.011,-0.003,-0.036,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,19,19,0.025,22,22,0.062,0.00015,0.00015,6.3e-06,0.04,0.04,0.0017,0,0,0,0,0,0,0,0
|
7690000,-0.29,0.013,-0.005,0.96,0.0051,-0.0079,-0.022,0.0045,0.0069,-0.036,-0.0016,-0.0057,3.8e-05,-0.0006,0.00053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.24,0.24,0.025,0.35,0.35,0.062,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7790000,-0.29,0.013,-0.0042,0.96,0.0068,-0.038,-0.024,0.012,-0.0066,-0.041,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,19,19,0.024,25,25,0.061,0.00015,0.00015,6.3e-06,0.04,0.04,0.0016,0,0,0,0,0,0,0,0
|
7790000,-0.29,0.013,-0.0049,0.96,0.0041,-0.01,-0.025,0.005,0.006,-0.041,-0.0016,-0.0057,3.8e-05,-0.00055,0.00049,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.26,0.26,0.024,0.4,0.4,0.061,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7890000,-0.29,0.013,-0.0042,0.96,0.0091,-0.043,-0.025,0.013,-0.011,-0.045,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,19,19,0.023,28,28,0.06,0.00015,0.00015,6.3e-06,0.04,0.04,0.0015,0,0,0,0,0,0,0,0
|
7890000,-0.29,0.013,-0.0049,0.96,0.0062,-0.014,-0.025,0.0056,0.0049,-0.045,-0.0016,-0.0057,3.8e-05,-0.00054,0.00047,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.29,0.29,0.023,0.46,0.46,0.06,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
7990000,-0.29,0.013,-0.0042,0.96,0.0088,-0.045,-0.021,0.013,-0.011,-0.041,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,17,17,0.022,24,24,0.059,0.00015,0.00015,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0
|
7990000,-0.29,0.013,-0.0048,0.96,0.0064,-0.016,-0.021,0.0062,0.0034,-0.042,-0.0016,-0.0057,3.9e-05,-0.00064,0.00056,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.32,0.32,0.022,0.52,0.52,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8090000,-0.29,0.013,-0.004,0.96,0.0082,-0.05,-0.022,0.014,-0.016,-0.044,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,17,17,0.022,27,27,0.059,0.00015,0.00015,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0
|
8090000,-0.29,0.013,-0.0047,0.96,0.0058,-0.02,-0.022,0.0067,0.0017,-0.044,-0.0016,-0.0057,3.9e-05,-0.00064,0.00056,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.35,0.35,0.022,0.6,0.6,0.059,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8190000,-0.29,0.013,-0.0041,0.96,0.008,-0.054,-0.018,0.013,-0.015,-0.038,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,15,15,0.021,24,24,0.058,0.00015,0.00015,6.3e-06,0.04,0.04,0.0013,0,0,0,0,0,0,0,0
|
8190000,-0.29,0.013,-0.0047,0.96,0.0061,-0.025,-0.018,0.0072,-0.00066,-0.038,-0.0016,-0.0057,3.9e-05,-0.00081,0.0007,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.38,0.38,0.021,0.68,0.68,0.058,6.6e-05,6.6e-05,4.5e-06,0.04,0.04,0.0013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8290000,-0.29,0.013,-0.004,0.96,0.0068,-0.06,-0.016,0.014,-0.021,-0.038,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,15,15,0.02,27,27,0.057,0.00015,0.00015,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0
|
8290000,-0.29,0.013,-0.0047,0.96,-0.00098,-0.0043,-0.016,0.0073,-0.0011,-0.038,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8390000,-0.29,0.013,-0.004,0.96,0.0087,-0.059,-0.015,0.013,-0.02,-0.036,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,13,13,0.02,24,24,0.057,0.00015,0.00015,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0
|
8390000,-0.29,0.013,-0.0047,0.96,0.0015,-0.0056,-0.016,0.0073,-0.0015,-0.036,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.02,1e+02,1e+02,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8490000,-0.29,0.013,-0.0038,0.96,0.0098,-0.065,-0.017,0.014,-0.026,-0.041,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,14,14,0.019,26,26,0.056,0.00015,0.00015,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0
|
8490000,-0.29,0.013,-0.0045,0.96,0.0026,-0.0096,-0.017,0.0074,-0.0019,-0.041,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,25,25,0.019,51,51,0.056,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8590000,-0.29,0.013,-0.0038,0.96,0.0087,-0.065,-0.012,0.014,-0.025,-0.036,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0023,0.0023,0.018,12,12,0.018,23,23,0.055,0.00015,0.00015,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0
|
8590000,-0.29,0.013,-0.0045,0.96,0.0021,-0.013,-0.012,0.0077,-0.003,-0.036,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.019,52,52,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8690000,-0.29,0.013,-0.0038,0.96,0.0094,-0.069,-0.014,0.014,-0.032,-0.037,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0023,0.0023,0.018,12,12,0.018,26,26,0.055,0.00015,0.00015,6.3e-06,0.04,0.04,0.001,0,0,0,0,0,0,0,0
|
8690000,-0.29,0.013,-0.0045,0.96,0.0026,-0.015,-0.014,0.0078,-0.0035,-0.037,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,35,35,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8790000,-0.29,0.013,-0.0037,0.96,0.0079,-0.069,-0.013,0.014,-0.029,-0.035,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0024,0.0024,0.018,10,10,0.018,23,23,0.055,0.00015,0.00015,6.3e-06,0.04,0.04,0.00096,0,0,0,0,0,0,0,0
|
8790000,-0.29,0.013,-0.0045,0.96,0.0017,-0.018,-0.013,0.0081,-0.0051,-0.035,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,25,25,0.018,37,37,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00097,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8890000,-0.29,0.013,-0.0037,0.96,0.0088,-0.075,-0.009,0.015,-0.037,-0.029,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0025,0.0025,0.018,10,10,0.017,25,25,0.054,0.00015,0.00015,6.3e-06,0.04,0.04,0.00091,0,0,0,0,0,0,0,0
|
8890000,-0.29,0.013,-0.0045,0.96,0.0023,-0.021,-0.0092,0.008,-0.0058,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,24,24,0.017,28,28,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00093,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
8990000,-0.29,0.013,-0.0037,0.96,0.0099,-0.075,-0.0083,0.014,-0.034,-0.032,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0026,0.0026,0.018,8.8,8.8,0.017,22,22,0.054,0.00015,0.00015,6.3e-06,0.04,0.04,0.00088,0,0,0,0,0,0,0,0
|
8990000,-0.29,0.013,-0.0044,0.96,0.0042,-0.026,-0.0084,0.0084,-0.0081,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,24,24,0.017,30,30,0.054,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00089,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9090000,-0.29,0.013,-0.0036,0.96,0.011,-0.082,-0.0093,0.015,-0.042,-0.032,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0027,0.0027,0.018,8.9,8.9,0.016,24,24,0.053,0.00015,0.00015,6.3e-06,0.04,0.04,0.00084,0,0,0,0,0,0,0,0
|
9090000,-0.29,0.013,-0.0044,0.96,0.0047,-0.03,-0.0094,0.0085,-0.0088,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,25,25,0.053,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00085,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9190000,-0.29,0.013,-0.0036,0.96,0.0071,-0.082,-0.0087,0.014,-0.038,-0.032,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0027,0.0027,0.018,7.7,7.7,0.016,21,21,0.052,0.00015,0.00015,6.3e-06,0.04,0.04,0.0008,0,0,0,0,0,0,0,0
|
9190000,-0.29,0.013,-0.0044,0.96,0.0018,-0.034,-0.0089,0.0088,-0.012,-0.032,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,23,23,0.016,27,27,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00081,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9290000,-0.29,0.013,-0.0034,0.96,0.0057,-0.088,-0.0071,0.015,-0.047,-0.03,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0028,0.0028,0.018,7.8,7.8,0.015,23,23,0.052,0.00015,0.00015,6.3e-06,0.04,0.04,0.00076,0,0,0,0,0,0,0,0
|
9290000,-0.29,0.013,-0.0042,0.96,-2.1e-05,-0.036,-0.0073,0.0085,-0.013,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0016,0.0016,0.018,21,21,0.015,23,23,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9390000,-0.29,0.013,-0.0033,0.96,0.0057,-0.087,-0.006,0.014,-0.043,-0.03,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0029,0.0029,0.018,6.8,6.8,0.015,21,21,0.052,0.00015,0.00015,6.3e-06,0.04,0.04,0.00073,0,0,0,0,0,0,0,0
|
9390000,-0.29,0.013,-0.0041,0.96,0.00053,-0.039,-0.0062,0.0085,-0.016,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,21,21,0.015,26,26,0.052,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00075,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9490000,-0.29,0.013,-0.0033,0.96,0.0064,-0.091,-0.0043,0.015,-0.052,-0.027,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.003,0.003,0.018,6.9,6.9,0.015,22,22,0.051,0.00015,0.00015,6.3e-06,0.04,0.04,0.0007,0,0,0,0,0,0,0,0
|
9490000,-0.29,0.013,-0.0041,0.96,0.00088,-0.04,-0.0045,0.0083,-0.016,-0.027,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,19,19,0.015,23,23,0.051,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00072,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9590000,-0.29,0.013,-0.0033,0.96,0.0064,-0.089,-0.0042,0.014,-0.048,-0.028,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0031,0.0031,0.018,6,6,0.014,20,20,0.05,0.00015,0.00015,6.3e-06,0.04,0.04,0.00067,0,0,0,0,0,0,0,0
|
9590000,-0.29,0.013,-0.0041,0.96,0.0015,-0.042,-0.0044,0.0085,-0.02,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,19,19,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00069,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9690000,-0.29,0.013,-0.0033,0.96,0.0073,-0.094,-0.0013,0.014,-0.057,-0.027,-0.0018,-0.0056,4.3e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0032,0.0032,0.018,6.1,6.1,0.014,22,22,0.05,0.00015,0.00015,6.3e-06,0.04,0.04,0.00065,0,0,0,0,0,0,0,0
|
9690000,-0.29,0.013,-0.0041,0.96,0.002,-0.042,-0.0015,0.0083,-0.02,-0.027,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,22,22,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00066,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9790000,-0.29,0.013,-0.0033,0.96,0.0063,-0.094,-0.0026,0.014,-0.053,-0.028,-0.0018,-0.0056,4.2e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0033,0.0033,0.018,5.4,5.4,0.014,19,19,0.05,0.00015,0.00015,6.3e-06,0.04,0.04,0.00062,0,0,0,0,0,0,0,0
|
9790000,-0.29,0.013,-0.0041,0.96,0.0014,-0.047,-0.0028,0.0085,-0.024,-0.028,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,17,17,0.014,25,25,0.05,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00064,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9890000,-0.29,0.013,-0.0032,0.96,0.0047,-0.099,-0.0013,0.014,-0.062,-0.028,-0.0018,-0.0056,4.2e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0034,0.0034,0.018,5.5,5.5,0.013,21,21,0.049,0.00015,0.00015,6.3e-06,0.04,0.04,0.0006,0,0,0,0,0,0,0,0
|
9890000,-0.29,0.013,-0.0041,0.96,-0.00042,-0.046,-0.0015,0.0083,-0.023,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0018,0.018,15,15,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00061,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
9990000,-0.29,0.013,-0.0032,0.96,0.0037,-0.1,-0.0006,0.015,-0.072,-0.03,-0.0018,-0.0056,4.2e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0035,0.0035,0.018,5.6,5.6,0.013,23,23,0.049,0.00015,0.00015,6.3e-06,0.04,0.04,0.00058,0,0,0,0,0,0,0,0
|
9990000,-0.29,0.013,-0.004,0.96,-0.0016,-0.049,-0.0008,0.0083,-0.028,-0.031,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,15,15,0.013,25,25,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10090000,-0.29,0.013,-0.0031,0.96,0.0051,-0.1,0.00061,0.014,-0.067,-0.029,-0.0018,-0.0056,4.2e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0036,0.0036,0.018,5,5,0.013,20,20,0.048,0.00015,0.00015,6.3e-06,0.04,0.04,0.00056,0,0,0,0,0,0,0,0
|
10090000,-0.29,0.013,-0.004,0.96,3.7e-05,-0.046,0.00042,0.0079,-0.026,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,13,13,0.013,22,22,0.049,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00057,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10190000,-0.29,0.013,-0.0031,0.96,0.0075,-0.11,0.0015,0.014,-0.078,-0.03,-0.0018,-0.0056,4.2e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0037,0.0037,0.018,5.1,5.1,0.012,22,22,0.048,0.00015,0.00015,6.3e-06,0.04,0.04,0.00054,0,0,0,0,0,0,0,0
|
10190000,-0.29,0.013,-0.0039,0.96,0.0024,-0.049,0.0013,0.0081,-0.03,-0.03,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.013,24,24,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00055,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10290000,-0.29,0.013,-0.0031,0.96,0.0072,-0.1,0.00043,0.014,-0.072,-0.029,-0.0018,-0.0056,4.2e-05,-4.5e-07,3.5e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0038,0.0038,0.018,4.6,4.6,0.012,19,19,0.048,0.00015,0.00015,6.3e-06,0.04,0.04,0.00052,0,0,0,0,0,0,0,0
|
10290000,-0.29,0.013,-0.004,0.96,0.0024,-0.053,0.00023,0.0083,-0.036,-0.029,-0.0016,-0.0057,3.9e-05,-0.00083,0.00072,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,14,14,0.012,27,27,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00053,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10390000,-0.29,0.013,-0.0031,0.96,0.014,-0.0064,-0.0025,0.0011,-0.0002,-0.028,-0.0018,-0.0056,4.2e-05,-4.9e-07,3.7e-07,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.004,0.004,0.018,0.25,0.25,0.56,0.25,0.25,0.048,0.00015,0.00015,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
10390000,-0.29,0.013,-0.0039,0.96,0.014,-0.0047,-0.0025,0.0011,-0.00013,-0.028,-0.0016,-0.0057,3.9e-05,-0.00085,0.00074,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.25,0.25,0.56,0.25,0.25,0.048,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00052,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10490000,-0.28,0.013,-0.0029,0.96,0.013,-0.011,0.007,0.0025,-0.0011,-0.023,-0.0018,-0.0056,4.2e-05,-1.7e-06,1.1e-06,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0041,0.0041,0.018,0.27,0.27,0.55,0.26,0.26,0.057,0.00015,0.00015,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
10490000,-0.29,0.013,-0.0038,0.96,0.013,-0.0077,0.007,0.0024,-0.00071,-0.023,-0.0016,-0.0057,3.9e-05,-0.00098,0.00083,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.26,0.26,0.55,0.26,0.26,0.057,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10590000,-0.28,0.013,-0.003,0.96,0.0017,-0.0098,0.013,0.00043,-0.00072,-0.021,-0.0018,-0.0055,4.1e-05,-0.0002,0.00035,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0041,0.0041,0.018,0.14,0.14,0.27,0.26,0.26,0.055,0.00014,0.00014,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
10590000,-0.29,0.013,-0.0038,0.96,0.0017,-0.0063,0.013,0.00043,-0.00048,-0.021,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.13,0.13,0.27,0.26,0.26,0.055,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00049,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10690000,-0.28,0.013,-0.0029,0.96,0.00056,-0.013,0.016,0.00055,-0.0019,-0.017,-0.0018,-0.0055,4.2e-05,-0.0002,0.00035,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0042,0.0042,0.018,0.16,0.16,0.26,0.27,0.27,0.065,0.00014,0.00014,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
10690000,-0.29,0.013,-0.0038,0.96,0.00055,-0.0081,0.016,0.00054,-0.0012,-0.017,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.14,0.14,0.26,0.27,0.27,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.00048,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10790000,-0.28,0.013,-0.0029,0.96,-0.0011,-0.017,0.014,0.00022,-0.0018,-0.015,-0.0017,-0.0056,4.1e-05,-0.00013,0.00046,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.004,0.004,0.018,0.11,0.11,0.17,0.13,0.13,0.062,0.00013,0.00013,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
10790000,-0.29,0.013,-0.0037,0.96,-0.0012,-0.012,0.014,0.00022,-0.0018,-0.015,-0.0016,-0.0057,3.9e-05,-0.0013,0.0011,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.1,0.1,0.17,0.13,0.13,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10890000,-0.28,0.013,-0.0029,0.96,-0.00082,-0.023,0.01,0.0001,-0.0037,-0.018,-0.0017,-0.0056,4.1e-05,-0.00013,0.00046,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0041,0.0041,0.018,0.14,0.14,0.16,0.14,0.14,0.068,0.00013,0.00013,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0
|
10890000,-0.29,0.013,-0.0037,0.96,-0.00081,-0.016,0.01,0.0001,-0.0031,-0.018,-0.0016,-0.0057,3.9e-05,-0.0012,0.0011,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.12,0.12,0.16,0.14,0.14,0.068,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.00047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
10990000,-0.28,0.013,-0.0033,0.96,0.00069,-0.023,0.016,9.7e-05,-0.0017,-0.011,-0.0016,-0.0056,3.7e-05,0.00033,0.0012,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0036,0.0036,0.018,0.11,0.11,0.12,0.093,0.093,0.065,0.00012,0.00012,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
10990000,-0.29,0.013,-0.0038,0.96,0.00071,-0.019,0.016,9.5e-05,-0.0017,-0.011,-0.0016,-0.0057,3.8e-05,-0.00093,0.0016,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.002,0.002,0.018,0.091,0.091,0.12,0.093,0.093,0.065,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11090000,-0.28,0.013,-0.0034,0.96,0.00045,-0.03,0.02,0.00018,-0.0044,-0.0073,-0.0016,-0.0056,3.7e-05,0.00033,0.0012,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0037,0.0037,0.018,0.14,0.14,0.11,0.1,0.1,0.069,0.00012,0.00012,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
11090000,-0.29,0.013,-0.0039,0.96,0.00049,-0.025,0.02,0.00018,-0.0038,-0.0074,-0.0016,-0.0057,3.8e-05,-0.00095,0.0017,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.11,0.11,0.11,0.099,0.099,0.069,6.3e-05,6.3e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11190000,-0.28,0.013,-0.004,0.96,0.0063,-0.024,0.026,0.0016,-0.0019,-0.00034,-0.0015,-0.0058,3.2e-05,0.0013,0.0019,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0031,0.0031,0.018,0.11,0.11,0.083,0.074,0.074,0.066,0.00011,0.00011,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
11190000,-0.29,0.013,-0.0042,0.96,0.0055,-0.022,0.026,0.0015,-0.0021,-0.00036,-0.0015,-0.0057,3.5e-05,-6.8e-05,0.0023,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.09,0.09,0.083,0.073,0.073,0.066,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11290000,-0.28,0.013,-0.0039,0.96,0.0069,-0.026,0.026,0.0023,-0.0045,-0.00012,-0.0015,-0.0058,3.2e-05,0.0013,0.0019,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0032,0.0032,0.018,0.14,0.14,0.077,0.082,0.082,0.069,0.00011,0.00011,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0
|
11290000,-0.29,0.013,-0.0042,0.96,0.006,-0.023,0.026,0.0021,-0.0044,-0.00013,-0.0015,-0.0057,3.5e-05,-5.3e-05,0.0023,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0019,0.0019,0.018,0.11,0.11,0.077,0.08,0.08,0.069,6e-05,6e-05,4.6e-06,0.039,0.039,0.00046,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11390000,-0.28,0.013,-0.0044,0.96,0.0051,-0.02,0.016,0.0014,-0.002,-0.0086,-0.0013,-0.0058,2.7e-05,0.0016,0.0028,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0026,0.0026,0.018,0.11,0.11,0.062,0.064,0.064,0.066,9.2e-05,9.2e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
11390000,-0.29,0.013,-0.0044,0.96,0.005,-0.019,0.016,0.0014,-0.0025,-0.0086,-0.0014,-0.0058,3.3e-05,0.00035,0.0033,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.091,0.091,0.062,0.063,0.063,0.066,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11490000,-0.28,0.013,-0.0044,0.96,0.0065,-0.021,0.02,0.0021,-0.0041,-0.0025,-0.0013,-0.0058,2.7e-05,0.0016,0.0029,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0026,0.0026,0.018,0.14,0.14,0.057,0.072,0.072,0.067,9.2e-05,9.2e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
11490000,-0.29,0.013,-0.0043,0.96,0.0063,-0.021,0.02,0.002,-0.0045,-0.0025,-0.0014,-0.0058,3.3e-05,0.00032,0.0033,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.11,0.11,0.057,0.07,0.07,0.067,5.7e-05,5.7e-05,4.6e-06,0.038,0.038,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11590000,-0.28,0.013,-0.0049,0.96,0.0019,-0.015,0.018,0.0011,-0.0019,-0.0036,-0.0012,-0.0059,2.4e-05,0.0018,0.0035,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0021,0.0021,0.018,0.11,0.11,0.048,0.058,0.058,0.065,8e-05,8e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
11590000,-0.29,0.013,-0.0047,0.96,0.0022,-0.016,0.018,0.0012,-0.0026,-0.0036,-0.0014,-0.0058,3.1e-05,0.00056,0.0041,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.09,0.09,0.048,0.057,0.057,0.065,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11690000,-0.28,0.013,-0.0049,0.96,0.0023,-0.019,0.018,0.0013,-0.0036,-0.0049,-0.0012,-0.0059,2.4e-05,0.0018,0.0035,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0022,0.0022,0.018,0.13,0.13,0.044,0.067,0.067,0.066,8e-05,8e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0
|
11690000,-0.29,0.013,-0.0047,0.96,0.0026,-0.021,0.018,0.0014,-0.0044,-0.0049,-0.0014,-0.0058,3.1e-05,0.00057,0.0041,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.044,0.065,0.065,0.066,5.4e-05,5.4e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11790000,-0.28,0.013,-0.0051,0.96,0.0018,-0.019,0.019,0.00092,-0.0033,-0.002,-0.0012,-0.0059,2.2e-05,0.0019,0.0037,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0017,0.0017,0.018,0.1,0.1,0.037,0.055,0.055,0.063,7.1e-05,7.1e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
11790000,-0.29,0.013,-0.0048,0.96,0.0022,-0.02,0.019,0.001,-0.004,-0.002,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.087,0.087,0.037,0.054,0.054,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11890000,-0.28,0.013,-0.0052,0.96,-0.00058,-0.021,0.017,0.001,-0.0052,-0.0013,-0.0012,-0.0059,2.2e-05,0.0019,0.0037,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0018,0.0018,0.018,0.12,0.12,0.034,0.064,0.064,0.063,7.1e-05,7.1e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
11890000,-0.29,0.013,-0.0049,0.96,-0.00013,-0.023,0.017,0.0012,-0.0061,-0.0013,-0.0013,-0.0058,2.9e-05,0.0007,0.0045,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0014,0.0014,0.018,0.1,0.1,0.034,0.062,0.062,0.063,5.1e-05,5.1e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
11990000,-0.28,0.013,-0.0057,0.96,0.0022,-0.012,0.015,0.0028,-0.0019,-0.005,-0.0011,-0.006,1.9e-05,0.0024,0.0041,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.099,0.099,0.03,0.065,0.065,0.061,6.4e-05,6.4e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
11990000,-0.29,0.013,-0.0054,0.96,0.0021,-0.015,0.015,0.0028,-0.0031,-0.005,-0.0013,-0.0059,2.6e-05,0.0015,0.0052,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.088,0.088,0.03,0.063,0.063,0.061,4.8e-05,4.8e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12090000,-0.28,0.013,-0.0056,0.96,0.0011,-0.013,0.018,0.003,-0.0031,0.0011,-0.0011,-0.006,1.9e-05,0.0024,0.0041,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0015,0.0015,0.018,0.12,0.12,0.027,0.075,0.075,0.06,6.4e-05,6.4e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12090000,-0.29,0.013,-0.0053,0.96,0.001,-0.016,0.018,0.003,-0.0046,0.0011,-0.0013,-0.0059,2.6e-05,0.0015,0.0052,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.1,0.1,0.027,0.073,0.073,0.06,4.8e-05,4.8e-05,4.6e-06,0.037,0.037,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12190000,-0.28,0.013,-0.0058,0.96,-0.00082,-0.004,0.017,0.0023,0.00072,0.0029,-0.001,-0.0061,1.6e-05,0.0026,0.0043,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.089,0.089,0.024,0.06,0.06,0.058,5.8e-05,5.8e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12190000,-0.29,0.013,-0.0054,0.96,-0.00085,-0.0074,0.017,0.0023,-0.00045,0.0029,-0.0012,-0.0059,2.4e-05,0.0018,0.0058,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.08,0.08,0.024,0.059,0.059,0.058,4.6e-05,4.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12290000,-0.28,0.013,-0.0059,0.96,0.0014,-0.0021,0.016,0.0023,0.00039,0.0039,-0.001,-0.0061,1.6e-05,0.0026,0.0043,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0013,0.0013,0.018,0.11,0.11,0.022,0.069,0.069,0.058,5.8e-05,5.8e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12290000,-0.29,0.013,-0.0055,0.96,0.0014,-0.006,0.016,0.0023,-0.0011,0.0039,-0.0012,-0.0059,2.4e-05,0.0018,0.0058,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.094,0.094,0.022,0.068,0.068,0.058,4.6e-05,4.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12390000,-0.28,0.013,-0.0059,0.96,0.00032,-0.00081,0.014,0.0017,0.00046,-0.0021,-0.00099,-0.006,1.6e-05,0.0026,0.0043,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0012,0.0011,0.018,0.081,0.081,0.02,0.056,0.056,0.056,5.4e-05,5.4e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12390000,-0.29,0.013,-0.0056,0.96,0.00033,-0.004,0.014,0.0017,-0.00049,-0.0021,-0.0012,-0.0059,2.4e-05,0.0019,0.0059,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00098,0.00098,0.018,0.074,0.074,0.02,0.055,0.055,0.056,4.4e-05,4.4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12490000,-0.28,0.013,-0.0059,0.96,0.00052,-0.0011,0.018,0.0017,0.00035,-7.8e-05,-0.00099,-0.006,1.6e-05,0.0026,0.0043,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0012,0.0012,0.018,0.095,0.095,0.018,0.065,0.065,0.055,5.4e-05,5.4e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12490000,-0.29,0.013,-0.0056,0.96,0.00054,-0.0048,0.018,0.0017,-0.00093,-8.4e-05,-0.0012,-0.0059,2.4e-05,0.0019,0.0059,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.001,0.001,0.018,0.087,0.087,0.018,0.064,0.064,0.055,4.4e-05,4.4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12590000,-0.28,0.013,-0.0058,0.96,0.00061,-0.0024,0.019,0.0029,-0.0014,0.0017,-0.001,-0.0061,1.7e-05,0.0026,0.0043,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.075,0.075,0.017,0.054,0.054,0.054,5.1e-05,5.1e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12590000,-0.29,0.013,-0.0055,0.96,0.00045,-0.0052,0.019,0.0029,-0.0021,0.0017,-0.0012,-0.0059,2.4e-05,0.0019,0.0057,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00091,0.00091,0.018,0.069,0.069,0.017,0.053,0.053,0.054,4.2e-05,4.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12690000,-0.28,0.013,-0.0058,0.96,9.5e-05,-0.00031,0.019,0.003,-0.0015,0.0033,-0.001,-0.0061,1.7e-05,0.0026,0.0043,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0011,0.0011,0.018,0.087,0.087,0.016,0.063,0.063,0.053,5.1e-05,5.1e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12690000,-0.29,0.013,-0.0054,0.96,-9.9e-05,-0.0036,0.019,0.003,-0.0025,0.0033,-0.0012,-0.0059,2.4e-05,0.0019,0.0057,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00094,0.00094,0.018,0.08,0.08,0.015,0.062,0.062,0.053,4.2e-05,4.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12790000,-0.28,0.012,-0.0056,0.96,0.0061,-0.0074,0.021,0.0065,-0.005,0.0054,-0.0011,-0.0061,1.8e-05,0.0027,0.0042,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00099,0.00099,0.018,0.074,0.074,0.014,0.063,0.063,0.052,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12790000,-0.29,0.012,-0.0053,0.96,0.0056,-0.0099,0.021,0.0064,-0.0057,0.0054,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.07,0.07,0.014,0.063,0.063,0.052,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12890000,-0.28,0.012,-0.0056,0.96,0.0067,-0.0071,0.022,0.0071,-0.0057,0.0085,-0.0011,-0.0061,1.8e-05,0.0026,0.0042,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.001,0.001,0.018,0.085,0.085,0.013,0.074,0.074,0.051,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12890000,-0.29,0.012,-0.0053,0.96,0.0062,-0.01,0.022,0.0069,-0.0067,0.0084,-0.0013,-0.0059,2.5e-05,0.002,0.0055,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.08,0.08,0.013,0.072,0.072,0.051,4e-05,4e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
12990000,-0.28,0.012,-0.0057,0.96,0.0038,-0.0054,0.022,0.005,-0.0039,0.0096,-0.0011,-0.0061,1.8e-05,0.0027,0.0042,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00094,0.00094,0.018,0.067,0.067,0.012,0.059,0.059,0.05,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
12990000,-0.29,0.012,-0.0054,0.96,0.0036,-0.008,0.022,0.0049,-0.0045,0.0096,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00084,0.00083,0.018,0.063,0.063,0.012,0.058,0.058,0.05,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13090000,-0.28,0.012,-0.0058,0.96,0.0036,-0.0061,0.02,0.0054,-0.0046,0.0085,-0.0011,-0.0061,1.8e-05,0.0027,0.0042,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00097,0.00097,0.018,0.077,0.077,0.012,0.068,0.068,0.049,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13090000,-0.29,0.012,-0.0055,0.96,0.0033,-0.009,0.02,0.0053,-0.0054,0.0085,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00086,0.00086,0.018,0.072,0.072,0.011,0.067,0.067,0.049,3.9e-05,3.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13190000,-0.28,0.012,-0.0057,0.96,0.0042,-0.0069,0.019,0.0052,-0.0059,0.0091,-0.0011,-0.0061,1.8e-05,0.0028,0.0042,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00091,0.00091,0.018,0.067,0.067,0.011,0.068,0.068,0.047,4.3e-05,4.3e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13190000,-0.29,0.012,-0.0054,0.96,0.004,-0.0095,0.019,0.0052,-0.0065,0.0091,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.063,0.063,0.011,0.068,0.068,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13290000,-0.28,0.012,-0.0057,0.96,0.0048,-0.0065,0.016,0.0057,-0.0066,0.0084,-0.0011,-0.0061,1.8e-05,0.0028,0.0041,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00093,0.00093,0.018,0.076,0.076,0.01,0.079,0.079,0.047,4.3e-05,4.3e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13290000,-0.29,0.012,-0.0054,0.96,0.0046,-0.0095,0.016,0.0056,-0.0075,0.0084,-0.0013,-0.0059,2.4e-05,0.002,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.072,0.072,0.01,0.078,0.078,0.047,3.8e-05,3.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13390000,-0.28,0.012,-0.0058,0.96,0.0032,-0.0047,0.016,0.004,-0.0045,0.0091,-0.0011,-0.0061,1.7e-05,0.0028,0.0041,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00087,0.00087,0.018,0.06,0.06,0.0097,0.062,0.062,0.046,4.1e-05,4.1e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13390000,-0.29,0.012,-0.0055,0.96,0.003,-0.0074,0.016,0.0039,-0.005,0.0091,-0.0012,-0.0059,2.4e-05,0.0021,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.057,0.057,0.0095,0.061,0.061,0.046,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13490000,-0.28,0.012,-0.0058,0.96,0.0033,-0.0068,0.015,0.0043,-0.0052,0.0053,-0.0011,-0.006,1.7e-05,0.0029,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0009,0.0009,0.018,0.068,0.068,0.0093,0.071,0.071,0.045,4.1e-05,4.1e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13490000,-0.29,0.012,-0.0055,0.96,0.0032,-0.0099,0.015,0.0043,-0.0059,0.0053,-0.0012,-0.0059,2.4e-05,0.0021,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.064,0.064,0.009,0.07,0.07,0.045,3.6e-05,3.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13590000,-0.28,0.012,-0.0058,0.96,0.0056,-0.0042,0.017,0.0066,-0.0035,0.0038,-0.0011,-0.0061,1.7e-05,0.0028,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00085,0.00085,0.018,0.055,0.055,0.0088,0.057,0.057,0.044,3.9e-05,3.9e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13590000,-0.29,0.012,-0.0055,0.96,0.0054,-0.0069,0.017,0.0065,-0.0039,0.0038,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.053,0.053,0.0086,0.057,0.057,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13690000,-0.28,0.012,-0.0057,0.96,0.006,-0.003,0.017,0.0072,-0.0039,0.0064,-0.0011,-0.0061,1.7e-05,0.0028,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00088,0.00088,0.018,0.063,0.063,0.0085,0.066,0.066,0.044,3.9e-05,3.9e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13690000,-0.29,0.012,-0.0054,0.96,0.0057,-0.0061,0.017,0.0071,-0.0046,0.0064,-0.0012,-0.006,2.3e-05,0.002,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.06,0.06,0.0083,0.065,0.065,0.044,3.5e-05,3.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13790000,-0.28,0.012,-0.0058,0.96,0.0083,-0.0015,0.017,0.01,-0.0014,0.0059,-0.0011,-0.0062,1.6e-05,0.0026,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.052,0.052,0.0082,0.054,0.054,0.043,3.7e-05,3.7e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13790000,-0.29,0.012,-0.0055,0.96,0.0079,-0.0045,0.017,0.01,-0.0018,0.0059,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.05,0.05,0.0079,0.054,0.054,0.042,3.3e-05,3.3e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13890000,-0.28,0.012,-0.0057,0.96,0.0085,-0.0022,0.018,0.011,-0.0016,0.0081,-0.0011,-0.0062,1.6e-05,0.0025,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00086,0.00086,0.018,0.059,0.059,0.008,0.062,0.062,0.042,3.7e-05,3.7e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13890000,-0.29,0.012,-0.0054,0.96,0.0081,-0.0056,0.018,0.011,-0.0023,0.0081,-0.0012,-0.006,2.3e-05,0.0018,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.056,0.056,0.0077,0.061,0.061,0.042,3.3e-05,3.3e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
13990000,-0.28,0.012,-0.0057,0.96,0.0036,-0.0064,0.017,0.0083,-0.0028,0.007,-0.0011,-0.0061,1.6e-05,0.0028,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00083,0.00083,0.018,0.05,0.05,0.0077,0.052,0.052,0.041,3.5e-05,3.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
13990000,-0.29,0.012,-0.0054,0.96,0.0034,-0.0094,0.017,0.0082,-0.0032,0.007,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.048,0.048,0.0074,0.052,0.052,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14090000,-0.28,0.012,-0.0057,0.96,0.0059,-0.0016,0.018,0.0087,-0.0032,0.0035,-0.0011,-0.0061,1.6e-05,0.0029,0.0038,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00085,0.00085,0.018,0.056,0.056,0.0076,0.059,0.059,0.041,3.5e-05,3.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
14090000,-0.29,0.012,-0.0054,0.96,0.0056,-0.0051,0.018,0.0086,-0.0039,0.0035,-0.0012,-0.006,2.3e-05,0.002,0.0055,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.054,0.054,0.0073,0.059,0.059,0.041,3.2e-05,3.2e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14190000,-0.28,0.012,-0.0058,0.96,0.0077,-0.0013,0.018,0.0084,-0.0025,0.0037,-0.0011,-0.0061,1.6e-05,0.003,0.0038,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.048,0.048,0.0074,0.05,0.05,0.04,3.4e-05,3.4e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
14190000,-0.29,0.012,-0.0054,0.96,0.0075,-0.0044,0.018,0.0083,-0.003,0.0037,-0.0012,-0.006,2.2e-05,0.002,0.0054,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.046,0.046,0.0071,0.05,0.05,0.04,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14290000,-0.28,0.012,-0.0057,0.96,0.0069,-0.0016,0.016,0.0093,-0.0026,0.0079,-0.0011,-0.0061,1.6e-05,0.0029,0.0038,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00084,0.00084,0.018,0.054,0.054,0.0073,0.058,0.058,0.04,3.4e-05,3.4e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
14290000,-0.29,0.012,-0.0054,0.96,0.0067,-0.0051,0.016,0.0091,-0.0034,0.0079,-0.0012,-0.006,2.2e-05,0.0019,0.0055,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.052,0.052,0.007,0.057,0.057,0.039,3.1e-05,3.1e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14390000,-0.28,0.012,-0.0057,0.96,0.0056,-0.0015,0.017,0.0086,-0.0035,0.012,-0.0011,-0.0061,1.7e-05,0.0029,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.046,0.047,0.0071,0.049,0.049,0.039,3.2e-05,3.2e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
14390000,-0.29,0.012,-0.0054,0.96,0.0054,-0.0047,0.018,0.0085,-0.004,0.012,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.045,0.045,0.0068,0.049,0.049,0.039,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14490000,-0.28,0.012,-0.0058,0.96,0.0079,-0.0017,0.021,0.0094,-0.0036,0.015,-0.0011,-0.0061,1.7e-05,0.0029,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00083,0.00083,0.018,0.053,0.053,0.0071,0.056,0.056,0.038,3.2e-05,3.2e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
14490000,-0.29,0.012,-0.0055,0.96,0.0077,-0.0052,0.021,0.0092,-0.0044,0.015,-0.0012,-0.006,2.3e-05,0.0019,0.0056,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.05,0.05,0.0067,0.056,0.056,0.038,2.9e-05,2.9e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14590000,-0.28,0.012,-0.0059,0.96,0.002,-0.004,0.019,0.0058,-0.0044,0.011,-0.0011,-0.0061,1.7e-05,0.0035,0.0038,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0008,0.0008,0.018,0.045,0.045,0.007,0.048,0.048,0.038,3e-05,3e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
14590000,-0.29,0.012,-0.0056,0.96,0.002,-0.0072,0.019,0.0058,-0.0049,0.011,-0.0012,-0.006,2.2e-05,0.0024,0.0054,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.044,0.044,0.0066,0.048,0.048,0.038,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14690000,-0.28,0.012,-0.0059,0.96,0.0031,-0.0042,0.019,0.0061,-0.0048,0.011,-0.0011,-0.0061,1.7e-05,0.0036,0.0037,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00082,0.00082,0.018,0.051,0.051,0.007,0.055,0.055,0.037,3e-05,3e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0
|
14690000,-0.29,0.012,-0.0056,0.96,0.0031,-0.0078,0.019,0.0061,-0.0056,0.011,-0.0012,-0.006,2.2e-05,0.0024,0.0053,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.049,0.049,0.0066,0.055,0.055,0.037,2.8e-05,2.8e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14790000,-0.28,0.012,-0.0062,0.96,-0.0013,0.001,0.019,0.0047,0.00049,0.014,-0.00098,-0.0061,1.5e-05,0.0032,0.0031,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.018,0.044,0.044,0.0069,0.048,0.048,0.037,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
14790000,-0.29,0.012,-0.0059,0.96,-0.0012,-0.0025,0.019,0.0047,-0.00016,0.014,-0.0011,-0.006,2e-05,0.002,0.0047,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.043,0.043,0.0065,0.048,0.048,0.037,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14890000,-0.28,0.012,-0.0062,0.96,-0.00033,0.004,0.023,0.0047,0.00074,0.014,-0.00098,-0.0061,1.5e-05,0.0032,0.003,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00081,0.00081,0.018,0.05,0.05,0.007,0.055,0.055,0.037,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
14890000,-0.29,0.012,-0.0058,0.96,-0.00029,9.5e-05,0.023,0.0047,-0.00028,0.015,-0.0011,-0.006,2e-05,0.002,0.0047,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.048,0.048,0.0066,0.054,0.054,0.036,2.6e-05,2.6e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
14990000,-0.28,0.012,-0.0062,0.96,-0.0013,0.0014,0.026,0.0038,-0.00099,0.016,-0.001,-0.0061,1.6e-05,0.0035,0.0032,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.018,0.043,0.043,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
14990000,-0.29,0.012,-0.0059,0.96,-0.0013,-0.002,0.026,0.0038,-0.0016,0.017,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.042,0.042,0.0065,0.047,0.047,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15090000,-0.28,0.012,-0.0061,0.96,-0.0011,0.00044,0.03,0.0037,-0.00085,0.019,-0.001,-0.0061,1.6e-05,0.0035,0.0032,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0008,0.0008,0.019,0.049,0.049,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
15090000,-0.29,0.012,-0.0058,0.96,-0.001,-0.0034,0.03,0.0037,-0.0019,0.019,-0.0011,-0.006,2.1e-05,0.0022,0.0048,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.018,0.047,0.047,0.0066,0.054,0.054,0.036,2.5e-05,2.5e-05,4.6e-06,0.036,0.036,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15190000,-0.28,0.012,-0.0063,0.96,-0.0013,0.0018,0.03,0.003,-0.00065,0.021,-0.001,-0.0061,1.6e-05,0.0036,0.0031,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00077,0.00077,0.019,0.042,0.042,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
15190000,-0.29,0.012,-0.006,0.96,-0.0013,-0.0017,0.03,0.003,-0.0013,0.021,-0.0011,-0.006,2.1e-05,0.0022,0.0047,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.041,0.041,0.0066,0.047,0.047,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00045,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15290000,-0.28,0.012,-0.0064,0.96,-0.0022,0.0028,0.03,0.0028,-0.00044,0.018,-0.001,-0.0061,1.6e-05,0.0039,0.0029,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00079,0.00079,0.019,0.048,0.048,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
15290000,-0.29,0.012,-0.0061,0.96,-0.0021,-0.001,0.03,0.0028,-0.0015,0.018,-0.0011,-0.006,2e-05,0.0024,0.0045,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00076,0.00076,0.018,0.046,0.046,0.0066,0.053,0.053,0.035,2.3e-05,2.3e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15390000,-0.28,0.012,-0.0064,0.96,-0.0034,0.00032,0.029,0.0023,-0.00052,0.018,-0.001,-0.0061,1.6e-05,0.0041,0.0028,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00076,0.00076,0.019,0.042,0.042,0.0071,0.047,0.047,0.035,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
15390000,-0.29,0.012,-0.0062,0.96,-0.0032,-0.0031,0.029,0.0024,-0.0013,0.018,-0.0011,-0.006,2e-05,0.0024,0.0044,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.041,0.041,0.0066,0.047,0.047,0.034,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15490000,-0.28,0.012,-0.0065,0.96,-0.0034,0.003,0.029,0.002,-0.00038,0.019,-0.001,-0.0061,1.6e-05,0.0042,0.0027,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00078,0.00078,0.019,0.047,0.047,0.0072,0.054,0.054,0.035,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0
|
15490000,-0.29,0.012,-0.0062,0.96,-0.0033,-0.00082,0.029,0.002,-0.0015,0.019,-0.0011,-0.006,2e-05,0.0025,0.0043,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00075,0.00075,0.018,0.046,0.046,0.0067,0.053,0.053,0.035,2.2e-05,2.2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15590000,-0.28,0.012,-0.0063,0.96,-0.0012,-0.0033,0.029,0.0045,-0.0047,0.018,-0.0011,-0.0061,1.8e-05,0.0045,0.0036,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00074,0.00074,0.019,0.041,0.041,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.3e-06,0.035,0.036,0.0005,0,0,0,0,0,0,0,0
|
15590000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0066,0.029,0.0044,-0.0054,0.018,-0.0012,-0.006,2.2e-05,0.0026,0.0051,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00072,0.00072,0.018,0.04,0.04,0.0067,0.046,0.046,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15690000,-0.28,0.012,-0.0062,0.96,-0.0034,-0.0011,0.029,0.0042,-0.0049,0.019,-0.0011,-0.0061,1.8e-05,0.0046,0.0035,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00076,0.00076,0.019,0.046,0.046,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.3e-06,0.035,0.036,0.0005,0,0,0,0,0,0,0,0
|
15690000,-0.29,0.012,-0.006,0.96,-0.0033,-0.0047,0.03,0.0042,-0.006,0.019,-0.0012,-0.006,2.2e-05,0.0026,0.0051,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00074,0.00074,0.018,0.045,0.045,0.0068,0.053,0.053,0.034,2e-05,2e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15790000,-0.28,0.012,-0.0063,0.96,-0.0023,0.00084,0.029,0.0036,-0.0039,0.02,-0.0011,-0.0061,1.8e-05,0.0046,0.0034,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.019,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
15790000,-0.29,0.012,-0.0061,0.96,-0.0022,-0.0025,0.03,0.0036,-0.0047,0.021,-0.0012,-0.006,2.2e-05,0.0026,0.0049,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.039,0.039,0.0068,0.046,0.046,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15890000,-0.28,0.012,-0.0064,0.96,-0.00075,-0.00087,0.03,0.0035,-0.0039,0.02,-0.0011,-0.0061,1.8e-05,0.0048,0.0032,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00074,0.00074,0.019,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
15890000,-0.29,0.012,-0.0061,0.96,-0.00061,-0.0045,0.03,0.0035,-0.005,0.02,-0.0012,-0.006,2.2e-05,0.0027,0.0048,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.018,0.044,0.044,0.0069,0.053,0.053,0.034,1.9e-05,1.9e-05,4.6e-06,0.035,0.035,0.00044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
15990000,-0.28,0.012,-0.0062,0.96,-0.00045,-0.00034,0.027,0.0029,-0.0032,0.019,-0.0011,-0.0061,1.8e-05,0.0051,0.0029,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.019,0.04,0.04,0.0074,0.046,0.046,0.034,1.8e-05,1.8e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
15990000,-0.29,0.012,-0.006,0.96,-0.00029,-0.0036,0.027,0.003,-0.004,0.02,-0.0012,-0.006,2.1e-05,0.0028,0.0045,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.039,0.039,0.0069,0.046,0.046,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16090000,-0.28,0.012,-0.0062,0.96,-7.1e-05,0.00075,0.024,0.003,-0.0032,0.019,-0.0011,-0.0061,1.8e-05,0.0053,0.0028,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00073,0.00073,0.019,0.045,0.045,0.0076,0.053,0.053,0.034,1.8e-05,1.8e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
16090000,-0.29,0.012,-0.006,0.96,0.00012,-0.0028,0.025,0.003,-0.0043,0.019,-0.0012,-0.006,2.1e-05,0.0029,0.0044,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.018,0.044,0.044,0.007,0.053,0.053,0.033,1.7e-05,1.7e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16190000,-0.28,0.012,-0.0062,0.96,-0.00048,0.00022,0.023,0.0011,-0.0028,0.016,-0.0011,-0.0061,1.8e-05,0.0059,0.0023,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0007,0.00069,0.019,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
16190000,-0.29,0.012,-0.006,0.96,-0.00023,-0.003,0.024,0.0012,-0.0036,0.016,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.038,0.038,0.0071,0.046,0.046,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16290000,-0.28,0.012,-0.0062,0.96,-0.0013,0.0014,0.023,0.001,-0.0027,0.017,-0.0011,-0.0061,1.8e-05,0.006,0.0022,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00071,0.00071,0.019,0.044,0.044,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0
|
16290000,-0.29,0.012,-0.006,0.96,-0.0011,-0.0021,0.024,0.0011,-0.0038,0.018,-0.0012,-0.006,2.1e-05,0.0034,0.0039,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0007,0.0007,0.018,0.043,0.043,0.0072,0.053,0.053,0.033,1.6e-05,1.6e-05,4.6e-06,0.034,0.034,0.00043,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16390000,-0.28,0.012,-0.0062,0.96,-0.001,0.0017,0.023,0.0022,-0.0023,0.017,-0.0011,-0.0061,1.8e-05,0.0059,0.0023,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00068,0.00068,0.019,0.038,0.039,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
16390000,-0.29,0.012,-0.006,0.96,-0.0008,-0.0014,0.024,0.0022,-0.0032,0.018,-0.0012,-0.006,2.1e-05,0.0033,0.0039,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00067,0.00067,0.018,0.038,0.038,0.0072,0.046,0.046,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16490000,-0.28,0.012,-0.0063,0.96,-0.0034,0.0027,0.026,0.002,-0.0021,0.021,-0.0011,-0.0061,1.8e-05,0.0058,0.0024,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00069,0.00069,0.019,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
16490000,-0.29,0.012,-0.0061,0.96,-0.0031,-0.00071,0.026,0.002,-0.0032,0.022,-0.0012,-0.006,2.1e-05,0.0032,0.0039,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00068,0.00068,0.018,0.042,0.042,0.0073,0.052,0.052,0.033,1.4e-05,1.5e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16590000,-0.28,0.012,-0.0063,0.96,-0.0084,0.0028,0.029,0.0015,-0.0018,0.021,-0.0011,-0.0061,1.8e-05,0.006,0.0023,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00066,0.00066,0.019,0.038,0.038,0.0079,0.046,0.046,0.034,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
16590000,-0.29,0.012,-0.0061,0.96,-0.0081,-0.00026,0.03,0.0015,-0.0027,0.022,-0.0012,-0.006,2.1e-05,0.0033,0.0038,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.037,0.037,0.0074,0.046,0.046,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16690000,-0.28,0.012,-0.0064,0.96,-0.011,0.0069,0.029,0.00046,-0.0014,0.022,-0.0011,-0.0061,1.8e-05,0.0061,0.0022,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00067,0.00067,0.019,0.042,0.042,0.008,0.053,0.053,0.034,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
16690000,-0.29,0.012,-0.0062,0.96,-0.011,0.0035,0.03,0.00053,-0.0025,0.023,-0.0012,-0.006,2.1e-05,0.0034,0.0037,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00066,0.00066,0.018,0.042,0.042,0.0075,0.052,0.052,0.033,1.3e-05,1.3e-05,4.6e-06,0.034,0.034,0.00042,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16790000,-0.28,0.012,-0.0063,0.96,-0.012,0.0063,0.028,0.00068,-0.0014,0.022,-0.0011,-0.0061,1.8e-05,0.0063,0.0023,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00064,0.00064,0.019,0.037,0.037,0.0081,0.046,0.046,0.034,1.2e-05,1.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
16790000,-0.29,0.012,-0.0061,0.96,-0.012,0.0033,0.029,0.00072,-0.0023,0.023,-0.0012,-0.0061,2.1e-05,0.0033,0.0038,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.037,0.037,0.0075,0.046,0.046,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16890000,-0.28,0.012,-0.0062,0.96,-0.012,0.0069,0.029,-0.00054,-0.00077,0.02,-0.0011,-0.0061,1.8e-05,0.0065,0.0021,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00066,0.00066,0.019,0.042,0.042,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
16890000,-0.29,0.012,-0.006,0.96,-0.011,0.0036,0.03,-0.00046,-0.0019,0.021,-0.0012,-0.0061,2.1e-05,0.0035,0.0037,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00065,0.00065,0.018,0.041,0.041,0.0076,0.052,0.052,0.033,1.2e-05,1.2e-05,4.6e-06,0.033,0.034,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
16990000,-0.28,0.012,-0.0062,0.96,-0.0069,0.0072,0.029,0.0025,-0.00095,0.019,-0.0011,-0.0061,1.9e-05,0.0062,0.0024,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00063,0.00063,0.019,0.04,0.04,0.0082,0.055,0.055,0.034,1.1e-05,1.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
16990000,-0.29,0.012,-0.006,0.96,-0.0067,0.0042,0.03,0.0025,-0.002,0.02,-0.0012,-0.0061,2.2e-05,0.0031,0.004,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.039,0.039,0.0076,0.054,0.054,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.00041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17090000,-0.28,0.012,-0.0063,0.96,-0.0089,0.0095,0.028,0.0017,-7e-05,0.018,-0.0011,-0.0061,1.9e-05,0.0065,0.0022,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00065,0.00065,0.019,0.044,0.044,0.0083,0.062,0.062,0.034,1.1e-05,1.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0
|
17090000,-0.29,0.011,-0.0061,0.96,-0.0087,0.0062,0.03,0.0017,-0.0014,0.02,-0.0012,-0.0061,2.2e-05,0.0033,0.0039,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00064,0.00064,0.018,0.044,0.044,0.0077,0.062,0.062,0.033,1.1e-05,1.1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17190000,-0.28,0.012,-0.0062,0.96,-0.007,0.0079,0.03,0.0036,-0.0036,0.022,-0.0012,-0.0061,2e-05,0.0065,0.0032,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00062,0.00062,0.019,0.042,0.042,0.0083,0.064,0.064,0.034,1e-05,1e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17190000,-0.29,0.011,-0.006,0.96,-0.0068,0.005,0.031,0.0036,-0.0048,0.023,-0.0013,-0.0061,2.3e-05,0.0033,0.0047,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00061,0.00062,0.018,0.041,0.041,0.0077,0.064,0.064,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17290000,-0.28,0.011,-0.0062,0.96,-0.0078,0.0079,0.03,0.0029,-0.0029,0.021,-0.0012,-0.0061,2e-05,0.0067,0.003,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00063,0.00063,0.019,0.046,0.047,0.0084,0.073,0.073,0.034,1e-05,1e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17290000,-0.29,0.011,-0.006,0.96,-0.0076,0.0047,0.031,0.0029,-0.0044,0.023,-0.0013,-0.0061,2.3e-05,0.0034,0.0046,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00063,0.00063,0.018,0.046,0.046,0.0078,0.072,0.072,0.033,1e-05,1e-05,4.6e-06,0.033,0.033,0.0004,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17390000,-0.28,0.011,-0.0062,0.96,-8.4e-05,0.014,0.029,0.0064,-0.001,0.021,-0.0012,-0.0062,2e-05,0.0064,0.0031,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0006,0.0006,0.019,0.038,0.038,0.0084,0.059,0.059,0.034,9.3e-06,9.3e-06,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17390000,-0.29,0.011,-0.006,0.96,2.7e-05,0.011,0.03,0.0064,-0.0019,0.022,-0.0013,-0.0061,2.3e-05,0.0029,0.0047,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.00059,0.00059,0.018,0.038,0.038,0.0078,0.058,0.058,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17490000,-0.28,0.011,-0.0062,0.96,0.0021,0.015,0.029,0.0066,0.00042,0.023,-0.0012,-0.0062,2e-05,0.0064,0.003,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00061,0.00061,0.019,0.043,0.043,0.0085,0.066,0.066,0.034,9.3e-06,9.3e-06,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17490000,-0.29,0.011,-0.006,0.96,0.0022,0.012,0.03,0.0066,-0.0008,0.024,-0.0013,-0.0061,2.3e-05,0.003,0.0046,-0.14,-0.017,-0.0037,0.57,0,0,0,0,0,0.0006,0.0006,0.019,0.042,0.042,0.0079,0.066,0.066,0.033,9.2e-06,9.2e-06,4.6e-06,0.033,0.033,0.00039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17590000,-0.28,0.012,-0.0062,0.96,-0.0019,0.012,0.028,0.002,-0.00055,0.02,-0.0012,-0.0061,2.1e-05,0.0075,0.0027,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.036,0.036,0.0085,0.055,0.055,0.034,8.3e-06,8.3e-06,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17590000,-0.29,0.011,-0.006,0.96,-0.0017,0.0093,0.029,0.002,-0.0013,0.022,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.036,0.036,0.0079,0.055,0.055,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17690000,-0.28,0.011,-0.0063,0.96,-0.0011,0.012,0.029,0.0018,0.00068,0.023,-0.0012,-0.0061,2.1e-05,0.0076,0.0027,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00059,0.00059,0.019,0.04,0.04,0.0086,0.062,0.062,0.034,8.3e-06,8.3e-06,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17690000,-0.29,0.011,-0.0061,0.96,-0.00088,0.0098,0.03,0.0018,-0.00037,0.024,-0.0013,-0.0061,2.3e-05,0.0039,0.0043,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.04,0.04,0.008,0.062,0.062,0.033,8.3e-06,8.3e-06,4.6e-06,0.033,0.033,0.00038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17790000,-0.28,0.011,-0.0063,0.96,-0.0012,0.013,0.029,0.0032,0.0016,0.028,-0.0012,-0.0061,2.1e-05,0.0073,0.003,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.038,0.038,0.0086,0.064,0.064,0.034,7.7e-06,7.7e-06,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17790000,-0.29,0.011,-0.0062,0.96,-0.001,0.011,0.031,0.0032,0.00064,0.03,-0.0013,-0.0061,2.3e-05,0.0036,0.0045,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.038,0.038,0.008,0.064,0.064,0.034,7.6e-06,7.6e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17890000,-0.28,0.011,-0.0062,0.96,-0.0036,0.015,0.029,0.0029,0.003,0.032,-0.0012,-0.0061,2.1e-05,0.0072,0.0031,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00058,0.00058,0.019,0.042,0.042,0.0086,0.072,0.072,0.035,7.7e-06,7.7e-06,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0
|
17890000,-0.29,0.011,-0.0061,0.96,-0.0034,0.012,0.03,0.0029,0.0018,0.034,-0.0013,-0.0061,2.3e-05,0.0036,0.0045,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00057,0.00057,0.019,0.042,0.042,0.0081,0.072,0.072,0.034,7.6e-06,7.6e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
17990000,-0.28,0.011,-0.0063,0.96,-0.0038,0.017,0.029,0.0025,0.0062,0.033,-0.0012,-0.0061,2e-05,0.0071,0.0027,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00055,0.00055,0.019,0.035,0.035,0.0086,0.058,0.058,0.034,6.9e-06,6.9e-06,6.3e-06,0.032,0.033,0.0005,0,0,0,0,0,0,0,0
|
17990000,-0.29,0.011,-0.0062,0.96,-0.0036,0.015,0.03,0.0025,0.0055,0.034,-0.0013,-0.0061,2.3e-05,0.0034,0.0041,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00055,0.00055,0.019,0.035,0.035,0.008,0.058,0.058,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18090000,-0.28,0.011,-0.0064,0.96,-0.0034,0.018,0.028,0.0021,0.008,0.031,-0.0012,-0.0061,2e-05,0.0074,0.0024,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00056,0.00056,0.019,0.039,0.039,0.0087,0.066,0.066,0.035,6.9e-06,6.9e-06,6.3e-06,0.032,0.033,0.0005,0,0,0,0,0,0,0,0
|
18090000,-0.29,0.011,-0.0063,0.96,-0.0032,0.016,0.029,0.0021,0.007,0.033,-0.0013,-0.0061,2.3e-05,0.0036,0.0039,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00056,0.00056,0.019,0.039,0.039,0.0081,0.065,0.065,0.034,6.8e-06,6.8e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18190000,-0.28,0.011,-0.0064,0.96,-0.0014,0.016,0.028,0.0033,0.0055,0.029,-0.0013,-0.0061,2.1e-05,0.0078,0.0027,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00054,0.00053,0.019,0.033,0.033,0.0086,0.055,0.055,0.035,6.2e-06,6.2e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18190000,-0.29,0.011,-0.0062,0.96,-0.0012,0.014,0.03,0.0033,0.0048,0.031,-0.0013,-0.0061,2.3e-05,0.0039,0.0042,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0081,0.054,0.054,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18290000,-0.28,0.011,-0.0064,0.96,-0.0022,0.016,0.027,0.0031,0.0071,0.027,-0.0013,-0.0061,2.1e-05,0.008,0.0025,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.037,0.037,0.0087,0.061,0.061,0.035,6.2e-06,6.2e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18290000,-0.29,0.011,-0.0063,0.96,-0.002,0.014,0.028,0.0032,0.0062,0.029,-0.0013,-0.0061,2.3e-05,0.0041,0.004,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00054,0.00054,0.019,0.037,0.037,0.0081,0.061,0.061,0.034,6.2e-06,6.2e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18390000,-0.28,0.011,-0.0062,0.96,0.0012,0.014,0.027,0.0054,0.0052,0.026,-0.0013,-0.0061,2.2e-05,0.0081,0.0029,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.0086,0.052,0.052,0.035,5.7e-06,5.7e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18390000,-0.29,0.011,-0.0061,0.96,0.0014,0.012,0.028,0.0054,0.0045,0.029,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.008,0.052,0.052,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18490000,-0.28,0.011,-0.0063,0.96,-0.0012,0.014,0.026,0.0053,0.0066,0.028,-0.0013,-0.0061,2.2e-05,0.0082,0.0028,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.0087,0.058,0.058,0.035,5.7e-06,5.7e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18490000,-0.29,0.011,-0.0062,0.96,-0.00099,0.012,0.027,0.0054,0.0057,0.03,-0.0013,-0.0061,2.4e-05,0.0041,0.0044,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.0081,0.058,0.058,0.034,5.6e-06,5.6e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18590000,-0.28,0.011,-0.0061,0.96,-0.0015,0.013,0.026,0.0043,0.0049,0.031,-0.0013,-0.0061,2.2e-05,0.0084,0.0031,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.0087,0.05,0.05,0.035,5.1e-06,5.1e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18590000,-0.29,0.011,-0.006,0.96,-0.0013,0.011,0.027,0.0044,0.0043,0.033,-0.0013,-0.0061,2.4e-05,0.0043,0.0046,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.0081,0.05,0.05,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18690000,-0.28,0.011,-0.0061,0.96,-0.0012,0.012,0.024,0.0042,0.0061,0.029,-0.0013,-0.0061,2.2e-05,0.0086,0.0029,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00052,0.00052,0.019,0.034,0.034,0.0087,0.056,0.056,0.035,5.1e-06,5.1e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18690000,-0.29,0.011,-0.006,0.96,-0.00091,0.0098,0.026,0.0042,0.0053,0.031,-0.0013,-0.0061,2.4e-05,0.0045,0.0044,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.00051,0.019,0.034,0.034,0.0081,0.056,0.056,0.034,5.1e-06,5.1e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18790000,-0.28,0.011,-0.006,0.96,0.00072,0.011,0.024,0.0048,0.0048,0.027,-0.0013,-0.0061,2.3e-05,0.009,0.0029,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.0087,0.048,0.048,0.035,4.7e-06,4.7e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18790000,-0.29,0.011,-0.0059,0.96,0.00094,0.0092,0.025,0.0048,0.0042,0.029,-0.0014,-0.0061,2.4e-05,0.0047,0.0045,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.0081,0.048,0.048,0.034,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18890000,-0.28,0.011,-0.006,0.96,0.0023,0.011,0.021,0.0049,0.006,0.023,-0.0013,-0.0061,2.3e-05,0.0093,0.0026,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00051,0.0005,0.019,0.034,0.034,0.0087,0.054,0.054,0.035,4.7e-06,4.7e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18890000,-0.29,0.011,-0.0059,0.96,0.0026,0.0093,0.023,0.005,0.0052,0.025,-0.0013,-0.0061,2.4e-05,0.005,0.0043,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.0005,0.019,0.033,0.033,0.0081,0.054,0.054,0.035,4.7e-06,4.7e-06,4.6e-06,0.032,0.032,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
18990000,-0.28,0.011,-0.006,0.96,0.0021,0.011,0.022,0.004,0.0047,0.026,-0.0013,-0.0061,2.3e-05,0.0095,0.0028,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.0087,0.047,0.047,0.035,4.3e-06,4.3e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
18990000,-0.29,0.011,-0.0058,0.96,0.0023,0.009,0.024,0.004,0.004,0.029,-0.0014,-0.0061,2.5e-05,0.0052,0.0044,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.008,0.047,0.047,0.034,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19090000,-0.28,0.011,-0.006,0.96,0.0042,0.012,0.023,0.0042,0.0057,0.022,-0.0013,-0.0061,2.3e-05,0.0099,0.0026,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0005,0.00049,0.019,0.033,0.033,0.0087,0.053,0.053,0.036,4.3e-06,4.3e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
19090000,-0.29,0.011,-0.0059,0.96,0.0044,0.01,0.025,0.0043,0.005,0.025,-0.0014,-0.0061,2.4e-05,0.0054,0.0042,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.0081,0.053,0.053,0.035,4.3e-06,4.3e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19190000,-0.28,0.011,-0.0059,0.96,0.0042,0.011,0.022,0.0034,0.0046,0.022,-0.0013,-0.0061,2.4e-05,0.01,0.0026,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.0086,0.046,0.046,0.036,3.9e-06,3.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0
|
19190000,-0.29,0.011,-0.0058,0.96,0.0044,0.0093,0.024,0.0034,0.004,0.024,-0.0014,-0.0061,2.5e-05,0.0058,0.0042,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.008,0.046,0.046,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.00031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19290000,-0.28,0.011,-0.0059,0.96,0.0052,0.011,0.023,0.0038,0.0057,0.021,-0.0013,-0.0061,2.4e-05,0.01,0.0024,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00049,0.00048,0.019,0.032,0.032,0.0087,0.052,0.052,0.036,3.9e-06,3.9e-06,6.3e-06,0.031,0.032,0.0005,0,0,0,0,0,0,0,0
|
19290000,-0.29,0.011,-0.0058,0.96,0.0054,0.0095,0.025,0.0039,0.0049,0.023,-0.0014,-0.0061,2.4e-05,0.0059,0.0041,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.008,0.052,0.052,0.035,3.9e-06,3.9e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19390000,-0.28,0.011,-0.006,0.96,0.0048,0.0095,0.024,0.003,0.0056,0.019,-0.0013,-0.0061,2.4e-05,0.011,0.0022,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.029,0.029,0.0086,0.046,0.046,0.036,3.5e-06,3.6e-06,6.3e-06,0.031,0.032,0.0005,0,0,0,0,0,0,0,0
|
19390000,-0.29,0.011,-0.0059,0.96,0.005,0.0079,0.026,0.003,0.005,0.022,-0.0014,-0.0061,2.4e-05,0.0062,0.0039,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.029,0.0079,0.045,0.045,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19490000,-0.28,0.011,-0.0061,0.96,0.0057,0.01,0.023,0.0035,0.0066,0.019,-0.0013,-0.0061,2.4e-05,0.011,0.0021,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00048,0.00047,0.019,0.031,0.031,0.0087,0.051,0.051,0.036,3.6e-06,3.6e-06,6.3e-06,0.031,0.032,0.0005,0,0,0,0,0,0,0,0
|
19490000,-0.29,0.011,-0.006,0.96,0.006,0.0083,0.025,0.0036,0.0058,0.022,-0.0014,-0.0061,2.4e-05,0.0063,0.0038,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.0079,0.051,0.051,0.035,3.5e-06,3.5e-06,4.6e-06,0.031,0.031,0.0003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19590000,-0.28,0.011,-0.0059,0.96,0.0077,0.0099,0.025,0.004,0.0042,0.019,-0.0014,-0.0061,2.4e-05,0.011,0.0023,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0086,0.045,0.045,0.036,3.2e-06,3.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
19590000,-0.29,0.011,-0.0058,0.96,0.0079,0.0084,0.027,0.0041,0.0036,0.022,-0.0014,-0.0061,2.5e-05,0.0066,0.004,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0078,0.045,0.045,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19690000,-0.28,0.011,-0.0059,0.96,0.0097,0.0089,0.023,0.0049,0.0051,0.019,-0.0014,-0.0061,2.4e-05,0.011,0.0022,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00047,0.00046,0.019,0.031,0.031,0.0086,0.051,0.051,0.036,3.2e-06,3.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
19690000,-0.29,0.011,-0.0058,0.96,0.01,0.0074,0.026,0.005,0.0043,0.022,-0.0014,-0.0061,2.5e-05,0.0067,0.0039,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0078,0.051,0.051,0.035,3.2e-06,3.2e-06,4.6e-06,0.031,0.031,0.00029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19790000,-0.28,0.011,-0.006,0.96,0.012,0.0078,0.022,0.0059,0.005,0.014,-0.0014,-0.0061,2.5e-05,0.012,0.002,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.0086,0.053,0.053,0.036,3e-06,3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
19790000,-0.29,0.011,-0.0059,0.96,0.013,0.0064,0.024,0.006,0.0043,0.018,-0.0014,-0.0061,2.5e-05,0.0071,0.0037,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.0078,0.053,0.053,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19890000,-0.28,0.011,-0.006,0.96,0.013,0.0077,0.022,0.0072,0.0057,0.013,-0.0014,-0.0061,2.5e-05,0.012,0.0019,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.033,0.033,0.0086,0.06,0.06,0.036,3e-06,3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
19890000,-0.29,0.011,-0.0059,0.96,0.013,0.0062,0.024,0.0074,0.0049,0.016,-0.0014,-0.0061,2.5e-05,0.0072,0.0036,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00046,0.00046,0.019,0.033,0.033,0.0078,0.059,0.059,0.035,3e-06,3e-06,4.6e-06,0.031,0.031,0.00028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
19990000,-0.28,0.012,-0.006,0.96,0.013,0.0092,0.019,0.0067,0.0058,0.0097,-0.0014,-0.0061,2.5e-05,0.012,0.0016,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.028,0.028,0.0085,0.051,0.051,0.036,2.7e-06,2.7e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
19990000,-0.29,0.011,-0.0059,0.96,0.013,0.0078,0.022,0.0068,0.0051,0.013,-0.0014,-0.0061,2.4e-05,0.0075,0.0033,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.028,0.028,0.0077,0.051,0.051,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20090000,-0.28,0.012,-0.0061,0.96,0.012,0.011,0.019,0.008,0.0068,0.013,-0.0014,-0.0061,2.5e-05,0.012,0.0017,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.031,0.031,0.0086,0.057,0.057,0.036,2.7e-06,2.7e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20090000,-0.29,0.011,-0.006,0.96,0.012,0.01,0.022,0.0081,0.006,0.017,-0.0014,-0.0061,2.4e-05,0.0075,0.0033,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.031,0.031,0.0077,0.057,0.057,0.035,2.7e-06,2.7e-06,4.6e-06,0.031,0.031,0.00027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20190000,-0.28,0.012,-0.006,0.96,0.011,0.0084,0.02,0.0077,0.0064,0.013,-0.0014,-0.006,2.5e-05,0.013,0.0016,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00044,0.019,0.03,0.03,0.0085,0.059,0.059,0.036,2.6e-06,2.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20190000,-0.29,0.012,-0.0059,0.96,0.011,0.0071,0.023,0.0078,0.0057,0.016,-0.0014,-0.006,2.4e-05,0.0078,0.0033,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.03,0.03,0.0076,0.059,0.059,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20290000,-0.28,0.012,-0.006,0.96,0.014,0.01,0.02,0.0089,0.0073,0.013,-0.0014,-0.006,2.5e-05,0.013,0.0016,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.033,0.033,0.0085,0.066,0.066,0.036,2.6e-06,2.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20290000,-0.29,0.012,-0.0059,0.96,0.015,0.0089,0.023,0.009,0.0064,0.017,-0.0014,-0.006,2.4e-05,0.0079,0.0032,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00045,0.00045,0.019,0.033,0.033,0.0076,0.066,0.066,0.035,2.6e-06,2.6e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20390000,-0.28,0.012,-0.006,0.96,0.015,0.0089,0.021,0.0084,0.0068,0.014,-0.0014,-0.006,2.5e-05,0.013,0.0015,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.031,0.031,0.0084,0.068,0.068,0.036,2.4e-06,2.4e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20390000,-0.29,0.012,-0.0059,0.96,0.015,0.0076,0.023,0.0085,0.006,0.018,-0.0014,-0.006,2.4e-05,0.0082,0.0032,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.031,0.031,0.0075,0.068,0.068,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20490000,-0.28,0.012,-0.006,0.96,0.019,0.011,0.02,0.01,0.0078,0.012,-0.0014,-0.006,2.5e-05,0.013,0.0014,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.034,0.034,0.0085,0.076,0.076,0.036,2.4e-06,2.4e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20490000,-0.29,0.012,-0.0059,0.96,0.02,0.0096,0.023,0.01,0.0068,0.016,-0.0014,-0.006,2.4e-05,0.0084,0.003,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.034,0.034,0.0075,0.076,0.076,0.035,2.4e-06,2.4e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20590000,-0.28,0.012,-0.0059,0.96,0.018,0.011,0.02,0.0089,0.0072,0.011,-0.0014,-0.006,2.5e-05,0.014,0.0012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00043,0.019,0.033,0.033,0.0084,0.078,0.078,0.036,2.2e-06,2.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20590000,-0.29,0.012,-0.0059,0.96,0.018,0.0099,0.023,0.009,0.0063,0.015,-0.0014,-0.006,2.4e-05,0.0088,0.0029,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00043,0.00043,0.019,0.033,0.033,0.0074,0.078,0.078,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20690000,-0.28,0.012,-0.0059,0.96,0.02,0.01,0.021,0.011,0.0082,0.011,-0.0014,-0.006,2.5e-05,0.014,0.0011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.035,0.035,0.0084,0.086,0.086,0.036,2.2e-06,2.2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20690000,-0.29,0.012,-0.0058,0.96,0.02,0.0092,0.023,0.011,0.0072,0.015,-0.0014,-0.006,2.4e-05,0.0089,0.0028,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00044,0.00044,0.019,0.035,0.035,0.0075,0.086,0.086,0.035,2.2e-06,2.2e-06,4.6e-06,0.031,0.031,0.00025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20790000,-0.28,0.012,-0.0053,0.96,0.02,0.0067,0.0055,0.0067,0.0054,0.0097,-0.0014,-0.006,2.6e-05,0.014,0.001,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.028,0.028,0.0084,0.067,0.067,0.036,2e-06,2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20790000,-0.29,0.012,-0.0052,0.96,0.02,0.0057,0.0084,0.0068,0.0047,0.014,-0.0014,-0.006,2.4e-05,0.0095,0.0026,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.028,0.028,0.0074,0.067,0.067,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20890000,-0.28,0.0069,0.0034,0.96,0.028,-0.0037,-0.11,0.0092,0.0055,0.0034,-0.0014,-0.006,2.6e-05,0.014,0.00095,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.031,0.031,0.0084,0.074,0.074,0.036,2e-06,2e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20890000,-0.29,0.0066,0.0035,0.96,0.028,-0.0047,-0.11,0.0093,0.0048,0.0075,-0.0014,-0.006,2.4e-05,0.0095,0.0026,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00042,0.00042,0.019,0.031,0.031,0.0073,0.074,0.074,0.035,2e-06,2e-06,4.6e-06,0.031,0.031,0.00024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
20990000,-0.28,0.0032,0.0064,0.96,0.04,-0.02,-0.25,0.0063,0.0038,-0.011,-0.0013,-0.006,2.6e-05,0.015,0.00087,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.027,0.027,0.0083,0.06,0.06,0.036,1.8e-06,1.8e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
20990000,-0.29,0.0029,0.0064,0.96,0.04,-0.021,-0.25,0.0064,0.0033,-0.0075,-0.0014,-0.006,2.4e-05,0.0097,0.0024,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.027,0.0072,0.06,0.06,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21090000,-0.28,0.0037,0.0048,0.96,0.056,-0.033,-0.37,0.011,0.0012,-0.042,-0.0013,-0.006,2.6e-05,0.015,0.00088,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.029,0.029,0.0084,0.066,0.066,0.036,1.8e-06,1.8e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21090000,-0.29,0.0034,0.0049,0.96,0.057,-0.034,-0.37,0.011,0.00054,-0.038,-0.0014,-0.006,2.4e-05,0.0097,0.0024,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.00041,0.019,0.029,0.029,0.0073,0.066,0.066,0.035,1.8e-06,1.8e-06,4.6e-06,0.031,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21190000,-0.28,0.0057,0.0022,0.96,0.059,-0.036,-0.5,0.0073,0.0018,-0.078,-0.0013,-0.006,2.5e-05,0.015,0.00027,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0083,0.055,0.055,0.036,1.6e-06,1.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21190000,-0.29,0.0054,0.0022,0.96,0.06,-0.037,-0.49,0.0074,0.0014,-0.075,-0.0013,-0.0059,2.3e-05,0.0099,0.0018,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0072,0.055,0.055,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00023,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21290000,-0.28,0.0072,0.00013,0.96,0.06,-0.04,-0.63,0.013,-0.002,-0.14,-0.0013,-0.006,2.5e-05,0.015,0.0002,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00041,0.0004,0.019,0.028,0.028,0.0083,0.061,0.061,0.036,1.6e-06,1.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21290000,-0.29,0.007,0.00019,0.96,0.06,-0.04,-0.62,0.013,-0.0025,-0.13,-0.0013,-0.0059,2.3e-05,0.0099,0.0017,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.028,0.028,0.0071,0.061,0.061,0.035,1.6e-06,1.6e-06,4.6e-06,0.03,0.031,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21390000,-0.28,0.0081,-0.0015,0.96,0.05,-0.03,-0.75,0.0093,0.0039,-0.2,-0.0012,-0.0059,2.3e-05,0.015,-0.0015,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.027,0.028,0.0082,0.063,0.063,0.036,1.6e-06,1.5e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0
|
21390000,-0.29,0.0079,-0.0014,0.96,0.051,-0.03,-0.75,0.0095,0.0034,-0.2,-0.0013,-0.0059,2.1e-05,0.01,-8.4e-05,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.027,0.028,0.0071,0.063,0.063,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21490000,-0.29,0.0086,-0.0023,0.96,0.045,-0.028,-0.89,0.014,0.0011,-0.29,-0.0012,-0.0059,2.3e-05,0.015,-0.0016,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.03,0.03,0.0083,0.07,0.07,0.036,1.6e-06,1.5e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0
|
21490000,-0.29,0.0084,-0.0022,0.96,0.046,-0.028,-0.89,0.014,0.00052,-0.28,-0.0013,-0.0059,2.1e-05,0.01,-0.00018,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.0004,0.019,0.03,0.03,0.0071,0.07,0.07,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21590000,-0.29,0.0088,-0.003,0.96,0.029,-0.017,-1,0.0066,0.0092,-0.38,-0.0012,-0.0059,2.2e-05,0.015,-0.0036,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.029,0.029,0.0082,0.072,0.072,0.036,1.5e-06,1.5e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0
|
21590000,-0.29,0.0085,-0.0029,0.96,0.03,-0.018,-1,0.0069,0.0086,-0.37,-0.0012,-0.0059,1.9e-05,0.01,-0.0022,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.029,0.029,0.007,0.072,0.072,0.034,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21690000,-0.29,0.0087,-0.0033,0.96,0.026,-0.013,-1.1,0.0094,0.0077,-0.49,-0.0012,-0.0059,2.2e-05,0.015,-0.0038,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.0004,0.00039,0.019,0.032,0.032,0.0082,0.08,0.08,0.036,1.5e-06,1.5e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0
|
21690000,-0.29,0.0085,-0.0033,0.96,0.027,-0.014,-1.1,0.0097,0.0071,-0.49,-0.0012,-0.0059,1.9e-05,0.011,-0.0024,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.032,0.032,0.007,0.08,0.08,0.035,1.5e-06,1.5e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21790000,-0.29,0.0089,-0.0039,0.96,0.017,-0.00064,-1.3,0.0047,0.018,-0.61,-0.0011,-0.0059,2e-05,0.015,-0.0057,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00038,0.02,0.031,0.031,0.0082,0.082,0.082,0.036,1.4e-06,1.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
21790000,-0.29,0.0087,-0.0038,0.96,0.018,-0.0013,-1.3,0.005,0.017,-0.61,-0.0011,-0.0059,1.8e-05,0.011,-0.0042,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00038,0.019,0.031,0.031,0.0069,0.081,0.081,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21890000,-0.29,0.0091,-0.0042,0.96,0.012,0.0038,-1.4,0.0061,0.018,-0.75,-0.0011,-0.0059,2e-05,0.016,-0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.02,0.033,0.034,0.0082,0.09,0.09,0.036,1.4e-06,1.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
21890000,-0.29,0.0088,-0.0041,0.96,0.013,0.0031,-1.4,0.0065,0.017,-0.75,-0.0011,-0.0059,1.8e-05,0.011,-0.0044,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00039,0.019,0.033,0.034,0.0069,0.09,0.09,0.034,1.4e-06,1.4e-06,4.6e-06,0.03,0.03,0.00021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
21990000,-0.29,0.0096,-0.0051,0.96,0.0013,0.014,-1.4,-0.0048,0.028,-0.89,-0.0011,-0.0059,1.9e-05,0.016,-0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.02,0.032,0.032,0.0082,0.091,0.091,0.036,1.3e-06,1.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
21990000,-0.29,0.0094,-0.005,0.96,0.002,0.014,-1.4,-0.0045,0.027,-0.89,-0.0011,-0.0059,1.6e-05,0.011,-0.0063,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.032,0.032,0.0068,0.091,0.091,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22090000,-0.29,0.01,-0.0057,0.96,-0.0024,0.019,-1.4,-0.0049,0.03,-1,-0.0011,-0.0059,1.9e-05,0.016,-0.0078,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00039,0.00038,0.02,0.034,0.034,0.0082,0.1,0.1,0.036,1.3e-06,1.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22090000,-0.29,0.01,-0.0057,0.96,-0.0017,0.018,-1.4,-0.0045,0.029,-1,-0.0011,-0.0059,1.6e-05,0.011,-0.0064,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0068,0.1,0.1,0.034,1.3e-06,1.3e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22190000,-0.29,0.011,-0.0063,0.96,-0.015,0.027,-1.4,-0.014,0.039,-1.2,-0.0011,-0.0059,1.9e-05,0.017,-0.0091,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00037,0.02,0.032,0.032,0.0081,0.1,0.1,0.036,1.2e-06,1.2e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22190000,-0.29,0.011,-0.0062,0.96,-0.014,0.026,-1.4,-0.014,0.038,-1.2,-0.0011,-0.0059,1.5e-05,0.012,-0.0077,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0067,0.1,0.1,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.0002,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22290000,-0.29,0.011,-0.007,0.96,-0.021,0.032,-1.4,-0.016,0.042,-1.3,-0.0011,-0.0059,1.9e-05,0.017,-0.0092,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.02,0.034,0.034,0.0081,0.11,0.11,0.036,1.2e-06,1.2e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22290000,-0.29,0.011,-0.0069,0.96,-0.021,0.031,-1.4,-0.015,0.041,-1.3,-0.0011,-0.0059,1.5e-05,0.012,-0.0078,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00038,0.00038,0.019,0.034,0.034,0.0067,0.11,0.11,0.034,1.2e-06,1.2e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22390000,-0.29,0.012,-0.0073,0.96,-0.031,0.037,-1.4,-0.025,0.045,-1.5,-0.001,-0.0059,1.9e-05,0.018,-0.0096,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.032,0.032,0.0081,0.11,0.11,0.036,1.1e-06,1.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22390000,-0.29,0.011,-0.0072,0.96,-0.031,0.036,-1.4,-0.025,0.044,-1.5,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.032,0.032,0.0066,0.11,0.11,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22490000,-0.29,0.012,-0.0074,0.96,-0.037,0.044,-1.4,-0.029,0.049,-1.6,-0.001,-0.0059,1.9e-05,0.018,-0.0097,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.034,0.034,0.0081,0.12,0.12,0.036,1.1e-06,1.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22490000,-0.29,0.012,-0.0073,0.96,-0.037,0.043,-1.4,-0.028,0.048,-1.6,-0.0011,-0.0059,1.5e-05,0.013,-0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22590000,-0.29,0.013,-0.0072,0.96,-0.042,0.049,-1.4,-0.029,0.053,-1.7,-0.0011,-0.0059,1.9e-05,0.018,-0.0095,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.02,0.032,0.032,0.0081,0.12,0.12,0.036,1.1e-06,1.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22590000,-0.29,0.012,-0.0072,0.96,-0.042,0.049,-1.4,-0.029,0.052,-1.7,-0.0011,-0.0059,1.5e-05,0.013,-0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.032,0.032,0.0065,0.12,0.12,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22690000,-0.29,0.013,-0.0071,0.96,-0.046,0.054,-1.4,-0.034,0.058,-1.9,-0.0011,-0.0059,1.9e-05,0.018,-0.0096,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.034,0.034,0.0081,0.13,0.13,0.036,1.1e-06,1.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22690000,-0.29,0.013,-0.0071,0.96,-0.046,0.054,-1.4,-0.033,0.057,-1.9,-0.0011,-0.0059,1.5e-05,0.013,-0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.034,0.034,0.0066,0.13,0.13,0.034,1.1e-06,1.1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22790000,-0.29,0.013,-0.007,0.96,-0.052,0.057,-1.4,-0.039,0.058,-2,-0.0011,-0.0059,1.9e-05,0.018,-0.0095,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.02,0.032,0.032,0.0081,0.13,0.13,0.036,1e-06,1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22790000,-0.29,0.013,-0.007,0.96,-0.052,0.056,-1.4,-0.039,0.058,-2,-0.0011,-0.0059,1.5e-05,0.013,-0.0081,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0065,0.13,0.13,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22890000,-0.28,0.014,-0.0072,0.96,-0.058,0.063,-1.4,-0.045,0.064,-2.2,-0.0011,-0.0059,1.9e-05,0.018,-0.0095,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.02,0.034,0.034,0.0081,0.14,0.14,0.036,1e-06,1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22890000,-0.29,0.013,-0.0071,0.96,-0.058,0.062,-1.4,-0.045,0.064,-2.2,-0.0011,-0.0059,1.5e-05,0.013,-0.0082,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0065,0.14,0.14,0.034,1e-06,1e-06,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
22990000,-0.28,0.014,-0.007,0.96,-0.062,0.061,-1.4,-0.049,0.061,-2.3,-0.0011,-0.0059,1.9e-05,0.019,-0.0092,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.032,0.032,0.0081,0.14,0.14,0.036,9.6e-07,9.6e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
22990000,-0.29,0.014,-0.0069,0.96,-0.061,0.06,-1.4,-0.049,0.061,-2.3,-0.0011,-0.0059,1.5e-05,0.014,-0.0078,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.032,0.032,0.0064,0.14,0.14,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23090000,-0.28,0.014,-0.007,0.96,-0.068,0.066,-1.4,-0.056,0.068,-2.5,-0.0011,-0.0059,1.9e-05,0.019,-0.0092,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.034,0.034,0.0081,0.15,0.15,0.036,9.6e-07,9.6e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23090000,-0.29,0.014,-0.0069,0.96,-0.068,0.065,-1.4,-0.055,0.067,-2.5,-0.0011,-0.0059,1.5e-05,0.014,-0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0064,0.15,0.15,0.034,9.6e-07,9.6e-07,4.6e-06,0.03,0.03,0.00018,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23190000,-0.28,0.014,-0.0068,0.96,-0.069,0.057,-1.4,-0.054,0.06,-2.6,-0.0011,-0.0059,2e-05,0.019,-0.0084,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.032,0.032,0.008,0.15,0.15,0.035,9.1e-07,9.1e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23190000,-0.29,0.014,-0.0067,0.96,-0.069,0.057,-1.4,-0.054,0.059,-2.6,-0.0011,-0.0059,1.5e-05,0.014,-0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.032,0.032,0.0063,0.15,0.15,0.033,9.1e-07,9.1e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23290000,-0.28,0.015,-0.0072,0.96,-0.075,0.062,-1.4,-0.061,0.066,-2.8,-0.0011,-0.0059,2e-05,0.019,-0.0084,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.034,0.034,0.0081,0.16,0.16,0.036,9.1e-07,9.1e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23290000,-0.29,0.014,-0.0072,0.96,-0.075,0.061,-1.4,-0.061,0.065,-2.8,-0.0011,-0.0059,1.5e-05,0.014,-0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.034,0.034,0.0063,0.16,0.16,0.034,9.1e-07,9.1e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23390000,-0.28,0.015,-0.0071,0.96,-0.073,0.062,-1.4,-0.054,0.065,-2.9,-0.0011,-0.0059,2e-05,0.019,-0.0078,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.032,0.032,0.008,0.16,0.16,0.036,8.6e-07,8.6e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23390000,-0.29,0.014,-0.007,0.96,-0.073,0.061,-1.4,-0.054,0.064,-2.9,-0.0011,-0.0059,1.6e-05,0.014,-0.0065,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.032,0.032,0.0063,0.16,0.16,0.033,8.6e-07,8.6e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23490000,-0.28,0.015,-0.0072,0.96,-0.078,0.064,-1.4,-0.062,0.071,-3,-0.0011,-0.0059,2e-05,0.019,-0.0079,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.033,0.033,0.0081,0.17,0.17,0.036,8.7e-07,8.6e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23490000,-0.29,0.015,-0.0071,0.96,-0.078,0.063,-1.4,-0.061,0.07,-3,-0.0011,-0.0059,1.6e-05,0.014,-0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.033,0.033,0.0063,0.17,0.17,0.033,8.6e-07,8.6e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23590000,-0.28,0.015,-0.0072,0.96,-0.076,0.056,-1.4,-0.056,0.058,-3.2,-0.0012,-0.0059,2e-05,0.019,-0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.031,0.031,0.008,0.17,0.17,0.035,8.2e-07,8.2e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23590000,-0.29,0.015,-0.0072,0.96,-0.076,0.055,-1.4,-0.056,0.057,-3.2,-0.0012,-0.0059,1.7e-05,0.014,-0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0062,0.17,0.17,0.033,8.2e-07,8.2e-07,4.6e-06,0.03,0.03,0.00017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23690000,-0.28,0.015,-0.0078,0.96,-0.075,0.058,-1.3,-0.064,0.063,-3.3,-0.0012,-0.0059,2e-05,0.019,-0.0071,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.033,0.033,0.0081,0.18,0.18,0.036,8.2e-07,8.2e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23690000,-0.29,0.015,-0.0078,0.96,-0.075,0.057,-1.3,-0.063,0.063,-3.3,-0.0012,-0.0059,1.7e-05,0.014,-0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.033,0.033,0.0062,0.18,0.18,0.033,8.2e-07,8.2e-07,4.7e-06,0.03,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23790000,-0.28,0.018,-0.0093,0.96,-0.06,0.054,-0.96,-0.051,0.057,-3.4,-0.0012,-0.0059,2.1e-05,0.019,-0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.03,0.03,0.008,0.18,0.18,0.035,7.9e-07,7.8e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23790000,-0.29,0.018,-0.0092,0.96,-0.06,0.053,-0.95,-0.05,0.057,-3.4,-0.0012,-0.0059,1.7e-05,0.014,-0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.019,0.03,0.03,0.0061,0.18,0.18,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23890000,-0.28,0.023,-0.012,0.96,-0.055,0.055,-0.52,-0.056,0.063,-3.5,-0.0012,-0.0059,2.1e-05,0.019,-0.0066,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.02,0.031,0.031,0.008,0.19,0.19,0.035,7.9e-07,7.8e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23890000,-0.29,0.023,-0.012,0.96,-0.056,0.054,-0.52,-0.056,0.062,-3.5,-0.0012,-0.0059,1.7e-05,0.014,-0.0053,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.019,0.031,0.031,0.0061,0.19,0.19,0.033,7.8e-07,7.8e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
23990000,-0.28,0.025,-0.014,0.96,-0.048,0.051,-0.14,-0.044,0.055,-3.6,-0.0012,-0.0059,2.2e-05,0.02,-0.007,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.029,0.029,0.008,0.19,0.19,0.036,7.5e-07,7.5e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
23990000,-0.29,0.025,-0.014,0.96,-0.049,0.05,-0.13,-0.044,0.055,-3.6,-0.0012,-0.0059,1.8e-05,0.015,-0.0058,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.029,0.029,0.0061,0.19,0.19,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24090000,-0.28,0.024,-0.014,0.96,-0.056,0.058,0.09,-0.049,0.061,-3.6,-0.0012,-0.0059,2.2e-05,0.02,-0.007,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.02,0.03,0.03,0.0081,0.2,0.2,0.036,7.5e-07,7.5e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24090000,-0.29,0.024,-0.014,0.96,-0.057,0.057,0.099,-0.049,0.06,-3.6,-0.0012,-0.0059,1.8e-05,0.015,-0.0059,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00037,0.019,0.03,0.03,0.0061,0.2,0.2,0.033,7.5e-07,7.5e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24190000,-0.28,0.02,-0.011,0.96,-0.059,0.053,0.077,-0.035,0.045,-3.6,-0.0013,-0.0059,2.3e-05,0.02,-0.0084,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.029,0.029,0.008,0.2,0.2,0.035,7.2e-07,7.2e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24190000,-0.29,0.02,-0.011,0.96,-0.059,0.052,0.088,-0.034,0.045,-3.6,-0.0013,-0.0059,1.8e-05,0.016,-0.0073,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.019,0.029,0.029,0.006,0.2,0.2,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24290000,-0.28,0.017,-0.009,0.96,-0.063,0.056,0.055,-0.041,0.051,-3.6,-0.0013,-0.0059,2.3e-05,0.02,-0.0084,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.031,0.031,0.0081,0.21,0.21,0.036,7.3e-07,7.2e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24290000,-0.29,0.016,-0.009,0.96,-0.064,0.055,0.066,-0.04,0.05,-3.6,-0.0013,-0.0059,1.8e-05,0.016,-0.0073,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.031,0.031,0.0061,0.21,0.21,0.033,7.2e-07,7.2e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24390000,-0.28,0.015,-0.0082,0.96,-0.044,0.049,0.071,-0.019,0.04,-3.6,-0.0013,-0.0059,2.4e-05,0.021,-0.0094,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.029,0.029,0.008,0.21,0.21,0.035,7e-07,7e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24390000,-0.29,0.015,-0.0082,0.96,-0.045,0.048,0.083,-0.019,0.04,-3.6,-0.0013,-0.0059,1.9e-05,0.016,-0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.21,0.21,0.033,7e-07,6.9e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24490000,-0.28,0.015,-0.0085,0.96,-0.039,0.047,0.069,-0.023,0.045,-3.6,-0.0013,-0.0059,2.4e-05,0.021,-0.0094,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.03,0.03,0.008,0.22,0.22,0.035,7e-07,7e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24490000,-0.29,0.015,-0.0084,0.96,-0.039,0.046,0.08,-0.023,0.045,-3.6,-0.0013,-0.0059,1.9e-05,0.016,-0.0083,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.03,0.03,0.006,0.22,0.22,0.033,7e-07,7e-07,4.7e-06,0.029,0.03,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24590000,-0.28,0.016,-0.0091,0.96,-0.026,0.044,0.065,-0.0027,0.038,-3.6,-0.0013,-0.006,2.5e-05,0.021,-0.01,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.029,0.029,0.008,0.22,0.22,0.036,6.7e-07,6.7e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24590000,-0.29,0.015,-0.009,0.96,-0.026,0.043,0.076,-0.0024,0.038,-3.6,-0.0013,-0.006,2e-05,0.017,-0.009,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.006,0.22,0.22,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24690000,-0.28,0.015,-0.0096,0.96,-0.023,0.043,0.064,-0.0051,0.042,-3.6,-0.0013,-0.006,2.5e-05,0.021,-0.01,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.03,0.03,0.0081,0.23,0.23,0.036,6.7e-07,6.7e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24690000,-0.29,0.015,-0.0095,0.96,-0.023,0.043,0.075,-0.0049,0.042,-3.5,-0.0013,-0.006,2e-05,0.017,-0.009,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.006,0.23,0.23,0.033,6.7e-07,6.7e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24790000,-0.28,0.015,-0.0097,0.96,-0.015,0.041,0.055,0.0084,0.033,-3.6,-0.0014,-0.006,2.6e-05,0.022,-0.011,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.029,0.029,0.008,0.23,0.23,0.035,6.5e-07,6.5e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24790000,-0.29,0.015,-0.0097,0.96,-0.015,0.04,0.067,0.0087,0.033,-3.5,-0.0014,-0.006,2e-05,0.017,-0.0095,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24890000,-0.28,0.014,-0.0096,0.96,-0.013,0.045,0.045,0.007,0.038,-3.6,-0.0014,-0.006,2.6e-05,0.022,-0.011,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.03,0.03,0.008,0.24,0.24,0.035,6.5e-07,6.5e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24890000,-0.29,0.014,-0.0095,0.96,-0.013,0.044,0.057,0.0073,0.037,-3.5,-0.0014,-0.006,2e-05,0.017,-0.0096,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.24,0.24,0.032,6.5e-07,6.5e-07,4.7e-06,0.029,0.029,0.00015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
24990000,-0.28,0.014,-0.0094,0.96,0.00051,0.045,0.037,0.022,0.031,-3.6,-0.0014,-0.006,2.7e-05,0.022,-0.011,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.008,0.23,0.23,0.035,6.3e-07,6.2e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
24990000,-0.29,0.014,-0.0093,0.96,-4e-05,0.044,0.049,0.022,0.031,-3.5,-0.0014,-0.006,2.1e-05,0.017,-0.01,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.019,0.029,0.029,0.0059,0.23,0.23,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25090000,-0.28,0.014,-0.0097,0.96,0.0051,0.045,0.035,0.022,0.035,-3.6,-0.0014,-0.006,2.7e-05,0.022,-0.011,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.03,0.03,0.0081,0.25,0.25,0.035,6.3e-07,6.3e-07,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
25090000,-0.29,0.014,-0.0096,0.96,0.0046,0.044,0.047,0.023,0.035,-3.5,-0.0014,-0.006,2.1e-05,0.017,-0.01,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0059,0.25,0.25,0.032,6.3e-07,6.2e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25190000,-0.28,0.014,-0.0099,0.96,0.015,0.039,0.035,0.037,0.023,-3.6,-0.0014,-0.006,2.8e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.029,0.008,0.24,0.24,0.035,6.1e-07,6e-07,6.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
25190000,-0.29,0.014,-0.0099,0.96,0.015,0.038,0.047,0.037,0.023,-3.5,-0.0014,-0.006,2.2e-05,0.018,-0.011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.029,0.029,0.0058,0.24,0.24,0.032,6e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25290000,-0.28,0.013,-0.01,0.96,0.021,0.041,0.029,0.039,0.027,-3.6,-0.0014,-0.006,2.8e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0081,0.26,0.26,0.036,6.1e-07,6e-07,6.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
25290000,-0.29,0.013,-0.01,0.96,0.02,0.041,0.042,0.039,0.027,-3.5,-0.0014,-0.006,2.2e-05,0.018,-0.011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.019,0.03,0.03,0.0058,0.26,0.26,0.032,6.1e-07,6e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25390000,-0.28,0.013,-0.01,0.96,0.029,0.039,0.028,0.046,0.021,-3.6,-0.0014,-0.006,2.9e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.008,0.25,0.25,0.035,5.9e-07,5.8e-07,6.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
25390000,-0.29,0.013,-0.01,0.96,0.028,0.039,0.041,0.046,0.021,-3.5,-0.0014,-0.006,2.3e-05,0.018,-0.011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.25,0.25,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25490000,-0.28,0.013,-0.01,0.96,0.035,0.04,0.027,0.049,0.025,-3.6,-0.0014,-0.006,2.9e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.008,0.27,0.27,0.035,5.9e-07,5.8e-07,6.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
25490000,-0.29,0.013,-0.01,0.96,0.035,0.04,0.04,0.049,0.024,-3.5,-0.0014,-0.006,2.3e-05,0.018,-0.011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.27,0.27,0.032,5.9e-07,5.8e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25590000,-0.28,0.013,-0.01,0.96,0.039,0.034,0.028,0.054,0.0079,-3.6,-0.0014,-0.006,3.1e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.008,0.26,0.26,0.035,5.7e-07,5.7e-07,6.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
25590000,-0.29,0.012,-0.01,0.96,0.039,0.034,0.041,0.054,0.0078,-3.5,-0.0014,-0.006,2.4e-05,0.018,-0.011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0058,0.26,0.26,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25690000,-0.28,0.012,-0.0099,0.96,0.041,0.033,0.017,0.058,0.011,-3.6,-0.0014,-0.006,3.1e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0081,0.28,0.28,0.035,5.7e-07,5.7e-07,6.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0
|
25690000,-0.29,0.012,-0.0098,0.96,0.041,0.033,0.031,0.058,0.011,-3.5,-0.0014,-0.006,2.4e-05,0.018,-0.011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0058,0.28,0.28,0.032,5.7e-07,5.7e-07,4.7e-06,0.029,0.029,0.00014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25790000,-0.28,0.011,-0.0097,0.96,0.05,0.028,0.017,0.062,0.0007,-3.6,-0.0015,-0.006,3.2e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.008,0.27,0.27,0.035,5.5e-07,5.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
25790000,-0.29,0.011,-0.0097,0.96,0.05,0.027,0.03,0.062,0.00063,-3.5,-0.0015,-0.006,2.5e-05,0.018,-0.011,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.27,0.27,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25890000,-0.28,0.012,-0.0098,0.96,0.057,0.027,0.019,0.067,0.0034,-3.6,-0.0015,-0.006,3.2e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0081,0.28,0.28,0.036,5.5e-07,5.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
25890000,-0.29,0.011,-0.0097,0.96,0.057,0.026,0.033,0.068,0.0033,-3.5,-0.0015,-0.006,2.5e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.28,0.28,0.032,5.5e-07,5.5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
25990000,-0.28,0.012,-0.0098,0.96,0.056,0.02,0.012,0.058,-0.0086,-3.6,-0.0015,-0.0059,3.3e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.008,0.28,0.28,0.035,5.4e-07,5.3e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
25990000,-0.29,0.012,-0.0097,0.96,0.056,0.02,0.026,0.059,-0.0087,-3.5,-0.0015,-0.0059,2.6e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0057,0.28,0.28,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26090000,-0.28,0.012,-0.0095,0.96,0.062,0.021,0.011,0.064,-0.0066,-3.6,-0.0015,-0.0059,3.3e-05,0.022,-0.012,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0081,0.29,0.29,0.035,5.4e-07,5.3e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26090000,-0.29,0.012,-0.0095,0.96,0.062,0.021,0.025,0.064,-0.0067,-3.5,-0.0015,-0.0059,2.6e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.03,0.03,0.0057,0.29,0.29,0.032,5.3e-07,5.3e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26190000,-0.28,0.012,-0.0093,0.96,0.064,0.011,0.0062,0.062,-0.023,-3.6,-0.0015,-0.0059,3.5e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.008,0.29,0.29,0.035,5.2e-07,5.2e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26190000,-0.29,0.012,-0.0093,0.96,0.063,0.011,0.02,0.062,-0.023,-3.5,-0.0015,-0.0059,2.8e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0056,0.29,0.29,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26290000,-0.28,0.013,-0.0093,0.96,0.066,0.01,0.0004,0.068,-0.022,-3.6,-0.0015,-0.0059,3.5e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.029,0.03,0.0081,0.3,0.3,0.036,5.2e-07,5.2e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26290000,-0.29,0.012,-0.0093,0.96,0.065,0.01,0.015,0.069,-0.022,-3.5,-0.0015,-0.0059,2.8e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.03,0.0057,0.3,0.3,0.032,5.2e-07,5.2e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26390000,-0.28,0.013,-0.0087,0.96,0.06,0.00024,0.0044,0.055,-0.037,-3.6,-0.0015,-0.0059,3.7e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.028,0.028,0.008,0.3,0.3,0.035,5.1e-07,5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26390000,-0.29,0.012,-0.0087,0.96,0.06,8e-05,0.019,0.056,-0.037,-3.5,-0.0015,-0.0059,2.9e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.028,0.028,0.0056,0.3,0.3,0.032,5e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26490000,-0.28,0.012,-0.0085,0.96,0.064,-0.0023,0.014,0.061,-0.037,-3.6,-0.0015,-0.0059,3.7e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.029,0.029,0.008,0.31,0.31,0.035,5.1e-07,5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26490000,-0.29,0.012,-0.0084,0.96,0.064,-0.0025,0.028,0.062,-0.037,-3.5,-0.0015,-0.0059,2.9e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.02,0.029,0.029,0.0056,0.31,0.31,0.032,5.1e-07,5e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26590000,-0.28,0.013,-0.0079,0.96,0.061,-0.013,0.014,0.056,-0.05,-3.6,-0.0015,-0.0059,3.8e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.028,0.028,0.008,0.31,0.31,0.035,4.9e-07,4.9e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26590000,-0.29,0.013,-0.0078,0.96,0.06,-0.013,0.028,0.057,-0.05,-3.5,-0.0015,-0.0059,3e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.028,0.028,0.0056,0.31,0.31,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26690000,-0.28,0.012,-0.0078,0.96,0.063,-0.018,0.012,0.062,-0.052,-3.6,-0.0015,-0.0059,3.8e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.029,0.029,0.0081,0.32,0.32,0.035,4.9e-07,4.9e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26690000,-0.29,0.012,-0.0077,0.96,0.063,-0.018,0.027,0.063,-0.052,-3.5,-0.0015,-0.0059,3e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.32,0.32,0.032,4.9e-07,4.9e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26790000,-0.28,0.012,-0.0076,0.96,0.063,-0.025,0.012,0.055,-0.065,-3.6,-0.0015,-0.0059,4e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.028,0.008,0.31,0.31,0.035,4.8e-07,4.8e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26790000,-0.29,0.012,-0.0076,0.96,0.063,-0.025,0.026,0.055,-0.065,-3.5,-0.0015,-0.0059,3.1e-05,0.018,-0.012,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.028,0.0056,0.31,0.31,0.031,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26890000,-0.28,0.012,-0.0069,0.96,0.069,-0.027,0.0069,0.062,-0.067,-3.6,-0.0015,-0.0059,4e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.029,0.029,0.0081,0.33,0.33,0.036,4.8e-07,4.8e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26890000,-0.29,0.012,-0.0069,0.96,0.069,-0.028,0.022,0.062,-0.067,-3.5,-0.0015,-0.0059,3.1e-05,0.018,-0.013,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.33,0.33,0.032,4.8e-07,4.8e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
26990000,-0.28,0.013,-0.0063,0.96,0.067,-0.034,0.006,0.05,-0.073,-3.6,-0.0015,-0.0059,4.1e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.027,0.027,0.008,0.32,0.32,0.035,4.7e-07,4.7e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
26990000,-0.29,0.012,-0.0063,0.96,0.067,-0.034,0.021,0.051,-0.073,-3.5,-0.0015,-0.0058,3.2e-05,0.018,-0.013,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.32,0.32,0.031,4.7e-07,4.6e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27090000,-0.28,0.013,-0.0062,0.96,0.07,-0.041,0.0088,0.057,-0.077,-3.6,-0.0015,-0.0059,4.1e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.029,0.029,0.0081,0.34,0.34,0.035,4.7e-07,4.7e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27090000,-0.29,0.013,-0.0061,0.96,0.07,-0.041,0.024,0.058,-0.077,-3.5,-0.0015,-0.0058,3.1e-05,0.019,-0.013,-0.13,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.029,0.029,0.0056,0.34,0.34,0.031,4.7e-07,4.7e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27190000,-0.28,0.013,-0.0062,0.96,0.068,-0.044,0.011,0.043,-0.079,-3.6,-0.0015,-0.0058,4.1e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.027,0.027,0.008,0.33,0.33,0.035,4.6e-07,4.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27190000,-0.29,0.013,-0.0062,0.96,0.068,-0.044,0.027,0.044,-0.079,-3.5,-0.0015,-0.0058,3.2e-05,0.019,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.027,0.027,0.0055,0.33,0.33,0.032,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27290000,-0.28,0.014,-0.0063,0.96,0.075,-0.049,0.12,0.05,-0.083,-3.6,-0.0015,-0.0058,4.1e-05,0.022,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.028,0.029,0.0081,0.35,0.35,0.035,4.6e-07,4.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27290000,-0.29,0.014,-0.0063,0.96,0.075,-0.049,0.14,0.051,-0.083,-3.5,-0.0015,-0.0058,3.2e-05,0.019,-0.013,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.028,0.029,0.0055,0.35,0.35,0.031,4.6e-07,4.5e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27390000,-0.28,0.017,-0.0076,0.96,0.071,-0.04,0.45,0.015,-0.029,-3.5,-0.0014,-0.0058,4.1e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.02,0.02,0.008,0.15,0.15,0.035,4.4e-07,4.4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27390000,-0.29,0.016,-0.0076,0.96,0.071,-0.04,0.46,0.015,-0.029,-3.5,-0.0014,-0.0058,3.1e-05,0.019,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0055,0.15,0.15,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27490000,-0.28,0.019,-0.0088,0.96,0.075,-0.045,0.76,0.022,-0.033,-3.5,-0.0014,-0.0058,4.1e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.021,0.021,0.008,0.16,0.16,0.035,4.5e-07,4.4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27490000,-0.29,0.018,-0.0087,0.96,0.075,-0.045,0.78,0.022,-0.033,-3.5,-0.0014,-0.0058,3.1e-05,0.019,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0055,0.16,0.16,0.031,4.4e-07,4.4e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27590000,-0.28,0.017,-0.0088,0.96,0.063,-0.046,0.85,0.011,-0.021,-3.4,-0.0014,-0.0058,4.1e-05,0.022,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.018,0.018,0.008,0.1,0.1,0.035,4.4e-07,4.3e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27590000,-0.29,0.017,-0.0088,0.96,0.063,-0.046,0.87,0.011,-0.021,-3.4,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27690000,-0.28,0.014,-0.0079,0.96,0.058,-0.043,0.76,0.017,-0.026,-3.3,-0.0014,-0.0058,4.1e-05,0.022,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.019,0.019,0.0081,0.1,0.1,0.035,4.4e-07,4.3e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27690000,-0.29,0.014,-0.0079,0.96,0.058,-0.044,0.78,0.017,-0.026,-3.3,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.1,0.1,0.031,4.3e-07,4.3e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27790000,-0.28,0.013,-0.0067,0.96,0.053,-0.04,0.75,0.012,-0.02,-3.3,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.018,0.018,0.008,0.076,0.076,0.035,4.3e-07,4.2e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27790000,-0.29,0.013,-0.0067,0.96,0.053,-0.041,0.77,0.012,-0.02,-3.2,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.018,0.0054,0.076,0.076,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27890000,-0.28,0.013,-0.0064,0.96,0.061,-0.046,0.79,0.018,-0.025,-3.2,-0.0014,-0.0058,4.2e-05,0.022,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.019,0.019,0.0081,0.08,0.08,0.036,4.3e-07,4.2e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27890000,-0.29,0.013,-0.0064,0.96,0.061,-0.046,0.81,0.018,-0.025,-3.2,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0055,0.08,0.08,0.031,4.3e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
27990000,-0.28,0.013,-0.0068,0.96,0.06,-0.049,0.78,0.02,-0.027,-3.1,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.019,0.019,0.008,0.082,0.082,0.035,4.2e-07,4.2e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
27990000,-0.29,0.013,-0.0068,0.96,0.06,-0.049,0.8,0.02,-0.027,-3.1,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0054,0.082,0.082,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28090000,-0.28,0.013,-0.007,0.96,0.063,-0.049,0.78,0.027,-0.032,-3,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.02,0.02,0.008,0.086,0.086,0.035,4.2e-07,4.2e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28090000,-0.29,0.013,-0.0071,0.96,0.063,-0.049,0.8,0.027,-0.032,-3,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.02,0.02,0.02,0.0054,0.086,0.086,0.031,4.2e-07,4.2e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28190000,-0.28,0.014,-0.0064,0.96,0.059,-0.047,0.79,0.026,-0.035,-3,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.02,0.02,0.008,0.089,0.089,0.035,4.1e-07,4.1e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28190000,-0.29,0.014,-0.0065,0.96,0.059,-0.047,0.81,0.026,-0.035,-2.9,-0.0014,-0.0058,3.1e-05,0.02,-0.015,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.02,0.02,0.0054,0.089,0.089,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28290000,-0.28,0.014,-0.0059,0.96,0.064,-0.049,0.79,0.033,-0.039,-2.9,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.021,0.021,0.0081,0.093,0.093,0.035,4.2e-07,4.1e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28290000,-0.29,0.014,-0.006,0.96,0.064,-0.049,0.81,0.033,-0.04,-2.9,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.093,0.093,0.031,4.1e-07,4.1e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28390000,-0.28,0.014,-0.0059,0.96,0.064,-0.05,0.79,0.034,-0.04,-2.8,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.021,0.021,0.008,0.096,0.096,0.035,4.1e-07,4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28390000,-0.29,0.014,-0.0059,0.96,0.064,-0.05,0.81,0.034,-0.04,-2.8,-0.0014,-0.0058,3e-05,0.02,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.021,0.021,0.0054,0.096,0.096,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28490000,-0.28,0.015,-0.0061,0.96,0.065,-0.054,0.79,0.04,-0.045,-2.8,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.022,0.022,0.0081,0.1,0.1,0.036,4.1e-07,4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28490000,-0.29,0.015,-0.0062,0.96,0.066,-0.054,0.81,0.04,-0.045,-2.7,-0.0014,-0.0058,3e-05,0.02,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.022,0.022,0.0054,0.1,0.1,0.031,4.1e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28590000,-0.28,0.015,-0.0062,0.96,0.057,-0.053,0.79,0.039,-0.048,-2.7,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.021,0.021,0.008,0.1,0.1,0.035,4e-07,3.9e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28590000,-0.29,0.015,-0.0062,0.96,0.057,-0.053,0.81,0.039,-0.048,-2.6,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.021,0.021,0.0054,0.1,0.1,0.031,4e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28690000,-0.28,0.014,-0.006,0.96,0.056,-0.055,0.79,0.045,-0.053,-2.6,-0.0014,-0.0058,4.2e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.023,0.023,0.008,0.11,0.11,0.035,4e-07,4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28690000,-0.29,0.014,-0.006,0.96,0.056,-0.055,0.81,0.045,-0.053,-2.6,-0.0014,-0.0058,3.1e-05,0.02,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0054,0.11,0.11,0.031,4e-07,4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28790000,-0.28,0.014,-0.0054,0.96,0.053,-0.052,0.79,0.045,-0.051,-2.5,-0.0014,-0.0058,4.1e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.022,0.022,0.008,0.11,0.11,0.035,3.9e-07,3.9e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28790000,-0.29,0.014,-0.0054,0.96,0.053,-0.052,0.81,0.045,-0.051,-2.5,-0.0014,-0.0058,2.9e-05,0.021,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0053,0.11,0.11,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28890000,-0.28,0.014,-0.0052,0.96,0.056,-0.053,0.78,0.05,-0.056,-2.5,-0.0014,-0.0058,4.1e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.023,0.023,0.0081,0.12,0.12,0.036,3.9e-07,3.9e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28890000,-0.29,0.014,-0.0053,0.96,0.056,-0.053,0.81,0.05,-0.056,-2.4,-0.0014,-0.0058,2.9e-05,0.021,-0.016,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0054,0.12,0.12,0.031,3.9e-07,3.9e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
28990000,-0.28,0.014,-0.005,0.96,0.053,-0.051,0.78,0.05,-0.056,-2.4,-0.0013,-0.0058,4.1e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.023,0.023,0.008,0.12,0.12,0.035,3.8e-07,3.8e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
28990000,-0.29,0.014,-0.0051,0.96,0.053,-0.051,0.81,0.05,-0.056,-2.3,-0.0013,-0.0058,2.9e-05,0.021,-0.017,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.12,0.12,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29090000,-0.28,0.014,-0.0048,0.96,0.055,-0.053,0.78,0.055,-0.061,-2.3,-0.0013,-0.0058,4.1e-05,0.022,-0.014,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.021,0.024,0.024,0.008,0.13,0.13,0.035,3.9e-07,3.8e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29090000,-0.29,0.014,-0.0049,0.96,0.055,-0.053,0.81,0.055,-0.061,-2.3,-0.0013,-0.0058,2.9e-05,0.021,-0.017,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.13,0.13,0.031,3.8e-07,3.8e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29190000,-0.28,0.014,-0.0048,0.96,0.055,-0.05,0.78,0.056,-0.058,-2.2,-0.0013,-0.0058,4e-05,0.022,-0.014,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.021,0.023,0.023,0.008,0.13,0.13,0.035,3.8e-07,3.7e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29190000,-0.29,0.014,-0.0049,0.96,0.055,-0.05,0.8,0.056,-0.058,-2.2,-0.0013,-0.0058,2.8e-05,0.021,-0.017,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.023,0.023,0.0053,0.13,0.13,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29290000,-0.28,0.014,-0.005,0.96,0.057,-0.056,0.78,0.061,-0.064,-2.2,-0.0013,-0.0058,4e-05,0.022,-0.014,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.025,0.025,0.008,0.14,0.14,0.035,3.8e-07,3.7e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29290000,-0.29,0.014,-0.0051,0.96,0.057,-0.056,0.81,0.061,-0.064,-2.1,-0.0013,-0.0058,2.8e-05,0.022,-0.017,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.14,0.14,0.031,3.8e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29390000,-0.28,0.014,-0.0055,0.96,0.053,-0.052,0.78,0.058,-0.059,-2.1,-0.0013,-0.0058,3.9e-05,0.022,-0.014,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.024,0.024,0.008,0.14,0.14,0.035,3.7e-07,3.7e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29390000,-0.29,0.014,-0.0057,0.96,0.053,-0.052,0.81,0.058,-0.059,-2,-0.0013,-0.0058,2.7e-05,0.022,-0.018,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.14,0.14,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29490000,-0.28,0.013,-0.0056,0.96,0.055,-0.052,0.78,0.063,-0.065,-2,-0.0013,-0.0058,3.9e-05,0.022,-0.014,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.025,0.025,0.008,0.15,0.15,0.036,3.7e-07,3.7e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29490000,-0.29,0.014,-0.0057,0.96,0.055,-0.052,0.81,0.063,-0.065,-2,-0.0013,-0.0058,2.7e-05,0.022,-0.018,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.15,0.15,0.031,3.7e-07,3.7e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29590000,-0.28,0.013,-0.0055,0.96,0.051,-0.049,0.78,0.06,-0.061,-1.9,-0.0013,-0.0058,3.9e-05,0.022,-0.014,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.024,0.024,0.008,0.15,0.15,0.035,3.6e-07,3.6e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29590000,-0.29,0.013,-0.0056,0.96,0.051,-0.049,0.81,0.06,-0.061,-1.9,-0.0013,-0.0058,2.6e-05,0.022,-0.018,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.15,0.15,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29690000,-0.28,0.013,-0.0055,0.96,0.054,-0.048,0.78,0.065,-0.066,-1.9,-0.0013,-0.0058,3.9e-05,0.022,-0.015,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.025,0.025,0.008,0.16,0.16,0.035,3.7e-07,3.6e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29690000,-0.29,0.013,-0.0057,0.96,0.054,-0.047,0.81,0.065,-0.066,-1.8,-0.0013,-0.0058,2.6e-05,0.022,-0.018,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.16,0.16,0.031,3.6e-07,3.6e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29790000,-0.28,0.014,-0.0053,0.96,0.051,-0.04,0.78,0.061,-0.061,-1.8,-0.0013,-0.0058,3.8e-05,0.022,-0.015,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.024,0.024,0.008,0.16,0.16,0.035,3.6e-07,3.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29790000,-0.29,0.014,-0.0055,0.96,0.051,-0.04,0.8,0.062,-0.061,-1.7,-0.0013,-0.0058,2.5e-05,0.022,-0.019,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.024,0.024,0.0053,0.16,0.16,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29890000,-0.28,0.014,-0.0048,0.96,0.051,-0.041,0.77,0.066,-0.065,-1.7,-0.0013,-0.0058,3.8e-05,0.022,-0.015,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.026,0.026,0.008,0.17,0.17,0.035,3.6e-07,3.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29890000,-0.29,0.014,-0.0049,0.96,0.051,-0.041,0.8,0.066,-0.065,-1.7,-0.0013,-0.0058,2.5e-05,0.023,-0.019,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.17,0.17,0.031,3.6e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
29990000,-0.28,0.014,-0.0049,0.96,0.046,-0.039,0.77,0.061,-0.064,-1.6,-0.0013,-0.0058,3.9e-05,0.022,-0.015,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.025,0.025,0.008,0.17,0.17,0.035,3.5e-07,3.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
29990000,-0.29,0.014,-0.005,0.96,0.046,-0.038,0.8,0.061,-0.064,-1.6,-0.0013,-0.0058,2.5e-05,0.023,-0.02,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0053,0.17,0.17,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30090000,-0.28,0.014,-0.005,0.96,0.046,-0.039,0.77,0.065,-0.068,-1.6,-0.0013,-0.0058,3.9e-05,0.023,-0.015,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.026,0.026,0.008,0.18,0.18,0.035,3.5e-07,3.5e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
30090000,-0.29,0.014,-0.0052,0.96,0.046,-0.039,0.8,0.065,-0.068,-1.5,-0.0013,-0.0058,2.5e-05,0.023,-0.02,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.18,0.18,0.031,3.5e-07,3.5e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30190000,-0.28,0.014,-0.005,0.96,0.041,-0.033,0.77,0.059,-0.059,-1.5,-0.0013,-0.0058,3.8e-05,0.023,-0.015,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.025,0.025,0.008,0.18,0.18,0.035,3.5e-07,3.4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
30190000,-0.29,0.014,-0.0052,0.96,0.041,-0.033,0.8,0.059,-0.059,-1.5,-0.0013,-0.0058,2.4e-05,0.023,-0.02,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.18,0.18,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.00011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30290000,-0.28,0.014,-0.005,0.96,0.039,-0.033,0.77,0.063,-0.062,-1.4,-0.0013,-0.0058,3.8e-05,0.023,-0.016,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.026,0.026,0.008,0.19,0.19,0.035,3.5e-07,3.4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
30290000,-0.29,0.014,-0.0052,0.96,0.039,-0.033,0.8,0.063,-0.062,-1.4,-0.0013,-0.0058,2.3e-05,0.024,-0.021,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0053,0.19,0.19,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30390000,-0.28,0.014,-0.0051,0.96,0.036,-0.026,0.76,0.062,-0.055,-1.4,-0.0013,-0.0058,3.7e-05,0.023,-0.016,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.021,0.025,0.025,0.0079,0.19,0.19,0.035,3.4e-07,3.3e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
30390000,-0.29,0.014,-0.0053,0.96,0.036,-0.026,0.79,0.062,-0.055,-1.3,-0.0012,-0.0058,2.2e-05,0.024,-0.021,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.19,0.19,0.03,3.4e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30490000,-0.28,0.014,-0.005,0.96,0.038,-0.026,0.77,0.065,-0.057,-1.3,-0.0013,-0.0058,3.7e-05,0.023,-0.016,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.022,0.026,0.026,0.008,0.2,0.2,0.035,3.4e-07,3.4e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
30490000,-0.29,0.014,-0.0053,0.96,0.038,-0.026,0.8,0.065,-0.057,-1.2,-0.0012,-0.0058,2.2e-05,0.024,-0.022,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.2,0.2,0.031,3.4e-07,3.4e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30590000,-0.28,0.014,-0.0053,0.96,0.037,-0.023,0.77,0.062,-0.053,-1.2,-0.0012,-0.0058,3.7e-05,0.023,-0.016,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.022,0.025,0.025,0.0079,0.2,0.2,0.035,3.3e-07,3.3e-07,6.4e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0
|
30590000,-0.29,0.015,-0.0056,0.96,0.037,-0.023,0.8,0.062,-0.053,-1.2,-0.0012,-0.0058,2.2e-05,0.024,-0.022,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.2,0.2,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30690000,-0.28,0.015,-0.0057,0.96,0.034,-0.022,0.76,0.065,-0.055,-1.1,-0.0012,-0.0058,3.7e-05,0.023,-0.016,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.022,0.026,0.026,0.008,0.21,0.21,0.035,3.4e-07,3.3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
30690000,-0.29,0.015,-0.0059,0.96,0.034,-0.022,0.8,0.065,-0.055,-1.1,-0.0012,-0.0058,2.2e-05,0.025,-0.022,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.21,0.21,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30790000,-0.28,0.014,-0.0055,0.96,0.027,-0.012,0.76,0.057,-0.042,-1.1,-0.0012,-0.0058,3.6e-05,0.023,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.022,0.025,0.025,0.008,0.21,0.21,0.035,3.3e-07,3.2e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
30790000,-0.29,0.014,-0.0057,0.96,0.027,-0.012,0.79,0.058,-0.042,-1,-0.0012,-0.0058,2e-05,0.025,-0.023,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.21,0.21,0.03,3.3e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30890000,-0.28,0.014,-0.0049,0.96,0.026,-0.0087,0.76,0.06,-0.043,-1,-0.0012,-0.0058,3.6e-05,0.023,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.022,0.026,0.026,0.008,0.22,0.22,0.035,3.3e-07,3.3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
30890000,-0.29,0.014,-0.0051,0.96,0.026,-0.0085,0.79,0.06,-0.043,-0.95,-0.0012,-0.0058,2e-05,0.025,-0.023,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.22,0.22,0.03,3.3e-07,3.3e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
30990000,-0.28,0.014,-0.005,0.96,0.023,-0.0073,0.76,0.057,-0.043,-0.94,-0.0012,-0.0058,3.6e-05,0.023,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.025,0.025,0.0079,0.22,0.22,0.035,3.2e-07,3.2e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
30990000,-0.29,0.014,-0.0053,0.96,0.023,-0.0071,0.79,0.057,-0.042,-0.88,-0.0012,-0.0058,2e-05,0.026,-0.024,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.02,0.025,0.025,0.0052,0.22,0.22,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31090000,-0.28,0.014,-0.0051,0.96,0.022,-0.0063,0.76,0.059,-0.043,-0.86,-0.0012,-0.0058,3.6e-05,0.023,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.022,0.026,0.026,0.008,0.23,0.23,0.036,3.3e-07,3.2e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31090000,-0.29,0.014,-0.0054,0.96,0.021,-0.0061,0.79,0.059,-0.043,-0.81,-0.0012,-0.0058,2e-05,0.026,-0.024,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.026,0.026,0.0052,0.23,0.23,0.031,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31190000,-0.28,0.014,-0.0053,0.96,0.019,-0.002,0.76,0.055,-0.038,-0.79,-0.0012,-0.0058,3.6e-05,0.023,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.025,0.025,0.0079,0.23,0.23,0.035,3.2e-07,3.2e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31190000,-0.29,0.014,-0.0056,0.96,0.019,-0.0017,0.8,0.055,-0.038,-0.74,-0.0012,-0.0058,2e-05,0.026,-0.025,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0052,0.23,0.23,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31290000,-0.28,0.014,-0.0055,0.96,0.016,0.00039,0.76,0.056,-0.038,-0.72,-0.0012,-0.0058,3.6e-05,0.023,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00036,0.022,0.026,0.026,0.008,0.24,0.24,0.035,3.2e-07,3.2e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31290000,-0.29,0.015,-0.0058,0.96,0.016,0.0006,0.8,0.056,-0.038,-0.67,-0.0012,-0.0058,1.9e-05,0.026,-0.025,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.24,0.24,0.03,3.2e-07,3.2e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31390000,-0.28,0.014,-0.0053,0.96,0.011,0.0042,0.76,0.05,-0.036,-0.65,-0.0012,-0.0058,3.6e-05,0.024,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.022,0.025,0.025,0.0079,0.24,0.24,0.035,3.2e-07,3.1e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31390000,-0.29,0.014,-0.0056,0.96,0.011,0.0044,0.8,0.05,-0.036,-0.59,-0.0012,-0.0058,1.9e-05,0.027,-0.025,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.24,0.24,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31490000,-0.28,0.014,-0.005,0.96,0.011,0.0071,0.76,0.051,-0.035,-0.58,-0.0012,-0.0058,3.6e-05,0.024,-0.017,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.026,0.026,0.008,0.25,0.25,0.035,3.2e-07,3.1e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31490000,-0.29,0.015,-0.0053,0.96,0.0098,0.0073,0.8,0.051,-0.035,-0.52,-0.0012,-0.0058,1.9e-05,0.027,-0.025,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.026,0.026,0.0052,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31590000,-0.28,0.015,-0.0048,0.96,0.011,0.0092,0.76,0.05,-0.032,-0.51,-0.0012,-0.0058,3.6e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.025,0.025,0.0079,0.25,0.25,0.035,3.1e-07,3.1e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31590000,-0.29,0.015,-0.0051,0.96,0.011,0.0094,0.8,0.05,-0.031,-0.45,-0.0012,-0.0058,1.9e-05,0.027,-0.026,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.25,0.25,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31690000,-0.28,0.015,-0.0048,0.96,0.013,0.011,0.76,0.051,-0.03,-0.44,-0.0012,-0.0058,3.6e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.026,0.026,0.008,0.26,0.26,0.035,3.1e-07,3.1e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31690000,-0.29,0.016,-0.0051,0.96,0.013,0.011,0.8,0.051,-0.03,-0.38,-0.0012,-0.0058,1.9e-05,0.028,-0.026,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.26,0.26,0.03,3.1e-07,3.1e-07,4.7e-06,0.029,0.029,0.0001,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31790000,-0.28,0.016,-0.005,0.96,0.0088,0.017,0.76,0.049,-0.02,-0.36,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.025,0.025,0.0079,0.26,0.26,0.035,3.1e-07,3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31790000,-0.29,0.016,-0.0053,0.96,0.008,0.017,0.8,0.049,-0.02,-0.31,-0.0012,-0.0058,1.8e-05,0.028,-0.026,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.26,0.26,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31890000,-0.28,0.015,-0.0047,0.96,0.0054,0.019,0.76,0.05,-0.018,-0.3,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.026,0.026,0.008,0.27,0.27,0.035,3.1e-07,3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31890000,-0.29,0.016,-0.005,0.96,0.0045,0.019,0.8,0.05,-0.018,-0.24,-0.0012,-0.0058,1.8e-05,0.028,-0.027,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.27,0.27,0.03,3.1e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
31990000,-0.28,0.015,-0.005,0.96,0.0027,0.02,0.75,0.049,-0.014,-0.23,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.025,0.025,0.0079,0.27,0.27,0.035,3e-07,3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
31990000,-0.29,0.015,-0.0054,0.96,0.0019,0.02,0.79,0.049,-0.014,-0.17,-0.0012,-0.0058,1.7e-05,0.029,-0.027,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.27,0.27,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32090000,-0.28,0.015,-0.0054,0.96,0.0029,0.024,0.76,0.049,-0.012,-0.16,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.026,0.026,0.008,0.28,0.28,0.035,3e-07,3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32090000,-0.29,0.015,-0.0058,0.96,0.002,0.024,0.8,0.049,-0.012,-0.097,-0.0012,-0.0058,1.7e-05,0.029,-0.027,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0052,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.9e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32190000,-0.28,0.015,-0.0057,0.96,0.00046,0.03,0.76,0.046,-0.0032,-0.092,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.022,0.025,0.025,0.0079,0.28,0.28,0.035,3e-07,3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32190000,-0.29,0.015,-0.006,0.96,-0.00048,0.03,0.8,0.047,-0.0032,-0.029,-0.0012,-0.0058,1.7e-05,0.029,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.28,0.28,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32290000,-0.28,0.015,-0.0055,0.96,-0.0013,0.033,0.75,0.046,-4.1e-05,-0.023,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.026,0.026,0.008,0.29,0.29,0.035,3e-07,3e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32290000,-0.29,0.016,-0.0059,0.96,-0.0023,0.033,0.79,0.047,3.9e-05,0.041,-0.0012,-0.0058,1.6e-05,0.029,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.026,0.026,0.0051,0.29,0.29,0.03,3e-07,3e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32390000,-0.28,0.015,-0.0057,0.96,-0.004,0.034,0.75,0.044,0.0026,0.051,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00037,0.00035,0.022,0.025,0.025,0.0079,0.29,0.29,0.035,3e-07,2.9e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32390000,-0.29,0.016,-0.006,0.96,-0.005,0.034,0.79,0.044,0.0026,0.12,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.021,0.025,0.025,0.0051,0.29,0.29,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32490000,-0.28,0.013,-0.0087,0.96,-0.042,0.092,-0.12,0.041,0.011,0.055,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.022,0.028,0.028,0.0078,0.3,0.3,0.035,3e-07,2.9e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32490000,-0.29,0.014,-0.0091,0.96,-0.045,0.093,-0.078,0.041,0.011,0.12,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00036,0.021,0.027,0.027,0.0051,0.3,0.3,0.03,3e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32590000,-0.28,0.013,-0.0086,0.96,-0.036,0.091,-0.12,0.047,0.0028,0.035,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.022,0.028,0.028,0.0075,0.3,0.3,0.035,2.9e-07,2.9e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32590000,-0.29,0.014,-0.0091,0.96,-0.039,0.091,-0.08,0.047,0.0028,0.1,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.026,0.026,0.0051,0.3,0.3,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32690000,-0.28,0.013,-0.0086,0.96,-0.032,0.098,-0.12,0.043,0.012,0.02,-0.0012,-0.0058,3.5e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00036,0.00035,0.022,0.031,0.031,0.0073,0.31,0.31,0.035,2.9e-07,2.9e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32690000,-0.29,0.014,-0.0091,0.96,-0.035,0.099,-0.082,0.044,0.012,0.087,-0.0012,-0.0058,1.6e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00036,0.021,0.027,0.027,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32790000,-0.28,0.013,-0.0083,0.96,-0.026,0.094,-0.12,0.048,0.0035,0.0047,-0.0012,-0.0058,3.6e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.022,0.031,0.031,0.0071,0.31,0.31,0.035,2.9e-07,2.9e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32790000,-0.29,0.014,-0.0089,0.96,-0.029,0.096,-0.083,0.049,0.0033,0.072,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.31,0.31,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32890000,-0.28,0.013,-0.0083,0.96,-0.026,0.1,-0.13,0.045,0.013,-0.011,-0.0012,-0.0058,3.6e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.022,0.035,0.036,0.007,0.32,0.32,0.035,2.9e-07,2.9e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32890000,-0.29,0.014,-0.0089,0.96,-0.03,0.1,-0.084,0.046,0.013,0.057,-0.0012,-0.0058,1.7e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.32,0.32,0.03,2.9e-07,2.9e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
32990000,-0.28,0.013,-0.0079,0.96,-0.02,0.091,-0.12,0.049,-0.00059,-0.024,-0.0012,-0.0058,3.6e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00033,0.00032,0.022,0.035,0.036,0.0067,0.31,0.31,0.035,2.9e-07,2.8e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
32990000,-0.29,0.014,-0.0087,0.96,-0.024,0.097,-0.084,0.05,-0.0015,0.043,-0.0012,-0.0058,1.8e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.31,0.31,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.8e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33090000,-0.28,0.013,-0.0079,0.96,-0.016,0.096,-0.12,0.047,0.0087,-0.031,-0.0012,-0.0058,3.6e-05,0.024,-0.018,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00033,0.00033,0.022,0.04,0.041,0.0066,0.33,0.33,0.035,2.9e-07,2.8e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
33090000,-0.29,0.014,-0.0087,0.96,-0.021,0.1,-0.081,0.048,0.0085,0.036,-0.0012,-0.0058,1.8e-05,0.03,-0.028,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.027,0.0051,0.33,0.33,0.03,2.9e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33190000,-0.28,0.013,-0.0074,0.96,-0.0096,0.085,-0.12,0.05,-0.0067,-0.037,-0.0013,-0.0058,3.7e-05,0.024,-0.019,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0003,0.0003,0.022,0.04,0.04,0.0064,0.32,0.32,0.035,2.8e-07,2.8e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
33190000,-0.29,0.014,-0.0085,0.96,-0.015,0.097,-0.08,0.051,-0.0088,0.028,-0.0012,-0.0057,1.8e-05,0.03,-0.027,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.32,0.32,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33290000,-0.28,0.013,-0.0075,0.96,-0.0063,0.087,-0.12,0.049,0.002,-0.045,-0.0013,-0.0058,3.7e-05,0.024,-0.019,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00031,0.0003,0.022,0.046,0.047,0.0063,0.34,0.34,0.034,2.8e-07,2.8e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
33290000,-0.29,0.014,-0.0086,0.96,-0.013,0.1,-0.079,0.049,0.0012,0.02,-0.0012,-0.0057,1.8e-05,0.03,-0.027,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.027,0.026,0.0051,0.34,0.34,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.7e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33390000,-0.28,0.013,-0.0072,0.96,-0.001,0.078,-0.12,0.05,-0.005,-0.053,-0.0013,-0.0057,3.7e-05,0.023,-0.02,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00028,0.00028,0.022,0.045,0.046,0.0062,0.33,0.33,0.034,2.8e-07,2.8e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
33390000,-0.29,0.014,-0.0085,0.96,-0.0075,0.096,-0.078,0.051,-0.0086,0.011,-0.0013,-0.0057,1.9e-05,0.031,-0.026,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.025,0.025,0.0051,0.33,0.33,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33490000,-0.28,0.013,-0.0072,0.96,0.0034,0.08,-0.12,0.05,0.0029,-0.062,-0.0013,-0.0057,3.7e-05,0.023,-0.02,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00028,0.00028,0.022,0.053,0.053,0.0061,0.35,0.35,0.034,2.8e-07,2.8e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
33490000,-0.29,0.014,-0.0084,0.96,-0.0037,0.1,-0.077,0.051,0.0012,0.0017,-0.0013,-0.0057,1.9e-05,0.031,-0.026,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00035,0.00035,0.021,0.026,0.026,0.0051,0.35,0.35,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33590000,-0.28,0.013,-0.0068,0.96,0.0061,0.069,-0.11,0.05,-0.0072,-0.069,-0.0013,-0.0057,3.8e-05,0.021,-0.023,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00025,0.00025,0.022,0.05,0.051,0.006,0.34,0.34,0.034,2.8e-07,2.7e-07,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
33590000,-0.29,0.014,-0.0083,0.96,-0.00053,0.097,-0.073,0.051,-0.013,-0.0062,-0.0013,-0.0057,2e-05,0.031,-0.025,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.025,0.025,0.0051,0.34,0.34,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33690000,-0.28,0.013,-0.0068,0.96,0.011,0.071,-0.11,0.05,-0.00024,-0.077,-0.0013,-0.0057,4.2e-05,0.021,-0.023,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00025,0.00025,0.018,0.058,0.059,0.0059,0.36,0.36,0.034,2.8e-07,2.8e-07,6.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0
|
33690000,-0.29,0.014,-0.0083,0.96,0.0033,0.1,-0.074,0.051,-0.0033,-0.014,-0.0013,-0.0057,2e-05,0.031,-0.025,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.8e-07,4.7e-06,0.029,0.029,9.6e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33790000,-0.28,0.013,-0.0065,0.96,0.013,0.059,-0.11,0.049,-0.0088,-0.083,-0.0013,-0.0057,4.3e-05,0.019,-0.025,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00022,0.00022,0.018,0.054,0.055,0.0059,0.35,0.35,0.034,2.8e-07,2.7e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
33790000,-0.29,0.014,-0.0082,0.96,0.0074,0.098,-0.069,0.051,-0.018,-0.021,-0.0013,-0.0057,2.1e-05,0.032,-0.024,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.0051,0.35,0.35,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33890000,-0.28,0.013,-0.0066,0.96,0.017,0.058,-0.11,0.051,-0.0029,-0.089,-0.0013,-0.0057,4.3e-05,0.019,-0.025,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00023,0.00022,0.018,0.063,0.063,0.0058,0.37,0.37,0.033,2.8e-07,2.7e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0
|
33890000,-0.29,0.014,-0.0082,0.96,0.011,0.1,-0.068,0.052,-0.0081,-0.028,-0.0013,-0.0057,2.1e-05,0.032,-0.024,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00035,0.021,0.026,0.026,0.0051,0.36,0.36,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
33990000,-0.28,0.013,-0.0064,0.96,0.019,0.051,-0.1,0.051,-0.0053,-0.092,-0.0013,-0.0057,4.3e-05,0.017,-0.026,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0002,0.0002,0.018,0.057,0.058,0.0058,0.36,0.36,0.033,2.8e-07,2.7e-07,6.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
33990000,-0.29,0.014,-0.008,0.96,0.014,0.097,-0.065,0.053,-0.018,-0.031,-0.0013,-0.0057,2.3e-05,0.032,-0.024,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.36,0.36,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34090000,-0.28,0.013,-0.0064,0.96,0.023,0.053,-0.1,0.053,-0.00012,-0.096,-0.0013,-0.0057,4.3e-05,0.017,-0.026,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.0002,0.0002,0.018,0.065,0.066,0.0058,0.37,0.37,0.033,2.8e-07,2.7e-07,6.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0
|
34090000,-0.29,0.014,-0.008,0.96,0.018,0.1,-0.063,0.055,-0.0077,-0.036,-0.0013,-0.0057,2.3e-05,0.032,-0.024,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.37,0.37,0.03,2.8e-07,2.7e-07,4.7e-06,0.029,0.029,9.5e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34190000,-0.28,0.014,-0.0063,0.96,0.023,0.044,-0.097,0.051,-0.0039,-0.098,-0.0013,-0.0057,4.3e-05,0.015,-0.028,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00019,0.00018,0.018,0.058,0.059,0.0058,0.37,0.37,0.033,2.8e-07,2.7e-07,6.2e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0
|
34190000,-0.29,0.014,-0.0079,0.96,0.021,0.099,-0.061,0.052,-0.02,-0.039,-0.0013,-0.0057,2.4e-05,0.032,-0.023,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.025,0.005,0.37,0.37,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34290000,-0.28,0.014,-0.0062,0.96,0.023,0.044,-0.096,0.053,0.0005,-0.1,-0.0013,-0.0057,4.3e-05,0.015,-0.028,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00019,0.00018,0.018,0.066,0.066,0.0058,0.38,0.38,0.033,2.8e-07,2.8e-07,6.2e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0
|
34290000,-0.29,0.014,-0.0078,0.96,0.021,0.1,-0.06,0.054,-0.01,-0.045,-0.0013,-0.0057,2.4e-05,0.032,-0.023,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.38,0.38,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34390000,-0.28,0.014,-0.0061,0.96,0.022,0.036,-0.091,0.05,-0.0023,-0.11,-0.0013,-0.0057,4.3e-05,0.012,-0.028,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00017,0.00017,0.018,0.059,0.059,0.0059,0.38,0.38,0.033,2.8e-07,2.8e-07,6.2e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0
|
34390000,-0.29,0.014,-0.0077,0.96,0.023,0.098,-0.055,0.051,-0.023,-0.049,-0.0013,-0.0057,2.4e-05,0.033,-0.023,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.025,0.024,0.005,0.38,0.38,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34490000,-0.28,0.014,-0.0062,0.96,0.024,0.036,-0.089,0.053,0.0013,-0.11,-0.0013,-0.0057,4.3e-05,0.012,-0.028,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00017,0.00017,0.018,0.066,0.066,0.0059,0.39,0.39,0.032,2.8e-07,2.8e-07,6.2e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0
|
34490000,-0.29,0.014,-0.0078,0.96,0.025,0.1,-0.053,0.054,-0.013,-0.052,-0.0013,-0.0057,2.5e-05,0.033,-0.023,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.026,0.026,0.0051,0.39,0.39,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.4e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34590000,-0.28,0.013,-0.0061,0.96,0.021,0.027,0.71,0.05,-0.0027,-0.08,-0.0013,-0.0057,4.4e-05,0.0099,-0.029,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00016,0.00016,0.018,0.055,0.056,0.0059,0.39,0.39,0.032,2.8e-07,2.8e-07,6.2e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0
|
34590000,-0.29,0.014,-0.0076,0.96,0.026,0.095,0.74,0.05,-0.028,-0.023,-0.0013,-0.0057,2.6e-05,0.033,-0.022,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.39,0.39,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34690000,-0.28,0.013,-0.0061,0.96,0.023,0.025,1.7,0.052,-2.4e-05,0.038,-0.0013,-0.0057,4.4e-05,0.0099,-0.029,-0.11,-0.017,-0.0037,0.57,0,0,0,0,0,0.00016,0.00016,0.018,0.059,0.059,0.006,0.4,0.4,0.032,2.8e-07,2.8e-07,6.2e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0
|
34690000,-0.29,0.013,-0.0077,0.96,0.031,0.095,1.7,0.053,-0.019,0.096,-0.0013,-0.0057,2.6e-05,0.033,-0.022,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.024,0.0051,0.4,0.4,0.03,2.7e-07,2.7e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34790000,-0.28,0.013,-0.0061,0.96,0.024,0.018,2.7,0.05,-0.0025,0.21,-0.0013,-0.0057,4.3e-05,0.011,-0.032,-0.1,-0.017,-0.0037,0.57,0,0,0,0,0,0.00016,0.00015,0.018,0.051,0.051,0.0061,0.4,0.4,0.032,2.8e-07,2.8e-07,6.2e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0
|
34790000,-0.29,0.013,-0.0076,0.96,0.033,0.086,2.7,0.049,-0.033,0.27,-0.0013,-0.0057,2.6e-05,0.035,-0.023,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.023,0.023,0.005,0.4,0.4,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
34890000,-0.28,0.013,-0.0061,0.96,0.027,0.015,3.6,0.052,-0.00082,0.5,-0.0013,-0.0057,4.3e-05,0.011,-0.032,-0.1,-0.017,-0.0037,0.57,0,0,0,0,0,0.00016,0.00015,0.018,0.055,0.055,0.0062,0.41,0.41,0.032,2.8e-07,2.8e-07,6.2e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0
|
34890000,-0.29,0.013,-0.0076,0.96,0.038,0.086,3.7,0.052,-0.024,0.57,-0.0013,-0.0057,2.5e-05,0.036,-0.024,-0.12,-0.017,-0.0037,0.57,0,0,0,0,0,0.00034,0.00034,0.021,0.024,0.025,0.005,0.41,0.41,0.03,2.7e-07,2.6e-07,4.7e-06,0.029,0.029,9.3e-05,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
|
||||||
|
|
|
|
@ -95,7 +95,7 @@ TEST_F(EkfAccelerometerTest, biasEstimatePositive)
|
||||||
const float biases[4] = {0.1f, 0.2f, 0.3f, 0.38f};
|
const float biases[4] = {0.1f, 0.2f, 0.3f, 0.38f};
|
||||||
|
|
||||||
for (int i = 0; i < 4; i ++) {
|
for (int i = 0; i < 4; i ++) {
|
||||||
testBias(biases[i], 10, 0.03f);
|
testBias(biases[i], 60, 0.03f);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -104,7 +104,7 @@ TEST_F(EkfAccelerometerTest, biasEstimateNegative)
|
||||||
const float biases[4] = {-0.12f, -0.22f, -0.31, -0.4f};
|
const float biases[4] = {-0.12f, -0.22f, -0.31, -0.4f};
|
||||||
|
|
||||||
for (int i = 0; i < 4; i ++) {
|
for (int i = 0; i < 4; i ++) {
|
||||||
testBias(biases[i], 10, 0.03f);
|
testBias(biases[i], 60, 0.03f);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -191,7 +191,7 @@ TEST_F(EkfBasicsTest, accelBiasEstimation)
|
||||||
_sensor_simulator.startGps();
|
_sensor_simulator.startGps();
|
||||||
_sensor_simulator.setImuBias(accel_bias_sim, Vector3f(0.0f, 0.0f, 0.0f));
|
_sensor_simulator.setImuBias(accel_bias_sim, Vector3f(0.0f, 0.0f, 0.0f));
|
||||||
_ekf->set_min_required_gps_health_time(1e6);
|
_ekf->set_min_required_gps_health_time(1e6);
|
||||||
_sensor_simulator.runSeconds(30);
|
_sensor_simulator.runSeconds(60);
|
||||||
|
|
||||||
const Vector3f pos = _ekf->getPosition();
|
const Vector3f pos = _ekf->getPosition();
|
||||||
const Vector3f vel = _ekf->getVelocity();
|
const Vector3f vel = _ekf->getVelocity();
|
||||||
|
|
|
@ -285,7 +285,7 @@ TEST_F(EkfExternalVisionTest, velocityFrameBody)
|
||||||
// THEN: As the drone is turned 90 degrees, velocity variance
|
// THEN: As the drone is turned 90 degrees, velocity variance
|
||||||
// along local y axis is expected to be bigger
|
// along local y axis is expected to be bigger
|
||||||
const Vector3f velVar_new = _ekf->getVelocityVariance();
|
const Vector3f velVar_new = _ekf->getVelocityVariance();
|
||||||
EXPECT_NEAR(velVar_new(1) / velVar_new(0), 70.f, 15.f);
|
EXPECT_NEAR(velVar_new(1) / velVar_new(0), 30.f, 15.f);
|
||||||
|
|
||||||
const Vector3f vel_earth_est = _ekf->getVelocity();
|
const Vector3f vel_earth_est = _ekf->getVelocity();
|
||||||
EXPECT_NEAR(vel_earth_est(0), 0.0f, 0.1f);
|
EXPECT_NEAR(vel_earth_est(0), 0.0f, 0.1f);
|
||||||
|
@ -319,7 +319,7 @@ TEST_F(EkfExternalVisionTest, velocityFrameLocal)
|
||||||
// THEN: Independently on drones heading, velocity variance
|
// THEN: Independently on drones heading, velocity variance
|
||||||
// along local x axis is expected to be bigger
|
// along local x axis is expected to be bigger
|
||||||
const Vector3f velVar_new = _ekf->getVelocityVariance();
|
const Vector3f velVar_new = _ekf->getVelocityVariance();
|
||||||
EXPECT_NEAR(velVar_new(0) / velVar_new(1), 70.f, 15.f);
|
EXPECT_NEAR(velVar_new(0) / velVar_new(1), 30.f, 15.f);
|
||||||
|
|
||||||
const Vector3f vel_earth_est = _ekf->getVelocity();
|
const Vector3f vel_earth_est = _ekf->getVelocity();
|
||||||
EXPECT_NEAR(vel_earth_est(0), 1.0f, 0.1f);
|
EXPECT_NEAR(vel_earth_est(0), 1.0f, 0.1f);
|
||||||
|
|
|
@ -182,7 +182,7 @@ TEST_F(EkfHeightFusionTest, gpsRef)
|
||||||
EXPECT_NEAR(baro_status.bias, baro_initial + baro_increment, 1.3f);
|
EXPECT_NEAR(baro_status.bias, baro_initial + baro_increment, 1.3f);
|
||||||
|
|
||||||
const BiasEstimator::status &rng_status = _ekf->getRngHgtBiasEstimatorStatus();
|
const BiasEstimator::status &rng_status = _ekf->getRngHgtBiasEstimatorStatus();
|
||||||
EXPECT_NEAR(rng_status.bias, 0.f, 1.f);
|
EXPECT_NEAR(rng_status.bias, 0.f, 1.1f); // TODO: why?
|
||||||
|
|
||||||
// BUT WHEN: the GPS jumps by a lot
|
// BUT WHEN: the GPS jumps by a lot
|
||||||
const float gps_step = 100.f;
|
const float gps_step = 100.f;
|
||||||
|
|
|
@ -175,7 +175,7 @@ TEST_F(EkfInitializationTest, initializeWithZeroTiltNotAtRest)
|
||||||
_ekf->set_vehicle_at_rest(false);
|
_ekf->set_vehicle_at_rest(false);
|
||||||
_sensor_simulator.simulateOrientation(quat_sim);
|
_sensor_simulator.simulateOrientation(quat_sim);
|
||||||
//_sensor_simulator.runSeconds(_init_tilt_period);
|
//_sensor_simulator.runSeconds(_init_tilt_period);
|
||||||
_sensor_simulator.runSeconds(7);
|
_sensor_simulator.runSeconds(10);
|
||||||
|
|
||||||
EXPECT_TRUE(_ekf->control_status_flags().tilt_align);
|
EXPECT_TRUE(_ekf->control_status_flags().tilt_align);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue